diff --git a/.github/workflows/cache_cleanup.yml b/.github/workflows/cache_cleanup.yml index cb3ffb5495c6ac..dfc73eebb223c2 100644 --- a/.github/workflows/cache_cleanup.yml +++ b/.github/workflows/cache_cleanup.yml @@ -7,7 +7,7 @@ on: jobs: cleanup: - runs-on: ubuntu-latest + runs-on: ubuntu-22.04 permissions: # `actions:write` permission is required to delete caches # See also: https://docs.github.com/en/rest/actions/cache?apiVersion=2022-11-28#delete-a-github-actions-cache-for-a-repository-using-a-cache-id diff --git a/.github/workflows/cygwin_build.yml b/.github/workflows/cygwin_build.yml index cef7c8e9a979ea..4b174721603596 100644 --- a/.github/workflows/cygwin_build.yml +++ b/.github/workflows/cygwin_build.yml @@ -64,6 +64,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -128,6 +130,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: diff --git a/.github/workflows/esp32_build.yml b/.github/workflows/esp32_build.yml index 34bf567f6de92d..adad8f8e0c3e5a 100644 --- a/.github/workflows/esp32_build.yml +++ b/.github/workflows/esp32_build.yml @@ -66,6 +66,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -132,6 +134,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -141,7 +145,7 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/macos_build.yml b/.github/workflows/macos_build.yml index 20fc6fd8943841..67e736006e902e 100644 --- a/.github/workflows/macos_build.yml +++ b/.github/workflows/macos_build.yml @@ -64,6 +64,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -128,6 +130,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: diff --git a/.github/workflows/test_ccache.yml b/.github/workflows/test_ccache.yml index 9029f2393d6419..fabff75687c479 100644 --- a/.github/workflows/test_ccache.yml +++ b/.github/workflows/test_ccache.yml @@ -56,6 +56,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -112,6 +114,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -121,8 +125,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -140,5 +144,5 @@ jobs: run: | PATH="/usr/lib/ccache:/opt/gcc-arm-none-eabi-${{matrix.gcc}}/bin:$PATH" Tools/scripts/build_tests/test_ccache.py --boards MatekF405,MatekF405-bdshot --min-cache-pct=75 - Tools/scripts/build_tests/test_ccache.py --boards CubeOrange,Durandal --min-cache-pct=75 + Tools/scripts/build_tests/test_ccache.py --boards Durandal,Pixhawk6X --min-cache-pct=70 diff --git a/.github/workflows/test_chibios.yml b/.github/workflows/test_chibios.yml index 038c7bbbe5b4f7..97a405eec79f04 100644 --- a/.github/workflows/test_chibios.yml +++ b/.github/workflows/test_chibios.yml @@ -58,6 +58,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -120,6 +122,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -129,8 +133,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_coverage.yml b/.github/workflows/test_coverage.yml index b6c5403ac77f90..508e2cb99cf39f 100644 --- a/.github/workflows/test_coverage.yml +++ b/.github/workflows/test_coverage.yml @@ -13,9 +13,9 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-${{ matrix.type }}:v0.0.29 + image: ardupilot/ardupilot-dev-${{ matrix.type }}:v0.1.0 options: --privileged strategy: fail-fast: false # don't cancel if a job from the matrix fails @@ -56,14 +56,6 @@ jobs: - name: setup ccache run: | . .github/workflows/ccache.env - - name: Configure CAN - if: ${{ matrix.config == 'sitltest-can'}} - run: | - sudo apt-get update - sudo apt-get -y install can-utils iproute2 linux-modules-extra-$(uname -r) - sudo modprobe vcan - sudo ip link add dev vcan0 type vcan - sudo ip link set up vcan0 - name: test ${{matrix.config}} ${{ matrix.toolchain }} env: CI_BUILD_TARGET: ${{matrix.config}} @@ -99,7 +91,7 @@ jobs: finish: if: always() needs: build - runs-on: ubuntu-latest + runs-on: ubuntu-22.04 steps: - name: Coveralls Finished uses: coverallsapp/github-action@master diff --git a/.github/workflows/test_dds.yml b/.github/workflows/test_dds.yml index db77005988547c..b4487d47315970 100644 --- a/.github/workflows/test_dds.yml +++ b/.github/workflows/test_dds.yml @@ -63,6 +63,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -126,6 +128,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -135,7 +139,7 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: image: ardupilot/ardupilot-dev-ros:latest options: --user 1001 diff --git a/.github/workflows/test_environment.yml b/.github/workflows/test_environment.yml index dd1f4d2036cab2..22c8f2b0e42f08 100644 --- a/.github/workflows/test_environment.yml +++ b/.github/workflows/test_environment.yml @@ -6,12 +6,12 @@ on: push: paths: - '.github/workflows/test_environment.yml' - - 'Tools/scripts/environment_install/**' + - 'Tools/environment_install/**' pull_request: paths: - '.github/workflows/test_environment.yml' - - 'Tools/scripts/environment_install/**' + - 'Tools/environment_install/**' concurrency: @@ -20,7 +20,7 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: image: ${{matrix.os}}:${{matrix.name}} options: --privileged @@ -68,7 +68,7 @@ jobs: software-properties-common ;; *"archlinux"*) - pacman -Sy --noconfirm --needed git sudo + pacman -Syu --noconfirm --needed git sudo ;; esac @@ -115,6 +115,7 @@ jobs: run: | git config --global --add safe.directory ${GITHUB_WORKSPACE} source ~/.bashrc + source $HOME/venv-ardupilot/bin/activate || true git config --global --add safe.directory /__w/ardupilot/ardupilot ./waf configure ./waf rover @@ -128,6 +129,7 @@ jobs: run: | git config --global --add safe.directory ${GITHUB_WORKSPACE} source ~/.bashrc + source $HOME/venv-ardupilot/bin/activate || true case ${{matrix.os}} in *"archlinux"*) export PATH=/opt/gcc-arm-none-eabi-10-2020-q4-major/bin:$PATH diff --git a/.github/workflows/test_linux_sbc.yml b/.github/workflows/test_linux_sbc.yml index fb8c8397752f0b..1c2259f3532a18 100644 --- a/.github/workflows/test_linux_sbc.yml +++ b/.github/workflows/test_linux_sbc.yml @@ -60,6 +60,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -121,6 +123,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -130,8 +134,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_replay.yml b/.github/workflows/test_replay.yml index e7a8cd72f86665..1cd0b1c6afb60a 100644 --- a/.github/workflows/test_replay.yml +++ b/.github/workflows/test_replay.yml @@ -67,6 +67,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -134,6 +136,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -143,8 +147,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_scripting.yml b/.github/workflows/test_scripting.yml index 8fbc8a10d7d150..c8d4b17c8255b3 100644 --- a/.github/workflows/test_scripting.yml +++ b/.github/workflows/test_scripting.yml @@ -21,8 +21,8 @@ concurrency: jobs: test-scripting: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-base:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-base:v0.1.0 steps: # git checkout the PR - uses: actions/checkout@v3 diff --git a/.github/workflows/test_scripts.yml b/.github/workflows/test_scripts.yml index 410037f5ba6e63..1728f5facd1dbd 100644 --- a/.github/workflows/test_scripts.yml +++ b/.github/workflows/test_scripts.yml @@ -8,8 +8,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-base:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-base:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -30,6 +30,4 @@ jobs: CI_BUILD_TARGET: ${{matrix.config}} shell: bash run: | - sudo apt update - sudo apt-get install -y astyle Tools/scripts/build_ci.sh diff --git a/.github/workflows/test_sitl_blimp.yml b/.github/workflows/test_sitl_blimp.yml new file mode 100644 index 00000000000000..7343f4b81ebde6 --- /dev/null +++ b/.github/workflows/test_sitl_blimp.yml @@ -0,0 +1,270 @@ +name: test blimp + +on: + push: + paths-ignore: + # remove other vehicles + - 'AntennaTracker/**' + - 'ArduPlane/**' + - 'ArduSub/**' + - 'ArduCopter/**' + - 'Rover/**' + # 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/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 other vehicles autotest + - 'Tools/autotest/antennatracker.py' + - 'Tools/autotest/arduplane.py' + - 'Tools/autotest/arducopter.py' + - 'Tools/autotest/ardusub.py' + - 'Tools/autotest/balancebot.py' + - 'Tools/autotest/helicopter.py' + - 'Tools/autotest/location.txt' + - 'Tools/autotest/quadplane.py' + - 'Tools/autotest/rover.py' + - 'Tools/autotest/sailboat.py' + - 'Tools/autotest/swarminit.txt' + # 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/**' + + + pull_request: + paths-ignore: + # remove other vehicles + - 'AntennaTracker/**' + - 'ArduPlane/**' + - 'ArduSub/**' + - 'ArduCopter/**' + - 'Rover/**' + # 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/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 other vehicles autotest + - 'Tools/autotest/antennatracker.py' + - 'Tools/autotest/arduplane.py' + - 'Tools/autotest/arducopter.py' + - 'Tools/autotest/ardusub.py' + - 'Tools/autotest/balancebot.py' + - 'Tools/autotest/helicopter.py' + - 'Tools/autotest/location.txt' + - 'Tools/autotest/quadplane.py' + - 'Tools/autotest/rover.py' + - 'Tools/autotest/sailboat.py' + - 'Tools/autotest/swarminit.txt' + # 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/**' + + workflow_dispatch: + +concurrency: + group: ci-${{github.workflow}}-${{ github.ref }} + cancel-in-progress: true + +jobs: + build: + runs-on: ubuntu-20.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + strategy: + fail-fast: false # don't cancel if a job from the matrix fails + matrix: + toolchain: [ + base, # GCC + clang, + ] + steps: + # git checkout the PR + - uses: actions/checkout@v3 + with: + submodules: 'recursive' + # Put ccache into github cache for faster build + - name: Prepare ccache timestamp + id: ccache_cache_timestamp + run: | + NOW=$(date -u +"%F-%T") + echo "timestamp=${NOW}" >> $GITHUB_OUTPUT + - name: ccache cache files + uses: actions/cache@v3 + with: + path: ~/.ccache + key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}} + restore-keys: ${{github.workflow}}-ccache-${{ matrix.toolchain }}- # restore ccache from either previous build on this branch or on master + - name: setup ccache + run: | + . .github/workflows/ccache.env + - name: build blimp ${{ matrix.toolchain }} + shell: bash + run: | + git config --global --add safe.directory ${GITHUB_WORKSPACE} + if [[ ${{ matrix.toolchain }} == "clang" ]]; then + export CC=clang + export CXX=clang++ + fi + PATH="/github/home/.local/bin:$PATH" + ./waf configure --board sitl + ./waf build --target bin/blimp + ccache -s + ccache -z + + autotest: + needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build + runs-on: ubuntu-20.04 + container: + image: ardupilot/ardupilot-dev-base:v0.0.29 + options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined + strategy: + fail-fast: false # don't cancel if a job from the matrix fails + matrix: + config: [ + sitltest-blimp, + ] + + steps: + # git checkout the PR + - uses: actions/checkout@v3 + with: + submodules: 'recursive' + # Put ccache into github cache for faster build + - name: Prepare ccache timestamp + id: ccache_cache_timestamp + run: | + NOW=$(date -u +"%F-%T") + echo "timestamp=${NOW}" >> $GITHUB_OUTPUT + - name: ccache cache files + uses: actions/cache/restore@v3 + with: + path: ~/.ccache + key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}} + restore-keys: ${{github.workflow}}-ccache-base- # restore ccache from either previous build on this branch or on master + - name: setup ccache + run: | + . .github/workflows/ccache.env + - name: test ${{matrix.config}} + env: + CI_BUILD_TARGET: ${{matrix.config}} + shell: bash + run: | + git config --global --add safe.directory ${GITHUB_WORKSPACE} + PATH="/github/home/.local/bin:$PATH" + Tools/scripts/build_ci.sh + + - name: Archive buildlog artifacts + uses: actions/upload-artifact@v3 + if: failure() + with: + name: fail-${{matrix.config}} + path: | + /tmp/buildlogs + /__w/ardupilot/ardupilot/logs + /__w/ardupilot/ardupilot/ap-*.core + /__w/ardupilot/ardupilot/core.* + /__w/ardupilot/ardupilot/dumpstack.sh_* + /__w/ardupilot/ardupilot/dumpcore.sh_* + retention-days: 14 + + - name: Archive .bin artifacts + uses: actions/upload-artifact@v3 + with: + name: BIN-${{matrix.config}} + path: /__w/ardupilot/ardupilot/logs + retention-days: 7 + diff --git a/.github/workflows/test_sitl_copter.yml b/.github/workflows/test_sitl_copter.yml index e5e53ce409f0b6..9783a04c3d9acd 100644 --- a/.github/workflows/test_sitl_copter.yml +++ b/.github/workflows/test_sitl_copter.yml @@ -73,6 +73,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: @@ -147,6 +149,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -156,8 +160,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -201,9 +205,9 @@ jobs: autotest: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.0.29 + image: ardupilot/ardupilot-dev-base:v0.1.0 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails @@ -269,9 +273,9 @@ jobs: retention-days: 7 build-gcc-heli: - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.0.29 + image: ardupilot/ardupilot-dev-base:v0.1.0 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined steps: # git checkout the PR @@ -305,8 +309,8 @@ jobs: autotest-heli: needs: build-gcc-heli # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-base:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-base:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_sitl_periph.yml b/.github/workflows/test_sitl_periph.yml index ddf9f5eb5f545b..d3bd91ff2c4fdf 100644 --- a/.github/workflows/test_sitl_periph.yml +++ b/.github/workflows/test_sitl_periph.yml @@ -73,6 +73,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -146,6 +148,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -155,8 +159,8 @@ concurrency: jobs: build-gcc-ap_periph: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-periph:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-periph:v0.1.0 steps: # git checkout the PR - uses: actions/checkout@v3 @@ -195,9 +199,9 @@ jobs: autotest-can: needs: build-gcc-ap_periph # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-periph:v0.0.29 + image: ardupilot/ardupilot-dev-periph:v0.1.0 options: --privileged strategy: fail-fast: false # don't cancel if a job from the matrix fails @@ -226,15 +230,6 @@ jobs: - name: setup ccache run: | . .github/workflows/ccache.env - - name: setup can-utils - run: | - kernel_ver=`uname -r` - if [ "$kernel_ver" = "5.4.0-1032-azure" ] || [ "$kernel_ver" = "5.11.4-051104-generic" ]; then echo "Unsupported Kernel $kernel_ver" && exit 0; fi; - sudo apt-get update - sudo apt-get -y install can-utils iproute2 linux-modules-extra-$(uname -r) - sudo modprobe vcan - sudo ip link add dev vcan0 type vcan - sudo ip link set up vcan0 - name: test ${{matrix.config}} env: CI_BUILD_TARGET: ${{matrix.config}} diff --git a/.github/workflows/test_sitl_plane.yml b/.github/workflows/test_sitl_plane.yml index 01b7b144f7a419..24a48476c102a7 100644 --- a/.github/workflows/test_sitl_plane.yml +++ b/.github/workflows/test_sitl_plane.yml @@ -74,6 +74,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -148,6 +150,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -157,8 +161,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -202,9 +206,9 @@ jobs: autotest: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.0.29 + image: ardupilot/ardupilot-dev-base:v0.1.0 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_rover.yml b/.github/workflows/test_sitl_rover.yml index d7776af2318383..5ca2fa60ace722 100644 --- a/.github/workflows/test_sitl_rover.yml +++ b/.github/workflows/test_sitl_rover.yml @@ -73,6 +73,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: @@ -147,6 +149,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -156,8 +160,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -201,9 +205,9 @@ jobs: autotest: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.0.29 + image: ardupilot/ardupilot-dev-base:v0.1.0 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_sub.yml b/.github/workflows/test_sitl_sub.yml index 2436abeae49c1b..57d69d575d2f45 100644 --- a/.github/workflows/test_sitl_sub.yml +++ b/.github/workflows/test_sitl_sub.yml @@ -75,6 +75,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -150,6 +152,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -159,8 +163,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -204,9 +208,9 @@ jobs: autotest: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.0.29 + image: ardupilot/ardupilot-dev-base:v0.1.0 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_tracker.yml b/.github/workflows/test_sitl_tracker.yml index 6f8acf59fea465..c869fb2d66a6a1 100644 --- a/.github/workflows/test_sitl_tracker.yml +++ b/.github/workflows/test_sitl_tracker.yml @@ -75,6 +75,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: @@ -150,6 +152,8 @@ on: # Remove some directories check - '.vscode/**' - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -159,8 +163,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -204,9 +208,9 @@ jobs: autotest: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.0.29 + image: ardupilot/ardupilot-dev-base:v0.1.0 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_size.yml b/.github/workflows/test_size.yml index e1f45fabfe48ca..84bb5bb154ec81 100644 --- a/.github/workflows/test_size.yml +++ b/.github/workflows/test_size.yml @@ -49,6 +49,8 @@ on: - 'libraries/AP_HAL_SITL/**' - 'libraries/AP_HAL_ESP32/**' - 'libraries/AP_HAL_Linux/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: @@ -58,8 +60,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -69,6 +71,8 @@ jobs: config: [ Durandal, MatekF405, + KakuteF7, + MatekH743-bdshot, Pixhawk1-1M, MatekF405-CAN, # see special "build bootloader" code below DrotekP3Pro, # see special "build bootloader" code below diff --git a/.github/workflows/test_unit_tests.yml b/.github/workflows/test_unit_tests.yml index 2bd0abf9ebf1f0..f843f07960b87a 100644 --- a/.github/workflows/test_unit_tests.yml +++ b/.github/workflows/test_unit_tests.yml @@ -44,6 +44,8 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' pull_request: paths-ignore: # Remove markdown files as irrelevant @@ -87,6 +89,8 @@ on: # remove non SITL HAL - 'libraries/AP_HAL_ChibiOS/**' - 'libraries/AP_HAL_ESP32/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' workflow_dispatch: concurrency: @@ -95,9 +99,9 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + image: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 options: --user 1001 strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.gitignore b/.gitignore index c5fae8527cf51e..42d336cd2a66e4 100644 --- a/.gitignore +++ b/.gitignore @@ -111,7 +111,8 @@ GRTAGS GTAGS *.apj .gdbinit -/.vscode +.vscode/* +!.vscode/extensions.json /.history Parameters.html Parameters.md @@ -153,3 +154,13 @@ dumpstack_*out build.tmp.binaries/ tasklist.json modules/esp_idf + +# Ignore Python virtual environments +# from: https://github.com/github/gitignore/blob/4488915eec0b3a45b5c63ead28f286819c0917de/Python.gitignore#L125 +.env +.venv +env/ +venv/ +ENV/ +env.bak/ +venv.bak/ diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 01af44c5848bf7..44def5fb51b4fe 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -16,7 +16,7 @@ exclude: | repos: - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.2.0 + rev: v4.4.0 hooks: #- id: trailing-whitespace #- id: end-of-file-fixer @@ -24,6 +24,11 @@ repos: name: Check line ending character (LF) args: ["--fix=lf"] types_or: [python, c, c++, shell] + exclude: | + (?x)^( + libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp | + libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h + )$ - id: check-added-large-files - id: check-executables-have-shebangs - id: check-shebang-scripts-are-executable @@ -37,12 +42,12 @@ repos: - id: check-yaml - repo: https://github.com/lsst-ts/pre-commit-xmllint - rev: v1.0.0 + rev: 6f36260b537bf9a42b6ea5262c915ae50786296e hooks: - id: format-xmllint files: libraries/AP_DDS/dds_xrce_profile.xml - repo: https://github.com/psf/black - rev: 23.1.0 + rev: 23.7.0 hooks: - id: black files: libraries\/AP_DDS\/(wscript|.*\.py)$ diff --git a/.vscode/extensions.json b/.vscode/extensions.json index e9cd876a0b91cf..4284ec07442f18 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -1,11 +1,13 @@ { "recommendations": [ + "augustocdias.tasks-shell-input", + "bierner.markdown-mermaid", "ms-vscode.cpptools", "sumneko.lua", "ms-python.python", "ms-python.vscode-pylance", "streetsidesoftware.code-spell-checker", "chiehyu.vscode-astyle", - "ardupilot-org.ardupilot-devenv" + "ardupilot-org.ardupilot-devenv", ] } diff --git a/AntennaTracker/AntennaTracker.txt b/AntennaTracker/AntennaTracker.txt index f66169dee5093a..8ced3605b22465 100644 --- a/AntennaTracker/AntennaTracker.txt +++ b/AntennaTracker/AntennaTracker.txt @@ -109,7 +109,7 @@ around. It might even damage itself. AntennaTracker (like other ardupilot software such as ArduPlane, ArduRover etc) has configuration values that control and tailor its operation, and which are stored in EEPROM on the processor. The configuration is restored from -EEPROM every time the processsor starts. +EEPROM every time the processor starts. You can use MissionPlanner, mavproxy or apm_planner or other mavlink compatible software to check and change the configuration of your AntennaTracker. @@ -219,7 +219,7 @@ the vehicle, cd to the ArduPlane directory and run this: ../Tools/autotest/sim_arduplane.sh -T --aircraft test -The -T flag tells sim_arduplane.sh to start an entenna tracker +The -T flag tells sim_arduplane.sh to start an antenna tracker simulator and also start a virtual antenna tracker in a window. To start the antenna tracker running run "tracker start" in the diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index f128d798919ef4..d38d8af77516d5 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -302,8 +302,10 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_SIMSTATE, MSG_SYSTEM_TIME, MSG_AHRS2, +#if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, +#endif MSG_EKF_STATUS_REPORT, }; static const ap_message STREAM_PARAMS_msgs[] = { @@ -425,7 +427,7 @@ MAV_RESULT GCS_MAVLINK_Tracker::handle_command_component_arm_disarm(const mavlin return MAV_RESULT_UNSUPPORTED; } -MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Tracker::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch(packet.command) { @@ -444,7 +446,7 @@ MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command return MAV_RESULT_ACCEPTED; default: - return GCS_MAVLINK::handle_command_long_packet(packet); + return GCS_MAVLINK::handle_command_int_packet(packet, msg); } } diff --git a/AntennaTracker/GCS_Mavlink.h b/AntennaTracker/GCS_Mavlink.h index ecc3953e7b3736..38f7cdb483e712 100644 --- a/AntennaTracker/GCS_Mavlink.h +++ b/AntennaTracker/GCS_Mavlink.h @@ -14,14 +14,14 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK protected: // telem_delay is not used by Tracker but is pure virtual, thus - // this implementaiton. it probably *should* be used by Tracker, + // this implementation. it probably *should* be used by Tracker, // as currently Tracker may brick XBees uint32_t telem_delay() const override { return 0; } MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet) override; MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override; - MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; int32_t global_position_int_relative_alt() const override { return 0; // what if we have been picked up and carried somewhere? diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 33cb304aa19ba1..e1757fba32e4cf 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -130,7 +130,7 @@ const AP_Param::Info Tracker::var_info[] = { // @Param: ONOFF_PITCH_MINT // @DisplayName: Pitch minimum movement time - // @Description: Minimim amount of time in seconds to move in pitch + // @Description: Minimum amount of time in seconds to move in pitch // @Units: s // @Increment: 0.01 // @Range: 0 2 @@ -379,6 +379,14 @@ const AP_Param::Info Tracker::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: PITCH2SRV_PDMX + // @DisplayName: Pitch axis controller PD sum maximum + // @Description: Pitch axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 4000 + // @Increment: 10 + // @Units: d% + // @User: Advanced + GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID), // @Param: YAW2SRV_P @@ -448,6 +456,14 @@ const AP_Param::Info Tracker::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: YAW2SRV_PDMX + // @DisplayName: Yaw axis controller PD sum maximum + // @Description: Yaw axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 4000 + // @Increment: 10 + // @Units: d% + // @User: Advanced + GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID), #if AP_SCRIPTING_ENABLED @@ -525,6 +541,18 @@ const AP_Param::Info Tracker::var_info[] = { // @Path: ../libraries/AP_Logger/AP_Logger.cpp GOBJECT(logger, "LOG", AP_Logger), +#if HAL_NAVEKF2_AVAILABLE + // @Group: EK2_ + // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp + GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2), +#endif + +#if HAL_NAVEKF3_AVAILABLE + // @Group: EK3_ + // @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp + GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3), +#endif + AP_VAREND }; diff --git a/AntennaTracker/Parameters.h b/AntennaTracker/Parameters.h index a3192e24b55944..972c36f52505e8 100644 --- a/AntennaTracker/Parameters.h +++ b/AntennaTracker/Parameters.h @@ -130,6 +130,8 @@ class Parameters { k_param_disarm_pwm, k_param_auto_opts, + k_param_NavEKF2, + k_param_NavEKF3, k_param_logger = 253, // 253 - Logging Group diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 8dc5245a3d0b73..1bdbc630bc2a9d 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -23,11 +23,12 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) // check if motor interlock and either Emergency Stop aux switches are used // at the same time. This cannot be allowed. + bool passed = true; if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) && (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP) || rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP))){ check_failed(display_failure, "Interlock/E-Stop Conflict"); - return false; + passed = false; } // check if motor interlock aux switch is in use @@ -35,17 +36,22 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) // otherwise exit immediately. if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) { check_failed(display_failure, "Motor Interlock Enabled"); - return false; + passed = false; } if (!disarm_switch_checks(display_failure)) { - return false; + passed = false; } // always check motors char failure_msg[50] {}; if (!copter.motors->arming_checks(ARRAY_SIZE(failure_msg), failure_msg)) { check_failed(display_failure, "Motors: %s", failure_msg); + passed = false; + } + + // If not passed all checks return false + if (!passed) { return false; } @@ -218,19 +224,6 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) } #if FRAME_CONFIG == HELI_FRAME - 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) { - check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid Heli FRAME_CLASS"); - return false; - } - - // check helicopter parameters - if (!copter.motors->parameter_check(display_failure)) { - check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Heli motors checks failed"); - return false; - } - char fail_msg[50]; // check input manager parameters if (!copter.input_manager.parameter_check(fail_msg, ARRAY_SIZE(fail_msg))) { @@ -630,7 +623,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) const char *rc_item = "Throttle"; #endif // check throttle is not too high - skips checks if arming from GCS/scripting in Guided,Guided_NoGPS or Auto - if (!((method == AP_Arming::Method::MAVLINK || 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->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS || copter.flightmode->mode_number() == Mode::Number::AUTO))) { // 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); @@ -797,7 +790,7 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che // do not allow disarm via mavlink if we think we are flying: if (do_disarm_checks && - method == AP_Arming::Method::MAVLINK && + AP_Arming::method_is_GCS(method) && !copter.ap.land_complete) { return false; } diff --git a/ArduCopter/AP_ExternalControl_Copter.cpp b/ArduCopter/AP_ExternalControl_Copter.cpp new file mode 100644 index 00000000000000..35353a412618f6 --- /dev/null +++ b/ArduCopter/AP_ExternalControl_Copter.cpp @@ -0,0 +1,37 @@ +/* + external control library for copter + */ + + +#include "AP_ExternalControl_Copter.h" +#if AP_EXTERNAL_CONTROL_ENABLED + +#include "Copter.h" + +/* + set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw + velocity is in earth frame, NED, m/s +*/ +bool AP_ExternalControl_Copter::set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) +{ + if (!ready_for_external_control()) { + return false; + } + const float yaw_rate_cds = isnan(yaw_rate_rads)? 0: degrees(yaw_rate_rads)*100; + + // Copter velocity is positive if aircraft is moving up which is opposite the incoming NED frame. + Vector3f velocity_NEU_ms { + linear_velocity.x, + linear_velocity.y, + -linear_velocity.z }; + Vector3f velocity_up_cms = velocity_NEU_ms * 100; + copter.mode_guided.set_velocity(velocity_up_cms, false, 0, !isnan(yaw_rate_rads), yaw_rate_cds); + return true; +} + +bool AP_ExternalControl_Copter::ready_for_external_control() +{ + return copter.flightmode->in_guided_mode() && copter.motors->armed(); +} + +#endif // AP_EXTERNAL_CONTROL_ENABLED diff --git a/ArduCopter/AP_ExternalControl_Copter.h b/ArduCopter/AP_ExternalControl_Copter.h new file mode 100644 index 00000000000000..e9a879106ebef0 --- /dev/null +++ b/ArduCopter/AP_ExternalControl_Copter.h @@ -0,0 +1,26 @@ +/* + external control library for copter + */ +#pragma once + +#include + +#if AP_EXTERNAL_CONTROL_ENABLED + +class AP_ExternalControl_Copter : public AP_ExternalControl { +public: + /* + Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw. + Velocity is in earth frame, NED [m/s]. + Yaw is in earth frame, NED [rad/s]. + */ + bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) override; +private: + /* + Return true if Copter is ready to handle external control data. + Currently checks mode and arm states. + */ + bool ready_for_external_control(); +}; + +#endif // AP_EXTERNAL_CONTROL_ENABLED diff --git a/ArduCopter/AP_Rally.cpp b/ArduCopter/AP_Rally.cpp index 31027d7909cdf5..46b6735f560e7d 100644 --- a/ArduCopter/AP_Rally.cpp +++ b/ArduCopter/AP_Rally.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include + +#if HAL_RALLY_ENABLED + #include #include "Copter.h" @@ -28,3 +32,5 @@ bool AP_Rally_Copter::is_valid(const Location &rally_point) const #endif return true; } + +#endif // HAL_RALLY_ENABLED diff --git a/ArduCopter/AP_Rally.h b/ArduCopter/AP_Rally.h index 466f5c04b9897b..27c3df857a9271 100644 --- a/ArduCopter/AP_Rally.h +++ b/ArduCopter/AP_Rally.h @@ -14,6 +14,10 @@ */ #pragma once +#include + +#if HAL_RALLY_ENABLED + #include #include @@ -28,3 +32,5 @@ class AP_Rally_Copter : public AP_Rally private: bool is_valid(const Location &rally_point) const override; }; + +#endif // HAL_RALLY_ENABLED diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index f7a0f448712d79..8bbbc186c19e14 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -583,6 +583,11 @@ void Copter::ten_hz_logging_loop() g2.winch.write_log(); } #endif +#if HAL_MOUNT_ENABLED + if (should_log(MASK_LOG_CAMERA)) { + camera_mount.write_log(); + } +#endif } // twentyfive_hz_logging - should be run at 25hz @@ -609,7 +614,7 @@ void Copter::twentyfive_hz_logging() #endif } -// three_hz_loop - 3.3hz loop +// three_hz_loop - 3hz loop void Copter::three_hz_loop() { // check if we've lost contact with the ground station @@ -739,7 +744,7 @@ void Copter::update_super_simple_bearing(bool force_update) void Copter::read_AHRS(void) { - // we tell AHRS to skip INS update as we have already done it in fast_loop() + // we tell AHRS to skip INS update as we have already done it in FAST_TASK. ahrs.update(true); } diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 3afe7f0f4b26e0..bb3942a8f4822c 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -100,6 +100,11 @@ #include "AP_Rally.h" // Rally point library #include "AP_Arming.h" +#include +#if AP_EXTERNAL_CONTROL_ENABLED +#include "AP_ExternalControl_Copter.h" +#endif + #include #if AP_BEACON_ENABLED #include @@ -193,6 +198,9 @@ class Copter : public AP_Vehicle { friend class AP_AdvancedFailsafe_Copter; #endif friend class AP_Arming_Copter; +#if AP_EXTERNAL_CONTROL_ENABLED + friend class AP_ExternalControl_Copter; +#endif friend class ToyMode; friend class RC_Channel_Copter; friend class RC_Channels_Copter; @@ -319,6 +327,12 @@ class Copter : public AP_Vehicle { AP_OpticalFlow optflow; #endif + // external control library +#if AP_EXTERNAL_CONTROL_ENABLED + AP_ExternalControl_Copter external_control; +#endif + + // system time in milliseconds of last recorded yaw reset from ekf uint32_t ekfYawReset_ms; int8_t ekf_primary_core; diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index bcf08cb8e1f90c..7c74d377dc2750 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -511,7 +511,9 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_GPS2_RAW, MSG_GPS2_RTK, MSG_NAV_CONTROLLER_OUTPUT, +#if AP_FENCE_ENABLED MSG_FENCE_STATUS, +#endif MSG_POSITION_TARGET_GLOBAL_INT, }; static const ap_message STREAM_POSITION_msgs[] = { @@ -544,8 +546,10 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_BATTERY_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_OPTICAL_FLOW, +#if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, +#endif MSG_EKF_STATUS_REPORT, MSG_VIBRATION, #if AP_RPM_ENABLED @@ -653,9 +657,9 @@ void GCS_MAVLINK_Copter::handle_landing_target(const mavlink_landing_target_t &p #endif } -MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK_Copter::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { - if (is_equal(packet.param6,1.0f)) { + if (packet.y == 1) { // compassmot calibration return copter.mavlink_compassmot(*this); } @@ -673,7 +677,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_do_set_roi(const Location &roi_loc return MAV_RESULT_ACCEPTED; } -MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { // reject reboot if user has also specified they want the "Auto" ESC calibration on next reboot if (copter.g.esc_calibrate == (uint8_t)Copter::ESCCalibrationModes::ESCCAL_AUTO) { @@ -736,18 +740,25 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_co #endif } -MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_int_t &packet) +MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch(packet.command) { - case MAV_CMD_DO_FOLLOW: + + case MAV_CMD_CONDITION_YAW: + return handle_MAV_CMD_CONDITION_YAW(packet); + + case MAV_CMD_DO_CHANGE_SPEED: + return handle_MAV_CMD_DO_CHANGE_SPEED(packet); + #if MODE_FOLLOW_ENABLED == ENABLED + case MAV_CMD_DO_FOLLOW: // param1: sysid of target to follow if ((packet.param1 > 0) && (packet.param1 <= 255)) { copter.g2.follow.set_target_sysid((uint8_t)packet.param1); return MAV_RESULT_ACCEPTED; } + return MAV_RESULT_DENIED; #endif - return MAV_RESULT_UNSUPPORTED; case MAV_CMD_DO_REPOSITION: return handle_command_int_do_reposition(packet); @@ -756,13 +767,70 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i case MAV_CMD_DO_PAUSE_CONTINUE: return handle_command_pause_continue(packet); + case MAV_CMD_DO_MOTOR_TEST: + return handle_MAV_CMD_DO_MOTOR_TEST(packet); + +#if PARACHUTE == ENABLED + case MAV_CMD_DO_PARACHUTE: + return handle_MAV_CMD_DO_PARACHUTE(packet); +#endif + +#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED + // Solo user presses pause button + case MAV_CMD_SOLO_BTN_PAUSE_CLICK: + return handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(packet); + // Solo user presses Fly button: + case MAV_CMD_SOLO_BTN_FLY_HOLD: + return handle_MAV_CMD_SOLO_BTN_FLY_HOLD(packet); + // Solo user holds down Fly button for a couple of seconds + case MAV_CMD_SOLO_BTN_FLY_CLICK: + return handle_MAV_CMD_SOLO_BTN_FLY_CLICK(packet); +#endif + +#if MODE_AUTO_ENABLED == ENABLED + case MAV_CMD_MISSION_START: + return handle_MAV_CMD_MISSION_START(packet); +#endif + +#if AP_WINCH_ENABLED + case MAV_CMD_DO_WINCH: + return handle_MAV_CMD_DO_WINCH(packet); +#endif + + case MAV_CMD_NAV_LOITER_UNLIM: + if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) { + return MAV_RESULT_FAILED; + } + return MAV_RESULT_ACCEPTED; + + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + if (!copter.set_mode(Mode::Number::RTL, ModeReason::GCS_COMMAND)) { + return MAV_RESULT_FAILED; + } + return MAV_RESULT_ACCEPTED; + + case MAV_CMD_NAV_VTOL_LAND: + case MAV_CMD_NAV_LAND: + if (!copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND)) { + return MAV_RESULT_FAILED; + } + return MAV_RESULT_ACCEPTED; + +#if MODE_AUTO_ENABLED == ENABLED + case MAV_CMD_DO_LAND_START: + if (copter.mode_auto.jump_to_landing_sequence_auto_RTL(ModeReason::GCS_COMMAND)) { + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_FAILED; +#endif + default: - return GCS_MAVLINK::handle_command_int_packet(packet); + return GCS_MAVLINK::handle_command_int_packet(packet, msg); } } #if HAL_MOUNT_ENABLED -MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch (packet.command) { case MAV_CMD_DO_MOUNT_CONTROL: @@ -779,7 +847,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t } #endif -MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) { switch(packet.command) { @@ -799,44 +867,13 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ return MAV_RESULT_ACCEPTED; } -#if MODE_AUTO_ENABLED == ENABLED - case MAV_CMD_DO_LAND_START: - if (copter.mode_auto.jump_to_landing_sequence_auto_RTL(ModeReason::GCS_COMMAND)) { - return MAV_RESULT_ACCEPTED; - } - return MAV_RESULT_FAILED; -#endif - - case MAV_CMD_NAV_LOITER_UNLIM: - if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) { - return MAV_RESULT_FAILED; - } - return MAV_RESULT_ACCEPTED; - - case MAV_CMD_NAV_RETURN_TO_LAUNCH: - if (!copter.set_mode(Mode::Number::RTL, ModeReason::GCS_COMMAND)) { - return MAV_RESULT_FAILED; - } - return MAV_RESULT_ACCEPTED; - - case MAV_CMD_NAV_VTOL_LAND: - case MAV_CMD_NAV_LAND: - if (!copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND)) { - return MAV_RESULT_FAILED; - } - return MAV_RESULT_ACCEPTED; - -#if MODE_FOLLOW_ENABLED == ENABLED - case MAV_CMD_DO_FOLLOW: - // param1: sysid of target to follow - if ((packet.param1 > 0) && (packet.param1 <= 255)) { - copter.g2.follow.set_target_sysid((uint8_t)packet.param1); - return MAV_RESULT_ACCEPTED; - } - return MAV_RESULT_FAILED; -#endif + default: + return GCS_MAVLINK::handle_command_long_packet(packet, msg); + } +} - case MAV_CMD_CONDITION_YAW: +MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet) +{ // param1 : target angle [0-360] // param2 : speed during change [deg per second] // param3 : direction (-1:ccw, +1:cw) @@ -852,8 +889,10 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED; +} - case MAV_CMD_DO_CHANGE_SPEED: +MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet) +{ // param1 : Speed type (0 or 1=Ground Speed, 2=Climb Speed, 3=Descent Speed) // param2 : new speed in m/s // param3 : unused @@ -877,9 +916,11 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ } } return MAV_RESULT_FAILED; +} #if MODE_AUTO_ENABLED == ENABLED - case MAV_CMD_MISSION_START: +MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet) +{ 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) { @@ -888,10 +929,14 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED; +} #endif + + #if PARACHUTE == ENABLED - case MAV_CMD_DO_PARACHUTE: +MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet) +{ // configure or release parachute switch ((uint16_t)packet.param1) { case PARACHUTE_DISABLE: @@ -906,9 +951,11 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED; +} #endif - case MAV_CMD_DO_MOTOR_TEST: +MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet) +{ // param1 : motor sequence number (a number from 1 to max number of motors on the vehicle) // param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) // param3 : throttle (range depends upon param2) @@ -920,10 +967,12 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ (uint8_t)packet.param2, packet.param3, packet.param4, - (uint8_t)packet.param5); + (uint8_t)packet.x); +} #if AP_WINCH_ENABLED - case MAV_CMD_DO_WINCH: +MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_DO_WINCH(const mavlink_command_int_t &packet) +{ // param1 : winch number (ignored) // param2 : action (0=relax, 1=relative length control, 2=rate control). See WINCH_ACTIONS enum. if (!copter.g2.winch.enabled()) { @@ -944,10 +993,12 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ break; } return MAV_RESULT_FAILED; -#endif +} +#endif // AP_WINCH_ENABLED - /* Solo user presses Fly button */ - case MAV_CMD_SOLO_BTN_FLY_CLICK: { +#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED +MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_FLY_CLICK(const mavlink_command_int_t &packet) +{ if (copter.failsafe.radio) { return MAV_RESULT_ACCEPTED; } @@ -957,10 +1008,10 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::GCS_COMMAND); } return MAV_RESULT_ACCEPTED; - } +} - /* Solo user holds down Fly button for a couple of seconds */ - case MAV_CMD_SOLO_BTN_FLY_HOLD: { +MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_FLY_HOLD(const mavlink_command_int_t &packet) +{ if (copter.failsafe.radio) { return MAV_RESULT_ACCEPTED; } @@ -978,10 +1029,10 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND); } return MAV_RESULT_ACCEPTED; - } +} - /* Solo user presses pause button */ - case MAV_CMD_SOLO_BTN_PAUSE_CLICK: { +MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(const mavlink_command_int_t &packet) +{ if (copter.failsafe.radio) { return MAV_RESULT_ACCEPTED; } @@ -1011,18 +1062,8 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_ } } return MAV_RESULT_ACCEPTED; - } - - // pause or resume an auto mission - case MAV_CMD_DO_PAUSE_CONTINUE: { - mavlink_command_int_t packet_int; - GCS_MAVLINK_Copter::convert_COMMAND_LONG_to_COMMAND_INT(packet, packet_int); - return handle_command_pause_continue(packet_int); - } - default: - return GCS_MAVLINK::handle_command_long_packet(packet); - } } +#endif // AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED MAV_RESULT GCS_MAVLINK_Copter::handle_command_pause_continue(const mavlink_command_int_t &packet) { @@ -1439,7 +1480,7 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg) } // end handle mavlink -MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_long_t &packet) { +MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_int_t &packet) { #if ADVANCED_FAILSAFE == ENABLED if (GCS_MAVLINK::handle_flight_termination(packet) == MAV_RESULT_ACCEPTED) { return MAV_RESULT_ACCEPTED; diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index f86ad153f2b0a2..eda1fd42c65cb5 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -1,6 +1,11 @@ #pragma once #include +#include + +#ifndef AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED +#define AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED 1 +#endif class GCS_MAVLINK_Copter : public GCS_MAVLINK { @@ -13,7 +18,7 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK uint32_t telem_delay() const override; - MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override; uint8_t sysid_my_gcs() const override; bool sysid_enforce() const override; @@ -21,19 +26,19 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK bool params_ready() const override; void send_banner() override; - MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; + MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; void send_attitude_target() override; void send_position_target_global_int() override; void send_position_target_local_ned() override; MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override; - MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; + MAV_RESULT handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; #if HAL_MOUNT_ENABLED - MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; + MAV_RESULT handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; #endif - MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override; - MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; + MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet); MAV_RESULT handle_command_pause_continue(const mavlink_command_int_t &packet); @@ -91,4 +96,23 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK uint8_t high_latency_wind_speed() const override; uint8_t high_latency_wind_direction() const override; #endif // HAL_HIGH_LATENCY2_ENABLED + + + MAV_RESULT handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet); + +#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED + MAV_RESULT handle_MAV_CMD_SOLO_BTN_FLY_CLICK(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_SOLO_BTN_FLY_HOLD(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(const mavlink_command_int_t &packet); +#endif + + MAV_RESULT handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet); + +#if AP_WINCH_ENABLED + MAV_RESULT handle_MAV_CMD_DO_WINCH(const mavlink_command_int_t &packet); +#endif + }; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 95c362ea17cb2e..334c4b02934414 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1040,6 +1040,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Description: set which surface to track in surface tracking // @Values: 0:Do not track, 1:Ground, 2:Ceiling // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("SURFTRAK_MODE", 51, ParametersG2, surftrak_mode, (uint8_t)Copter::SurfaceTracking::Surface::GROUND), // @Param: FS_DR_ENABLE diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index 0f8ea1c7754138..b3c7b19c2e972e 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,5 +1,81 @@ ArduPilot Copter Release Notes: ------------------------------------------------------------------ +Copter 4.4.2-beta1 13-Oct-2023 +Changes from 4.4.1 +1) Autopilot related enhancements and fixes + - BETAFPV-F405 support + - MambaF405v2 battery and serial setup corrected + - mRo Control Zero OEM H7 bdshot support + - SpeedyBee-F405-Wing gets VTX power control + - SpeedyBee-F405-Mini support + - T-Motor H743 Mini support +2) EKF3 supports baroless boards +3) GPS-for-yaw allows base GPS to update at only 3Hz +4) INA battery monitor supports config of shunt resistor used (see BATTx_SHUNT) +5) Log VER message includes vehicle type +6) OpenDroneId option to auto-store IDs in persistent flash +7) RC SBUS protection against invalid data in first 4 channels +8) Bug fixes + - BMI088 IMU error value handling fixed to avoid occasional negative spike + - Dev environment CI autotest stability improvements + - OSD correct DisplayPort BF MSP symbols + - OSD option to correct direction arrows for BF font set + - Sensor status reporting to GCS fixed for baroless boards +------------------------------------------------------------------ +Copter 4.4.1 26-Sep-2023 / 4.4.1-beta2 14-Sep-2023 +Changes from 4.4.1-beta1 +1) Autopilot related enhancements + - H750 external flash optimisations for to lower CPU load + - MambaF405Mini fixes to match manufacturer's recommended wiring + - RADIX2 HD support + - YJUAV_A6SE support +2) Bug fixes + - Airbotf4 features minimised to build for 4.4 + - ChibiOS clock fix for 480Mhz H7 boards (affected FDCAN) + - RPI hardware version check fix +------------------------------------------------------------------ +Copter 4.4.1-beta1 05-Sep-2023 +Changes from 4.4.0 +1) Autopilot related fixes and enhancements + - KakuteH7-wing get 8 bit directional dshot channel support + - Luminousbee5 boards defaults updated + - Navigator autopilot GPIOs fix (PWM output was broken) + - Pixhawk6C Serial RTS lines pulled low on startup + - QiotekZealotF427 and QiotekZealotH743 battery monitor default fixed + - SDMODELH7V1 support +2) Driver enhancements + - DroneCAN battery monitors allow reset of battery SoC + - Himark DroneCAN servo support + - Hobbywing DroneCAN ESC support +3) EKF3 high vibration handling improved with EK3_GLITCH_RADIUS option +4) Custom build server gets mission storage on SDCard selection +5) SITL default parameter handling bug fix +------------------------------------------------------------------ +Copter 4.4.0 18-Aug-2023 / 4.4.0-beta5 12-Aug-2023 +Changes from 4.4.0-beta4 +1) Autopilots specific changes + - SIYI N7 support +2) Bug fixes + - DroneCAN airspeed sensor fix to handle missing packets + - DroneCAN GPS RTK injection fix + - Notch filter gyro glitch caused by race condition fixed +------------------------------------------------------------------ +Copter 4.4.0-beta4 27-July-2023 +Changes from 4.4.0-beta3 +1) Autopilots specific changes + - Diatone-Mamba-MK4-H743v2 uses SPL06 baro (was DPS280) + - DMA for I2C disabled on F7 and H7 boards + - Foxeer H743v1 default serial protocol config fixes + - HeeWing-F405 and F405v2 support + - iFlight BlitzF7 support +2) Scripts may take action based on VTOL motor loss +3) Bug fixes + - BLHeli returns battery status requested via MSP (avoids hang when using esc-configurator) + - CRSFv3 rescans at baudrates to avoid RX loss + - EK3_ABIAS_P_NSE param range fix + - Scripting restart memory corruption bug fixed + - Siyi A8/ZR10 driver fix to avoid crash if serial port not configured +------------------------------------------------------------------ Copter 4.4.0-beta3 03-July-2023 Changes from 4.4.0-beta2 1) Autopilots specific changes @@ -24,7 +100,6 @@ Changes from 4.4.0-beta2 - SERVOx_PROTOCOL "SToRM32 Gimbal Serial" value renamed to "Gimbal" because also used by Siyi - SERIALx_OPTION "Swap" renamed to "SwapTXRX" for clarity - SBF GPS ellipsoid height fixed - - Scripting restart memory corruption bug fixed - Ublox M10S GPS auto configuration fixed - ZigZag mode user takeoff fixed (users could not takeoff in ZigZag mode previously) ------------------------------------------------------------------ @@ -264,7 +339,14 @@ Changes from 4.3.6 - Webots 2023a simulator support - XPlane support for wider range of aircraft ------------------------------------------------------------------ -Copter 4.3.7-beta1 24-May-2023 +Copter 4.3.8 24-Aug-2023 / 4.3.8-beta1 12-Aug-2023 +Changes from 4.3.7 +1) Bug fixes + - DroneCAN GPS RTK injection fix + - INAxxx battery monitors allow for battery reset remaining + - Notch filter gyro glitch caused by race condition fixed + - Scripting restart memory corruption bug fixed +------------------------------------------------------------------ Copter 4.3.7 31-May-2023 / 4.3.7-beta1 24-May-2023 Changes from 4.3.6 1) Bug fixes diff --git a/ArduCopter/afs_copter.cpp b/ArduCopter/afs_copter.cpp index 9f669eee8cd656..3bad987a343d3e 100644 --- a/ArduCopter/afs_copter.cpp +++ b/ArduCopter/afs_copter.cpp @@ -68,4 +68,9 @@ AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Copter::afs_mode(void) return AP_AdvancedFailsafe::AFS_STABILIZED; } +//to force entering auto mode when datalink loss + void AP_AdvancedFailsafe_Copter::set_mode_auto(void) + { + copter.set_mode(Mode::Number::AUTO,ModeReason::GCS_FAILSAFE); + } #endif // ADVANCED_FAILSAFE diff --git a/ArduCopter/afs_copter.h b/ArduCopter/afs_copter.h index fd733519733c38..b7c8bc8b21c854 100644 --- a/ArduCopter/afs_copter.h +++ b/ArduCopter/afs_copter.h @@ -39,6 +39,9 @@ class AP_AdvancedFailsafe_Copter : public AP_AdvancedFailsafe // return the AFS mapped control mode enum control_mode afs_mode(void) override; + + //to force entering auto mode when datalink loss + void set_mode_auto(void) override; }; #endif // ADVANCED_FAILSAFE diff --git a/ArduCopter/config.h b/ArduCopter/config.h index a260b6cba4ec67..7a7b6900c2fa7d 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -27,6 +27,7 @@ /// change in your local copy of APM_Config.h. /// #include "APM_Config.h" +#include ////////////////////////////////////////////////////////////////////////////// @@ -146,8 +147,8 @@ ////////////////////////////////////////////////////////////////////////////// // Nav-Guided - allows external nav computer to control vehicle -#ifndef NAV_GUIDED - # define NAV_GUIDED !HAL_MINIMIZE_FEATURES +#ifndef AC_NAV_GUIDED + # define AC_NAV_GUIDED ENABLED #endif ////////////////////////////////////////////////////////////////////////////// @@ -189,7 +190,7 @@ ////////////////////////////////////////////////////////////////////////////// // Follow - follow another vehicle or GCS #ifndef MODE_FOLLOW_ENABLED -# define MODE_FOLLOW_ENABLED !HAL_MINIMIZE_FEATURES +# define MODE_FOLLOW_ENABLED AP_FOLLOW_ENABLED #endif ////////////////////////////////////////////////////////////////////////////// @@ -201,7 +202,7 @@ ////////////////////////////////////////////////////////////////////////////// // GuidedNoGPS mode - control vehicle's angles from GCS #ifndef MODE_GUIDED_NOGPS_ENABLED -# define MODE_GUIDED_NOGPS_ENABLED !HAL_MINIMIZE_FEATURES +# define MODE_GUIDED_NOGPS_ENABLED ENABLED #endif ////////////////////////////////////////////////////////////////////////////// @@ -237,7 +238,7 @@ ////////////////////////////////////////////////////////////////////////////// // System ID - conduct system identification tests on vehicle #ifndef MODE_SYSTEMID_ENABLED -# define MODE_SYSTEMID_ENABLED !HAL_MINIMIZE_FEATURES +# define MODE_SYSTEMID_ENABLED ENABLED #endif ////////////////////////////////////////////////////////////////////////////// @@ -249,19 +250,19 @@ ////////////////////////////////////////////////////////////////////////////// // ZigZag - allow vehicle to fly in a zigzag manner with predefined point A B #ifndef MODE_ZIGZAG_ENABLED -# define MODE_ZIGZAG_ENABLED !HAL_MINIMIZE_FEATURES +# define MODE_ZIGZAG_ENABLED ENABLED #endif ////////////////////////////////////////////////////////////////////////////// // Turtle - allow vehicle to be flipped over after a crash #ifndef MODE_TURTLE_ENABLED -# define MODE_TURTLE_ENABLED !HAL_MINIMIZE_FEATURES && !defined(DISABLE_DSHOT) && FRAME_CONFIG != HELI_FRAME +# define MODE_TURTLE_ENABLED HAL_DSHOT_ENABLED && FRAME_CONFIG != HELI_FRAME #endif ////////////////////////////////////////////////////////////////////////////// // Flowhold - use optical flow to hover in place #ifndef MODE_FLOWHOLD_ENABLED -# define MODE_FLOWHOLD_ENABLED !HAL_MINIMIZE_FEATURES && AP_OPTICALFLOW_ENABLED +# define MODE_FLOWHOLD_ENABLED AP_OPTICALFLOW_ENABLED #endif ////////////////////////////////////////////////////////////////////////////// @@ -269,17 +270,18 @@ ////////////////////////////////////////////////////////////////////////////// // Weathervane - allow vehicle to yaw into wind #ifndef WEATHERVANE_ENABLED -# define WEATHERVANE_ENABLED !HAL_MINIMIZE_FEATURES +# define WEATHERVANE_ENABLED ENABLED #endif ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// // Autorotate - autonomous auto-rotation - helicopters only +#ifndef MODE_AUTOROTATE_ENABLED #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if FRAME_CONFIG == HELI_FRAME #ifndef MODE_AUTOROTATE_ENABLED - # define MODE_AUTOROTATE_ENABLED !HAL_MINIMIZE_FEATURES + # define MODE_AUTOROTATE_ENABLED ENABLED #endif #else # define MODE_AUTOROTATE_ENABLED DISABLED @@ -287,6 +289,7 @@ #else # define MODE_AUTOROTATE_ENABLED DISABLED #endif +#endif ////////////////////////////////////////////////////////////////////////////// // RADIO CONFIGURATION @@ -561,7 +564,7 @@ #endif #ifndef AC_OAPATHPLANNER_ENABLED - #define AC_OAPATHPLANNER_ENABLED !HAL_MINIMIZE_FEATURES + #define AC_OAPATHPLANNER_ENABLED ENABLED #endif #if MODE_FOLLOW_ENABLED && !AC_AVOID_ENABLED diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 18a04aec4fdf8d..786e56b5a0e522 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -101,7 +101,7 @@ void Copter::thrust_loss_check() { static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed - // no-op if suppresed by flight options param + // no-op if suppressed by flight options param if ((copter.g2.flight_options & uint32_t(FlightOptions::DISABLE_THRUST_LOSS_CHECK)) != 0) { return; } @@ -181,7 +181,7 @@ void Copter::thrust_loss_check() // check for a large yaw imbalance, could be due to badly calibrated ESC or misaligned motors void Copter::yaw_imbalance_check() { - // no-op if suppresed by flight options param + // no-op if suppressed by flight options param if ((copter.g2.flight_options & uint32_t(FlightOptions::DISABLE_YAW_IMBALANCE_WARNING)) != 0) { return; } diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index d1e0822b200bdb..888bb87025fe5e 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -666,7 +666,7 @@ void Mode::land_run_vertical_control(bool pause_descent) // doing precland but too far away from the obstacle // do not descend cmb_rate = 0.0f; - } else if (target_pos_meas.z > 35.0f && target_pos_meas.z < 200.0f) { + } else if (target_pos_meas.z > 35.0f && target_pos_meas.z < 200.0f && !copter.precland.do_fast_descend()) { // very close to the ground and doing prec land, lets slow down to make sure we land on target // compute desired descent velocity const float precland_acceptable_error_cm = 15.0f; diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 0829a36d2ef9ab..28c78411797a85 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -2,6 +2,7 @@ #include "Copter.h" #include +#include // TODO why is this needed if Copter.h includes this class Parameters; class ParametersG2; @@ -566,7 +567,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 NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED == ENABLED void do_nav_guided_enable(const AP_Mission::Mission_Command& cmd); void do_guided_limits(const AP_Mission::Mission_Command& cmd); #endif @@ -604,7 +605,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 NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED == ENABLED bool verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd); #endif bool verify_nav_delay(const AP_Mission::Mission_Command& cmd); @@ -957,6 +958,10 @@ class ModeFlowHold : public Mode { class ModeGuided : public Mode { public: +#if AP_EXTERNAL_CONTROL_ENABLED + friend class AP_ExternalControl_Copter; +#endif + // inherit constructor using Mode::Mode; Number mode_number() const override { return Number::GUIDED; } @@ -1718,6 +1723,7 @@ class ModeAvoidADSB : public ModeGuided { }; +#if AP_FOLLOW_ENABLED class ModeFollow : public ModeGuided { public: @@ -1747,6 +1753,7 @@ class ModeFollow : public ModeGuided { uint32_t last_log_ms; // system time of last time desired velocity was logging }; +#endif class ModeZigZag : public Mode { diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index b67c3219eb9d8e..c1972dbf000ed0 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -136,7 +136,7 @@ void ModeAuto::run() case SubMode::NAVGUIDED: case SubMode::NAV_SCRIPT_TIME: -#if NAV_GUIDED == ENABLED || AP_SCRIPTING_ENABLED +#if AC_NAV_GUIDED == ENABLED || AP_SCRIPTING_ENABLED nav_guided_run(); #endif break; @@ -502,7 +502,7 @@ void ModeAuto::circle_start() set_submode(SubMode::CIRCLE); } -#if NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED == ENABLED // auto_nav_guided_start - hand over control to external navigation controller in AUTO mode void ModeAuto::nav_guided_start() { @@ -519,7 +519,7 @@ void ModeAuto::nav_guided_start() // set submode set_submode(SubMode::NAVGUIDED); } -#endif //NAV_GUIDED +#endif //AC_NAV_GUIDED bool ModeAuto::is_landing() const { @@ -647,7 +647,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) do_spline_wp(cmd); break; -#if NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED == ENABLED case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer do_nav_guided_enable(cmd); break; @@ -719,7 +719,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) #endif //AP_FENCE_ENABLED break; -#if NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED == ENABLED case MAV_CMD_DO_GUIDED_LIMITS: // 220 accept guided mode limits do_guided_limits(cmd); break; @@ -892,7 +892,7 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd) cmd_complete = verify_spline_wp(cmd); break; -#if NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED == ENABLED case MAV_CMD_NAV_GUIDED_ENABLE: cmd_complete = verify_nav_guided_enable(cmd); break; @@ -1033,7 +1033,7 @@ void ModeAuto::circle_run() attitude_control->input_thrust_vector_heading(pos_control->get_thrust_vector(), auto_yaw.get_heading()); } -#if NAV_GUIDED == ENABLED || AP_SCRIPTING_ENABLED +#if AC_NAV_GUIDED == ENABLED || 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() @@ -1041,7 +1041,7 @@ void ModeAuto::nav_guided_run() // call regular guided flight mode run function copter.mode_guided.run(); } -#endif // NAV_GUIDED || AP_SCRIPTING_ENABLED +#endif // AC_NAV_GUIDED || AP_SCRIPTING_ENABLED // auto_loiter_run - loiter in AUTO flight mode // called by auto_run at 100hz or more @@ -1751,7 +1751,7 @@ void ModeAuto::get_spline_from_cmd(const AP_Mission::Mission_Command& cmd, const } } -#if NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED == ENABLED // do_nav_guided_enable - initiate accepting commands from external nav computer void ModeAuto::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd) { @@ -1770,7 +1770,7 @@ void ModeAuto::do_guided_limits(const AP_Mission::Mission_Command& cmd) cmd.content.guided_limits.alt_max * 100.0f, // convert meters to cm cmd.content.guided_limits.horiz_max * 100.0f); // convert meters to cm } -#endif // NAV_GUIDED +#endif // AC_NAV_GUIDED // do_nav_delay - Delay the next navigation command void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd) @@ -1782,7 +1782,11 @@ void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd) nav_delay_time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds } else { // absolute delay to utc time +#if AP_RTC_ENABLED nav_delay_time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0); +#else + nav_delay_time_max_ms = 0; +#endif } gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000)); } @@ -2188,7 +2192,7 @@ bool ModeAuto::verify_spline_wp(const AP_Mission::Mission_Command& cmd) return false; } -#if NAV_GUIDED == ENABLED +#if AC_NAV_GUIDED == ENABLED // verify_nav_guided - check if we have breached any limits bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd) { @@ -2200,7 +2204,7 @@ bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd) // check time and position limits return copter.mode_guided.limit_check(); } -#endif // NAV_GUIDED +#endif // AC_NAV_GUIDED // verify_nav_delay - check if we have waited long enough bool ModeAuto::verify_nav_delay(const AP_Mission::Mission_Command& cmd) diff --git a/ArduCopter/mode_autorotate.cpp b/ArduCopter/mode_autorotate.cpp index fb009a1d3421d7..414401c2e9a571 100644 --- a/ArduCopter/mode_autorotate.cpp +++ b/ArduCopter/mode_autorotate.cpp @@ -47,7 +47,7 @@ bool ModeAutorotate::init(bool ignore_checks) // Display message gcs().send_text(MAV_SEVERITY_INFO, "Autorotation initiated"); - // Set all inial flags to on + // Set all intial flags to on _flags.entry_initial = 1; _flags.ss_glide_initial = 1; _flags.flare_initial = 1; @@ -173,7 +173,7 @@ void ModeAutorotate::run() g2.arot.set_desired_fwd_speed(); // Set target head speed in head speed controller - _target_head_speed = HEAD_SPEED_TARGET_RATIO; //Ensure target hs is set to glide in case hs hasent reached target for glide + _target_head_speed = HEAD_SPEED_TARGET_RATIO; //Ensure target hs is set to glide in case hs has not reached target for glide g2.arot.set_target_head_speed(_target_head_speed); // Prevent running the initial glide functions again diff --git a/ArduCopter/mode_circle.cpp b/ArduCopter/mode_circle.cpp index 1c73b807dd3dce..bb9a6612f948c5 100644 --- a/ArduCopter/mode_circle.cpp +++ b/ArduCopter/mode_circle.cpp @@ -26,9 +26,13 @@ bool ModeCircle::init(bool ignore_checks) // Check if the CIRCLE_OPTIONS parameter have roi_at_center if (copter.circle_nav->roi_at_center()) { - Vector3p loc = copter.circle_nav->get_center(); - loc.z = 0; - Location circle_center(loc, Location::AltFrame::ABOVE_TERRAIN); + const Vector3p &pos { copter.circle_nav->get_center() }; + Location circle_center; + if (!AP::ahrs().get_location_from_origin_offset(circle_center, pos * 0.01)) { + return false; + } + // point at the ground: + circle_center.set_alt_cm(0, Location::AltFrame::ABOVE_TERRAIN); s->set_roi_target(circle_center); } #endif diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index fd313a1c0d0831..4d0f9e3154cfb2 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -100,7 +100,7 @@ void ModeGuided::run() bool ModeGuided::allows_arming(AP_Arming::Method method) const { // always allow arming from the ground station or scripting - if (method == AP_Arming::Method::MAVLINK || method == AP_Arming::Method::SCRIPTING) { + if (AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::SCRIPTING) { return true; } @@ -1087,7 +1087,6 @@ uint32_t ModeGuided::wp_distance() const return get_horizontal_distance_cm(inertial_nav.get_position_xy_cm(), guided_pos_target_cm.tofloat().xy()); case SubMode::PosVelAccel: return pos_control->get_pos_error_xy_cm(); - break; default: return 0; } @@ -1102,7 +1101,6 @@ int32_t ModeGuided::wp_bearing() const return get_bearing_cd(inertial_nav.get_position_xy_cm(), guided_pos_target_cm.tofloat().xy()); case SubMode::PosVelAccel: return pos_control->get_bearing_to_target_cd(); - break; case SubMode::TakeOff: case SubMode::Accel: case SubMode::VelAccel: diff --git a/ArduCopter/mode_systemid.cpp b/ArduCopter/mode_systemid.cpp index 1a942780b8dfc0..15dc1eba4f0ede 100644 --- a/ArduCopter/mode_systemid.cpp +++ b/ArduCopter/mode_systemid.cpp @@ -107,7 +107,7 @@ bool ModeSystemId::init(bool ignore_checks) // systemId_exit - clean up systemId controller before exiting void ModeSystemId::exit() { - // reset the feedfoward enabled parameter to the initialized state + // reset the feedforward enabled parameter to the initialized state attitude_control->bf_feedforward(att_bf_feedforward); } @@ -261,11 +261,7 @@ void ModeSystemId::run() attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate); // output pilot's throttle - if (copter.is_tradheli()) { - attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt); - } else { - attitude_control->set_throttle_out(pilot_throttle_scaled, true, g.throttle_filt); - } + attitude_control->set_throttle_out(pilot_throttle_scaled, !copter.is_tradheli(), g.throttle_filt); if (log_subsample <= 0) { log_data(); diff --git a/ArduCopter/mode_zigzag.cpp b/ArduCopter/mode_zigzag.cpp index 1bb82aaadba4a5..2952158ec615a6 100644 --- a/ArduCopter/mode_zigzag.cpp +++ b/ArduCopter/mode_zigzag.cpp @@ -585,27 +585,15 @@ void ModeZigZag::spray(bool b) uint32_t ModeZigZag::wp_distance() const { - if (is_auto) { - return wp_nav->get_wp_distance_to_destination(); - } else { - return 0; - } + return is_auto ? wp_nav->get_wp_distance_to_destination() : 0; } int32_t ModeZigZag::wp_bearing() const { - if (is_auto) { - return wp_nav->get_wp_bearing_to_destination(); - } else { - return 0; - } + return is_auto ? wp_nav->get_wp_bearing_to_destination() : 0; } float ModeZigZag::crosstrack_error() const { - if (is_auto) { - return wp_nav->crosstrack_error(); - } else { - return 0; - } + return is_auto ? wp_nav->crosstrack_error() : 0; } #endif // MODE_ZIGZAG_ENABLED == ENABLED diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 669b646fe595d0..221a92bb9a2700 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -153,8 +153,10 @@ void Copter::init_ardupilot() barometer.set_log_baro_bit(MASK_LOG_IMU); barometer.calibrate(); +#if RANGEFINDER_ENABLED == ENABLED // initialise rangefinder init_rangefinder(); +#endif #if HAL_PROXIMITY_ENABLED // init proximity sensor diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index 7be7455207ba50..60ee3d4692c12d 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -218,6 +218,11 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure) ret = false; } + if ((plane.quadplane.tailsitter.enable > 0) && (plane.quadplane.q_fwd_thr_use != QuadPlane::FwdThrUse::OFF)) { + check_failed(ARMING_CHECK_PARAMETERS, display_failure, "set Q_FWD_THR_USE to 0"); + ret = false; + } + return ret; } #endif // HAL_QUADPLANE_ENABLED @@ -325,7 +330,7 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_checks) { if (do_disarm_checks && - (method == AP_Arming::Method::MAVLINK || + (AP_Arming::method_is_GCS(method) || method == AP_Arming::Method::RUDDER)) { if (plane.is_flying()) { // don't allow mavlink or rudder disarm while flying diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 47f379a2e1f657..61d76425333278 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -245,7 +245,12 @@ void Plane::update_logging10(void) ahrs.Write_AOA_SSA(); } else if (log_faster) { ahrs.Write_AOA_SSA(); - } + } +#if HAL_MOUNT_ENABLED + if (should_log(MASK_LOG_CAMERA)) { + camera_mount.write_log(); + } +#endif } /* diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 77e41ba2fefe4f..39a9461ea63e7d 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -32,7 +32,7 @@ float Plane::calc_speed_scaler(void) speed_scaler = MIN(speed_scaler, new_scaler); // we also decay the integrator to prevent an integrator from before - // we were at low speed persistint at high speed + // we were at low speed persistent at high speed rollController.decay_I(); pitchController.decay_I(); yawController.decay_I(); @@ -51,7 +51,7 @@ float Plane::calc_speed_scaler(void) } if (!plane.ahrs.airspeed_sensor_enabled() && (plane.flight_option_enabled(FlightOptions::SURPRESS_TKOFF_SCALING)) && - (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF)) { //scaling is surpressed during climb phase of automatic takeoffs with no airspeed sensor being used due to problems with inaccurate airspeed estimates + (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF)) { //scaling is suppressed during climb phase of automatic takeoffs with no airspeed sensor being used due to problems with inaccurate airspeed estimates return MIN(speed_scaler, 1.0f) ; } return speed_scaler; @@ -131,6 +131,16 @@ float Plane::stabilize_roll_get_roll_out() if (!quadplane.use_fw_attitude_controllers()) { // use the VTOL rate for control, to ensure consistency const auto &pid_info = quadplane.attitude_control->get_rate_roll_pid().get_pid_info(); + + // scale FF to angle P + if (quadplane.option_is_set(QuadPlane::OPTION::SCALE_FF_ANGLE_P)) { + const float mc_angR = quadplane.attitude_control->get_angle_roll_p().kP() + * quadplane.attitude_control->get_last_angle_P_scale().x; + if (is_positive(mc_angR)) { + rollController.set_ff_scale(MIN(1.0, 1.0 / (mc_angR * rollController.tau()))); + } + } + const float roll_out = rollController.get_rate_out(degrees(pid_info.target), speed_scaler); /* when slaving fixed wing control to VTOL control we need to decay the integrator to prevent opposing integrators balancing between the two controllers @@ -174,6 +184,16 @@ float Plane::stabilize_pitch_get_pitch_out() if (!quadplane.use_fw_attitude_controllers()) { // use the VTOL rate for control, to ensure consistency const auto &pid_info = quadplane.attitude_control->get_rate_pitch_pid().get_pid_info(); + + // scale FF to angle P + if (quadplane.option_is_set(QuadPlane::OPTION::SCALE_FF_ANGLE_P)) { + const float mc_angP = quadplane.attitude_control->get_angle_pitch_p().kP() + * quadplane.attitude_control->get_last_angle_P_scale().y; + if (is_positive(mc_angP)) { + pitchController.set_ff_scale(MIN(1.0, 1.0 / (mc_angP * pitchController.tau()))); + } + } + const int32_t pitch_out = pitchController.get_rate_out(degrees(pid_info.target), speed_scaler); /* when slaving fixed wing control to VTOL control we need to decay the integrator to prevent opposing integrators balancing between the two controllers @@ -266,7 +286,7 @@ void Plane::stabilize_stick_mixing_fbw() // non-linear and ends up as 2x the maximum, to ensure that // the user can direct the plane in any direction with stick // mixing. - float roll_input = channel_roll->norm_input(); + float roll_input = channel_roll->norm_input_dz(); if (roll_input > 0.5f) { roll_input = (3*roll_input - 1); } else if (roll_input < -0.5f) { @@ -280,7 +300,7 @@ void Plane::stabilize_stick_mixing_fbw() return; } - float pitch_input = channel_pitch->norm_input(); + float pitch_input = channel_pitch->norm_input_dz(); if (pitch_input > 0.5f) { pitch_input = (3*pitch_input - 1); } else if (pitch_input < -0.5f) { @@ -307,38 +327,57 @@ void Plane::stabilize_stick_mixing_fbw() */ void Plane::stabilize_yaw() { + bool ground_steering = false; if (landing.is_flaring()) { // in flaring then enable ground steering - steering_control.ground_steering = true; + ground_steering = true; } else { // otherwise use ground steering when no input control and we // are below the GROUND_STEER_ALT - steering_control.ground_steering = (channel_roll->get_control_in() == 0 && + ground_steering = (channel_roll->get_control_in() == 0 && fabsf(relative_altitude) < g.ground_steer_alt); if (!landing.is_ground_steering_allowed()) { // don't use ground steering on landing approach - steering_control.ground_steering = false; + ground_steering = false; } } /* - first calculate steering_control.steering for a nose or tail + first calculate steering for a nose or tail wheel. We use "course hold" mode for the rudder when either performing a flare (when the wings are held level) or when in course hold in FBWA mode (when we are below GROUND_STEER_ALT) */ + float steering_output = 0.0; if (landing.is_flaring() || - (steer_state.hold_course_cd != -1 && steering_control.ground_steering)) { - calc_nav_yaw_course(); - } else if (steering_control.ground_steering) { - calc_nav_yaw_ground(); + (steer_state.hold_course_cd != -1 && ground_steering)) { + steering_output = calc_nav_yaw_course(); + } else if (ground_steering) { + steering_output = calc_nav_yaw_ground(); } /* - now calculate steering_control.rudder for the rudder + now calculate rudder for the rudder */ - calc_nav_yaw_coordinated(); + const float rudder_output = calc_nav_yaw_coordinated(); + + if (!ground_steering) { + // Not doing ground steering, output rudder on steering channel + SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder_output); + SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder_output); + + } else if (!SRV_Channels::function_assigned(SRV_Channel::k_steering)) { + // Ground steering active but no steering output configured, output steering on rudder channel + SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, steering_output); + SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_output); + + } else { + // Ground steering with both steering and rudder channels + SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder_output); + SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_output); + } + } /* @@ -370,15 +409,17 @@ void Plane::stabilize() const float elevator = pitchController.get_rate_out(nav_scripting.pitch_rate_dps, speed_scaler); SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, aileron); SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, elevator); + float rudder = 0; if (yawController.rate_control_enabled()) { - float rudder = nav_scripting.rudder_offset_pct * 45; + rudder = nav_scripting.rudder_offset_pct * 45; if (nav_scripting.run_yaw_rate_controller) { rudder += yawController.get_rate_out(nav_scripting.yaw_rate_dps, speed_scaler, false); } else { yawController.reset_I(); } - steering_control.rudder = rudder; } + SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, rudder); + SRV_Channels::set_output_scaled(SRV_Channel::k_steering, rudder); #endif } else { plane.control_mode->run(); @@ -427,7 +468,7 @@ void Plane::calc_throttle() /* calculate yaw control for coordinated flight */ -void Plane::calc_nav_yaw_coordinated() +int16_t Plane::calc_nav_yaw_coordinated() { const float speed_scaler = get_speed_scaler(); bool disable_integrator = false; @@ -445,7 +486,7 @@ void Plane::calc_nav_yaw_coordinated() // user is doing an AUTOTUNE with yaw rate control const float rudd_expo = rudder_in_expo(true); const float yaw_rate = (rudd_expo/SERVO_MAX) * g.acro_yaw_rate; - // add in the corrdinated turn yaw rate to make it easier to fly while tuning the yaw rate controller + // add in the coordinated turn yaw rate to make it easier to fly while tuning the yaw rate controller const float coordination_yaw_rate = degrees(GRAVITY_MSS * tanf(radians(nav_roll_cd*0.01f))/MAX(aparm.airspeed_min,smoothed_airspeed)); commanded_rudder = yawController.get_rate_out(yaw_rate+coordination_yaw_rate, speed_scaler, false); using_rate_controller = true; @@ -461,35 +502,35 @@ void Plane::calc_nav_yaw_coordinated() commanded_rudder += rudder_in; } - steering_control.rudder = constrain_int16(commanded_rudder, -4500, 4500); - if (!using_rate_controller) { /* When not running the yaw rate controller, we need to reset the rate */ yawController.reset_rate_PID(); } + + return constrain_int16(commanded_rudder, -4500, 4500); } /* calculate yaw control for ground steering with specific course */ -void Plane::calc_nav_yaw_course(void) +int16_t Plane::calc_nav_yaw_course(void) { // holding a specific navigation course on the ground. Used in // auto-takeoff and landing int32_t bearing_error_cd = nav_controller->bearing_error_cd(); - steering_control.steering = steerController.get_steering_out_angle_error(bearing_error_cd); + int16_t steering = steerController.get_steering_out_angle_error(bearing_error_cd); if (stick_mixing_enabled()) { - steering_control.steering = channel_rudder->stick_mixing(steering_control.steering); + steering = channel_rudder->stick_mixing(steering); } - steering_control.steering = constrain_int16(steering_control.steering, -4500, 4500); + return constrain_int16(steering, -4500, 4500); } /* calculate yaw control for ground steering */ -void Plane::calc_nav_yaw_ground(void) +int16_t Plane::calc_nav_yaw_ground(void) { if (gps.ground_speed() < 1 && is_zero(get_throttle_input()) && @@ -498,8 +539,7 @@ void Plane::calc_nav_yaw_ground(void) // manual rudder control while still steer_state.locked_course = false; steer_state.locked_course_err = 0; - steering_control.steering = rudder_input(); - return; + return rudder_input(); } // if we haven't been steering for 1s then clear locked course @@ -526,15 +566,16 @@ void Plane::calc_nav_yaw_ground(void) } } + int16_t steering; if (!steer_state.locked_course) { // use a rate controller at the pilot specified rate - steering_control.steering = steerController.get_steering_out_rate(steer_rate); + steering = steerController.get_steering_out_rate(steer_rate); } else { // use a error controller on the summed error int32_t yaw_error_cd = -ToDeg(steer_state.locked_course_err)*100; - steering_control.steering = steerController.get_steering_out_angle_error(yaw_error_cd); + steering = steerController.get_steering_out_angle_error(yaw_error_cd); } - steering_control.steering = constrain_int16(steering_control.steering, -4500, 4500); + return constrain_int16(steering, -4500, 4500); } @@ -617,11 +658,11 @@ void Plane::update_load_factor(void) nav_roll_cd = constrain_int32(nav_roll_cd, -2500, 2500); roll_limit_cd = MIN(roll_limit_cd, 2500); } else if (max_load_factor < aerodynamic_load_factor) { - // the demanded nav_roll would take us past the aerodymamic + // the demanded nav_roll would take us past the aerodynamic // load limit. Limit our roll to a bank angle that will keep // the load within what the airframe can handle. We always // allow at least 25 degrees of roll however, to ensure the - // aircraft can be maneuvered with a bad airspeed estimate. At + // aircraft can be manoeuvred with a bad airspeed estimate. At // 25 degrees the load factor is 1.1 (10%) int32_t roll_limit = degrees(acosf(sq(1.0f / max_load_factor)))*100; if (roll_limit < 2500) { diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 1a32d712d4a076..17e3762f5957ba 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -596,7 +596,9 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_GPS2_RAW, MSG_GPS2_RTK, MSG_NAV_CONTROLLER_OUTPUT, +#if AP_FENCE_ENABLED MSG_FENCE_STATUS, +#endif MSG_POSITION_TARGET_GLOBAL_INT, }; static const ap_message STREAM_POSITION_msgs[] = { @@ -644,8 +646,10 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_BATTERY_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_OPTICAL_FLOW, +#if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, +#endif MSG_EKF_STATUS_REPORT, MSG_VIBRATION, }; @@ -696,7 +700,7 @@ void GCS_MAVLINK_Plane::handle_change_alt_request(AP_Mission::Mission_Command &c } -MAV_RESULT GCS_MAVLINK_Plane::handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK_Plane::handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { plane.in_calibration = true; MAV_RESULT ret = GCS_MAVLINK::handle_command_preflight_calibration(packet, msg); @@ -711,7 +715,7 @@ void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status, #if HAL_ADSB_ENABLED plane.avoidance_adsb.handle_msg(msg); #endif -#if AP_SCRIPTING_ENABLED +#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED // pass message to follow library plane.g2.follow.handle_msg(msg); #endif @@ -917,11 +921,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl float new_target_heading = radians(wrap_180(packet.param2)); - // if packet is requesting us to go to the heading we are already going to, we-re already on it. - if ( (is_equal(new_target_heading,plane.guided_state.target_heading))) { // compare two floats as near-enough - return MAV_RESULT_ACCEPTED; - } - // course over ground if ( int(packet.param1) == HEADING_TYPE_COURSE_OVER_GROUND) { // compare as nearest int plane.guided_state.target_heading_type = GUIDED_HEADING_COG; @@ -950,10 +949,13 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl } -MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet) +MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch(packet.command) { + case MAV_CMD_DO_AUTOTUNE_ENABLE: + return handle_MAV_CMD_DO_AUTOTUNE_ENABLE(packet); + case MAV_CMD_DO_REPOSITION: return handle_command_int_do_reposition(packet); @@ -963,26 +965,62 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in case MAV_CMD_GUIDED_CHANGE_HEADING: return handle_command_int_guided_slew_commands(packet); +#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED case MAV_CMD_DO_FOLLOW: -#if AP_SCRIPTING_ENABLED // param1: sysid of target to follow if ((packet.param1 > 0) && (packet.param1 <= 255)) { plane.g2.follow.set_target_sysid((uint8_t)packet.param1); return MAV_RESULT_ACCEPTED; } + return MAV_RESULT_DENIED; +#endif + +#if AP_ICENGINE_ENABLED + case MAV_CMD_DO_ENGINE_CONTROL: + if (!plane.g2.ice_control.engine_control(packet.param1, packet.param2, packet.param3)) { + return MAV_RESULT_FAILED; + } + return MAV_RESULT_ACCEPTED; +#endif + + case MAV_CMD_DO_CHANGE_SPEED: + return handle_command_DO_CHANGE_SPEED(packet); + +#if PARACHUTE == ENABLED + case MAV_CMD_DO_PARACHUTE: + return handle_MAV_CMD_DO_PARACHUTE(packet); +#endif + +#if HAL_QUADPLANE_ENABLED + case MAV_CMD_DO_MOTOR_TEST: + return handle_MAV_CMD_DO_MOTOR_TEST(packet); + + case MAV_CMD_DO_VTOL_TRANSITION: + return handle_command_DO_VTOL_TRANSITION(packet); #endif + + case MAV_CMD_DO_GO_AROUND: + return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; + + case MAV_CMD_DO_LAND_START: + // attempt to switch to next DO_LAND_START command in the mission + if (plane.mission.jump_to_landing_sequence()) { + plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND); + return MAV_RESULT_ACCEPTED; + } return MAV_RESULT_FAILED; - + + case MAV_CMD_MISSION_START: + plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND); + return MAV_RESULT_ACCEPTED; + default: - return GCS_MAVLINK::handle_command_int_packet(packet); + return GCS_MAVLINK::handle_command_int_packet(packet, msg); } } -MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_CHANGE_SPEED(const mavlink_command_int_t &packet) { - switch(packet.command) { - - case MAV_CMD_DO_CHANGE_SPEED: { // if we're in failsafe modes (e.g., RTL, LOITER) or in pilot // controlled modes (e.g., MANUAL, TRAINING) // this command should be ignored since it comes in from GCS @@ -993,15 +1031,15 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l return MAV_RESULT_FAILED; } - AP_Mission::Mission_Command cmd; - if (AP_Mission::mavlink_cmd_long_to_mission_cmd(packet, cmd) != MAV_MISSION_ACCEPTED) { - return MAV_RESULT_DENIED; - } - if (plane.do_change_speed(cmd)) { + if (plane.do_change_speed(packet.param1, packet.param2, packet.param3)) { return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED; - } +} + +MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +{ + switch(packet.command) { case MAV_CMD_NAV_LOITER_UNLIM: plane.set_mode(plane.mode_loiter, ModeReason::GCS_COMMAND); @@ -1023,28 +1061,21 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l } #endif // HAL_QUADPLANE_ENABLED - case MAV_CMD_MISSION_START: - plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND); - return MAV_RESULT_ACCEPTED; - - case MAV_CMD_DO_LAND_START: - // attempt to switch to next DO_LAND_START command in the mission - if (plane.mission.jump_to_landing_sequence()) { - plane.set_mode(plane.mode_auto, ModeReason::GCS_COMMAND); - return MAV_RESULT_ACCEPTED; - } - return MAV_RESULT_FAILED; - - case MAV_CMD_DO_GO_AROUND: - return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; + default: + return GCS_MAVLINK::handle_command_long_packet(packet, msg); + } +} - case MAV_CMD_DO_AUTOTUNE_ENABLE: +MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet) +{ // param1 : enable/disable plane.autotune_enable(!is_zero(packet.param1)); return MAV_RESULT_ACCEPTED; +} #if PARACHUTE == ENABLED - case MAV_CMD_DO_PARACHUTE: +MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet) +{ // configure or release parachute switch ((uint16_t)packet.param1) { case PARACHUTE_DISABLE: @@ -1071,10 +1102,13 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l break; } return MAV_RESULT_FAILED; +} #endif + #if HAL_QUADPLANE_ENABLED - case MAV_CMD_DO_MOTOR_TEST: +MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet) +{ // param1 : motor sequence number (a number from 1 to max number of motors on the vehicle) // param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) // param3 : throttle (range depends upon param2) @@ -1085,37 +1119,17 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l (uint8_t)packet.param2, (uint16_t)packet.param3, packet.param4, - (uint8_t)packet.param5); + (uint8_t)packet.x); +} - case MAV_CMD_DO_VTOL_TRANSITION: +MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet) +{ if (!plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)packet.param1)) { return MAV_RESULT_FAILED; } return MAV_RESULT_ACCEPTED; -#endif - -#if AP_ICENGINE_ENABLED - case MAV_CMD_DO_ENGINE_CONTROL: - if (!plane.g2.ice_control.engine_control(packet.param1, packet.param2, packet.param3)) { - return MAV_RESULT_FAILED; - } - return MAV_RESULT_ACCEPTED; -#endif - -#if AP_SCRIPTING_ENABLED - case MAV_CMD_DO_FOLLOW: - // param1: sysid of target to follow - if ((packet.param1 > 0) && (packet.param1 <= 255)) { - plane.g2.follow.set_target_sysid((uint8_t)packet.param1); - return MAV_RESULT_ACCEPTED; - } - return MAV_RESULT_FAILED; -#endif - - default: - return GCS_MAVLINK::handle_command_long_packet(packet); - } } +#endif // this is called on receipt of a MANUAL_CONTROL packet and is // expected to call manual_override to override RC input on desired diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index aa8455b5de0173..c6643c39b9df52 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -23,9 +23,9 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK bool sysid_enforce() const override; - MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; - MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override; - MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_command_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_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet) override; void send_position_target_global_int() override; @@ -54,7 +54,11 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override; MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet); MAV_RESULT handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet); - + MAV_RESULT handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet); + MAV_RESULT handle_command_DO_CHANGE_SPEED(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet); + MAV_RESULT handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet); bool try_send_message(enum ap_message id) override; void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override; diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 4dde2e5dbe7ace..8f46404a85669f 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -79,6 +79,7 @@ struct PACKED log_Control_Tuning { float rudder_out; float throttle_dem; float airspeed_estimate; + uint8_t airspeed_estimate_status; float synthetic_airspeed; float EAS2TAS; int32_t groundspeed_undershoot; @@ -88,7 +89,8 @@ struct PACKED log_Control_Tuning { void Plane::Log_Write_Control_Tuning() { float est_airspeed = 0; - ahrs.airspeed_estimate(est_airspeed); + AP_AHRS::AirspeedEstimateType airspeed_estimate_type = AP_AHRS::AirspeedEstimateType::NO_NEW_ESTIMATE; + ahrs.airspeed_estimate(est_airspeed, airspeed_estimate_type); float synthetic_airspeed; if (!ahrs.synthetic_airspeed(synthetic_airspeed)) { @@ -106,6 +108,7 @@ void Plane::Log_Write_Control_Tuning() rudder_out : SRV_Channels::get_output_scaled(SRV_Channel::k_rudder), throttle_dem : TECS_controller.get_throttle_demand(), airspeed_estimate : est_airspeed, + airspeed_estimate_status : (uint8_t)airspeed_estimate_type, synthetic_airspeed : synthetic_airspeed, EAS2TAS : ahrs.get_EAS2TAS(), groundspeed_undershoot : groundspeed_undershoot, @@ -113,6 +116,7 @@ void Plane::Log_Write_Control_Tuning() logger.WriteBlock(&pkt, sizeof(pkt)); } +#if OFFBOARD_GUIDED == ENABLED struct PACKED log_OFG_Guided { LOG_PACKET_HEADER; uint64_t time_us; @@ -128,7 +132,6 @@ struct PACKED log_OFG_Guided { // Write a OFG Guided packet. void Plane::Log_Write_OFG_Guided() { -#if OFFBOARD_GUIDED == ENABLED struct log_OFG_Guided pkt = { LOG_PACKET_HEADER_INIT(LOG_OFG_MSG), time_us : AP_HAL::micros64(), @@ -141,8 +144,8 @@ void Plane::Log_Write_OFG_Guided() target_heading_limit : guided_state.target_heading_accel_limit }; logger.WriteBlock(&pkt, sizeof(pkt)); -#endif } +#endif struct PACKED log_Nav_Tuning { LOG_PACKET_HEADER; @@ -222,6 +225,7 @@ struct PACKED log_AETR { float throttle; float rudder; float flap; + float steering; float speed_scaler; }; @@ -235,6 +239,7 @@ void Plane::Log_Write_AETR() ,throttle : SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) ,rudder : SRV_Channels::get_output_scaled(SRV_Channel::k_rudder) ,flap : SRV_Channels::get_slew_limited_output_scaled(SRV_Channel::k_flap_auto) + ,steering : SRV_Channels::get_output_scaled(SRV_Channel::k_steering) ,speed_scaler : get_speed_scaler(), }; @@ -301,15 +306,17 @@ const struct LogStructure Plane::log_structure[] = { // @Field: NavPitch: desired pitch // @Field: Pitch: achieved pitch // @Field: ThO: scaled output throttle -// @Field: RdrOut: scaled output rudder +// @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: synthetic airspeed measurement derived from non-airspeed sensors, NaN if not available +// @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: E2T: equivalent to true airspeed ratio // @Field: GU: groundspeed undershoot when flying with minimum groundspeed { LOG_CTUN_MSG, sizeof(log_Control_Tuning), - "CTUN", "Qccccffffffi", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThO,RdrOut,ThD,As,SAs,E2T,GU", "sdddd---nn-n", "FBBBB---00-B" , true }, + "CTUN", "QccccffffBffi", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThO,RdO,ThD,As,AsT,SAs,E2T,GU", "sdddd---n-n-n", "FBBBB---000-B" , true }, // @LoggerMessage: NTUN // @Description: Navigation Tuning information - e.g. vehicle destination @@ -377,8 +384,8 @@ const struct LogStructure Plane::log_structure[] = { // @Field: CRt: climb rate // @Field: TMix: transition throttle mix value // @Field: Sscl: speed scalar for tailsitter control surfaces -// @Field: Trn: Transistion state -// @Field: Ast: Q assist active state +// @Field: Trn: Transition state: 0-AirspeedWait,1-Timer,2-Done / TailSitter: 0-FW Wait,1-VTOL Wait,2-Done +// @Field: Ast: Q assist active #if HAL_QUADPLANE_ENABLED { LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning), "QTUN", "QffffffeccffBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trn,Ast", "s----mmmnn----", "F----00000-0--" , true }, @@ -396,7 +403,8 @@ const struct LogStructure Plane::log_structure[] = { // @Field: FF: controller feed-forward portion of response // @Field: Dmod: scaler applied to D gain to reduce limit cycling // @Field: SRate: slew rate -// @Field: Limit: 1 if I term is limited due to output saturation +// @Field: Flags: bitmask of PID state flags +// @FieldBitmaskEnum: Flags: log_PID_Flags { LOG_PIQR_MSG, sizeof(log_PID), "PIQR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, { LOG_PIQP_MSG, sizeof(log_PID), @@ -418,7 +426,8 @@ const struct LogStructure Plane::log_structure[] = { // @Field: FF: controller feed-forward portion of response // @Field: Dmod: scaler applied to D gain to reduce limit cycling // @Field: SRate: slew rate -// @Field: Limit: 1 if I term is limited due to output saturation +// @Field: Flags: bitmask of PID state flags +// @FieldBitmaskEnum: Flags: log_PID_Flags { LOG_PIDG_MSG, sizeof(log_PID), "PIDG", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, @@ -430,10 +439,12 @@ const struct LogStructure Plane::log_structure[] = { // @Field: Thr: Pre-mixer value for throttle output (between -100 and 100) // @Field: Rudd: Pre-mixer value for rudder output (between -4500 and 4500) // @Field: Flap: Pre-mixer value for flaps output (between 0 and 100) +// @Field: Steer: Pre-mixer value for steering output (between -4500 and 4500) // @Field: SS: Surface movement / airspeed scaling value { LOG_AETR_MSG, sizeof(log_AETR), - "AETR", "Qffffff", "TimeUS,Ail,Elev,Thr,Rudd,Flap,SS", "s------", "F------" , true }, + "AETR", "Qfffffff", "TimeUS,Ail,Elev,Thr,Rudd,Flap,Steer,SS", "s-------", "F-------" , true }, +#if OFFBOARD_GUIDED == ENABLED // @LoggerMessage: OFG // @Description: OFfboard-Guided - an advanced version of GUIDED for companion computers that includes rate/s. // @Field: TimeUS: Time since system startup @@ -446,6 +457,7 @@ const struct LogStructure Plane::log_structure[] = { // @Field: HdgA: target heading lim { LOG_OFG_MSG, sizeof(log_OFG_Guided), "OFG", "QffffBff", "TimeUS,Arsp,ArspA,Alt,AltA,AltF,Hdg,HdgA", "s-------", "F-------" , true }, +#endif }; void Plane::Log_Write_Vehicle_Startup_Messages() diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 86957031025455..720eed4c273694 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -38,6 +38,14 @@ const AP_Param::Info Plane::var_info[] = { // @User: Standard ASCALAR(autotune_level, "AUTOTUNE_LEVEL", 6), + // @Param: AUTOTUNE_OPTIONS + // @DisplayName: Autotune options bitmask + // @Description: Autotune specific options + // @Bitmask: 0: Disable FLTD update + // @Bitmask: 1: Disable FLTT update + // @User: Advanced + ASCALAR(autotune_options, "AUTOTUNE_OPTIONS", 0), + // @Param: TELEM_DELAY // @DisplayName: Telemetry startup delay // @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up @@ -151,7 +159,7 @@ const AP_Param::Info Plane::var_info[] = { // @Param: TKOFF_TDRAG_SPD1 // @DisplayName: Takeoff tail dragger speed1 - // @Description: This parameter sets the airspeed at which to stop holding the tail down and transition to rudder control of steering on the ground. When TKOFF_TDRAG_SPD1 is reached the pitch of the aircraft will be held level until TKOFF_ROTATE_SPD is reached, at which point the takeoff pitch specified in the mission will be used to "rotate" the pitch for takeoff climb. Set TKOFF_TDRAG_SPD1 to zero to go straight to rotation. This should be set to zero for hand launch and catapult launch. It should also be set to zero for tricycle undercarriages unless you are using the method above to genetly hold the nose wheel down. For tail dragger aircraft it should be set just below the stall speed. + // @Description: This parameter sets the airspeed at which to stop holding the tail down and transition to rudder control of steering on the ground. When TKOFF_TDRAG_SPD1 is reached the pitch of the aircraft will be held level until TKOFF_ROTATE_SPD is reached, at which point the takeoff pitch specified in the mission will be used to "rotate" the pitch for takeoff climb. Set TKOFF_TDRAG_SPD1 to zero to go straight to rotation. This should be set to zero for hand launch and catapult launch. It should also be set to zero for tricycle undercarriages unless you are using the method above to gently hold the nose wheel down. For tail dragger aircraft it should be set just below the stall speed. // @Units: m/s // @Range: 0 30 // @Increment: 0.1 @@ -792,9 +800,11 @@ const AP_Param::Info Plane::var_info[] = { GOBJECT(quadplane, "Q_", QuadPlane), #endif +#if AP_TUNING_ENABLED // @Group: TUNE_ // @Path: tuning.cpp,../libraries/AP_Tuning/AP_Tuning.cpp GOBJECT(tuning, "TUNE_", AP_Tuning_Plane), +#endif #if HAL_QUADPLANE_ENABLED // @Group: Q_A_ @@ -1235,7 +1245,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15 AP_GROUPINFO("ONESHOT_MASK", 32, ParametersG2, oneshot_mask, 0), -#if AP_SCRIPTING_ENABLED +#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED // @Group: FOLL // @Path: ../libraries/AP_Follow/AP_Follow.cpp AP_SUBGROUPINFO(follow, "FOLL", 33, ParametersG2, AP_Follow), @@ -1247,8 +1257,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Bitmask: 0:Roll,1:Pitch,2:Yaw // @User: Standard AP_GROUPINFO("AUTOTUNE_AXES", 34, ParametersG2, axis_bitmask, 7), - - AP_GROUPEND }; diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 45382c31d5e7a7..7210bfe7771267 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -356,6 +356,7 @@ class Parameters { k_param_fence, // vehicle fence - unused k_param_acro_yaw_rate, k_param_takeoff_throttle_max_t, + k_param_autotune_options, }; AP_Int16 format_version; @@ -420,7 +421,7 @@ class Parameters { AP_Int8 flight_mode6; AP_Int8 initial_mode; - // Navigational maneuvering limits + // Navigational manoeuvring limits // AP_Int16 alt_offset; AP_Int16 acro_roll_rate; @@ -540,17 +541,17 @@ class ParametersG2 { AP_Int8 crow_flap_options; AP_Int8 crow_flap_aileron_matching; - // Forward throttle battery voltage compenstaion + // Forward throttle battery voltage compensation AP_Float fwd_thr_batt_voltage_max; AP_Float fwd_thr_batt_voltage_min; AP_Int8 fwd_thr_batt_idx; #if OFFBOARD_GUIDED == ENABLED // guided yaw heading PID - AC_PID guidedHeading{5000.0, 0.0, 0.0, 0 , 10.0, 5.0, 5.0 , 5.0 , 0.2}; + AC_PID guidedHeading{5000.0, 0.0, 0.0, 0 , 10.0, 5.0, 5.0 , 5.0 , 0.0}; #endif -#if AP_SCRIPTING_ENABLED +#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED AP_Follow follow; #endif diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index c68bd006e011b6..fe8a935dc7c748 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -83,11 +83,18 @@ #include #include // Landing Gear library #include +#include +#if AP_EXTERNAL_CONTROL_ENABLED +#include +#endif #include "GCS_Mavlink.h" #include "GCS_Plane.h" #include "quadplane.h" +#include +#if AP_TUNING_ENABLED #include "tuning.h" +#endif // Configuration #include "config.h" @@ -211,16 +218,6 @@ class Plane : public AP_Vehicle { bool training_manual_roll; // user has manual roll control bool training_manual_pitch; // user has manual pitch control - /* - keep steering and rudder control separated until we update servos, - to allow for a separate wheel servo from rudder servo - */ - struct { - bool ground_steering; // are we doing ground steering? - int16_t steering; // value for nose/tail wheel - int16_t rudder; // value for rudder - } steering_control; - // should throttle be pass-thru in guided? bool guided_throttle_passthru; @@ -228,6 +225,9 @@ class Plane : public AP_Vehicle { // external failsafe boards during baro and airspeed calibration bool in_calibration; + // are we currently in long failsafe but have postponed it in MODE TAKEOFF until min level alt is reached + bool long_failsafe_pending; + // GCS selection GCS_Plane _gcs; // avoid using this; use gcs() GCS_Plane &gcs() { return _gcs; } @@ -246,7 +246,7 @@ class Plane : public AP_Vehicle { #endif #if HAL_RALLY_ENABLED - // Rally Ponints + // Rally Points AP_Rally rally; #endif @@ -312,7 +312,7 @@ class Plane : public AP_Vehicle { // Failsafe struct { - // Used to track if the value on channel 3 (throtttle) has fallen below the failsafe threshold + // Used to track if the value on channel 3 (throttle) has fallen below the failsafe threshold // RC receiver should be set up to output a low throttle value when signal is lost bool rc_failsafe; @@ -507,6 +507,9 @@ class Plane : public AP_Vehicle { // how much correction have we added for terrain data float terrain_correction; + + // last home altitude for detecting changes + int32_t last_home_alt_cm; } auto_state; #if AP_SCRIPTING_ENABLED @@ -553,8 +556,7 @@ class Plane : public AP_Vehicle { float target_heading_accel_limit; uint32_t target_heading_time_ms; guided_heading_type_t target_heading_type; - bool target_heading_limit_low; - bool target_heading_limit_high; + bool target_heading_limit; #endif // OFFBOARD_GUIDED == ENABLED } guided_state; @@ -616,7 +618,7 @@ class Plane : public AP_Vehicle { // The instantaneous desired pitch angle. Hundredths of a degree int32_t nav_pitch_cd; - // the aerodymamic load factor. This is calculated from the demanded + // the aerodynamic load factor. This is calculated from the demanded // roll before the roll is clipped, using 1/sqrt(cos(nav_roll)) float aerodynamic_load_factor = 1.0f; @@ -769,11 +771,16 @@ class Plane : public AP_Vehicle { AP_Mount camera_mount; #endif - // Arming/Disarming mangement class + // Arming/Disarming management class AP_Arming_Plane arming; AP_Param param_loader {var_info}; + // dummy implementation of external control +#if AP_EXTERNAL_CONTROL_ENABLED + AP_ExternalControl external_control; +#endif + static const AP_Scheduler::Task scheduler_tasks[]; static const AP_Param::Info var_info[]; @@ -788,8 +795,10 @@ class Plane : public AP_Vehicle { QuadPlane quadplane{ahrs}; #endif +#if AP_TUNING_ENABLED // support for transmitter tuning AP_Tuning_Plane tuning; +#endif static const struct LogStructure log_structure[]; @@ -868,9 +877,9 @@ class Plane : public AP_Vehicle { float stabilize_pitch_get_pitch_out(); void stabilize_stick_mixing_fbw(); void stabilize_yaw(); - void calc_nav_yaw_coordinated(); - void calc_nav_yaw_course(void); - void calc_nav_yaw_ground(void); + int16_t calc_nav_yaw_coordinated(); + int16_t calc_nav_yaw_course(void); + int16_t calc_nav_yaw_ground(void); // Log.cpp uint32_t last_log_fast_ms; @@ -935,22 +944,14 @@ class Plane : public AP_Vehicle { bool verify_command_callback(const AP_Mission::Mission_Command& cmd); float get_wp_radius() const; - void do_nav_delay(const AP_Mission::Mission_Command& cmd); - bool verify_nav_delay(const AP_Mission::Mission_Command& cmd); - bool is_land_command(uint16_t cmd) const; + bool do_change_speed(uint8_t speedtype, float speed_target_ms, float rhtottle_pct); /* return true if in a specific AUTO mission command */ bool in_auto_mission_id(uint16_t command) const; - - // Delay the next navigation command - struct { - uint32_t time_max_ms; - uint32_t time_start_ms; - } nav_delay; - + #if AP_SCRIPTING_ENABLED // nav scripting support void do_nav_script_time(const AP_Mission::Mission_Command& cmd); @@ -1036,6 +1037,7 @@ class Plane : public AP_Vehicle { void loiter_angle_reset(void); void loiter_angle_update(void); void navigate(); + void check_home_alt_change(void); void calc_airspeed_errors(); float mode_auto_target_airspeed_cm(); void calc_gndspeed_undershoot(); diff --git a/ArduPlane/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index e476982eb85c09..cb426ab21f4a28 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -176,6 +176,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option, case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC: case AUX_FUNC::EMERGENCY_LANDING_EN: case AUX_FUNC::FW_AUTOTUNE: + case AUX_FUNC::VFWD_THR_OVERRIDE: break; case AUX_FUNC::SOARING: @@ -271,6 +272,15 @@ bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit case AUX_FUNC::QSTABILIZE: do_aux_function_change_mode(Mode::Number::QSTABILIZE, ch_flag); break; + + case AUX_FUNC::VFWD_THR_OVERRIDE: { + const bool enable = (ch_flag == AuxSwitchPos::HIGH); + if (enable != plane.quadplane.vfwd_enable_active) { + plane.quadplane.vfwd_enable_active = enable; + gcs().send_text(MAV_SEVERITY_INFO, "QFwdThr: %s", enable?"ON":"OFF"); + } + break; + } #endif case AUX_FUNC::SOARING: diff --git a/ArduPlane/ReleaseNotes.txt b/ArduPlane/ReleaseNotes.txt index 632365ef165e39..aea5447a21c41d 100644 --- a/ArduPlane/ReleaseNotes.txt +++ b/ArduPlane/ReleaseNotes.txt @@ -1,3 +1,80 @@ +Release 4.4.1 26th September 2023 +--------------------------------- + +No changes from beta2 + +Release 4.4.1-beta2 12th September 2023 +-------------------------------------- + +Changes from 4.4.1-beta1 + +- Airbotf4 features minimised to build for 4.4 +- ChibiOS clock fix for 480Mhz H7 boards (affected FDCAN) +- H750 external flash optimisations for to lower CPU load +- MambaF405Mini fixes to match manufacturer's recommended wiring +- RADIX2 HD support +- RPI hardware version check fix +- YJUAV_A6SE support + +Release 4.4.1-beta1 5th September 2023 +-------------------------------------- + +Changes from 4.4.1 + +- support Himark DroneCAN servos +- support Hobbywing DroneCAN ESCs +- fixed control surface deflection on quadplanes in VTOL takeoff wait +- fixed bug in parameter default handling in SITL +- allow selection of mission sdcard storage on custom.ardupilot.org +- added support for SDMODELH7V1 +- fixed battery monitor default for QiotekZealotF427 and QiotekZealotH743 +- support 8 bit directional dshot channels on KakuteH7-wing +- improved handling of high vibration in EKF3 with new EK3_GLITCH_RADIUS options +- allow reset of battery SoC for DroneCAN battery monitors +- update GPIOs for Navigator board in HAL_Linux +- pull RTS lines low on Pixhawk6C on startup +- added log_file_content in scripting for aerobatics +- added asymmetry factor for skid steering on rovers +- updated defaults for luminousbee5 boards + +Happy flying! + +Release 4.4.0 18th August 2023 +------------------------------ + +No changes from beta5 + +Release 4.4.0-beta5 11th August 2023 +------------------------------------ + +Changes from 4.4.0-beta4 + +- fixed handling of missing DroneCAN airspeed packet +- fixed reset of target altitude in plane GUIDED mode +- added SIYI N7 flight controller +- fixed auto-enable of fence with forced arm +- fixed race condition that caused notch filter gyro glitches +- fixed bug with RTK injection for DroneCAN + +Release 4.4.0 beta4 +------------------- + +Changes from 4.4.0-beta3 + +1) flight controller specific changes + - Diatone-Mamba-MK4-H743v2 uses SPL06 baro (was DPS280) + - DMA for I2C disabled on F7 and H7 boards + - Foxeer H743v1 default serial protocol config fixes + - HeeWing-F405 and F405v2 support + - iFlight BlitzF7 support +2) Scripts may take action based on VTOL motor loss +3) Bug fixes + - BLHeli returns battery status requested via MSP (avoids hang when using esc-configurator) + - CRSFv3 rescans at baudrates to avoid RX loss + - EK3_ABIAS_P_NSE param range fix + - Scripting restart memory corruption bug fixed + - Siyi A8/ZR10 driver fix to avoid crash if serial port not configured + Release 4.4.0 beta3 ------------------- @@ -207,7 +284,7 @@ of changes. Many thanks to all the people who have contributed! - Gimbal/Mount2 can be moved to retracted or neutral position - Gremsy ZIO support - IMAGE_START_CAPTURE, SET_CAMERA_ZOOM/FOCUS, VIDEO_START/STOP_CAPTURE command support - - Paramters renamed and rescaled + - Parameters renamed and rescaled i) CAM_TRIGG_TYPE renamed to CAM1_TYPE and options have changed ii) CAM_DURATION renamed to CAM1_DURATION and scaled in seconds iii) CAM_FEEDBACK_PIN/POL renamed to CAM1_FEEBAK_PIN/POL diff --git a/ArduPlane/afs_plane.cpp b/ArduPlane/afs_plane.cpp index 2900d6e767a0f4..298d7f5fe8479b 100644 --- a/ArduPlane/afs_plane.cpp +++ b/ArduPlane/afs_plane.cpp @@ -103,4 +103,11 @@ AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Plane::afs_mode(void) } return AP_AdvancedFailsafe::AFS_STABILIZED; } + +//to force entering auto mode when datalink loss + void AP_AdvancedFailsafe_Plane::set_mode_auto(void) + { + plane.set_mode(plane.mode_auto,ModeReason::GCS_FAILSAFE); + } + #endif // AP_ADVANCEDFAILSAFE_ENABLED diff --git a/ArduPlane/afs_plane.h b/ArduPlane/afs_plane.h index 142de7f3452538..ffd341481c3ff9 100644 --- a/ArduPlane/afs_plane.h +++ b/ArduPlane/afs_plane.h @@ -39,6 +39,9 @@ class AP_AdvancedFailsafe_Plane : public AP_AdvancedFailsafe // return the AFS mapped control mode enum control_mode afs_mode(void) override; + + //to force entering auto mode when datalink loss + void set_mode_auto(void) override; }; #endif // AP_ADVANCEDFAILSAFE_ENABLED diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp index 6387edef12aad0..04aa72b2707469 100644 --- a/ArduPlane/altitude.cpp +++ b/ArduPlane/altitude.cpp @@ -28,6 +28,27 @@ void Plane::adjust_altitude_target() control_mode->update_target_altitude(); } +void Plane::check_home_alt_change(void) +{ + int32_t home_alt_cm = ahrs.get_home().alt; + if (home_alt_cm != auto_state.last_home_alt_cm && hal.util->get_soft_armed()) { + // cope with home altitude changing + const int32_t alt_change_cm = home_alt_cm - auto_state.last_home_alt_cm; + if (next_WP_loc.terrain_alt) { + /* + next_WP_loc for terrain alt WP are quite strange. They + have terrain_alt=1, but also have relative_alt=0 and + have been calculated to be relative to home. We need to + adjust for the change in home alt + */ + next_WP_loc.alt += alt_change_cm; + } + // reset TECS to force the field elevation estimate to reset + TECS_controller.reset(); + } + auto_state.last_home_alt_cm = home_alt_cm; +} + /* setup for a gradual glide slope to the next waypoint, if appropriate */ diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 2edc79b158e5c3..9ad4f9531318b1 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -206,7 +206,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) #endif case MAV_CMD_NAV_DELAY: - do_nav_delay(cmd); + mode_auto.do_nav_delay(cmd); break; default: @@ -311,7 +311,7 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret #endif case MAV_CMD_NAV_DELAY: - return verify_nav_delay(cmd); + return mode_auto.verify_nav_delay(cmd); // do commands (always return true) case MAV_CMD_DO_CHANGE_SPEED: @@ -533,7 +533,7 @@ void Plane::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd) } // do_nav_delay - Delay the next navigation command -void Plane::do_nav_delay(const AP_Mission::Mission_Command& cmd) +void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd) { nav_delay.time_start_ms = millis(); @@ -542,7 +542,11 @@ void Plane::do_nav_delay(const AP_Mission::Mission_Command& cmd) nav_delay.time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds } else { // absolute delay to utc time +#if AP_RTC_ENABLED nav_delay.time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0); +#else + nav_delay.time_max_ms = 0; +#endif } gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay.time_max_ms/1000)); } @@ -552,7 +556,11 @@ void Plane::do_nav_delay(const AP_Mission::Mission_Command& cmd) /********************************************************************************/ bool Plane::verify_takeoff() { - if (ahrs.dcm_yaw_initialised() && steer_state.hold_course_cd == -1) { + bool trust_ahrs_yaw = AP::ahrs().initialised(); +#if AP_AHRS_DCM_ENABLED + trust_ahrs_yaw |= ahrs.dcm_yaw_initialised(); +#endif + if (trust_ahrs_yaw && steer_state.hold_course_cd == -1) { const float min_gps_speed = 5; if (auto_state.takeoff_speed_time_ms == 0 && gps.status() >= AP_GPS::GPS_OK_FIX_3D && @@ -880,9 +888,9 @@ bool Plane::verify_altitude_wait(const AP_Mission::Mission_Command &cmd) } // verify_nav_delay - check if we have waited long enough -bool Plane::verify_nav_delay(const AP_Mission::Mission_Command& cmd) +bool ModeAuto::verify_nav_delay(const AP_Mission::Mission_Command& cmd) { - if (arming.is_armed_and_safety_off()) { + if (AP::arming().is_armed_and_safety_off()) { // don't delay while armed, we need a nav controller running return true; } @@ -946,28 +954,36 @@ void Plane::do_loiter_at_location() bool Plane::do_change_speed(const AP_Mission::Mission_Command& cmd) { - switch (cmd.content.speed.speed_type) - { + return do_change_speed( + (uint8_t)cmd.content.speed.speed_type, + cmd.content.speed.target_ms, + cmd.content.speed.throttle_pct + ); +} + +bool Plane::do_change_speed(uint8_t speedtype, float speed_target_ms, float throttle_pct) +{ + switch (speedtype) { case 0: // Airspeed - if (is_equal(cmd.content.speed.target_ms, -2.0f)) { + if (is_equal(speed_target_ms, -2.0f)) { new_airspeed_cm = -1; // return to default airspeed return true; - } else if ((cmd.content.speed.target_ms >= aparm.airspeed_min.get()) && - (cmd.content.speed.target_ms <= aparm.airspeed_max.get())) { - new_airspeed_cm = cmd.content.speed.target_ms * 100; //new airspeed target for AUTO or GUIDED modes - gcs().send_text(MAV_SEVERITY_INFO, "Set airspeed %u m/s", (unsigned)cmd.content.speed.target_ms); + } else if ((speed_target_ms >= aparm.airspeed_min.get()) && + (speed_target_ms <= aparm.airspeed_max.get())) { + new_airspeed_cm = speed_target_ms * 100; //new airspeed target for AUTO or GUIDED modes + gcs().send_text(MAV_SEVERITY_INFO, "Set airspeed %u m/s", (unsigned)speed_target_ms); return true; } break; case 1: // Ground speed - gcs().send_text(MAV_SEVERITY_INFO, "Set groundspeed %u", (unsigned)cmd.content.speed.target_ms); - aparm.min_gndspeed_cm.set(cmd.content.speed.target_ms * 100); + gcs().send_text(MAV_SEVERITY_INFO, "Set groundspeed %u", (unsigned)speed_target_ms); + aparm.min_gndspeed_cm.set(speed_target_ms * 100); return true; } - if (cmd.content.speed.throttle_pct > 0 && cmd.content.speed.throttle_pct <= 100) { - gcs().send_text(MAV_SEVERITY_INFO, "Set throttle %u", (unsigned)cmd.content.speed.throttle_pct); - aparm.throttle_cruise.set(cmd.content.speed.throttle_pct); + if (throttle_pct > 0 && throttle_pct <= 100) { + gcs().send_text(MAV_SEVERITY_INFO, "Set throttle %u", (unsigned)throttle_pct); + aparm.throttle_cruise.set(throttle_pct); return true; } diff --git a/ArduPlane/config.h b/ArduPlane/config.h index ba29c2062d8015..a8c6c890c96cb0 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -238,7 +238,7 @@ #endif #ifndef OFFBOARD_GUIDED - #define OFFBOARD_GUIDED !HAL_MINIMIZE_FEATURES + #define OFFBOARD_GUIDED 1 #endif ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduPlane/ekf_check.cpp b/ArduPlane/ekf_check.cpp index 86b972225ce76a..e36e4ef1abcdf7 100644 --- a/ArduPlane/ekf_check.cpp +++ b/ArduPlane/ekf_check.cpp @@ -112,7 +112,7 @@ bool Plane::ekf_over_threshold() return false; } - // Get EKF innovations normalised wrt the innovaton test limits. + // Get EKF innovations normalised wrt the innovation test limits. // A value above 1.0 means the EKF has rejected that sensor data float position_variance, vel_variance, height_variance, tas_variance; Vector3f mag_variance; @@ -157,7 +157,7 @@ void Plane::failsafe_ekf_event() ekf_check_state.failsafe_on = true; AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED); - // if not in a VTOL mode requring position, then nothing needs to be done + // if not in a VTOL mode requiring position, then nothing needs to be done #if HAL_QUADPLANE_ENABLED if (!quadplane.in_vtol_posvel_mode()) { return; diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index 21aef78f402b53..f49814aca9b903 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -107,6 +107,7 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason) { + // This is how to handle a long loss of control signal failsafe. // If the GCS is locked up we allow control to revert to RC RC_Channels::clear_overrides(); @@ -124,6 +125,14 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason case Mode::Number::CIRCLE: case Mode::Number::LOITER: case Mode::Number::THERMAL: + case Mode::Number::TAKEOFF: + if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF && !(g.fs_action_long == FS_ACTION_LONG_GLIDE || g.fs_action_long == FS_ACTION_LONG_PARACHUTE)) { + // don't failsafe if in inital climb of TAKEOFF mode and FS action is not parachute or glide + // long failsafe will be re-called if still in fs after initial climb + long_failsafe_pending = true; + break; + } + if(plane.emergency_landing) { set_mode(mode_fbwa, reason); // emergency landing switch overrides normal action to allow out of range landing break; @@ -131,6 +140,8 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) { #if PARACHUTE == ENABLED parachute_release(); + //stop motors to avoid parachute tangling + plane.arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE, false); #endif } else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) { set_mode(mode_fbwa, reason); @@ -168,9 +179,12 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason case Mode::Number::AVOID_ADSB: case Mode::Number::GUIDED: + if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) { #if PARACHUTE == ENABLED parachute_release(); + //stop motors to avoid parachute tangling + plane.arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE, false); #endif } else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) { set_mode(mode_fbwa, reason); @@ -191,7 +205,6 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason case Mode::Number::QRTL: case Mode::Number::LOITER_ALT_QLAND: #endif - case Mode::Number::TAKEOFF: case Mode::Number::INITIALISING: break; } @@ -212,6 +225,7 @@ void Plane::failsafe_short_off_event(ModeReason reason) void Plane::failsafe_long_off_event(ModeReason reason) { + long_failsafe_pending = false; // We're back in radio contact with RC or GCS if (reason == ModeReason:: GCS_FAILSAFE) { gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe Off"); diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index 3b2c27396f59d0..ffe578736aff14 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -261,7 +261,7 @@ void Plane::crash_detection_update(void) if (g.takeoff_throttle_min_accel > 0 && !throttle_suppressed) { // if you have an acceleration holding back throttle, but you met the - // accel threshold but still not fying, then you either shook/hit the + // accel threshold but still not flying, then you either shook/hit the // plane or it was a failed launch. crashed = true; crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS; diff --git a/ArduPlane/mode.cpp b/ArduPlane/mode.cpp index a1fdb5ac2d50b4..a9af6555b7a6a4 100644 --- a/ArduPlane/mode.cpp +++ b/ArduPlane/mode.cpp @@ -59,6 +59,7 @@ bool Mode::enter() plane.guided_state.target_heading_type = GUIDED_HEADING_NONE; plane.guided_state.target_airspeed_cm = -1; // same as above, although an airspeed of -1 is rare on plane. plane.guided_state.target_alt = -1; // same as above, although a target alt of -1 is rare on plane. + plane.guided_state.target_alt_time_ms = 0; plane.guided_state.last_target_alt = 0; #endif @@ -88,6 +89,9 @@ bool Mode::enter() // initialize speed variable used in AUTO and GUIDED for DO_CHANGE_SPEED commands plane.new_airspeed_cm = -1; + + // clear postponed long failsafe if mode change (from GCS) occurs before recall of long failsafe + plane.long_failsafe_pending = false; #if HAL_QUADPLANE_ENABLED quadplane.mode_enter(); @@ -230,3 +234,10 @@ bool Mode::is_taking_off() const { return (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF); } + +// Helper to output to both k_rudder and k_steering servo functions +void Mode::output_rudder_and_steering(float val) +{ + SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, val); + SRV_Channels::set_output_scaled(SRV_Channel::k_steering, val); +} diff --git a/ArduPlane/mode.h b/ArduPlane/mode.h index ec94ed4457d9b2..a88dbec5b6e3c1 100644 --- a/ArduPlane/mode.h +++ b/ArduPlane/mode.h @@ -8,6 +8,7 @@ #include #include "quadplane.h" #include +#include class AC_PosControl; class AC_AttitudeControl_Multi; @@ -146,6 +147,9 @@ class Mode // mode specific pre-arm checks virtual bool _pre_arm_checks(size_t buflen, char *buffer) const; + // Helper to output to both k_rudder and k_steering servo functions + void output_rudder_and_steering(float val); + #if HAL_QUADPLANE_ENABLED // References for convenience, used by QModes AC_PosControl*& pos_control; @@ -217,12 +221,24 @@ class ModeAuto : public Mode bool mode_allows_autotuning() const override { return true; } bool is_landing() const override; - + + void do_nav_delay(const AP_Mission::Mission_Command& cmd); + bool verify_nav_delay(const AP_Mission::Mission_Command& cmd); + protected: bool _enter() override; void _exit() override; bool _pre_arm_checks(size_t buflen, char *buffer) const override; + +private: + + // Delay the next navigation command + struct { + uint32_t time_max_ms; + uint32_t time_start_ms; + } nav_delay; + }; diff --git a/ArduPlane/mode_acro.cpp b/ArduPlane/mode_acro.cpp index e30fc50483fb72..c15970b9bdecec 100644 --- a/ArduPlane/mode_acro.cpp +++ b/ArduPlane/mode_acro.cpp @@ -68,7 +68,7 @@ void ModeAcro::stabilize() int32_t roll_error_cd = -ToDeg(acro_state.locked_roll_err)*100; plane.nav_roll_cd = ahrs.roll_sensor + roll_error_cd; // try to reduce the integrated angular error to zero. We set - // 'stabilze' to true, which disables the roll integrator + // 'stabilize' to true, which disables the roll integrator SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.rollController.get_servo_out(roll_error_cd, speed_scaler, true, false)); @@ -104,22 +104,24 @@ void ModeAcro::stabilize() SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, plane.pitchController.get_rate_out(pitch_rate, speed_scaler)); } - plane.steering_control.steering = plane.rudder_input(); - + float rudder_output; if (plane.g.acro_yaw_rate > 0 && plane.yawController.rate_control_enabled()) { // user has asked for yaw rate control with yaw rate scaled by ACRO_YAW_RATE const float rudd_expo = plane.rudder_in_expo(true); const float yaw_rate = (rudd_expo/SERVO_MAX) * plane.g.acro_yaw_rate; - plane.steering_control.steering = plane.steering_control.rudder = plane.yawController.get_rate_out(yaw_rate, speed_scaler, false); + rudder_output = plane.yawController.get_rate_out(yaw_rate, speed_scaler, false); } else if (plane.flight_option_enabled(FlightOptions::ACRO_YAW_DAMPER)) { // use yaw controller - plane.calc_nav_yaw_coordinated(); + rudder_output = plane.calc_nav_yaw_coordinated(); } else { /* manual rudder */ - plane.steering_control.rudder = plane.steering_control.steering; + rudder_output = plane.rudder_input(); } + + output_rudder_and_steering(rudder_output); + } /* @@ -215,7 +217,7 @@ void ModeAcro::stabilize_quaternion() // call to rate controllers SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.rollController.get_rate_out(desired_rates.x, speed_scaler)); SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, plane.pitchController.get_rate_out(desired_rates.y, speed_scaler)); - plane.steering_control.steering = plane.steering_control.rudder = plane.yawController.get_rate_out(desired_rates.z, speed_scaler, false); + output_rudder_and_steering(plane.yawController.get_rate_out(desired_rates.z, speed_scaler, false)); acro_state.roll_active_last = roll_active; acro_state.pitch_active_last = pitch_active; diff --git a/ArduPlane/mode_guided.cpp b/ArduPlane/mode_guided.cpp index 2d712c75987222..a523ddf87065ed 100644 --- a/ArduPlane/mode_guided.cpp +++ b/ArduPlane/mode_guided.cpp @@ -61,16 +61,11 @@ void ModeGuided::update() float bank_limit = degrees(atanf(plane.guided_state.target_heading_accel_limit/GRAVITY_MSS)) * 1e2f; bank_limit = MIN(bank_limit, plane.roll_limit_cd); - plane.g2.guidedHeading.update_error(error, delta); // push error into AC_PID , possible improvement is to use update_all instead.? + // push error into AC_PID + const float desired = plane.g2.guidedHeading.update_error(error, delta, plane.guided_state.target_heading_limit); - float i = plane.g2.guidedHeading.get_i(); // get integrator TODO - if (((is_negative(error) && !plane.guided_state.target_heading_limit_low) || (is_positive(error) && !plane.guided_state.target_heading_limit_high))) { - i = plane.g2.guidedHeading.get_i(); - } - - float desired = plane.g2.guidedHeading.get_p() + i + plane.g2.guidedHeading.get_d(); - plane.guided_state.target_heading_limit_low = (desired <= -bank_limit); - plane.guided_state.target_heading_limit_high = (desired >= bank_limit); + // Check for output saturation + plane.guided_state.target_heading_limit = fabsf(desired) >= bank_limit; plane.nav_roll_cd = constrain_int32(desired, -bank_limit, bank_limit); plane.update_load_factor(); diff --git a/ArduPlane/mode_manual.cpp b/ArduPlane/mode_manual.cpp index 4dc3d067d88ee7..1f8fcd702cd14e 100644 --- a/ArduPlane/mode_manual.cpp +++ b/ArduPlane/mode_manual.cpp @@ -5,9 +5,7 @@ void ModeManual::update() { SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.roll_in_expo(false)); SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, plane.pitch_in_expo(false)); - //rudder in sets rudder, but is also assigned to steering values used later in servos.cpp for steering - plane.steering_control.steering = plane.steering_control.rudder = plane.rudder_in_expo(false); - SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, plane.steering_control.steering); + output_rudder_and_steering(plane.rudder_in_expo(false)); float throttle = plane.get_throttle_input(true); diff --git a/ArduPlane/mode_qacro.cpp b/ArduPlane/mode_qacro.cpp index b74a4343841611..d49e1e0fb6152f 100644 --- a/ArduPlane/mode_qacro.cpp +++ b/ArduPlane/mode_qacro.cpp @@ -9,7 +9,7 @@ bool ModeQAcro::_enter() quadplane.transition->force_transition_complete(); attitude_control->relax_attitude_controllers(); - // disable yaw rate time contant to mantain old behaviour + // disable yaw rate time constant to maintain old behaviour quadplane.disable_yaw_rate_time_constant(); IGNORE_RETURN(ahrs.get_quaternion(plane.mode_acro.acro_state.q)); diff --git a/ArduPlane/mode_qhover.cpp b/ArduPlane/mode_qhover.cpp index 1fe4848296a0c6..fac2147f93c455 100644 --- a/ArduPlane/mode_qhover.cpp +++ b/ArduPlane/mode_qhover.cpp @@ -37,6 +37,7 @@ void ModeQHover::run() quadplane.relax_attitude_control(); pos_control->relax_z_controller(0); } else { + plane.quadplane.assign_tilt_to_fwd_thr(); quadplane.hold_hover(quadplane.get_pilot_desired_climb_rate_cms()); } diff --git a/ArduPlane/mode_qloiter.cpp b/ArduPlane/mode_qloiter.cpp index e39ad63559ed42..50dd8deea749bb 100644 --- a/ArduPlane/mode_qloiter.cpp +++ b/ArduPlane/mode_qloiter.cpp @@ -83,6 +83,8 @@ void ModeQLoiter::run() plane.nav_roll_cd = loiter_nav->get_roll(); plane.nav_pitch_cd = loiter_nav->get_pitch(); + plane.quadplane.assign_tilt_to_fwd_thr(); + if (quadplane.transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd)) { pos_control->set_externally_limited_xy(); } diff --git a/ArduPlane/mode_qrtl.cpp b/ArduPlane/mode_qrtl.cpp index 16e805a40d5c05..9be1c962bd6a4b 100644 --- a/ArduPlane/mode_qrtl.cpp +++ b/ArduPlane/mode_qrtl.cpp @@ -103,6 +103,9 @@ void ModeQRTL::run() // nav roll and pitch are controller by position controller plane.nav_roll_cd = pos_control->get_roll_cd(); plane.nav_pitch_cd = pos_control->get_pitch_cd(); + + plane.quadplane.assign_tilt_to_fwd_thr(); + if (quadplane.transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd)) { pos_control->set_externally_limited_xy(); } @@ -123,7 +126,7 @@ void ModeQRTL::run() ftype alt_diff; if (!stopping_loc.get_alt_distance(plane.next_WP_loc, alt_diff) || is_positive(alt_diff)) { - // climb finshed or cant get alt diff, head home + // climb finished or cant get alt diff, head home submode = SubMode::RTL; plane.prev_WP_loc = plane.current_loc; diff --git a/ArduPlane/mode_qstabilize.cpp b/ArduPlane/mode_qstabilize.cpp index 39f168fd736d55..2f78a210fb3c2d 100644 --- a/ArduPlane/mode_qstabilize.cpp +++ b/ArduPlane/mode_qstabilize.cpp @@ -47,6 +47,8 @@ void ModeQStabilize::run() return; } + plane.quadplane.assign_tilt_to_fwd_thr(); + // special check for ESC calibration in QSTABILIZE if (quadplane.esc_calibration != 0) { quadplane.run_esc_calibration(); @@ -81,7 +83,7 @@ void ModeQStabilize::set_tailsitter_roll_pitch(const float roll_input, const flo plane.quadplane.transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd); } -// set the desired roll and pitch for normal quadplanes, also limited by forward flight limtis +// set the desired roll and pitch for normal quadplanes, also limited by forward flight limits void ModeQStabilize::set_limited_roll_pitch(const float roll_input, const float pitch_input) { plane.nav_roll_cd = roll_input * MIN(plane.roll_limit_cd, plane.quadplane.aparm.angle_max); diff --git a/ArduPlane/mode_takeoff.cpp b/ArduPlane/mode_takeoff.cpp index 834fa93de97a45..db212361c398e8 100644 --- a/ArduPlane/mode_takeoff.cpp +++ b/ArduPlane/mode_takeoff.cpp @@ -1,5 +1,6 @@ #include "mode.h" #include "Plane.h" +#include /* mode takeoff parameters @@ -34,7 +35,7 @@ const AP_Param::GroupInfo ModeTakeoff::var_info[] = { // @Param: DIST // @DisplayName: Takeoff mode distance - // @Description: This is the distance from the takeoff location where the plane will loiter. The loiter point will be in the direction of takeoff (the direction the plane is facing when the motor starts) + // @Description: This is the distance from the takeoff location where the plane will loiter. The loiter point will be in the direction of takeoff (the direction the plane is facing when the plane begins takeoff) // @Range: 0 500 // @Increment: 1 // @Units: m @@ -150,6 +151,11 @@ void ModeTakeoff::update() plane.calc_nav_roll(); plane.calc_nav_pitch(); plane.calc_throttle(); + //check if in long failsafe, if it is recall long failsafe now to get fs action via events call + if (plane.long_failsafe_pending) { + plane.long_failsafe_pending = false; + plane.failsafe_long_on_event(FAILSAFE_LONG, ModeReason::MODE_TAKEOFF_FAILSAFE); + } } } diff --git a/ArduPlane/mode_training.cpp b/ArduPlane/mode_training.cpp index 2ee8b672723ed3..23c81fbcc288f8 100644 --- a/ArduPlane/mode_training.cpp +++ b/ArduPlane/mode_training.cpp @@ -64,9 +64,6 @@ void ModeTraining::run() } // Always manual rudder control - const float pilot_rudder = plane.rudder_in_expo(false); - plane.steering_control.rudder = pilot_rudder; - plane.steering_control.steering = pilot_rudder; - SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, pilot_rudder); + output_rudder_and_steering(plane.rudder_in_expo(false)); } diff --git a/ArduPlane/motor_test.cpp b/ArduPlane/motor_test.cpp index 67dee708b50b7b..38229d2f351344 100644 --- a/ArduPlane/motor_test.cpp +++ b/ArduPlane/motor_test.cpp @@ -67,7 +67,7 @@ void QuadPlane::motor_test_output() // sanity check throttle values if (pwm >= RC_Channel::RC_MIN_LIMIT_PWM && pwm <= RC_Channel::RC_MAX_LIMIT_PWM) { - // turn on motor to specified pwm vlaue + // turn on motor to specified pwm value motors->output_test_seq(motor_test.seq, pwm); } else { motor_test_stop(); diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 52ef65436628eb..76846b0fe6ed64 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -73,7 +73,7 @@ void Plane::loiter_angle_update(void) loiter.next_sum_lap_cd = loiter.sum_cd + lap_check_interval_cd; } else if (!loiter.reached_target_alt && labs(loiter.sum_cd) >= loiter.next_sum_lap_cd) { - // check every few laps for scenario where up/downdrafts inhibit you from loitering up/down for too long + // check every few laps for scenario where up/downward inhibit you from loitering up/down for too long loiter.unable_to_acheive_target_alt = labs(current_loc.alt - loiter.start_lap_alt_cm) < 500; loiter.start_lap_alt_cm = current_loc.alt; loiter.next_sum_lap_cd += lap_check_interval_cd; @@ -95,6 +95,8 @@ void Plane::navigate() return; } + check_home_alt_change(); + // waypoint distance from plane // ---------------------------- auto_state.wp_distance = current_loc.get_distance(next_WP_loc); @@ -186,7 +188,7 @@ void Plane::calc_airspeed_errors() get_throttle_input()) + ((int32_t)aparm.airspeed_min * 100); } #if OFFBOARD_GUIDED == ENABLED - } else if (control_mode == &mode_guided && guided_state.target_airspeed_cm > 0.0) { // if offbd guided speed change cmd not set, then this section is skipped + } 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(); float delta = 1e-3f * (now - guided_state.target_airspeed_time_ms); diff --git a/ArduPlane/qautotune.h b/ArduPlane/qautotune.h index 1a1bf6e873fdc2..3ec890ac3dc3f9 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 && !HAL_MINIMIZE_FEATURES + #define QAUTOTUNE_ENABLED HAL_QUADPLANE_ENABLED #endif #if QAUTOTUNE_ENABLED diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 5a8a895f1ef6ba..9557637af40d58 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -167,7 +167,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: VFWD_GAIN // @DisplayName: Forward velocity hold gain - // @Description: Controls use of forward motor in vtol modes. If this is zero then the forward motor will not be used for position control in VTOL modes. A value of 0.05 is a good place to start if you want to use the forward motor for position control. No forward motor will be used in QSTABILIZE or QHOVER modes. Use QLOITER for position hold with the forward motor. + // @Description: The use of this parameter is no longer recommended and has been superseded by a method that works in all VTOL modes with the exception of autotune which is controlled by the Q_FWD_THR_USE parameter. This Q_VFD_GAIN parameter controls use of the forward motor in VTOL modes that use the velocity controller. Set to 0 to disable this function. A value of 0.05 is a good place to start if you want to use the forward motor for position control. No forward motor will be used in QSTABILIZE or QHOVER modes. Use QLOITER for position hold with the forward motor. // @Range: 0 0.5 // @Increment: 0.01 // @User: Standard @@ -269,7 +269,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Bitmask: 8: Mtrs_Only_Qassist-in tailsitters only uses VTOL motors and not flying surfaces for QASSIST // @Bitmask: 10: Disarmed Yaw Tilt-enable motor tilt for yaw when disarmed // @Bitmask: 11: Delay Spoolup-delay VTOL spoolup for 2 seconds after arming - // @Bitmask: 12: Disable Qassist-based on synthetic airspeed even if airspeed sensor is used + // @Bitmask: 12: Disable speed based Qassist when using synthethic airspeed estimates // @Bitmask: 13: Disable Ground Effect Compensation-on baro altitude reports // @Bitmask: 14: Ignore forward flight angle limits-in Qmodes and use Q_ANGLE_MAX exclusively // @Bitmask: 15: ThrLandControl-enable throttle stick control of landing rate @@ -279,6 +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. AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0), AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2), @@ -399,7 +400,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Param: ASSIST_ALT // @DisplayName: Quadplane assistance altitude - // @Description: This is the altitude below which quadplane assistance will be triggered. This acts the same way as Q_ASSIST_ANGLE and Q_ASSIST_SPEED, but triggers if the aircraft drops below the given altitude while the VTOL motors are not running. A value of zero disables this feature. The altutude is calculated as being above ground level. The height above ground is given from a Lidar used if available and RNGFND_LANDING=1. Otherwise it comes from terrain data if TERRAIN_FOLLOW=1 and comes from height above home otherwise. + // @Description: This is the altitude below which quadplane assistance will be triggered. This acts the same way as Q_ASSIST_ANGLE and Q_ASSIST_SPEED, but triggers if the aircraft drops below the given altitude while the VTOL motors are not running. A value of zero disables this feature. The altitude is calculated as being above ground level. The height above ground is given from a Lidar used if available and RNGFND_LANDING=1. Otherwise it comes from terrain data if TERRAIN_FOLLOW=1 and comes from height above home otherwise. // @Units: m // @Range: 0 120 // @Increment: 1 @@ -504,6 +505,30 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @User: Standard AP_GROUPINFO("RTL_ALT_MIN", 34, QuadPlane, qrtl_alt_min, 10), + // @Param: FWD_THR_GAIN + // @DisplayName: Q mode fwd throttle gain + // @Description: This parameter sets the gain from forward accel/tilt to forward throttle in Q modes. The Q modes this feature operates in is controlled by the Q_FWD_THR_USE parameter. Vehicles using separate forward thrust motors, eg quadplanes, should set this parameter to (all up weight) / (maximum combined thrust of forward motors) with a value of 2 being typical. Vehicles that tilt lifting rotors to provide forward thrust should set this parameter to (all up weight) / (weight lifted by tilting rotors) which for most aircraft can be approximated as (total number of lifting rotors) / (number of lifting rotors that tilt). When using this method of forward throttle control, the forward tilt angle limit is controlled by the Q_FWD_PIT_LIM parameter. + // @Range: 0.0 5.0 + // @Increment: 0.1 + // @User: Standard + AP_GROUPINFO("FWD_THR_GAIN", 35, QuadPlane, q_fwd_thr_gain, 2.0f), + + // @Param: FWD_PIT_LIM + // @DisplayName: Q mode forward pitch limit + // @Description: When forward throttle is being controlled by the Q_FWD_THR_GAIN parameter in Q modes, the vehicle forward (nose down) pitch rotation will be limited to the value specified by this parameter and the any additional forward acceleration required will be produced by use of the forward thrust motor(s) or tilting of moveable rotors. Larger values allow the vehicle to pitch more nose down. Set initially to the amount of nose down pitch required to remove wing lift. + // @Units: deg + // @Range: 0.0 5.0 + // @Increment: 0.1 + // @User: Standard + AP_GROUPINFO("FWD_PIT_LIM", 36, QuadPlane, q_fwd_pitch_lim, 3.0f), + + // @Param: FWD_THR_USE + // @DisplayName: Q mode forward throttle use + // @Description: This parameter determines when the feature that uses forward throttle instead of forward tilt is used. The amount of forward throttle is controlled by the Q_FWD_THR_GAIN parameter. The maximum amount of forward pitch allowed is controlled by the Q_FWD_PIT_LIM parameter. Q_FWD_THR_USE = 0 disables the feature. Q_FWD_THR_USE = 1 enables the feature in all position controlled modes such as QLOITER, QLAND, QRTL and VTOL TAKEOFF. Q_FWD_THR_USE = 2 enables the feature in all Q modes except QAUTOTUNE and QACRO. When enabling the feature, the legacy method of controlling forward throttle use via velocity controller error should be disabled by setting Q_VFWD_GAIN to 0. Do not use this feature with tailsitters. + // @Values: 0:Off,1:On in all position controlled Q modes,2:On in all Q modes except QAUTOTUNE and QACRO + // @User: Standard + AP_GROUPINFO("FWD_THR_USE", 37, QuadPlane, q_fwd_thr_use, uint8_t(FwdThrUse::OFF)), + AP_GROUPEND }; @@ -2068,6 +2093,9 @@ bool QuadPlane::handle_do_vtol_transition(enum MAV_VTOL_STATE state) const gcs().send_text(MAV_SEVERITY_NOTICE, "Entered VTOL mode"); } plane.auto_state.vtol_mode = true; + // This is a precaution. It should be looked after by the call to QuadPlane::mode_enter(void) on mode entry. + plane.quadplane.q_fwd_throttle = 0.0f; + plane.quadplane.q_fwd_pitch_lim_cd = 100.0f * plane.quadplane.q_fwd_pitch_lim; return true; case MAV_VTOL_STATE_FW: @@ -2223,6 +2251,10 @@ void QuadPlane::run_xy_controller(float accel_limit) pos_control->init_xy_controller(); } pos_control->set_lean_angle_max_cd(MIN(4500, MAX(accel_to_angle(accel_limit)*100, aparm.angle_max))); + if (q_fwd_throttle > 0.95f) { + // prevent wind up of the velocity controller I term due to a saturated forward throttle + pos_control->set_externally_limited_xy(); + } pos_control->update_xy_controller(); } @@ -2538,7 +2570,6 @@ void QuadPlane::vtol_position_controller(void) } } - if (poscontrol.get_state() == QPOS_APPROACH) { poscontrol_init_approach(); } @@ -2675,6 +2706,8 @@ void QuadPlane::vtol_position_controller(void) plane.nav_roll_cd = pos_control->get_roll_cd(); plane.nav_pitch_cd = pos_control->get_pitch_cd(); + assign_tilt_to_fwd_thr(); + if (transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd)) { pos_control->set_externally_limited_xy(); } @@ -2728,6 +2761,8 @@ void QuadPlane::vtol_position_controller(void) plane.nav_roll_cd = pos_control->get_roll_cd(); plane.nav_pitch_cd = pos_control->get_pitch_cd(); + assign_tilt_to_fwd_thr(); + if (transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd)) { pos_control->set_externally_limited_xy(); } @@ -2772,6 +2807,8 @@ void QuadPlane::vtol_position_controller(void) plane.nav_roll_cd = pos_control->get_roll_cd(); plane.nav_pitch_cd = pos_control->get_pitch_cd(); + assign_tilt_to_fwd_thr(); + // call attitude controller set_pilot_yaw_rate_time_constant(); attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, @@ -2895,6 +2932,111 @@ void QuadPlane::vtol_position_controller(void) } } +/* + determine which fwd throttle handling method is active + */ +QuadPlane::ActiveFwdThr QuadPlane::get_vfwd_method(void) const +{ + const bool have_fwd_thr_gain = is_positive(q_fwd_thr_gain); + const bool have_vfwd_gain = is_positive(vel_forward.gain); + +#if AP_ICENGINE_ENABLED + const auto ice_state = plane.g2.ice_control.get_state(); + if (ice_state != AP_ICEngine::ICE_DISABLED && ice_state != AP_ICEngine::ICE_RUNNING) { + // we need the engine running for fwd throttle + return ActiveFwdThr::NONE; + } +#endif + +#if QAUTOTUNE_ENABLED + if (plane.control_mode == &plane.mode_qautotune) { + return ActiveFwdThr::NONE; + } +#endif + + if (have_fwd_thr_gain) { + if (vfwd_enable_active) { + // user has used AUX function to activate new method + return ActiveFwdThr::NEW; + } + if (q_fwd_thr_use == FwdThrUse::ALL) { + return ActiveFwdThr::NEW; + } + if (q_fwd_thr_use == FwdThrUse::POSCTRL && pos_control->is_active_xy()) { + return ActiveFwdThr::NEW; + } + } + if (have_vfwd_gain && pos_control->is_active_xy()) { + return ActiveFwdThr::OLD; + } + return ActiveFwdThr::NONE; +} + +/* + map from pitch tilt to fwd throttle when enabled + */ +void QuadPlane::assign_tilt_to_fwd_thr(void) { + + const auto fwd_thr_active = get_vfwd_method(); + if (fwd_thr_active != ActiveFwdThr::NEW) { + q_fwd_throttle = 0.0f; + q_fwd_pitch_lim_cd = 100.0f * q_fwd_pitch_lim; + return; + } + // Handle the case where we are limiting the forward pitch angle to prevent negative wing lift + // and are using the forward thrust motor or tilting rotors to provide the forward acceleration + float fwd_tilt_rad = radians(constrain_float(-0.01f * (float)plane.nav_pitch_cd, 0.0f, 45.0f)); + q_fwd_throttle = MIN(q_fwd_thr_gain * tanf(fwd_tilt_rad), 1.0f); + + // Relax forward tilt limit if the position controller is saturating in the forward direction because + // the forward thrust motor could be failed + const float fwd_tilt_range_cd = (float)aparm.angle_max - 100.0f * q_fwd_pitch_lim; + if (is_positive(fwd_tilt_range_cd)) { + // rate limit the forward tilt change to slew between the motor good and motor failed + // value over 10 seconds + const bool fwd_limited = plane.quadplane.pos_control->is_active_xy() and plane.quadplane.pos_control->get_fwd_pitch_is_limited(); + const float fwd_pitch_lim_cd_tgt = fwd_limited ? (float)aparm.angle_max : 100.0f * q_fwd_pitch_lim; + const float delta_max = 0.1f * fwd_tilt_range_cd * plane.G_Dt; + q_fwd_pitch_lim_cd += constrain_float((fwd_pitch_lim_cd_tgt - q_fwd_pitch_lim_cd), -delta_max, delta_max); + // Don't let the forward pitch limit be more than the forward pitch demand before limiting to + // avoid opening up the limit more than necessary + q_fwd_pitch_lim_cd = MIN(q_fwd_pitch_lim_cd, MAX(-(float)plane.nav_pitch_cd, 100.0f * q_fwd_pitch_lim)); + } else { + // take the lesser of the two limits + q_fwd_pitch_lim_cd = (float)aparm.angle_max; + } + + float fwd_thr_scaler; + if (!in_vtol_land_approach()) { + // To prevent forward motor prop strike, reduce throttle to zero when close to ground. + float alt_cutoff = MAX(0,vel_forward_alt_cutoff); + float height_above_ground = plane.relative_ground_altitude(plane.g.rangefinder_landing); + fwd_thr_scaler = linear_interpolate(0.0f, 1.0f, height_above_ground, alt_cutoff, alt_cutoff+2); + } else { + // When we are doing horizontal positioning in a VTOL land we always allow the fwd motor + // to run. Otherwise a bad height above landing point estimate could cause the aircraft + // not to be able to approach the landing point + fwd_thr_scaler = 1.0f; + } + q_fwd_throttle *= fwd_thr_scaler; + + // When reducing forward throttle use, relax lower pitch limit to maintain forward + // acceleration capability. + const float nav_pitch_lower_limit_cd = - (int32_t)((float)aparm.angle_max * (1.0f - fwd_thr_scaler) + q_fwd_pitch_lim_cd * fwd_thr_scaler); + + // Diagnostics logging - remove when feature is fully flight tested. + AP::logger().WriteStreaming("FWDT", + "TimeUS,fts,qfplcd,npllcd,npcd,qft", // labels + "Qfffff", // fmt + AP_HAL::micros64(), + (double)fwd_thr_scaler, + (double)q_fwd_pitch_lim_cd, + (double)nav_pitch_lower_limit_cd, + (double)plane.nav_pitch_cd, + (double)q_fwd_throttle); + + plane.nav_pitch_cd = MAX(plane.nav_pitch_cd, (int32_t)nav_pitch_lower_limit_cd); +} /* we want to limit WP speed to a lower speed when more than 20 degrees @@ -2946,6 +3088,10 @@ void QuadPlane::setup_target_position(void) */ void QuadPlane::takeoff_controller(void) { + // reset fixed wing controller to neutral as base output + plane.nav_roll_cd = 0; + plane.nav_pitch_cd = 0; + if (!plane.arming.is_armed_and_safety_off()) { return; } @@ -3007,8 +3153,6 @@ void QuadPlane::takeoff_controller(void) takeoff_last_run_ms = now; if (no_navigation) { - plane.nav_roll_cd = 0; - plane.nav_pitch_cd = 0; pos_control->relax_velocity_controller_xy(); } else { pos_control->set_accel_desired_xy_cmss(zero); @@ -3018,6 +3162,8 @@ void QuadPlane::takeoff_controller(void) // nav roll and pitch are controller by position controller plane.nav_roll_cd = pos_control->get_roll_cd(); plane.nav_pitch_cd = pos_control->get_pitch_cd(); + + assign_tilt_to_fwd_thr(); } run_xy_controller(); @@ -3075,6 +3221,8 @@ void QuadPlane::waypoint_controller(void) plane.nav_roll_cd = wp_nav->get_roll(); plane.nav_pitch_cd = wp_nav->get_pitch(); + assign_tilt_to_fwd_thr(); + if (transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd)) { pos_control->set_externally_limited_xy(); } @@ -3533,6 +3681,11 @@ void QuadPlane::Log_Write_QControl_Tuning() */ float QuadPlane::forward_throttle_pct() { + // handle special case where forward thrust motor is used instead of forward pitch. + if (get_vfwd_method() == ActiveFwdThr::NEW) { + return 100.0f * q_fwd_throttle; + } + /* Unless an RC channel is assigned for manual forward throttle control, we don't use forward throttle in QHOVER or QSTABILIZE as they are the primary @@ -3556,15 +3709,9 @@ float QuadPlane::forward_throttle_pct() } /* - in qautotune mode or modes without a velocity controller + see if the controller should be active */ - bool use_forward_gain = (vel_forward.gain > 0); -#if QAUTOTUNE_ENABLED - if (plane.control_mode == &plane.mode_qautotune) { - use_forward_gain = false; - } -#endif - if (!use_forward_gain) { + if (get_vfwd_method() != ActiveFwdThr::OLD) { return 0; } @@ -4434,6 +4581,9 @@ void QuadPlane::mode_enter(void) // state for special behaviour guided_wait_takeoff_on_mode_enter = guided_wait_takeoff; guided_wait_takeoff = false; + + q_fwd_throttle = 0.0f; + q_fwd_pitch_lim_cd = 100.0f * q_fwd_pitch_lim; } // Set attitude control yaw rate time constant to pilot input command model value diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index ae65c3768e1666..b919be2c445869 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -395,6 +395,32 @@ class QuadPlane AP_Float acro_pitch_rate; AP_Float acro_yaw_rate; + // gain from forward acceleration to forward throttle + AP_Float q_fwd_thr_gain; + + // limit applied to forward pitch to prevent wing producing negative lift + AP_Float q_fwd_pitch_lim; + + // which fwd throttle handling method is active + enum class ActiveFwdThr : uint8_t { + NONE = 0, + OLD = 1, + NEW = 2, + }; + // override with AUX function + bool vfwd_enable_active; + + // specifies when the feature controlled by q_fwd_thr_gain and q_fwd_pitch_lim is used + enum class FwdThrUse : uint8_t { + OFF = 0, + POSCTRL = 1, + ALL = 2, + }; + AP_Enum q_fwd_thr_use; + + // return which vfwd method to use + ActiveFwdThr get_vfwd_method(void) const; + // time we last got an EKF yaw reset uint32_t ekfYawReset_ms; @@ -411,6 +437,9 @@ class QuadPlane Location last_auto_target; + float q_fwd_throttle; // forward throttle used in q modes + float q_fwd_pitch_lim_cd; // forward pitch limit applied when using q_fwd_throttle + // when did we last run the attitude controller? uint32_t last_att_control_ms; @@ -581,6 +610,7 @@ class QuadPlane TRANS_FAIL_TO_FW=(1<<19), FS_RTL=(1<<20), DISARMED_TILT_UP=(1<<21), + SCALE_FF_ANGLE_P=(1<<22), }; bool option_is_set(OPTION option) const { return (options.get() & int32_t(option)) != 0; @@ -682,6 +712,11 @@ class QuadPlane */ void set_desired_spool_state(AP_Motors::DesiredSpoolState state); + /* + limit forward pitch demand if using rotor tilt or forward flight motor to provide forward acceleration. + */ + void assign_tilt_to_fwd_thr(void); + /* get a scaled Q_WP_SPEED based on direction of movement */ diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 7a28ca11f59f1a..cb7e68ff226f32 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -210,8 +210,10 @@ void Plane::read_radio() quadplane.tailsitter.check_input(); #endif +#if AP_TUNING_ENABLED // check for transmitter tuning changes tuning.check_input(control_mode->mode_number()); +#endif } int16_t Plane::rudder_input(void) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 30a49fccc41715..ced42525788e83 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -546,7 +546,7 @@ void Plane::set_servos_controlled(void) control_mode == &mode_autotune) { // a manual throttle mode if (!rc().has_valid_input()) { - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, g.throttle_passthru_stabilize ? 0.0 : MAX(min_throttle,0)); } else if (g.throttle_passthru_stabilize) { // manual pass through of throttle while in FBWA or // STABILIZE mode with THR_PASS_STAB set @@ -819,28 +819,6 @@ void Plane::set_servos(void) return; } - /* - see if we are doing ground steering. - */ - if (!steering_control.ground_steering) { - // we are not at an altitude for ground steering. Set the nose - // wheel to the rudder just in case the barometer has drifted - // a lot - steering_control.steering = steering_control.rudder; - } else if (!SRV_Channels::function_assigned(SRV_Channel::k_steering)) { - // we are within the ground steering altitude but don't have a - // dedicated steering channel. Set the rudder to the ground - // steering output - steering_control.rudder = steering_control.steering; - } - - // clear ground_steering to ensure manual control if the yaw stabilizer doesn't run - steering_control.ground_steering = false; - - - SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, steering_control.rudder); - SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering_control.steering); - if (control_mode != &mode_manual) { set_servos_controlled(); } @@ -946,7 +924,7 @@ void Plane::indicate_waiting_for_rud_neutral_to_takeoff(void) SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, 0); channel_function_mixer(SRV_Channel::k_rudder, SRV_Channel::k_elevator, SRV_Channel::k_vtail_right, SRV_Channel::k_vtail_left); if (!SRV_Channels::function_assigned(SRV_Channel::k_rudder) && !SRV_Channels::function_assigned(SRV_Channel::k_vtail_left)) { - // if no rudder indication possible, neutral elevons during wait becuase on takeoff stance they are usually both full up + // if no rudder indication possible, neutral elevons during wait because on takeoff stance they are usually both full up SRV_Channels::set_output_scaled(SRV_Channel::k_elevon_right, 0); SRV_Channels::set_output_scaled(SRV_Channel::k_elevon_left, 0); } diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 6f21b75abc7519..7c7066bef06b60 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -257,7 +257,7 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason) if (control_mode == &new_mode) { // don't switch modes if we are already in the correct mode. - // only make happy noise if using a difent method to switch, this stops beeping for repeated change mode requests from GCS + // only make happy noise if using a different method to switch, this stops beeping for repeated change mode requests from GCS if ((reason != control_mode_reason) && (reason != ModeReason::INITIALISED)) { AP_Notify::events.user_mode_change = 1; } diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index 3c8fe77d728402..f40fa33d1f26eb 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -27,7 +27,7 @@ const AP_Param::GroupInfo Tailsitter::var_info[] = { // @Param: ENABLE // @DisplayName: Enable Tailsitter // @Values: 0:Disable, 1:Enable, 2:Enable Always - // @Description: This enables Tailsitter functionality. A value of 2 forces Qassist active and always stabilize in forward flight with airmode for stabalisation at 0 throttle, for use on vehicles with no control surfaces, vehicle will not arm in forward flight modes, see also Q_OPTIONS "Mtrs_Only_Qassist" + // @Description: This enables Tailsitter functionality. A value of 2 forces Qassist active and always stabilize in forward flight with airmode for stabilisation at 0 throttle, for use on vehicles with no control surfaces, vehicle will not arm in forward flight modes, see also Q_OPTIONS "Mtrs_Only_Qassist" // @User: Standard // @RebootRequired: True AP_GROUPINFO_FLAGS("ENABLE", 1, Tailsitter, enable, 0, AP_PARAM_FLAG_ENABLE), @@ -161,7 +161,7 @@ const AP_Param::GroupInfo Tailsitter::var_info[] = { // @Param: MIN_VO // @DisplayName: Tailsitter Disk loading minimum outflow speed - // @Description: Use in conjunction with disk therory gain scaling and Q_TAILSIT_DSKLD to specify minumum airspeed over control surfaces, this will be used to boost throttle, when decending for example, 0 disables + // @Description: Use in conjunction with disk theory gain scaling and Q_TAILSIT_DSKLD to specify minumum airspeed over control surfaces, this will be used to boost throttle, when descending for example, 0 disables // @Range: 0 15 AP_GROUPINFO("MIN_VO", 22, Tailsitter, disk_loading_min_outflow, 0), @@ -330,7 +330,7 @@ void Tailsitter::output(void) SRV_Channels::set_output_pwm(SRV_Channel::k_throttleLeft, throttle_pwm); SRV_Channels::set_output_pwm(SRV_Channel::k_throttleRight, throttle_pwm); - // throttle output is not used by AP_Motors so might have diffrent PWM range, set scaled + // throttle output is not used by AP_Motors so might have different PWM range, set scaled SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle * 100.0); } } @@ -366,20 +366,32 @@ void Tailsitter::output(void) if (quadplane.option_is_set(QuadPlane::OPTION::TAILSIT_Q_ASSIST_MOTORS_ONLY)) { // only use motors for Q assist, control surfaces remain under plane control. Zero copter I terms and use plane. // Smoothly relax to zero so there is no step change in output, must also set limit flags so integrator cannot build faster than the relax. - // Assume there is always roll and pitch control surfaces, otherwise motors only assist should not be set. + // Assume there is always roll control surfaces, otherwise motors only assist should not be set. const float dt = quadplane.attitude_control->get_dt(); - quadplane.attitude_control->get_rate_pitch_pid().relax_integrator(0.0, dt, AC_ATTITUDE_RATE_RELAX_TC); - motors->limit.pitch = true; + + // VTOL yaw / FW roll quadplane.attitude_control->get_rate_yaw_pid().relax_integrator(0.0, dt, AC_ATTITUDE_RATE_RELAX_TC); motors->limit.yaw = true; + // VTOL and FW pitch + if (_have_elevator || _have_elevon || _have_v_tail) { + // have pitch control surfaces, use them + quadplane.attitude_control->get_rate_pitch_pid().relax_integrator(0.0, dt, AC_ATTITUDE_RATE_RELAX_TC); + motors->limit.pitch = true; + } else { + // no pitch control surfaces, zero plane I terms and use motors + // We skip the outputting to surfaces for this axis from the copter controller but there are none setup + plane.pitchController.reset_I(); + } + + // VTOL roll / FW yaw if (_have_rudder || _have_v_tail) { // there are yaw control surfaces, zero motor I term quadplane.attitude_control->get_rate_roll_pid().relax_integrator(0.0, dt, AC_ATTITUDE_RATE_RELAX_TC); motors->limit.roll = true; } else { // no yaw control surfaces, zero plane I terms and use motors - // We skip the outputing to surfaces for this axis from the copter controller but there are none setup + // We skip the outputting to surfaces for this axis from the copter controller but there are none setup plane.yawController.reset_I(); } @@ -501,7 +513,7 @@ void Tailsitter::output(void) bool Tailsitter::transition_fw_complete(void) { if (!plane.arming.is_armed_and_safety_off()) { - // instant trainsition when disarmed, no message + // instant transition when disarmed, no message return true; } if (labs(quadplane.ahrs_view->pitch_sensor) > transition_angle_fw*100) { @@ -527,7 +539,7 @@ bool Tailsitter::transition_fw_complete(void) bool Tailsitter::transition_vtol_complete(void) const { if (!plane.arming.is_armed_and_safety_off()) { - // instant trainsition when disarmed, no message + // instant transition when disarmed, no message return true; } // for vectored tailsitters at zero pilot throttle @@ -622,7 +634,7 @@ void Tailsitter::speed_scaling(void) float spd_scaler = 1.0f; float disk_loading_min_throttle = 0.0; - // Scaleing with throttle + // Scaling with throttle float throttle_scaler = throttle_scale_max; if (is_positive(throttle)) { throttle_scaler = constrain_float(hover_throttle / throttle, gain_scaling_min, throttle_scale_max); @@ -918,7 +930,7 @@ bool Tailsitter_Transition::allow_stick_mixing() const if (tailsitter.in_vtol_transition()) { return false; } - // Transitioning into fixed wing flight, leveling off + // Transitioning into fixed wing flight, levelling off if ((transition_state == TRANSITION_DONE) && (fw_limit_start_ms != 0)) { return false; } diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index 2b316fe8e0b0ef..5574ad2c9b0c10 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -238,7 +238,7 @@ int16_t Plane::get_takeoff_pitch_min_cd(void) return auto_state.takeoff_pitch_cd * scalar; } - // are we entering the region where we want to start leveling off before we reach takeoff alt? + // are we entering the region where we want to start levelling off before we reach takeoff alt? if (auto_state.sink_rate < -0.1f) { float sec_to_target = (remaining_height_to_target_cm * 0.01f) / (-auto_state.sink_rate); if (sec_to_target > 0 && @@ -262,7 +262,7 @@ int16_t Plane::get_takeoff_pitch_min_cd(void) */ int8_t Plane::takeoff_tail_hold(void) { - bool in_takeoff = ((control_mode == &mode_auto && !auto_state.takeoff_complete) || + bool in_takeoff = ((plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF) || (control_mode == &mode_fbwa && auto_state.fbwa_tdrag_takeoff_mode)); if (!in_takeoff) { // not in takeoff diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index 5591fb3b6d1733..e8babe5e86d93b 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -39,7 +39,7 @@ const AP_Param::GroupInfo Tiltrotor::var_info[] = { // @Param: TYPE // @DisplayName: Tiltrotor type - // @Description: This is the type of tiltrotor when TILT_MASK is non-zero. A continuous tiltrotor can tilt the rotors to any angle on demand. A binary tiltrotor assumes a retract style servo where the servo is either fully forward or fully up. In both cases the servo can't move faster than Q_TILT_RATE. A vectored yaw tiltrotor will use the tilt of the motors to control yaw in hover, Bicopter tiltrottor must use the tailsitter frame class (10) + // @Description: This is the type of tiltrotor when TILT_MASK is non-zero. A continuous tiltrotor can tilt the rotors to any angle on demand. A binary tiltrotor assumes a retract style servo where the servo is either fully forward or fully up. In both cases the servo can't move faster than Q_TILT_RATE. A vectored yaw tiltrotor will use the tilt of the motors to control yaw in hover, Bicopter tiltrotor must use the tailsitter frame class (10) // @Values: 0:Continuous,1:Binary,2:VectoredYaw,3:Bicopter AP_GROUPINFO("TYPE", 5, Tiltrotor, type, TILT_TYPE_CONTINUOUS), @@ -54,7 +54,7 @@ const AP_Param::GroupInfo Tiltrotor::var_info[] = { // @Param: YAW_ANGLE // @DisplayName: Tilt minimum angle for vectored yaw - // @Description: This is the angle of the tilt servos when in VTOL mode and at minimum output. This needs to be set for Q_TILT_TYPE=3 to enable vectored control for yaw of tricopter tilt quadplanes. This is also used to limit the forwards travel of bicopter tilts when in VTOL modes + // @Description: This is the angle of the tilt servos when in VTOL mode and at minimum output (fully back). This needs to be set in addition to Q_TILT_TYPE=2, to enable vectored control for yaw in tilt quadplanes. This is also used to limit the forward travel of bicopter tilts(Q_TILT_TYPE=3) when in VTOL modes. // @Range: 0 30 AP_GROUPINFO("YAW_ANGLE", 7, Tiltrotor, tilt_yaw_angle, 0), @@ -115,7 +115,7 @@ void Tiltrotor::setup() && (type != TILT_TYPE_BICOPTER)); - // check if there are any perminant VTOL motors + // check if there are any permanent VTOL motors for (uint8_t i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; ++i) { if (motors->is_motor_enabled(i) && ((tilt_mask & (1U<<1)) == 0)) { // enabled motor not set in tilt mask @@ -193,7 +193,7 @@ void Tiltrotor::slew(float newtilt) SRV_Channels::set_output_scaled(SRV_Channel::k_motor_tilt, 1000 * current_tilt); } -// return the current tilt value that represens forward flight +// return the current tilt value that represents forward flight // tilt wings can sustain forward flight with some amount of wing tilt float Tiltrotor::get_fully_forward_tilt() const { @@ -258,21 +258,25 @@ void Tiltrotor::continuous_update(void) /* we are in a VTOL mode. We need to work out how much tilt is - needed. There are 4 strategies we will use: + needed. There are 5 strategies we will use: - 1) without manual forward throttle control, the angle will be set to zero - in QAUTOTUNE QACRO, QSTABILIZE and QHOVER. This - enables these modes to be used as a safe recovery mode. + 1) With use of a forward throttle controlled by Q_FWD_THR_GAIN in all + VTOL modes except Q_AUTOTUNE, we set the angle based on a calculated + forward throttle. - 2) with manual forward throttle control we will set the angle based on - the demanded forward throttle via RC input. + 2) With manual forward throttle control we set the angle based on the + RC input demanded forward throttle for QACRO, QSTABILIZE and QHOVER. - 3) in fixed wing assisted flight or velocity controlled modes we - will set the angle based on the demanded forward throttle, - with a maximum tilt given by Q_TILT_MAX. This relies on - Q_VFWD_GAIN being set. + 3) Without a RC input or calculated forward throttle value, the angle + will be set to zero in QAUTOTUNE, QACRO, QSTABILIZE and QHOVER. + This enables these modes to be used as a safe recovery mode. - 4) if we are in TRANSITION_TIMER mode then we are transitioning + 4) In fixed wing assisted flight or velocity controlled modes we will + set the angle based on the demanded forward throttle, with a maximum + tilt given by Q_TILT_MAX. This relies on Q_FWD_THR_GAIN or Q_VFWD_GAIN + being set. + + 5) if we are in TRANSITION_TIMER mode then we are transitioning to forward flight and should put the rotors all the way forward */ @@ -283,11 +287,23 @@ void Tiltrotor::continuous_update(void) } #endif - // if not in assisted flight and in QACRO, QSTABILIZE or QHOVER mode if (!quadplane.assisted_flight && - (plane.control_mode == &plane.mode_qacro || - plane.control_mode == &plane.mode_qstabilize || - plane.control_mode == &plane.mode_qhover)) { + quadplane.get_vfwd_method() == QuadPlane::ActiveFwdThr::NEW && + quadplane.is_flying_vtol()) + { + // We are using the rotor tilt functionality controlled by Q_FWD_THR_GAIN which can + // 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_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; + } else if (!quadplane.assisted_flight && + (plane.control_mode == &plane.mode_qacro || + plane.control_mode == &plane.mode_qstabilize || + plane.control_mode == &plane.mode_qhover)) + { if (quadplane.rc_fwd_thr_ch == nullptr) { // no manual throttle control, set angle to zero slew(0); diff --git a/ArduPlane/tuning.cpp b/ArduPlane/tuning.cpp index 2218a11ab0a67d..be860264fd339a 100644 --- a/ArduPlane/tuning.cpp +++ b/ArduPlane/tuning.cpp @@ -1,3 +1,7 @@ +#include + +#if AP_TUNING_ENABLED + #include "Plane.h" /* @@ -90,6 +94,7 @@ const AP_Tuning_Plane::tuning_name AP_Tuning_Plane::tuning_names[] = { { TUNING_PIT_I, "PitchI" }, { TUNING_PIT_D, "PitchD" }, { TUNING_PIT_FF, "PitchFF" }, + { TUNING_Q_FWD_THR, "QModeFwdThr" }, { TUNING_NONE, nullptr } }; @@ -186,6 +191,9 @@ AP_Float *AP_Tuning_Plane::get_param_pointer(uint8_t parm) case TUNING_RATE_YAW_FF: return &plane.quadplane.attitude_control->get_rate_yaw_pid().ff(); + + case TUNING_Q_FWD_THR: + return &plane.quadplane.q_fwd_thr_gain; #endif // HAL_QUADPLANE_ENABLED // fixed wing tuning parameters @@ -305,3 +313,4 @@ void AP_Tuning_Plane::reload_value(uint8_t parm) } } +#endif // AP_TUNING_ENABLED diff --git a/ArduPlane/tuning.h b/ArduPlane/tuning.h index 0a005f7dafdbfb..4334455a09657f 100644 --- a/ArduPlane/tuning.h +++ b/ArduPlane/tuning.h @@ -1,3 +1,9 @@ +#pragma once + +#include + +#if AP_TUNING_ENABLED + #include /* @@ -70,6 +76,8 @@ class AP_Tuning_Plane : public AP_Tuning TUNING_PIT_I = 55, TUNING_PIT_D = 56, TUNING_PIT_FF = 57, + + TUNING_Q_FWD_THR = 58, }; /* @@ -108,3 +116,5 @@ class AP_Tuning_Plane : public AP_Tuning // mask of what params have been set uint64_t have_set; }; + +#endif // AP_TUNING_ENABLED diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 9869ed29b80ad3..b8ded91fddc343 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -210,6 +210,11 @@ void Sub::ten_hz_logging_loop() if (should_log(MASK_LOG_CTUN)) { attitude_control.control_monitor_log(); } +#if HAL_MOUNT_ENABLED + if (should_log(MASK_LOG_CAMERA)) { + camera_mount.write_log(); + } +#endif } // twentyfive_hz_logging_loop diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index f4ed519b5b6751..4bc904184e86d5 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -354,7 +354,9 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_GPS2_RAW, MSG_GPS2_RTK, MSG_NAV_CONTROLLER_OUTPUT, +#if AP_FENCE_ENABLED MSG_FENCE_STATUS, +#endif MSG_NAMED_FLOAT }; static const ap_message STREAM_POSITION_msgs[] = { @@ -386,8 +388,10 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_BATTERY_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_OPTICAL_FLOW, +#if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, +#endif MSG_EKF_STATUS_REPORT, MSG_VIBRATION, #if AP_RPM_ENABLED @@ -431,9 +435,9 @@ MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration_baro(const mav return MAV_RESULT_ACCEPTED; } -MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK_Sub::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { - if (is_equal(packet.param6,1.0f)) { + if (packet.y == 1) { // compassmot calibration //result = sub.mavlink_compassmot(chan); gcs().send_text(MAV_SEVERITY_INFO, "#CompassMot calibration not supported"); @@ -459,23 +463,51 @@ bool GCS_MAVLINK_Sub::set_home(const Location& loc, bool _lock) { return sub.set_home(loc, _lock); } - -MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { - switch (packet.command) { + switch(packet.command) { + + case MAV_CMD_CONDITION_YAW: + return handle_MAV_CMD_CONDITION_YAW(packet); + + case MAV_CMD_DO_CHANGE_SPEED: + return handle_MAV_CMD_DO_CHANGE_SPEED(packet); + + case MAV_CMD_DO_MOTOR_TEST: + return handle_MAV_CMD_DO_MOTOR_TEST(packet); + + case MAV_CMD_MISSION_START: + return handle_MAV_CMD_MISSION_START(packet); + case MAV_CMD_NAV_LOITER_UNLIM: + return handle_MAV_CMD_NAV_LOITER_UNLIM(packet); + + case MAV_CMD_NAV_LAND: + return handle_MAV_CMD_NAV_LAND(packet); + + } + + return GCS_MAVLINK::handle_command_int_packet(packet, msg); +} + +MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_NAV_LOITER_UNLIM(const mavlink_command_int_t &packet) +{ if (!sub.set_mode(Mode::Number::POSHOLD, ModeReason::GCS_COMMAND)) { return MAV_RESULT_FAILED; } return MAV_RESULT_ACCEPTED; +} - case MAV_CMD_NAV_LAND: +MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_NAV_LAND(const mavlink_command_int_t &packet) +{ if (!sub.set_mode(Mode::Number::SURFACE, ModeReason::GCS_COMMAND)) { return MAV_RESULT_FAILED; } return MAV_RESULT_ACCEPTED; +} - case MAV_CMD_CONDITION_YAW: +MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet) +{ // param1 : target angle [0-360] // param2 : speed during change [deg per second] // param3 : direction (-1:ccw, +1:cw) @@ -486,9 +518,11 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_lon sub.mode_auto.set_auto_yaw_look_at_heading(packet.param1, packet.param2, (int8_t)packet.param3, (uint8_t)packet.param4); return MAV_RESULT_ACCEPTED; } - return MAV_RESULT_FAILED; + return MAV_RESULT_DENIED; +} - case MAV_CMD_DO_CHANGE_SPEED: +MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet) +{ // param1 : unused // param2 : new speed in m/s // param3 : unused @@ -498,14 +532,18 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_lon return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED; +} - case MAV_CMD_MISSION_START: +MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet) +{ if (sub.motors.armed() && sub.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) { return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED; +} - case MAV_CMD_DO_MOTOR_TEST: +MAV_RESULT GCS_MAVLINK_Sub::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet) +{ // param1 : motor sequence number (a number from 1 to max number of motors on the vehicle) // param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) // param3 : throttle (range depends upon param2) @@ -514,14 +552,8 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_lon return MAV_RESULT_FAILED; } return MAV_RESULT_ACCEPTED; - - default: - return GCS_MAVLINK::handle_command_long_packet(packet); - } } - - void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg) { switch (msg.msgid) { @@ -606,34 +638,32 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg) 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) { + packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED && + packet.coordinate_frame != MAV_FRAME_BODY_FRD) { break; } 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; - - /* - * for future use: - * bool force = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_FORCE; - * bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE; - * bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE; - */ + bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE; + bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE; // prepare position Vector3f pos_vector; if (!pos_ignore) { // convert to cm pos_vector = Vector3f(packet.x * 100.0f, packet.y * 100.0f, -packet.z * 100.0f); - // rotate to body-frame if necessary + // rotate from body-frame if necessary if (packet.coordinate_frame == MAV_FRAME_BODY_NED || + packet.coordinate_frame == MAV_FRAME_BODY_FRD || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) { sub.rotate_body_frame_to_NE(pos_vector.x, pos_vector.y); } // add body offset if necessary if (packet.coordinate_frame == MAV_FRAME_LOCAL_OFFSET_NED || packet.coordinate_frame == MAV_FRAME_BODY_NED || + packet.coordinate_frame == MAV_FRAME_BODY_FRD || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) { pos_vector += sub.inertial_nav.get_position_neu_cm(); } @@ -644,19 +674,31 @@ void GCS_MAVLINK_Sub::handleMessage(const mavlink_message_t &msg) if (!vel_ignore) { // convert to cm vel_vector = Vector3f(packet.vx * 100.0f, packet.vy * 100.0f, -packet.vz * 100.0f); - // rotate to body-frame if necessary - if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) { + // rotate from body-frame if necessary + if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_FRD || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) { sub.rotate_body_frame_to_NE(vel_vector.x, vel_vector.y); } } + // prepare yaw + float yaw_cd = 0.0f; + bool yaw_relative = false; + float yaw_rate_cds = 0.0f; + if (!yaw_ignore) { + yaw_cd = ToDeg(packet.yaw) * 100.0f; + yaw_relative = packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED; + } + if (!yaw_rate_ignore) { + yaw_rate_cds = ToDeg(packet.yaw_rate) * 100.0f; + } + // send request if (!pos_ignore && !vel_ignore && acc_ignore) { - sub.mode_guided.guided_set_destination_posvel(pos_vector, vel_vector); + sub.mode_guided.guided_set_destination_posvel(pos_vector, vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative); } else if (pos_ignore && !vel_ignore && acc_ignore) { - sub.mode_guided.guided_set_velocity(vel_vector); + sub.mode_guided.guided_set_velocity(vel_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative); } else if (!pos_ignore && vel_ignore && acc_ignore) { - sub.mode_guided.guided_set_destination(pos_vector); + sub.mode_guided.guided_set_destination(pos_vector, !yaw_ignore, yaw_cd, !yaw_rate_ignore, yaw_rate_cds, yaw_relative); } break; @@ -765,7 +807,7 @@ uint64_t GCS_MAVLINK_Sub::capabilities() const ); } -MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_long_t &packet) { +MAV_RESULT GCS_MAVLINK_Sub::handle_flight_termination(const mavlink_command_int_t &packet) { if (packet.param1 > 0.5f) { sub.arming.disarm(AP_Arming::Method::TERMINATION); return MAV_RESULT_ACCEPTED; diff --git a/ArduSub/GCS_Mavlink.h b/ArduSub/GCS_Mavlink.h index 334586941c2a0d..91c62ddff5278a 100644 --- a/ArduSub/GCS_Mavlink.h +++ b/ArduSub/GCS_Mavlink.h @@ -15,12 +15,13 @@ class GCS_MAVLINK_Sub : public GCS_MAVLINK { return 0; }; - MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override; MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override; MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override; - MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; - MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; + 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; // override sending of scaled_pressure3 to send on-board temperature: void send_scaled_pressure3() override; @@ -51,6 +52,13 @@ class GCS_MAVLINK_Sub : public GCS_MAVLINK { int16_t vfr_hud_throttle() const override; + MAV_RESULT handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_NAV_LOITER_UNLIM(const mavlink_command_int_t &packet); + MAV_RESULT handle_MAV_CMD_NAV_LAND(const mavlink_command_int_t &packet); + #if HAL_HIGH_LATENCY2_ENABLED int16_t high_latency_target_altitude() const override; uint8_t high_latency_tgt_heading() const override; diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 7bd1ff3eb10f1e..e7162c5ebcf1b7 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -701,22 +701,7 @@ void Sub::load_parameters() AP_Param::set_frame_type_flags(AP_PARAM_FRAME_SUB); convert_old_parameters(); - - AP_Param::set_default_by_name("BRD_SAFETY_DEFLT", 0); - AP_Param::set_default_by_name("ARMING_CHECK", - AP_Arming::ARMING_CHECK_RC | - AP_Arming::ARMING_CHECK_VOLTAGE | - AP_Arming::ARMING_CHECK_BATTERY); - AP_Param::set_default_by_name("CIRCLE_RATE", 2.0f); - AP_Param::set_default_by_name("ATC_ACCEL_Y_MAX", 110000.0f); - AP_Param::set_default_by_name("RC3_TRIM", 1100); - AP_Param::set_default_by_name("COMPASS_OFFS_MAX", 1000); - AP_Param::set_default_by_name("INS_GYR_CAL", 0); - AP_Param::set_default_by_name("MNT1_TYPE", 1); - AP_Param::set_default_by_name("MNT1_DEFLT_MODE", MAV_MOUNT_MODE_RC_TARGETING); - AP_Param::set_default_by_name("MNT1_RC_RATE", 30); - AP_Param::set_default_by_name("RC7_OPTION", 214); // MOUNT1_YAW - AP_Param::set_default_by_name("RC8_OPTION", 213); // MOUNT1_PITCH + AP_Param::set_defaults_from_table(defaults_table, ARRAY_SIZE(defaults_table)); // We should ignore this parameter since ROVs are neutral buoyancy AP_Param::set_by_name("MOT_THST_HOVER", 0.5); diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index 731e1321e17fe5..f170667859e8f5 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -6,6 +6,7 @@ #include #include +#include #if AP_SCRIPTING_ENABLED #include @@ -48,7 +49,7 @@ class Parameters { // Layout version number, always key zero. // k_param_format_version = 0, - k_param_software_type, // unusued + k_param_software_type, // unused k_param_g2, // 2nd block of parameters @@ -349,3 +350,22 @@ class ParametersG2 { extern const AP_Param::Info var_info[]; +// Sub-specific default parameters +static const struct AP_Param::defaults_table_struct defaults_table[] = { + { "BRD_SAFETY_DEFLT", 0 }, + { "ARMING_CHECK", AP_Arming::ARMING_CHECK_RC | + AP_Arming::ARMING_CHECK_VOLTAGE | + AP_Arming::ARMING_CHECK_BATTERY}, + { "CIRCLE_RATE", 2.0f}, + { "ATC_ACCEL_Y_MAX", 110000.0f}, + { "RC3_TRIM", 1100}, + { "COMPASS_OFFS_MAX", 1000}, + { "INS_GYR_CAL", 0}, + { "MNT1_TYPE", 1}, + { "MNT1_DEFLT_MODE", MAV_MOUNT_MODE_RC_TARGETING}, + { "MNT1_RC_RATE", 30}, + { "RC7_OPTION", 214}, // MOUNT1_YAW + { "RC8_OPTION", 213}, // MOUNT1_PITCH + { "MOT_PWM_MIN", 1100}, + { "MOT_PWM_MAX", 1900}, +}; diff --git a/ArduSub/ReleaseNotes.txt b/ArduSub/ReleaseNotes.txt index 937999ce180a49..6d68f5216e7f51 100644 --- a/ArduSub/ReleaseNotes.txt +++ b/ArduSub/ReleaseNotes.txt @@ -704,7 +704,7 @@ Changes from 3.1.4 11) CLI removed from APM1/2 to save flash space, critical functions moved to MAVLink: a) Individual motor tests (see MP's Initial Setup > Optional Hardware > Motor Test) b) compassmot (see MP's Initial Setup > Optional Hardware > Compass/Motor Calib) - c) parameter reset to factory defautls (see MP's Config/Tuning > Full Parameter List > Reset to Default) + c) parameter reset to factory defaults (see MP's Config/Tuning > Full Parameter List > Reset to Default) ------------------------------------------------------------------ ArduCopter 3.1.5 27-May-2014 / 3.1.5-rc2 20-May-2014 Changes from 3.1.5-rc1 diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index 4275ddb7109d46..2a90c7f3a685e3 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -43,7 +43,13 @@ Sub::Sub() #if CONFIG_HAL_BOARD != HAL_BOARD_SITL failsafe.pilot_input = true; #endif + if (_singleton != nullptr) { + AP_HAL::panic("Can only be one Sub"); + } + _singleton = this; } +Sub *Sub::_singleton = nullptr; + Sub sub; AP_Vehicle& vehicle = sub; diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index a9864acbc53b2b..2e4c3a41360444 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -72,6 +72,7 @@ #include "AP_Arming_Sub.h" #include "GCS_Sub.h" #include "mode.h" +#include "script_button.h" #include // Optical Flow library @@ -295,6 +296,9 @@ class Sub : public AP_Vehicle { // Navigation Yaw control // auto flight mode's yaw mode uint8_t auto_yaw_mode; + + // Parameter to set yaw rate only + bool yaw_rate_only; // Yaw will point at this location if auto_yaw_mode is set to AUTO_YAW_ROI Vector3f roi_WP; @@ -526,7 +530,7 @@ class Sub : public AP_Vehicle { uint16_t get_pilot_speed_dn() const; void convert_old_parameters(void); - bool handle_do_motor_test(mavlink_command_long_t command); + bool handle_do_motor_test(mavlink_command_int_t command); bool init_motor_test(); bool verify_motor_test(); @@ -577,8 +581,26 @@ class Sub : public AP_Vehicle { AutoSubMode auto_mode; // controls which auto controller is run GuidedSubMode guided_mode; +#if AP_SCRIPTING_ENABLED + ScriptButton script_buttons[4]; +#endif // AP_SCRIPTING_ENABLED + public: void mainloop_failsafe_check(); + + static Sub *_singleton; + + static Sub *get_singleton() { + return _singleton; + } + +#if AP_SCRIPTING_ENABLED + // For Lua scripting, so index is 1..4, not 0..3 + bool is_button_pressed(uint8_t index); + + // For Lua scripting, so index is 1..4, not 0..3 + uint8_t get_and_clear_button_count(uint8_t index); +#endif // AP_SCRIPTING_ENABLED }; extern const AP_HAL::HAL& hal; diff --git a/ArduSub/commands_logic.cpp b/ArduSub/commands_logic.cpp index f35eac79675ef5..681022a3dd93bf 100644 --- a/ArduSub/commands_logic.cpp +++ b/ArduSub/commands_logic.cpp @@ -401,7 +401,11 @@ void Sub::do_nav_delay(const AP_Mission::Mission_Command& cmd) nav_delay_time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds } else { // absolute delay to utc time +#if AP_RTC_ENABLED nav_delay_time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0); +#else + nav_delay_time_max_ms = 0; +#endif } gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000)); } diff --git a/ArduSub/defines.h b/ArduSub/defines.h index 20224305a97491..87e45820bc9828 100644 --- a/ArduSub/defines.h +++ b/ArduSub/defines.h @@ -26,7 +26,8 @@ enum autopilot_yaw_mode { AUTO_YAW_LOOK_AT_HEADING = 3, // point towards a particular angle (not pilot input accepted) AUTO_YAW_LOOK_AHEAD = 4, // point in the direction the vehicle is moving AUTO_YAW_RESETTOARMEDYAW = 5, // point towards heading at time motors were armed - AUTO_YAW_CORRECT_XTRACK = 6 // steer the sub in order to correct for crosstrack error during line following + AUTO_YAW_CORRECT_XTRACK = 6, // steer the sub in order to correct for crosstrack error during line following + AUTO_YAW_RATE = 7 // steer the sub with the desired yaw rate }; // Acro Trainer types @@ -38,7 +39,7 @@ enum autopilot_yaw_mode { #define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received) #define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl #define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL 2 // auto pilot will face next waypoint except when doing RTL at which time it will stay in it's last -#define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicotpers) +#define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicopters) #define WP_YAW_BEHAVIOR_CORRECT_XTRACK 4 // point towards intermediate position target during line following diff --git a/ArduSub/joystick.cpp b/ArduSub/joystick.cpp index 5f0f83fe9de98f..f10d7d3a451089 100644 --- a/ArduSub/joystick.cpp +++ b/ArduSub/joystick.cpp @@ -593,6 +593,21 @@ void Sub::handle_jsbutton_press(uint8_t _button, bool shift, bool held) case JSButton::button_function_t::k_custom_6: // Not implemented break; + +#if AP_SCRIPTING_ENABLED + case JSButton::button_function_t::k_script_1: + sub.script_buttons[0].press(); + break; + case JSButton::button_function_t::k_script_2: + sub.script_buttons[1].press(); + break; + case JSButton::button_function_t::k_script_3: + sub.script_buttons[2].press(); + break; + case JSButton::button_function_t::k_script_4: + sub.script_buttons[3].press(); + break; +#endif // AP_SCRIPTING_ENABLED } } @@ -637,6 +652,21 @@ void Sub::handle_jsbutton_release(uint8_t _button, bool shift) { } break; #endif + +#if AP_SCRIPTING_ENABLED + case JSButton::button_function_t::k_script_1: + sub.script_buttons[0].release(); + break; + case JSButton::button_function_t::k_script_2: + sub.script_buttons[1].release(); + break; + case JSButton::button_function_t::k_script_3: + sub.script_buttons[2].release(); + break; + case JSButton::button_function_t::k_script_4: + sub.script_buttons[3].release(); + break; +#endif // AP_SCRIPTING_ENABLED } } @@ -730,3 +760,15 @@ void Sub::clear_input_hold() zTrim = 0; input_hold_engaged = false; } + +#if AP_SCRIPTING_ENABLED +bool Sub::is_button_pressed(uint8_t index) +{ + return script_buttons[index - 1].is_pressed(); +} + +uint8_t Sub::get_and_clear_button_count(uint8_t index) +{ + return script_buttons[index - 1].get_and_clear_count(); +} +#endif // AP_SCRIPTING_ENABLED diff --git a/ArduSub/mode.h b/ArduSub/mode.h index ffe01a525e4dba..584f5b26d315db 100644 --- a/ArduSub/mode.h +++ b/ArduSub/mode.h @@ -291,9 +291,13 @@ class ModeGuided : public Mode void guided_set_angle(const Quaternion&, float); void guided_limit_set(uint32_t timeout_ms, float alt_min_cm, float alt_max_cm, float horiz_max_cm); bool guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity); + bool 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); bool guided_set_destination(const Vector3f& destination); bool guided_set_destination(const Location&); + bool guided_set_destination(const Vector3f& destination, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw); void guided_set_velocity(const Vector3f& velocity); + void guided_set_velocity(const Vector3f& velocity, bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_yaw); + void guided_set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle); float get_auto_heading(); void guided_limit_clear(); void set_auto_yaw_mode(autopilot_yaw_mode yaw_mode); @@ -340,6 +344,7 @@ class ModeAuto : public ModeGuided void auto_nav_guided_start(); void set_auto_yaw_roi(const Location &roi_location); void set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, int8_t direction, uint8_t relative_angle); + void set_yaw_rate(float turn_rate_dps); bool auto_terrain_recover_start(); protected: diff --git a/ArduSub/mode_auto.cpp b/ArduSub/mode_auto.cpp index 4370e1dfd8d5ba..87ad912976b5cf 100644 --- a/ArduSub/mode_auto.cpp +++ b/ArduSub/mode_auto.cpp @@ -345,7 +345,7 @@ void ModeAuto::auto_loiter_run() // set_auto_yaw_look_at_heading - sets the yaw look at heading for auto mode void ModeAuto::set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps, int8_t direction, uint8_t relative_angle) { - // get current yaw target + // get current yaw int32_t curr_yaw_target = attitude_control->get_att_target_euler_cd().z; // get final angle, 1 = Relative, 0 = Absolute @@ -357,18 +357,15 @@ void ModeAuto::set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps if (direction < 0) { angle_deg = -angle_deg; } - sub.yaw_look_at_heading = wrap_360_cd((angle_deg*100+curr_yaw_target)); + sub.yaw_look_at_heading = wrap_360_cd((angle_deg * 100 + curr_yaw_target)); } // get turn speed - // TODO actually implement this, right now, yaw_look_at_heading_slew is unused - // see AP_Float _slew_yaw in AC_AttitudeControl if (is_zero(turn_rate_dps)) { // default to regular auto slew rate sub.yaw_look_at_heading_slew = AUTO_YAW_SLEW_RATE; } else { - int32_t turn_rate = (wrap_180_cd(sub.yaw_look_at_heading - curr_yaw_target) / 100) / turn_rate_dps; - sub.yaw_look_at_heading_slew = constrain_int32(turn_rate, 1, 360); // deg / sec + sub.yaw_look_at_heading_slew = MIN(turn_rate_dps, AUTO_YAW_SLEW_RATE); // deg / sec } // set yaw mode @@ -377,6 +374,17 @@ void ModeAuto::set_auto_yaw_look_at_heading(float angle_deg, float turn_rate_dps // TO-DO: restore support for clockwise and counter clockwise rotation held in cmd.content.yaw.direction. 1 = clockwise, -1 = counterclockwise } + +// sets the desired yaw rate +void ModeAuto::set_yaw_rate(float turn_rate_dps) +{ + // set sub to desired yaw rate + sub.yaw_look_at_heading_slew = MIN(turn_rate_dps, AUTO_YAW_SLEW_RATE); // deg / sec + + // set yaw mode + set_auto_yaw_mode(AUTO_YAW_RATE); +} + // set_auto_yaw_roi - sets the yaw to look at roi for auto mode void ModeAuto::set_auto_yaw_roi(const Location &roi_location) { diff --git a/ArduSub/mode_guided.cpp b/ArduSub/mode_guided.cpp index 4c65cca42c77f3..25857bf5c94e64 100644 --- a/ArduSub/mode_guided.cpp +++ b/ArduSub/mode_guided.cpp @@ -109,6 +109,9 @@ void ModeGuided::guided_vel_control_start() // initialise velocity controller position_control->init_z_controller(); position_control->init_xy_controller(); + + // pilot always controls yaw + set_auto_yaw_mode(AUTO_YAW_HOLD); } // initialise guided mode's posvel controller @@ -213,6 +216,39 @@ bool ModeGuided::guided_set_destination(const Location& dest_loc) return true; } +// guided_set_destination - sets guided mode's target destination and target heading +// Returns true if the fence is enabled and guided waypoint is within the fence +// 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); + if (!sub.fence.check_destination_within_fence(dest_loc)) { + AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); + // failure is propagated to GCS with NAK + return false; + } +#endif + + // set yaw state + guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw); + + update_time_ms = AP_HAL::millis(); + + // no need to check return status because terrain data is not used + sub.wp_nav.set_wp_destination(destination, false); + + // log target + sub.Log_Write_GuidedTarget(sub.guided_mode, destination, Vector3f()); + return true; +} + // guided_set_velocity - sets guided mode's target velocity void ModeGuided::guided_set_velocity(const Vector3f& velocity) { @@ -227,6 +263,24 @@ void ModeGuided::guided_set_velocity(const Vector3f& velocity) position_control->set_vel_desired_cms(velocity); } +// guided_set_velocity - sets guided mode's target velocity +void ModeGuided::guided_set_velocity(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_Velocity) { + guided_vel_control_start(); + } + + // set yaw state + guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw); + + update_time_ms = AP_HAL::millis(); + + // set position controller velocity target + position_control->set_vel_desired_cms(velocity); + +} + // set guided mode posvel target bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, const Vector3f& velocity) { @@ -259,6 +313,42 @@ bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, cons return true; } +// 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); + if (!sub.fence.check_destination_within_fence(dest_loc)) { + AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); + // failure is propagated to GCS with NAK + return false; + } + #endif + + // set yaw state + guided_set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw); + + update_time_ms = AP_HAL::millis(); + + posvel_pos_target_cm = destination.topostype(); + posvel_vel_target_cms = velocity; + + position_control->input_pos_vel_accel_xy(posvel_pos_target_cm.xy(), posvel_vel_target_cms.xy(), Vector2f()); + float dz = posvel_pos_target_cm.z; + position_control->input_pos_vel_accel_z(dz, posvel_vel_target_cms.z, 0); + posvel_pos_target_cm.z = dz; + + // log target + sub.Log_Write_GuidedTarget(sub.guided_mode, destination, velocity); + return true; +} + // set guided mode angle target void ModeGuided::guided_set_angle(const Quaternion &q, float climb_rate_cms) { @@ -277,6 +367,44 @@ void ModeGuided::guided_set_angle(const Quaternion &q, float climb_rate_cms) guided_angle_state.update_time_ms = AP_HAL::millis(); } +// helper function to set yaw state and targets +void ModeGuided::guided_set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle) +{ + float current_yaw = wrap_2PI(AP::ahrs().get_yaw()); + float euler_yaw_angle; + float yaw_error; + + euler_yaw_angle = wrap_2PI((yaw_cd * 0.01f)); + yaw_error = wrap_PI(euler_yaw_angle - current_yaw); + + int direction = 0; + if (yaw_error < 0){ + direction = -1; + } else { + direction = 1; + } + + /* + case 1: target yaw only + case 2: target yaw and yaw rate + case 3: target yaw rate only + case 4: hold current yaw + */ + if (use_yaw && !use_yaw_rate) { + sub.yaw_rate_only = false; + sub.mode_auto.set_auto_yaw_look_at_heading(yaw_cd * 0.01f, 0.0f, direction, relative_angle); + } else if (use_yaw && use_yaw_rate) { + sub.yaw_rate_only = false; + sub.mode_auto.set_auto_yaw_look_at_heading(yaw_cd * 0.01f, yaw_rate_cds * 0.01f, direction, relative_angle); + } else if (!use_yaw && use_yaw_rate) { + sub.yaw_rate_only = true; + sub.mode_auto.set_yaw_rate(yaw_rate_cds * 0.01f); + } else{ + sub.yaw_rate_only = false; + set_auto_yaw_mode(AUTO_YAW_HOLD); + } +} + // guided_run - runs the guided controller // should be called at 100hz or more void ModeGuided::run() @@ -327,6 +455,12 @@ void ModeGuided::guided_pos_control_run() target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if (!is_zero(target_yaw_rate)) { set_auto_yaw_mode(AUTO_YAW_HOLD); + } else{ + if (sub.yaw_rate_only){ + set_auto_yaw_mode(AUTO_YAW_RATE); + } else{ + set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING); + } } } @@ -351,6 +485,14 @@ void ModeGuided::guided_pos_control_run() if (sub.auto_yaw_mode == AUTO_YAW_HOLD) { // roll & pitch & yaw rate from pilot attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate); + } else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) { + // roll, pitch from pilot, yaw & yaw_rate from auto_control + target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0; + attitude_control->input_euler_angle_roll_pitch_slew_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate); + } else if (sub.auto_yaw_mode == AUTO_YAW_RATE) { + // roll, pitch from pilot, yaw_rate from auto_control + target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0; + attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate); } else { // roll, pitch from pilot, yaw heading from auto_heading() attitude_control->input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true); @@ -380,6 +522,12 @@ void ModeGuided::guided_vel_control_run() target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if (!is_zero(target_yaw_rate)) { set_auto_yaw_mode(AUTO_YAW_HOLD); + } else{ + if (sub.yaw_rate_only){ + set_auto_yaw_mode(AUTO_YAW_RATE); + } else{ + set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING); + } } } @@ -395,6 +543,8 @@ void ModeGuided::guided_vel_control_run() position_control->stop_pos_xy_stabilisation(); // call velocity controller which includes z axis controller position_control->update_xy_controller(); + + position_control->set_pos_target_z_from_climb_rate_cm(position_control->get_vel_desired_cms().z); position_control->update_z_controller(); float lateral_out, forward_out; @@ -408,6 +558,14 @@ void ModeGuided::guided_vel_control_run() if (sub.auto_yaw_mode == AUTO_YAW_HOLD) { // roll & pitch & yaw rate from pilot attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate); + } else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) { + // roll, pitch from pilot, yaw & yaw_rate from auto_control + target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0; + attitude_control->input_euler_angle_roll_pitch_slew_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate); + } else if (sub.auto_yaw_mode == AUTO_YAW_RATE) { + // roll, pitch from pilot, yaw_rate from auto_control + target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0; + attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate); } else { // roll, pitch from pilot, yaw heading from auto_heading() attitude_control->input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true); @@ -438,6 +596,12 @@ void ModeGuided::guided_posvel_control_run() target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if (!is_zero(target_yaw_rate)) { set_auto_yaw_mode(AUTO_YAW_HOLD); + } else{ + if (sub.yaw_rate_only){ + set_auto_yaw_mode(AUTO_YAW_RATE); + } else{ + set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING); + } } } @@ -474,6 +638,14 @@ void ModeGuided::guided_posvel_control_run() if (sub.auto_yaw_mode == AUTO_YAW_HOLD) { // roll & pitch & yaw rate from pilot attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate); + } else if (sub.auto_yaw_mode == AUTO_YAW_LOOK_AT_HEADING) { + // roll, pitch from pilot, yaw & yaw_rate from auto_control + target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0; + attitude_control->input_euler_angle_roll_pitch_slew_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), target_yaw_rate); + } else if (sub.auto_yaw_mode == AUTO_YAW_RATE) { + // roll, pitch from pilot, and yaw_rate from auto_control + target_yaw_rate = sub.yaw_look_at_heading_slew * 100.0; + attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate); } else { // roll, pitch from pilot, yaw heading from auto_heading() attitude_control->input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), get_auto_heading(), true); @@ -554,6 +726,10 @@ void ModeGuided::set_auto_yaw_mode(autopilot_yaw_mode yaw_mode) // perform initialisation switch (sub.auto_yaw_mode) { + + case AUTO_YAW_HOLD: + // pilot controls the heading + break; case AUTO_YAW_LOOK_AT_NEXT_WP: // wpnav will initialise heading when wpnav's set_destination method is called @@ -577,6 +753,10 @@ void ModeGuided::set_auto_yaw_mode(autopilot_yaw_mode yaw_mode) case AUTO_YAW_RESETTOARMEDYAW: // initial_armed_bearing will be set during arming so no init required break; + + case AUTO_YAW_RATE: + // set target yaw rate to yaw_look_at_heading_slew + break; } } diff --git a/ArduSub/mode_poshold.cpp b/ArduSub/mode_poshold.cpp index 8c1b389464c1ab..b85e359ede568c 100644 --- a/ArduSub/mode_poshold.cpp +++ b/ArduSub/mode_poshold.cpp @@ -93,7 +93,7 @@ void ModePoshold::run() } else { // hold current heading - // this check is required to prevent bounce back after very fast yaw maneuvers + // this check is required to prevent bounce back after very fast yaw manoeuvres // the inertia of the vehicle causes the heading to move slightly past the point when pilot input actually stopped if (tnow < sub.last_pilot_yaw_input_ms + 250) { // give 250ms to slow down, then set target heading target_yaw_rate = 0; // Stop rotation on yaw axis diff --git a/ArduSub/motors.cpp b/ArduSub/motors.cpp index 9e25f51513e605..895ade8c8c53b5 100644 --- a/ArduSub/motors.cpp +++ b/ArduSub/motors.cpp @@ -78,7 +78,7 @@ bool Sub::verify_motor_test() return true; } -bool Sub::handle_do_motor_test(mavlink_command_long_t command) { +bool Sub::handle_do_motor_test(mavlink_command_int_t command) { last_do_motor_test_ms = AP_HAL::millis(); // If we are not already testing motors, initialize test @@ -103,9 +103,9 @@ bool Sub::handle_do_motor_test(mavlink_command_long_t command) { float throttle = command.param3; // float timeout_s = command.param4; // not used // float motor_count = command.param5; // not used - float test_type = command.param6; + const uint32_t test_type = command.y; - if (!is_equal(test_type, (float)MOTOR_TEST_ORDER_BOARD)) { + if (test_type != MOTOR_TEST_ORDER_BOARD) { gcs().send_text(MAV_SEVERITY_WARNING, "bad test type %0.2f", (double)test_type); return false; // test type not supported here } diff --git a/ArduSub/script_button.cpp b/ArduSub/script_button.cpp new file mode 100644 index 00000000000000..fa8f85079636d0 --- /dev/null +++ b/ArduSub/script_button.cpp @@ -0,0 +1,47 @@ +#include "AP_Scripting/AP_Scripting_config.h" + +#if AP_SCRIPTING_ENABLED + +#include +#include "script_button.h" + +void ScriptButton::press() +{ + if (!pressed) { + pressed = true; + + // The count will max out at 255, but it won't roll over to 0. + if (count < std::numeric_limits::max()) { + count++; + } + } +} + +void ScriptButton::release() +{ + pressed = false; +} + +bool ScriptButton::is_pressed() const +{ + return pressed; +} + +uint8_t ScriptButton::get_count() const +{ + return count; +} + +void ScriptButton::clear_count() +{ + count = 0; +} + +uint8_t ScriptButton::get_and_clear_count() +{ + auto result = get_count(); + clear_count(); + return result; +} + +#endif // AP_SCRIPTING_ENABLED diff --git a/ArduSub/script_button.h b/ArduSub/script_button.h new file mode 100644 index 00000000000000..31a08a24004096 --- /dev/null +++ b/ArduSub/script_button.h @@ -0,0 +1,34 @@ +#pragma once + +#if AP_SCRIPTING_ENABLED + +#include + +// Joystick button object for use in Lua scripts. +// +// Provide 2 ways to use a joystick button: +// is_pressed() returns true if the button is currently (as of the most recent MANUAL_CONTROL msg) pressed +// get_and_clear_count() returns the number of times the button was pressed since the last call +// +class ScriptButton { +public: + ScriptButton(): pressed(false), count(0) {} + + void press(); + + void release(); + + bool is_pressed() const WARN_IF_UNUSED; + + uint8_t get_count() const WARN_IF_UNUSED; + + void clear_count(); + + uint8_t get_and_clear_count(); + +private: + bool pressed; + uint8_t count; +}; + +#endif // AP_SCRIPTING_ENABLED diff --git a/BUILD.md b/BUILD.md index 3ddaaef4ee096a..9124d7acb7d3d1 100644 --- a/BUILD.md +++ b/BUILD.md @@ -163,6 +163,18 @@ list some basic and more used commands as example. ./waf --targets tests/test_math ``` +* **Use clang instead of gcc** + + Currently, gcc is the default on linux, and clang is used for MacOS. + Building with clang on linux can be accomplished by setting the CXX + environment variables during the configure step, e.g.: + + ``` + CXX=clang++ CC=clang ./waf configure --board=sitl + ``` + + Note: Your clang binary names may differ. + * **Other options** It's possible to see all available commands and options: diff --git a/Blimp/AP_Arming.cpp b/Blimp/AP_Arming.cpp index c72d250cc2dbc8..ea36c2c1f0d873 100644 --- a/Blimp/AP_Arming.cpp +++ b/Blimp/AP_Arming.cpp @@ -107,7 +107,7 @@ bool AP_Arming_Blimp::parameter_checks(bool display_failure) // failsafe parameter checks if (blimp.g.failsafe_throttle) { // check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900 - if (blimp.channel_down->get_radio_min() <= blimp.g.failsafe_throttle_value+10 || blimp.g.failsafe_throttle_value < 910) { + if (blimp.channel_up->get_radio_min() <= blimp.g.failsafe_throttle_value+10 || blimp.g.failsafe_throttle_value < 910) { check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check FS_THR_VALUE"); return false; } diff --git a/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index c923e0ea61f94b..ff5327006738d9 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -53,7 +53,7 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = { FAST_TASK_CLASS(AP_InertialSensor, &blimp.ins, update), // send outputs to the motors library immediately FAST_TASK(motors_output), - // run EKF state estimator (expensive) + // run EKF state estimator (expensive) FAST_TASK(read_AHRS), // Inertial Nav FAST_TASK(read_inertia), @@ -217,12 +217,27 @@ void Blimp::read_AHRS(void) ahrs.update(true); IGNORE_RETURN(ahrs.get_velocity_NED(vel_ned)); - IGNORE_RETURN(ahrs.get_relative_position_NED_home(pos_ned)); + IGNORE_RETURN(ahrs.get_relative_position_NED_origin(pos_ned)); vel_yaw = ahrs.get_yaw_rate_earth(); Vector2f vel_xy_filtd = vel_xy_filter.apply({vel_ned.x, vel_ned.y}); vel_ned_filtd = {vel_xy_filtd.x, vel_xy_filtd.y, vel_z_filter.apply(vel_ned.z)}; vel_yaw_filtd = vel_yaw_filter.apply(vel_yaw); + + AP::logger().WriteStreaming("VNF", "TimeUS,X,XF,Y,YF,Z,ZF,Yaw,YawF,PX,PY,PZ,PYaw", "Qffffffffffff", + AP_HAL::micros64(), + vel_ned.x, + vel_ned_filtd.x, + vel_ned.y, + vel_ned_filtd.y, + vel_ned.z, + vel_ned_filtd.z, + vel_yaw, + vel_yaw_filtd, + pos_ned.x, + pos_ned.y, + pos_ned.z, + blimp.ahrs.get_yaw()); } // read baro and log control tuning diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index 0c6e7a2627e37e..32ac39b5bddf4f 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -59,6 +59,7 @@ #include "config.h" #include "Fins.h" +#include "Loiter.h" #include "RC_Channel.h" // RC Channel Library @@ -91,8 +92,10 @@ class Blimp : public AP_Vehicle friend class ModeLand; friend class ModeVelocity; friend class ModeLoiter; + friend class ModeRTL; friend class Fins; + friend class Loiter; Blimp(void); @@ -108,7 +111,7 @@ class Blimp : public AP_Vehicle // primary input control channels RC_Channel *channel_right; RC_Channel *channel_front; - RC_Channel *channel_down; + RC_Channel *channel_up; RC_Channel *channel_yaw; AP_Logger logger; @@ -172,7 +175,7 @@ class Blimp : public AP_Vehicle RCMapper rcmap; - // intertial nav alt when we armed + // inertial nav alt when we armed float arming_altitude_m; // Failsafe @@ -191,6 +194,7 @@ class Blimp : public AP_Vehicle // Motor Output Fins *motors; + Loiter *loiter; int32_t _home_bearing; uint32_t _home_distance; @@ -360,8 +364,8 @@ class Blimp : 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_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target); - void Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out); - void Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z); + + void Log_Write_Vehicle_Startup_Messages(); void log_init(void); void Write_FINI(float right, float front, float down, float yaw); @@ -378,7 +382,7 @@ class Blimp : public AP_Vehicle void notify_flight_mode(); // mode_land.cpp - void set_mode_land_with_pause(ModeReason reason); + void set_mode_land_failsafe(ModeReason reason); bool landing_with_GPS(); // // motors.cpp @@ -430,6 +434,7 @@ class Blimp : public AP_Vehicle ModeLand mode_land; ModeVelocity mode_velocity; ModeLoiter mode_loiter; + ModeRTL mode_rtl; // mode.cpp Mode *mode_from_mode_num(const Mode::Number mode); diff --git a/Blimp/Fins.h b/Blimp/Fins.h index e51a465b3690b9..89541eea7cd97d 100644 --- a/Blimp/Fins.h +++ b/Blimp/Fins.h @@ -10,6 +10,7 @@ class Fins { public: friend class Blimp; + friend class Loiter; enum motor_frame_class { MOTOR_FRAME_UNDEFINED = 0, @@ -49,7 +50,7 @@ class Fins uint16_t _speed_hz; // speed in hz to send updates to motors float _throttle_avg_max; // last throttle input from set_throttle_avg_max - float _time; //current timestep + float _time; // current timestamp bool _armed; // 0 if disarmed, 1 if armed @@ -70,7 +71,7 @@ class Fins int8_t _num_added; -//MIR This should probably become private in future. + //MIR This should probably become private in future. public: float right_out; //input right movement, negative for left, +1 to -1 float front_out; //input front/forwards movement, negative for backwards, +1 to -1 @@ -95,7 +96,7 @@ class Fins float get_throttle() { //Only for Mavlink - essentially just an indicator of how hard the fins are working. - //Note that this is the unconstrained version, so if the higher level control gives too high input, + //Note that this is the unconstrained version, so if the higher level control gives too high input, //throttle will be displayed as more than 100. return fmaxf(fmaxf(fabsf(down_out),fabsf(front_out)), fmaxf(fabsf(right_out),fabsf(yaw_out))); } diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index ed97aaa8971e12..78442c9aaabb77 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -52,8 +52,8 @@ void GCS_MAVLINK_Blimp::send_position_target_global_int() } static constexpr uint16_t POSITION_TARGET_TYPEMASK_LAST_BYTE = 0xF000; static constexpr uint16_t TYPE_MASK = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE | - POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE | - POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE; + POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE | + POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE; mavlink_msg_position_target_global_int_send( chan, @@ -102,11 +102,11 @@ int16_t GCS_MAVLINK_Blimp::vfr_hud_throttle() const */ void GCS_MAVLINK_Blimp::send_pid_tuning() { - if(blimp.control_mode == Mode::Number::MANUAL || blimp.control_mode == Mode::Number::LAND) { + if (blimp.control_mode == Mode::Number::MANUAL || blimp.control_mode == Mode::Number::LAND) { //No PIDs are used in Manual or Land mode. return; } - + static const int8_t axes[] = { PID_SEND::VELX, PID_SEND::VELY, @@ -323,7 +323,9 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_GPS2_RAW, MSG_GPS2_RTK, MSG_NAV_CONTROLLER_OUTPUT, +#if AP_FENCE_ENABLED MSG_FENCE_STATUS, +#endif MSG_POSITION_TARGET_GLOBAL_INT, }; static const ap_message STREAM_POSITION_msgs[] = { @@ -353,8 +355,10 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_BATTERY_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_OPTICAL_FLOW, +#if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, +#endif MSG_EKF_STATUS_REPORT, MSG_VIBRATION, #if AP_RPM_ENABLED @@ -417,7 +421,7 @@ void GCS_MAVLINK_Blimp::send_banner() send_text(MAV_SEVERITY_INFO, "Frame: %s", blimp.get_frame_string()); } -MAV_RESULT GCS_MAVLINK_Blimp::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK_Blimp::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg); } @@ -466,20 +470,17 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_do_reposition(const mavlink_com return MAV_RESULT_ACCEPTED; } -MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_packet(const mavlink_command_int_t &packet) +MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch (packet.command) { - case MAV_CMD_DO_FOLLOW: - return MAV_RESULT_UNSUPPORTED; - case MAV_CMD_DO_REPOSITION: return handle_command_int_do_reposition(packet); default: - return GCS_MAVLINK::handle_command_int_packet(packet); + return GCS_MAVLINK::handle_command_int_packet(packet, msg); } } -MAV_RESULT GCS_MAVLINK_Blimp::handle_command_long_packet(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Blimp::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) { switch (packet.command) { @@ -505,7 +506,7 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_long_packet(const mavlink_command_l return MAV_RESULT_FAILED; default: - return GCS_MAVLINK::handle_command_long_packet(packet); + return GCS_MAVLINK::handle_command_long_packet(packet, msg); } } @@ -530,7 +531,7 @@ void GCS_MAVLINK_Blimp::handleMessage(const mavlink_message_t &msg) } // end handle mavlink -MAV_RESULT GCS_MAVLINK_Blimp::handle_flight_termination(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Blimp::handle_flight_termination(const mavlink_command_int_t &packet) { MAV_RESULT result = MAV_RESULT_FAILED; if (packet.param1 > 0.5f) { diff --git a/Blimp/GCS_Mavlink.h b/Blimp/GCS_Mavlink.h index 036fe4066645d4..ed406ac0f93661 100644 --- a/Blimp/GCS_Mavlink.h +++ b/Blimp/GCS_Mavlink.h @@ -13,7 +13,7 @@ class GCS_MAVLINK_Blimp : public GCS_MAVLINK uint32_t telem_delay() const override; - MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override; uint8_t sysid_my_gcs() const override; bool sysid_enforce() const override; @@ -21,13 +21,13 @@ class GCS_MAVLINK_Blimp : public GCS_MAVLINK bool params_ready() const override; void send_banner() override; - MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; + MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; void send_position_target_global_int() override; MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override; - MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override; - MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; + MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet); @@ -73,7 +73,7 @@ class GCS_MAVLINK_Blimp : public GCS_MAVLINK POSZ = 7, POSYAW = 8, }; - + #if HAL_HIGH_LATENCY2_ENABLED uint8_t high_latency_wind_speed() const override; uint8_t high_latency_wind_direction() const override; diff --git a/Blimp/Log.cpp b/Blimp/Log.cpp index 6b74b028fd2e2f..01a3e0f3e7b293 100644 --- a/Blimp/Log.cpp +++ b/Blimp/Log.cpp @@ -30,7 +30,7 @@ struct PACKED log_FINO { //Write a fin input packet void Blimp::Write_FINI(float right, float front, float down, float yaw) { - const struct log_FINI pkt{ + const struct log_FINI pkt { LOG_PACKET_HEADER_INIT(LOG_FINI_MSG), time_us : AP_HAL::micros64(), Right : right, @@ -44,7 +44,7 @@ void Blimp::Write_FINI(float right, float front, float down, float yaw) //Write a fin output packet void Blimp::Write_FINO(float *amp, float *off) { - const struct log_FINO pkt{ + const struct log_FINO pkt { LOG_PACKET_HEADER_INIT(LOG_FINO_MSG), time_us : AP_HAL::micros64(), Fin1_Amp : amp[0], @@ -92,7 +92,9 @@ void Blimp::Log_Write_PIDs() // Write an attitude packet void Blimp::Log_Write_Attitude() { - + //Attitude targets are all zero since Blimp doesn't have attitude control, + //but the rest of the log message is useful. + ahrs.Write_Attitude(Vector3f{0,0,0}); } // Write an EKF and POS packet @@ -232,7 +234,6 @@ tuning_max : tune_max logger.WriteBlock(&pkt_tune, sizeof(pkt_tune)); } - // type and unit information can be found in // libraries/AP_Logger/Logstructure.h; search for "log_Units" for // units and "Format characters" for field type information @@ -247,8 +248,10 @@ const struct LogStructure Blimp::log_structure[] = { // @Field: D: Down // @Field: Y: Yaw - { LOG_FINI_MSG, sizeof(log_FINI), - "FINI", "Qffff", "TimeUS,R,F,D,Y", "s----", "F----" }, + { + LOG_FINI_MSG, sizeof(log_FINI), + "FINI", "Qffff", "TimeUS,R,F,D,Y", "s----", "F----" + }, // @LoggerMessage: FINO // @Description: Fin output @@ -262,8 +265,10 @@ const struct LogStructure Blimp::log_structure[] = { // @Field: F4A: Fin 4 Amplitude // @Field: F4O: Fin 4 Offset - { LOG_FINO_MSG, sizeof(log_FINO), - "FINO", "Qffffffff", "TimeUS,F1A,F1O,F2A,F2O,F3A,F3O,F4A,F4O", "s--------", "F--------" }, + { + LOG_FINO_MSG, sizeof(log_FINO), + "FINO", "Qffffffff", "TimeUS,F1A,F1O,F2A,F2O,F3A,F3O,F4A,F4O", "s--------", "F--------" + }, // @LoggerMessage: PIDD,PIVN,PIVE,PIVD,PIVY // @Description: Proportional/Integral/Derivative gain values @@ -277,17 +282,28 @@ const struct LogStructure Blimp::log_structure[] = { // @Field: FF: controller feed-forward portion of response // @Field: Dmod: scaler applied to D gain to reduce limit cycling // @Field: SRate: slew rate - // @Field: Limit: 1 if I term is limited due to output saturation - { LOG_PIDD_MSG, sizeof(log_PID), - "PIDD", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, - { LOG_PIVN_MSG, sizeof(log_PID), - "PIVN", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, - { LOG_PIVE_MSG, sizeof(log_PID), - "PIVE", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, - { LOG_PIVD_MSG, sizeof(log_PID), - "PIVD", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, - { LOG_PIVY_MSG, sizeof(log_PID), - "PIVY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS }, + // @Field: Flags: bitmask of PID state flags + // @FieldBitmaskEnum: Flags: log_PID_Flags + { + LOG_PIDD_MSG, sizeof(log_PID), + "PIDD", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS + }, + { + LOG_PIVN_MSG, sizeof(log_PID), + "PIVN", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS + }, + { + LOG_PIVE_MSG, sizeof(log_PID), + "PIVE", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS + }, + { + LOG_PIVD_MSG, sizeof(log_PID), + "PIVD", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS + }, + { + LOG_PIVY_MSG, sizeof(log_PID), + "PIVY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS + }, // @LoggerMessage: PTUN // @Description: Parameter Tuning information @@ -403,8 +419,6 @@ void Blimp::Log_Write_Data(LogDataID id, uint16_t value) {} void Blimp::Log_Write_Data(LogDataID id, float value) {} void Blimp::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max) {} void Blimp::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {} -void Blimp::Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out) {} -void Blimp::Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z) {} void Blimp::Log_Write_Vehicle_Startup_Messages() {} void Blimp::log_init(void) {} diff --git a/Blimp/Loiter.cpp b/Blimp/Loiter.cpp new file mode 100644 index 00000000000000..8c6b5d5e7aea7c --- /dev/null +++ b/Blimp/Loiter.cpp @@ -0,0 +1,202 @@ +#include "Blimp.h" + +#define MA 0.99 +#define MO (1-MA) + +void Loiter::run(Vector3f& target_pos, float& target_yaw, Vector4b axes_disabled) +{ + const float dt = blimp.scheduler.get_last_loop_time_s(); + + float scaler_xz_n; + float xz_out = fabsf(blimp.motors->front_out) + fabsf(blimp.motors->down_out); + if (xz_out > 1) { + scaler_xz_n = 1 / xz_out; + } else { + scaler_xz_n = 1; + } + scaler_xz = scaler_xz*MA + scaler_xz_n*MO; + + float scaler_yyaw_n; + float yyaw_out = fabsf(blimp.motors->right_out) + fabsf(blimp.motors->yaw_out); + if (yyaw_out > 1) { + scaler_yyaw_n = 1 / yyaw_out; + } else { + scaler_yyaw_n = 1; + } + scaler_yyaw = scaler_yyaw*MA + scaler_yyaw_n*MO; + + AP::logger().WriteStreaming("BSC", "TimeUS,xz,yyaw,xzn,yyawn", + "Qffff", + AP_HAL::micros64(), + scaler_xz, scaler_yyaw, scaler_xz_n, scaler_yyaw_n); + + float yaw_ef = blimp.ahrs.get_yaw(); + Vector3f err_xyz = target_pos - blimp.pos_ned; + float err_yaw = wrap_PI(target_yaw - yaw_ef); + + Vector4b zero; + if ((fabsf(err_xyz.x) < blimp.g.pid_dz) || !blimp.motors->_armed || (blimp.g.dis_mask & (1<<(2-1)))) { + zero.x = true; + } + if ((fabsf(err_xyz.y) < blimp.g.pid_dz) || !blimp.motors->_armed || (blimp.g.dis_mask & (1<<(1-1)))) { + zero.y = true; + } + if ((fabsf(err_xyz.z) < blimp.g.pid_dz) || !blimp.motors->_armed || (blimp.g.dis_mask & (1<<(3-1)))) { + zero.z = true; + } + if ((fabsf(err_yaw) < blimp.g.pid_dz) || !blimp.motors->_armed || (blimp.g.dis_mask & (1<<(4-1)))) { + zero.yaw = true; + } + + //Disabled means "don't update PIDs or output anything at all". Zero means actually output zero thrust. I term is limited in either case." + Vector4b limit = zero || axes_disabled; + + Vector3f target_vel_ef; + if (!axes_disabled.x && !axes_disabled.y) target_vel_ef = {blimp.pid_pos_xy.update_all(target_pos, blimp.pos_ned, dt, {(float)limit.x, (float)limit.y, (float)limit.z}), 0}; + if (!axes_disabled.z) { + target_vel_ef.z = blimp.pid_pos_z.update_all(target_pos.z, blimp.pos_ned.z, dt, limit.z); + } + + float target_vel_yaw = 0; + if (!axes_disabled.yaw) { + target_vel_yaw = blimp.pid_pos_yaw.update_error(wrap_PI(target_yaw - yaw_ef), dt, limit.yaw); + blimp.pid_pos_yaw.set_target_rate(target_yaw); + blimp.pid_pos_yaw.set_actual_rate(yaw_ef); + } + + Vector3f target_vel_ef_c{constrain_float(target_vel_ef.x, -blimp.g.max_vel_xy, blimp.g.max_vel_xy), + constrain_float(target_vel_ef.y, -blimp.g.max_vel_xy, blimp.g.max_vel_xy), + constrain_float(target_vel_ef.z, -blimp.g.max_vel_z, blimp.g.max_vel_z)}; + float target_vel_yaw_c = constrain_float(target_vel_yaw, -blimp.g.max_vel_yaw, blimp.g.max_vel_yaw); + + Vector2f target_vel_ef_c_scaled_xy = {target_vel_ef_c.x * scaler_xz, target_vel_ef_c.y * scaler_yyaw}; + Vector2f vel_ned_filtd_scaled_xy = {blimp.vel_ned_filtd.x * scaler_xz, blimp.vel_ned_filtd.y * scaler_yyaw}; + + Vector2f actuator; + if (!axes_disabled.x && !axes_disabled.y) actuator = blimp.pid_vel_xy.update_all(target_vel_ef_c_scaled_xy, vel_ned_filtd_scaled_xy, dt, {(float)limit.x, (float)limit.y}); + float act_down = 0; + if (!axes_disabled.z) { + act_down = blimp.pid_vel_z.update_all(target_vel_ef_c.z * scaler_xz, blimp.vel_ned_filtd.z * scaler_xz, dt, limit.z); + } + blimp.rotate_NE_to_BF(actuator); + float act_yaw = 0; + if (!axes_disabled.yaw) { + act_yaw = blimp.pid_vel_yaw.update_all(target_vel_yaw_c * scaler_yyaw, blimp.vel_yaw_filtd * scaler_yyaw, dt, limit.yaw); + } + + if (!blimp.motors->armed()) { + blimp.pid_pos_xy.set_integrator(Vector2f(0,0)); + blimp.pid_pos_z.set_integrator(0); + blimp.pid_pos_yaw.set_integrator(0); + blimp.pid_vel_xy.set_integrator(Vector2f(0,0)); + blimp.pid_vel_z.set_integrator(0); + blimp.pid_vel_yaw.set_integrator(0); + target_pos = blimp.pos_ned; + target_yaw = blimp.ahrs.get_yaw(); + } + + if (zero.x) { + blimp.motors->front_out = 0; + } else if (axes_disabled.x); + else { + blimp.motors->front_out = actuator.x; + } + if (zero.y) { + blimp.motors->right_out = 0; + } else if (axes_disabled.y); + else { + blimp.motors->right_out = actuator.y; + } + if (zero.z) { + blimp.motors->down_out = 0; + } else if (axes_disabled.z); + else { + blimp.motors->down_out = act_down; + } + if (zero.yaw) { + blimp.motors->yaw_out = 0; + } else if (axes_disabled.yaw); + else { + blimp.motors->yaw_out = act_yaw; + } + + AP::logger().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); + AP::logger().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); + AP::logger().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); +} + +void Loiter::run_vel(Vector3f& target_vel_ef, float& target_vel_yaw, Vector4b axes_disabled) +{ + const float dt = blimp.scheduler.get_last_loop_time_s(); + + Vector4b zero; + if (!blimp.motors->_armed || (blimp.g.dis_mask & (1<<(2-1)))) { + zero.x = true; + } + if (!blimp.motors->_armed || (blimp.g.dis_mask & (1<<(1-1)))) { + zero.y = true; + } + if (!blimp.motors->_armed || (blimp.g.dis_mask & (1<<(3-1)))) { + zero.z = true; + } + if (!blimp.motors->_armed || (blimp.g.dis_mask & (1<<(4-1)))) { + zero.yaw = true; + } + //Disabled means "don't update PIDs or output anything at all". Zero means actually output zero thrust. I term is limited in either case." + Vector4b limit = zero || axes_disabled; + + Vector3f target_vel_ef_c{constrain_float(target_vel_ef.x, -blimp.g.max_vel_xy, blimp.g.max_vel_xy), + constrain_float(target_vel_ef.y, -blimp.g.max_vel_xy, blimp.g.max_vel_xy), + constrain_float(target_vel_ef.z, -blimp.g.max_vel_z, blimp.g.max_vel_z)}; + float target_vel_yaw_c = constrain_float(target_vel_yaw, -blimp.g.max_vel_yaw, blimp.g.max_vel_yaw); + + Vector2f target_vel_ef_c_scaled_xy = {target_vel_ef_c.x * scaler_xz, target_vel_ef_c.y * scaler_yyaw}; + Vector2f vel_ned_filtd_scaled_xy = {blimp.vel_ned_filtd.x * scaler_xz, blimp.vel_ned_filtd.y * scaler_yyaw}; + + Vector2f actuator; + if (!axes_disabled.x && !axes_disabled.y) actuator = blimp.pid_vel_xy.update_all(target_vel_ef_c_scaled_xy, vel_ned_filtd_scaled_xy, dt, {(float)limit.x, (float)limit.y}); + float act_down = 0; + if (!axes_disabled.z) { + act_down = blimp.pid_vel_z.update_all(target_vel_ef_c.z * scaler_xz, blimp.vel_ned_filtd.z * scaler_xz, dt, limit.z); + } + blimp.rotate_NE_to_BF(actuator); + float act_yaw = 0; + if (!axes_disabled.yaw) { + act_yaw = blimp.pid_vel_yaw.update_all(target_vel_yaw_c * scaler_yyaw, blimp.vel_yaw_filtd * scaler_yyaw, dt, limit.yaw); + } + + if (!blimp.motors->armed()) { + blimp.pid_vel_xy.set_integrator(Vector2f(0,0)); + blimp.pid_vel_z.set_integrator(0); + blimp.pid_vel_yaw.set_integrator(0); + } + + if (zero.x) { + blimp.motors->front_out = 0; + } else if (axes_disabled.x); + else { + blimp.motors->front_out = actuator.x; + } + if (zero.y) { + blimp.motors->right_out = 0; + } else if (axes_disabled.y); + else { + blimp.motors->right_out = actuator.y; + } + if (zero.z) { + blimp.motors->down_out = 0; + } else if (axes_disabled.z); + else { + blimp.motors->down_out = act_down; + } + if (zero.yaw) { + blimp.motors->yaw_out = 0; + } else if (axes_disabled.yaw); + else { + blimp.motors->yaw_out = act_yaw; + } + + AP::logger().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); + AP::logger().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); + AP::logger().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); +} diff --git a/Blimp/Loiter.h b/Blimp/Loiter.h new file mode 100644 index 00000000000000..c21fdd57c6f251 --- /dev/null +++ b/Blimp/Loiter.h @@ -0,0 +1,59 @@ +#pragma once + +class Vector4b +{ +public: + bool x; + bool y; + bool z; + bool yaw; + + constexpr Vector4b() + : x(0) + , y(0) + , z(0) + , yaw(0) {} + + constexpr Vector4b(const bool x0, const bool y0, const bool z0, const bool yaw0) + : x(x0) + , y(y0) + , z(z0) + , yaw(yaw0) {} + + Vector4b operator &&(const Vector4b &v) + { + Vector4b temp{x && v.x, y && v.y, z && v.z, yaw && v.yaw}; + return temp; + } + + Vector4b operator ||(const Vector4b &v) + { + Vector4b temp{x || v.x, y || v.y, z || v.z, yaw || v.yaw}; + return temp; + } + +}; + + + +class Loiter +{ +public: + friend class Blimp; + friend class Fins; + + float scaler_xz; + float scaler_yyaw; + + //constructor + Loiter(uint16_t loop_rate) + { + scaler_xz = 1; + scaler_yyaw = 1; + }; + + //Run Loiter controller with target position and yaw in global frame. Expects to be called at loop rate. + void run(Vector3f& target_pos, float& target_yaw, Vector4b axes_disabled); + //Run Loiter controller with target velocity and velocity in global frame. Expects to be called at loop rate. + void run_vel(Vector3f& target_vel, float& target_vel_yaw, Vector4b axes_disabled); +}; diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index 487d0981146b01..bb0ac2bb40d6af 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -53,15 +53,6 @@ const AP_Param::Info Blimp::var_info[] = { // @Increment: .5 GSCALAR(throttle_filt, "PILOT_THR_FILT", 0), - // @Param: PILOT_TKOFF_ALT - // @DisplayName: Pilot takeoff altitude - // @Description: Altitude that altitude control modes will climb to when a takeoff is triggered with the throttle stick. - // @User: Standard - // @Units: cm - // @Range: 0.0 1000.0 - // @Increment: 10 - GSCALAR(pilot_takeoff_alt, "PILOT_TKOFF_ALT", PILOT_TKOFF_ALT_DEFAULT), - // @Param: PILOT_THR_BHV // @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. @@ -184,7 +175,7 @@ const AP_Param::Info Blimp::var_info[] = { // @Param: LOG_BITMASK // @DisplayName: Log bitmask // @Description: Bitmap of what log types to enable in on-board logger. This value is made up of the sum of each of the log types you want to be saved. On boards supporting microSD cards or other large block-storage devices it is usually best just to enable all basic log types by setting this to 65535. - // @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,6:RC Input,7:IMU,9:Battery Monitor,10:RC Output,11:Optical Flow,12:PID,13:Compass + // @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,6:RC Input,7:IMU,9:Battery Monitor,10:RC Output,12:PID,13:Compass // @User: Standard GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK), @@ -272,12 +263,20 @@ const AP_Param::Info Blimp::var_info[] = { // @Param: DIS_MASK // @DisplayName: Disable output mask - // @Description: Mask for disabling one or more of the 4 output axis in mode Velocity or Loiter + // @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), + // @Param: PID_DZ + // @DisplayName: Deadzone for the position PIDs + // @Description: Output 0 thrust signal when blimp is within this distance (in meters) of the target position. Warning: If this param is greater than MAX_POS_XY param then the blimp won't move at all in the XY plane in Loiter mode as it does not allow more than a second's lag. Same for the other axes. + // @Units: m + // @Range: 0.1 1 + // @User: Standard + GSCALAR(pid_dz, "PID_DZ", 0), + // @Param: RC_SPEED // @DisplayName: ESC Update Speed // @Description: This is the speed in Hertz that your ESCs will receive updates @@ -722,6 +721,14 @@ const AP_Param::Info Blimp::var_info[] = { // @Range: 0 200 // @Increment: 0.5 // @User: Advanced + + // @Param: POSYAW_PDMX + // @DisplayName: Position (yaw) axis controller PD sum maximum + // @Description: Position (yaw) axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 4000 + // @Increment: 10 + // @Units: d% + // @User: Advanced GOBJECT(pid_pos_yaw, "POSYAW_", AC_PID), // @Group: diff --git a/Blimp/Parameters.h b/Blimp/Parameters.h index c819ad0ab46543..8ec466d62c0c6d 100644 --- a/Blimp/Parameters.h +++ b/Blimp/Parameters.h @@ -87,7 +87,7 @@ class Parameters k_param_log_bitmask, k_param_throttle_filt, k_param_throttle_behavior, - k_param_pilot_takeoff_alt, + k_param_pilot_takeoff_alt, //unused // AP_ADSB Library k_param_adsb, @@ -110,6 +110,7 @@ class Parameters k_param_max_pos_yaw, k_param_simple_mode, k_param_dis_mask, + k_param_pid_dz, // // 90: misc2 @@ -135,7 +136,7 @@ class Parameters k_param_gcs2, k_param_serial_manager, k_param_gcs3, - k_param_gcs_pid_mask, // 126 + k_param_gcs_pid_mask, k_param_gcs4, k_param_gcs5, k_param_gcs6, @@ -213,7 +214,6 @@ class Parameters AP_Float throttle_filt; AP_Int16 throttle_behavior; - AP_Float pilot_takeoff_alt; AP_Int8 failsafe_gcs; // ground station failsafe behavior AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position @@ -254,6 +254,7 @@ class Parameters AP_Int8 simple_mode; AP_Int16 dis_mask; + AP_Float pid_dz; AP_Int8 rtl_alt_type; diff --git a/Blimp/RC_Channel.cpp b/Blimp/RC_Channel.cpp index 12ef4838473148..7709867cf25c4a 100644 --- a/Blimp/RC_Channel.cpp +++ b/Blimp/RC_Channel.cpp @@ -106,7 +106,7 @@ bool RC_Channel_Blimp::do_aux_function(const aux_func_t ch_option, const AuxSwit case AUX_FUNC::SAVE_TRIM: if ((ch_flag == AuxSwitchPos::HIGH) && (blimp.control_mode <= Mode::Number::MANUAL) && - (blimp.channel_down->get_control_in() == 0)) { + (blimp.channel_up->get_control_in() == 0)) { blimp.save_trim(); } break; diff --git a/Blimp/config.h b/Blimp/config.h index 10cac9ea72bf7b..9c5908f65fed98 100644 --- a/Blimp/config.h +++ b/Blimp/config.h @@ -22,13 +22,6 @@ # define ARMING_DELAY_SEC 2.0f #endif -////////////////////////////////////////////////////////////////////////////// -// FRAME_CONFIG -// -#ifndef FRAME_CONFIG -# define FRAME_CONFIG MULTICOPTER_FRAME -#endif - ////////////////////////////////////////////////////////////////////////////// // PWM control // default RC speed in Hz @@ -36,53 +29,6 @@ # define RC_FAST_SPEED 490 #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 - -#ifndef RANGEFINDER_TIMEOUT_MS -# define RANGEFINDER_TIMEOUT_MS 1000 // rangefinder filter reset if no updates from sensor in 1 second -#endif - -#ifndef RANGEFINDER_GAIN_DEFAULT -# define RANGEFINDER_GAIN_DEFAULT 0.8f // gain for controlling how quickly rangefinder range adjusts target altitude (lower means slower reaction) -#endif - -#ifndef SURFACE_TRACKING_TIMEOUT_MS -# 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_WPNAV_FILT_HZ -# define RANGEFINDER_WPNAV_FILT_HZ 0.25f // filter frequency for rangefinder altitude provided to waypoint navigation class -#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 - -////////////////////////////////////////////////////////////////////////////// -// Proximity sensor -// -#ifndef PROXIMITY_ENABLED -# define PROXIMITY_ENABLED ENABLED -#endif - #ifndef MAV_SYSTEM_ID # define MAV_SYSTEM_ID 1 #endif @@ -125,100 +71,9 @@ # define EKF_ORIGIN_MAX_DIST_M 50000 // EKF origin and waypoints (including home) must be within 50km #endif -////////////////////////////////////////////////////////////////////////////// -// OPTICAL_FLOW -#ifndef OPTFLOW -# define OPTFLOW ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// Auto Tuning -#ifndef AUTOTUNE_ENABLED -# define AUTOTUNE_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// Parachute release -#ifndef PARACHUTE -# define PARACHUTE HAL_PARACHUTE_ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// Acro - fly vehicle in acrobatic mode -#ifndef MODE_ACRO_ENABLED -# define MODE_ACRO_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// Auto mode - allows vehicle to trace waypoints and perform automated actions -#ifndef MODE_AUTO_ENABLED -# define MODE_AUTO_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// Brake mode - bring vehicle to stop -#ifndef MODE_BRAKE_ENABLED -# define MODE_BRAKE_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// Circle - fly vehicle around a central point -#ifndef MODE_CIRCLE_ENABLED -# define MODE_CIRCLE_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// Drift - fly vehicle in altitude-held, coordinated-turn mode -#ifndef MODE_DRIFT_ENABLED -# define MODE_DRIFT_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// flip - fly vehicle in flip in pitch and roll direction mode -#ifndef MODE_FLIP_ENABLED -# define MODE_FLIP_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// Guided mode - control vehicle's position or angles from GCS -#ifndef MODE_GUIDED_ENABLED -# define MODE_GUIDED_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// Loiter mode - allows vehicle to hold global position -#ifndef MODE_LOITER_ENABLED -# define MODE_LOITER_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// Position Hold - enable holding of global position -#ifndef MODE_POSHOLD_ENABLED -# define MODE_POSHOLD_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// RTL - Return To Launch -#ifndef MODE_RTL_ENABLED -# define MODE_RTL_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// SmartRTL - allows vehicle to retrace a (loop-eliminated) breadcrumb home -#ifndef MODE_SMARTRTL_ENABLED -# define MODE_SMARTRTL_ENABLED ENABLED -#endif - -////////////////////////////////////////////////////////////////////////////// -// RADIO CONFIGURATION -////////////////////////////////////////////////////////////////////////////// -////////////////////////////////////////////////////////////////////////////// - - ////////////////////////////////////////////////////////////////////////////// // FLIGHT_MODE // - #ifndef FLIGHT_MODE_1 # define FLIGHT_MODE_1 Mode::Number::MANUAL #endif @@ -238,7 +93,6 @@ # define FLIGHT_MODE_6 Mode::Number::MANUAL #endif - ////////////////////////////////////////////////////////////////////////////// // Throttle Failsafe // @@ -246,188 +100,17 @@ # define FS_THR_VALUE_DEFAULT 975 #endif -////////////////////////////////////////////////////////////////////////////// -// Takeoff -// -#ifndef PILOT_TKOFF_ALT_DEFAULT -# define PILOT_TKOFF_ALT_DEFAULT 0 // default final alt above home for pilot initiated takeoff -#endif - - -////////////////////////////////////////////////////////////////////////////// -// Landing -// -#ifndef LAND_SPEED -# define LAND_SPEED 50 // the descent speed for the final stage of landing in cm/s -#endif -#ifndef LAND_REPOSITION_DEFAULT -# define LAND_REPOSITION_DEFAULT 1 // by default the pilot can override roll/pitch during landing -#endif -#ifndef LAND_WITH_DELAY_MS -# define LAND_WITH_DELAY_MS 4000 // default delay (in milliseconds) when a land-with-delay is triggered during a failsafe event -#endif -#ifndef LAND_CANCEL_TRIGGER_THR -# define LAND_CANCEL_TRIGGER_THR 700 // land is cancelled by input throttle above 700 -#endif -#ifndef LAND_RANGEFINDER_MIN_ALT_CM -#define LAND_RANGEFINDER_MIN_ALT_CM 200 -#endif - -////////////////////////////////////////////////////////////////////////////// -// Landing Detector -// -#ifndef LAND_DETECTOR_TRIGGER_SEC -# define LAND_DETECTOR_TRIGGER_SEC 1.0f // number of seconds to detect a landing -#endif -#ifndef LAND_DETECTOR_MAYBE_TRIGGER_SEC -# define LAND_DETECTOR_MAYBE_TRIGGER_SEC 0.2f // number of seconds that means we might be landed (used to reset horizontal position targets to prevent tipping over) -#endif -#ifndef LAND_DETECTOR_ACCEL_LPF_CUTOFF -# define LAND_DETECTOR_ACCEL_LPF_CUTOFF 1.0f // frequency cutoff of land detector accelerometer filter -#endif -#ifndef LAND_DETECTOR_ACCEL_MAX -# define LAND_DETECTOR_ACCEL_MAX 1.0f // vehicle acceleration must be under 1m/s/s -#endif - -////////////////////////////////////////////////////////////////////////////// -// Flight mode definitions -// - -// Acro Mode -#ifndef ACRO_RP_P -# define ACRO_RP_P 4.5f -#endif - -#ifndef ACRO_YAW_P -# define ACRO_YAW_P 4.5f -#endif - -#ifndef ACRO_LEVEL_MAX_ANGLE -# define ACRO_LEVEL_MAX_ANGLE 3000 -#endif - -#ifndef ACRO_BALANCE_ROLL -#define ACRO_BALANCE_ROLL 1.0f -#endif - -#ifndef ACRO_BALANCE_PITCH -#define ACRO_BALANCE_PITCH 1.0f -#endif - -#ifndef ACRO_RP_EXPO_DEFAULT -#define ACRO_RP_EXPO_DEFAULT 0.3f -#endif - -#ifndef ACRO_Y_EXPO_DEFAULT -#define ACRO_Y_EXPO_DEFAULT 0.0f -#endif - -#ifndef ACRO_THR_MID_DEFAULT -#define ACRO_THR_MID_DEFAULT 0.0f -#endif - -// RTL Mode -#ifndef RTL_ALT_FINAL -# define RTL_ALT_FINAL 0 // the altitude the vehicle will move to as the final stage of Returning to Launch. Set to zero to land. -#endif - -#ifndef RTL_ALT -# define RTL_ALT 1500 // default alt to return to home in cm, 0 = Maintain current altitude -#endif - -#ifndef RTL_ALT_MIN -# define RTL_ALT_MIN 200 // min height above ground for RTL (i.e 2m) -#endif - -#ifndef RTL_CLIMB_MIN_DEFAULT -# define RTL_CLIMB_MIN_DEFAULT 0 // vehicle will always climb this many cm as first stage of RTL -#endif - -#ifndef RTL_ABS_MIN_CLIMB -# define RTL_ABS_MIN_CLIMB 250 // absolute minimum initial climb -#endif - -#ifndef RTL_CONE_SLOPE_DEFAULT -# define RTL_CONE_SLOPE_DEFAULT 3.0f // slope of RTL cone (height / distance). 0 = No cone -#endif - -#ifndef RTL_MIN_CONE_SLOPE -# define RTL_MIN_CONE_SLOPE 0.5f // minimum slope of cone -#endif - -#ifndef RTL_LOITER_TIME -# define RTL_LOITER_TIME 5000 // Time (in milliseconds) to loiter above home before beginning final descent -#endif - -// AUTO Mode -#ifndef WP_YAW_BEHAVIOR_DEFAULT -# define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL -#endif - -#ifndef YAW_LOOK_AHEAD_MIN_SPEED -# define YAW_LOOK_AHEAD_MIN_SPEED 100 // minimum ground speed in cm/s required before blimp is aimed at ground course -#endif - -////////////////////////////////////////////////////////////////////////////// -// Stabilize Rate Control -// -#ifndef ROLL_PITCH_YAW_INPUT_MAX -# define ROLL_PITCH_YAW_INPUT_MAX 4500 // roll, pitch and yaw input range -#endif -#ifndef DEFAULT_ANGLE_MAX -# define DEFAULT_ANGLE_MAX 4500 // ANGLE_MAX parameters default value -#endif - -////////////////////////////////////////////////////////////////////////////// -// Stop mode defaults -// -#ifndef BRAKE_MODE_SPEED_Z -# define BRAKE_MODE_SPEED_Z 250 // z-axis speed in cm/s in Brake Mode -#endif -#ifndef BRAKE_MODE_DECEL_RATE -# define BRAKE_MODE_DECEL_RATE 750 // acceleration rate in cm/s/s in Brake Mode -#endif - -////////////////////////////////////////////////////////////////////////////// -// PosHold parameter defaults -// -#ifndef POSHOLD_BRAKE_RATE_DEFAULT -# define POSHOLD_BRAKE_RATE_DEFAULT 8 // default POSHOLD_BRAKE_RATE param value. Rotation rate during braking in deg/sec -#endif -#ifndef POSHOLD_BRAKE_ANGLE_DEFAULT -# define POSHOLD_BRAKE_ANGLE_DEFAULT 3000 // default POSHOLD_BRAKE_ANGLE param value. Max lean angle during braking in centi-degrees -#endif - ////////////////////////////////////////////////////////////////////////////// // Throttle control defaults // - #ifndef THR_DZ_DEFAULT # define THR_DZ_DEFAULT 100 // the deadzone above and below mid throttle while in althold or loiter #endif -// default maximum vertical velocity and acceleration the pilot may request -#ifndef PILOT_VELZ_MAX -# define PILOT_VELZ_MAX 250 // maximum vertical velocity in cm/s -#endif -#ifndef PILOT_ACCEL_Z_DEFAULT -# define PILOT_ACCEL_Z_DEFAULT 250 // vertical acceleration in cm/s/s while altitude is under pilot control -#endif - #ifndef AUTO_DISARMING_DELAY # define AUTO_DISARMING_DELAY 10 #endif -////////////////////////////////////////////////////////////////////////////// -// Throw mode configuration -// -#ifndef THROW_HIGH_SPEED -# define THROW_HIGH_SPEED 500.0f // vehicle much reach this total 3D speed in cm/s (or be free falling) -#endif -#ifndef THROW_VERTICAL_SPEED -# define THROW_VERTICAL_SPEED 50.0f // motors start when vehicle reaches this total 3D speed in cm/s -#endif - ////////////////////////////////////////////////////////////////////////////// // Logging control // diff --git a/Blimp/defines.h b/Blimp/defines.h index f356e77600f551..0a73072a1aea5f 100644 --- a/Blimp/defines.h +++ b/Blimp/defines.h @@ -10,111 +10,6 @@ #define ENABLE ENABLED #define DISABLE DISABLED -// Autopilot Yaw Mode enumeration -enum autopilot_yaw_mode { - AUTO_YAW_HOLD = 0, // pilot controls the heading - AUTO_YAW_LOOK_AT_NEXT_WP = 1, // point towards next waypoint (no pilot input accepted) - AUTO_YAW_ROI = 2, // point towards a location held in roi (no pilot input accepted) - AUTO_YAW_FIXED = 3, // point towards a particular angle (no pilot input accepted) - AUTO_YAW_LOOK_AHEAD = 4, // point in the direction the blimp is moving - AUTO_YAW_RESETTOARMEDYAW = 5, // point towards heading at time motors were armed - AUTO_YAW_RATE = 6, // turn at a specified rate (held in auto_yaw_rate) - AUTO_YAW_CIRCLE = 7, // use AC_Circle's provided yaw (used during Loiter-Turns commands) -}; - -// Frame types -#define UNDEFINED_FRAME 0 -#define MULTICOPTER_FRAME 1 -#define HELI_FRAME 2 - -// Tuning enumeration -enum tuning_func { - TUNING_NONE = 0, // - TUNING_STABILIZE_ROLL_PITCH_KP = 1, // stabilize roll/pitch angle controller's P term - TUNING_STABILIZE_YAW_KP = 3, // stabilize yaw heading controller's P term - TUNING_RATE_ROLL_PITCH_KP = 4, // body frame roll/pitch rate controller's P term - TUNING_RATE_ROLL_PITCH_KI = 5, // body frame roll/pitch rate controller's I term - TUNING_YAW_RATE_KP = 6, // body frame yaw rate controller's P term - TUNING_THROTTLE_RATE_KP = 7, // throttle rate controller's P term (desired rate to acceleration or motor output) - TUNING_WP_SPEED = 10, // maximum speed to next way point (0 to 10m/s) - TUNING_LOITER_POSITION_KP = 12, // loiter distance controller's P term (position error to speed) - TUNING_HELI_EXTERNAL_GYRO = 13, // TradHeli specific external tail gyro gain - TUNING_ALTITUDE_HOLD_KP = 14, // altitude hold controller's P term (alt error to desired rate) - TUNING_RATE_ROLL_PITCH_KD = 21, // body frame roll/pitch rate controller's D term - TUNING_VEL_XY_KP = 22, // loiter rate controller's P term (speed error to tilt angle) - TUNING_ACRO_RP_KP = 25, // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate - TUNING_YAW_RATE_KD = 26, // body frame yaw rate controller's D term - TUNING_VEL_XY_KI = 28, // loiter rate controller's I term (speed error to tilt angle) - TUNING_AHRS_YAW_KP = 30, // ahrs's compass effect on yaw angle (0 = very low, 1 = very high) - TUNING_AHRS_KP = 31, // accelerometer effect on roll/pitch angle (0=low) - TUNING_ACCEL_Z_KP = 34, // accel based throttle controller's P term - TUNING_ACCEL_Z_KI = 35, // accel based throttle controller's I term - TUNING_ACCEL_Z_KD = 36, // accel based throttle controller's D term - TUNING_DECLINATION = 38, // compass declination in radians - TUNING_CIRCLE_RATE = 39, // circle turn rate in degrees (hard coded to about 45 degrees in either direction) - TUNING_ACRO_YAW_KP = 40, // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate - TUNING_RANGEFINDER_GAIN = 41, // rangefinder gain - TUNING_EKF_VERTICAL_POS = 42, // unused - TUNING_EKF_HORIZONTAL_POS = 43, // unused - TUNING_EKF_ACCEL_NOISE = 44, // unused - TUNING_RC_FEEL_RP = 45, // roll-pitch input smoothing - TUNING_RATE_PITCH_KP = 46, // body frame pitch rate controller's P term - TUNING_RATE_PITCH_KI = 47, // body frame pitch rate controller's I term - TUNING_RATE_PITCH_KD = 48, // body frame pitch rate controller's D term - TUNING_RATE_ROLL_KP = 49, // body frame roll rate controller's P term - TUNING_RATE_ROLL_KI = 50, // body frame roll rate controller's I term - TUNING_RATE_ROLL_KD = 51, // body frame roll rate controller's D term - TUNING_RATE_PITCH_FF = 52, // body frame pitch rate controller FF term - TUNING_RATE_ROLL_FF = 53, // body frame roll rate controller FF term - TUNING_RATE_YAW_FF = 54, // body frame yaw rate controller FF term - TUNING_RATE_MOT_YAW_HEADROOM = 55, // motors yaw headroom minimum - TUNING_RATE_YAW_FILT = 56, // yaw rate input filter - UNUSED = 57, // was winch control - TUNING_SYSTEM_ID_MAGNITUDE = 58 // magnitude of the system ID signal -}; - -// Yaw behaviours during missions - possible values for WP_YAW_BEHAVIOR parameter -#define WP_YAW_BEHAVIOR_NONE 0 // auto pilot will never control yaw during missions or rtl (except for DO_CONDITIONAL_YAW command received) -#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP 1 // auto pilot will face next waypoint or home during rtl -#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL 2 // auto pilot will face next waypoint except when doing RTL at which time it will stay in it's last -#define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicopters) - -// Auto modes -enum AutoMode { - Auto_TakeOff, - Auto_WP, - Auto_Land, - Auto_RTL, - Auto_CircleMoveToEdge, - Auto_Circle, - Auto_Spline, - Auto_NavGuided, - Auto_Loiter, - Auto_LoiterToAlt, - Auto_NavPayloadPlace, -}; - -// Guided modes -enum GuidedMode { - Guided_TakeOff, - Guided_WP, - Guided_Velocity, - Guided_PosVel, - Guided_Angle, -}; - -enum PayloadPlaceStateType { - PayloadPlaceStateType_FlyToLocation, - PayloadPlaceStateType_Descent_Start, - PayloadPlaceStateType_Descent, - PayloadPlaceStateType_Release, - PayloadPlaceStateType_Releasing, - PayloadPlaceStateType_Delay, - PayloadPlaceStateType_Ascent_Start, - PayloadPlaceStateType_Ascent, - PayloadPlaceStateType_Done, -}; - // bit options for DEV_OPTIONS parameter enum DevOptions { DevOptionADSBMAVLink = 1, @@ -184,8 +79,7 @@ enum LoggingParameters { // EKF failsafe definitions (FS_EKF_ACTION parameter) #define FS_EKF_ACTION_LAND 1 // switch to LAND mode on EKF failsafe -#define FS_EKF_ACTION_ALTHOLD 2 // switch to ALTHOLD mode on EKF failsafe -#define FS_EKF_ACTION_LAND_EVEN_STABILIZE 3 // switch to Land mode on EKF failsafe even if in a manual flight mode like stabilize +#define FS_EKF_ACTION_LAND_EVEN_MANUAL 3 // switch to Land mode on EKF failsafe even if in Manual mode // for PILOT_THR_BHV parameter #define THR_BEHAVE_FEEDBACK_FROM_MID_STICK (1<<0) diff --git a/Blimp/ekf_check.cpp b/Blimp/ekf_check.cpp index 8bc678922f0b5b..fd524b99ab91a5 100644 --- a/Blimp/ekf_check.cpp +++ b/Blimp/ekf_check.cpp @@ -148,16 +148,16 @@ void Blimp::failsafe_ekf_event() AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED); // does this mode require position? - if (!blimp.flightmode->requires_GPS() && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_STABILIZE)) { + if (!blimp.flightmode->requires_GPS() && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_MANUAL)) { return; } // take action based on fs_ekf_action parameter switch (g.fs_ekf_action) { case FS_EKF_ACTION_LAND: - case FS_EKF_ACTION_LAND_EVEN_STABILIZE: + case FS_EKF_ACTION_LAND_EVEN_MANUAL: default: - set_mode_land_with_pause(ModeReason::EKF_FAILSAFE); + set_mode_land_failsafe(ModeReason::EKF_FAILSAFE); break; } } diff --git a/Blimp/events.cpp b/Blimp/events.cpp index cbd778cd6ca69f..452f624c5b879f 100644 --- a/Blimp/events.cpp +++ b/Blimp/events.cpp @@ -98,8 +98,8 @@ void Blimp::failsafe_gcs_check() const uint32_t gcs_last_seen_ms = gcs().sysid_myggcs_last_seen_time_ms(); if (gcs_last_seen_ms == 0) { - return; - } + return; + } // calc time since last gcs update // note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs @@ -148,7 +148,7 @@ void Blimp::do_failsafe_action(Failsafe_Action action, ModeReason reason) case Failsafe_Action_None: return; case Failsafe_Action_Land: - set_mode_land_with_pause(reason); + set_mode_land_failsafe(reason); break; case Failsafe_Action_Terminate: { arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE); diff --git a/Blimp/mode.cpp b/Blimp/mode.cpp index 511ac6be5bbc84..b7d80bd906100f 100644 --- a/Blimp/mode.cpp +++ b/Blimp/mode.cpp @@ -16,9 +16,10 @@ Mode::Mode(void) : inertial_nav(blimp.inertial_nav), ahrs(blimp.ahrs), motors(blimp.motors), + loiter(blimp.loiter), channel_right(blimp.channel_right), channel_front(blimp.channel_front), - channel_down(blimp.channel_down), + channel_up(blimp.channel_up), channel_yaw(blimp.channel_yaw), G_Dt(blimp.G_Dt) { }; @@ -41,6 +42,9 @@ Mode *Blimp::mode_from_mode_num(const Mode::Number mode) case Mode::Number::LOITER: ret = &mode_loiter; break; + case Mode::Number::RTL: + ret = &mode_rtl; + break; default: break; } @@ -136,7 +140,7 @@ void Blimp::update_flight_mode() // exit_mode - high level call to organise cleanup as a flight mode is exited void Blimp::exit_mode(Mode *&old_flightmode, - Mode *&new_flightmode){} + Mode *&new_flightmode) {} // notify_flight_mode - sets notify object based on current flight mode. Only used for OreoLED notify device void Blimp::notify_flight_mode() @@ -152,18 +156,23 @@ void Mode::update_navigation() run_autopilot(); } -// returns desired angle in centi-degrees -void Mode::get_pilot_desired_accelerations(float &right_out, float &front_out) const +// returns desired thrust/acceleration +void Mode::get_pilot_input(Vector3f &pilot, float &yaw) { // throttle failsafe check if (blimp.failsafe.radio || !blimp.ap.rc_receiver_present) { - right_out = 0; - front_out = 0; + pilot.y = 0; + pilot.x = 0; + pilot.z = 0; + yaw = 0; return; } - // fetch roll and pitch inputs - right_out = channel_right->get_control_in(); - front_out = channel_front->get_control_in(); + // fetch pilot inputs + pilot.y = channel_right->get_control_in() / float(RC_SCALE); + pilot.x = channel_front->get_control_in() / float(RC_SCALE); + //TODO: need to make this channel_up instead, and then have it .negative. before being sent to pilot.z -> this is "throttle" channel, so higher = up. + pilot.z = -channel_up->get_control_in() / float(RC_SCALE); + yaw = channel_yaw->get_control_in() / float(RC_SCALE); } bool Mode::is_disarmed_or_landed() const diff --git a/Blimp/mode.h b/Blimp/mode.h index ed9e60353f0f7d..8a990fbb31b30c 100644 --- a/Blimp/mode.h +++ b/Blimp/mode.h @@ -17,6 +17,7 @@ class Mode MANUAL = 1, // manual control VELOCITY = 2, // velocity mode LOITER = 3, // loiter mode (position hold) + RTL = 4, // rtl }; // constructor @@ -83,7 +84,7 @@ class Mode void update_navigation(); // pilot input processing - void get_pilot_desired_accelerations(float &right_out, float &front_out) const; + void get_pilot_input(Vector3f &pilot, float &yaw); protected: @@ -104,72 +105,14 @@ class Mode AP_InertialNav &inertial_nav; AP_AHRS &ahrs; Fins *&motors; + Loiter *&loiter; RC_Channel *&channel_right; RC_Channel *&channel_front; - RC_Channel *&channel_down; + RC_Channel *&channel_up; RC_Channel *&channel_yaw; float &G_Dt; public: - // Navigation Yaw control - class AutoYaw - { - - public: - // mode(): current method of determining desired yaw: - autopilot_yaw_mode mode() const - { - return (autopilot_yaw_mode)_mode; - } - void set_mode_to_default(bool rtl); - void set_mode(autopilot_yaw_mode new_mode); - autopilot_yaw_mode default_mode(bool rtl) const; - - void set_rate(float new_rate_cds); - - // set_roi(...): set a "look at" location: - void set_roi(const Location &roi_location); - - void set_fixed_yaw(float angle_deg, - float turn_rate_dps, - int8_t direction, - bool relative_angle); - - private: - - // yaw_cd(): main product of AutoYaw; the heading: - float yaw_cd(); - - // rate_cds(): desired yaw rate in centidegrees/second: - float rate_cds(); - - float look_ahead_yaw(); - float roi_yaw(); - - // auto flight mode's yaw mode - uint8_t _mode = AUTO_YAW_LOOK_AT_NEXT_WP; - - // Yaw will point at this location if mode is set to AUTO_YAW_ROI - Vector3f roi; - - // bearing from current location to the ROI - float _roi_yaw; - - // yaw used for YAW_FIXED yaw_mode - int32_t _fixed_yaw; - - // Deg/s we should turn - int16_t _fixed_yaw_slewrate; - - // heading when in yaw_look_ahead_yaw - float _look_ahead_yaw; - - // used to reduce update rate to 100hz: - uint8_t roi_yaw_counter; - - }; - static AutoYaw auto_yaw; - // pass-through functions to reduce code churn on conversion; // these are candidates for moving into the Mode base // class. @@ -304,7 +247,6 @@ class ModeLoiter : public Mode private: Vector3f target_pos; float target_yaw; - float loop_period; }; class ModeLand : public Mode @@ -347,3 +289,43 @@ class ModeLand : public Mode private: }; + +class ModeRTL : public Mode +{ + +public: + // inherit constructor + using Mode::Mode; + + virtual bool init(bool ignore_checks) override; + virtual void run() override; + + bool requires_GPS() const override + { + return true; + } + bool has_manual_throttle() const override + { + return false; + } + bool allows_arming(bool from_gcs) const override + { + return true; + }; + bool is_autopilot() const override + { + return false; + //TODO + } + +protected: + + const char *name() const override + { + return "RTL"; + } + const char *name4() const override + { + return "RTL"; + } +}; diff --git a/Blimp/mode_land.cpp b/Blimp/mode_land.cpp index f6e334839e1d04..640e69ef528df8 100644 --- a/Blimp/mode_land.cpp +++ b/Blimp/mode_land.cpp @@ -13,12 +13,11 @@ void ModeLand::run() motors->down_out = 0; } -// set_mode_land_with_pause - sets mode to LAND and triggers 4 second delay before descent starts -// this is always called from a failsafe so we trigger notification to pilot -void Blimp::set_mode_land_with_pause(ModeReason reason) +// set_mode_land_failsafe - sets mode to LAND +// this is always called from a failsafe so we trigger notification to pilot +void Blimp::set_mode_land_failsafe(ModeReason reason) { set_mode(Mode::Number::LAND, reason); - //TODO: Add pause // alert pilot to mode change AP_Notify::events.failsafe_mode_change = 1; diff --git a/Blimp/mode_loiter.cpp b/Blimp/mode_loiter.cpp index 71e2794c2bbae3..725a702480815a 100644 --- a/Blimp/mode_loiter.cpp +++ b/Blimp/mode_loiter.cpp @@ -3,66 +3,47 @@ * Init and run calls for loiter flight mode */ +//Number of seconds of movement that the target position can be ahead of actual position. +#define POS_LAG 1 - bool ModeLoiter::init(bool ignore_checks){ +bool ModeLoiter::init(bool ignore_checks) +{ target_pos = blimp.pos_ned; target_yaw = blimp.ahrs.get_yaw(); return true; - } +} //Runs the main loiter controller void ModeLoiter::run() { const float dt = blimp.scheduler.get_last_loop_time_s(); - - Vector3f pilot; - pilot.x = channel_front->get_control_in() / float(RC_SCALE) * g.max_pos_xy * dt; - pilot.y = channel_right->get_control_in() / float(RC_SCALE) * g.max_pos_xy * dt; - pilot.z = channel_down->get_control_in() / float(RC_SCALE) * g.max_pos_z * dt; - float pilot_yaw = channel_yaw->get_control_in() / float(RC_SCALE) * g.max_pos_yaw * dt; - if (g.simple_mode == 0){ + Vector3f pilot; + float pilot_yaw; + get_pilot_input(pilot, pilot_yaw); + pilot.x *= g.max_pos_xy * dt; + pilot.y *= g.max_pos_xy * dt; + pilot.z *= g.max_pos_z * dt; + pilot_yaw *= g.max_pos_yaw * dt; + + if (g.simple_mode == 0) { //If simple mode is disabled, input is in body-frame, thus needs to be rotated. blimp.rotate_BF_to_NE(pilot.xy()); } - target_pos.x += pilot.x; - target_pos.y += pilot.y; - target_pos.z += pilot.z; - target_yaw = wrap_PI(target_yaw + pilot_yaw); - - //Pos controller's output becomes target for velocity controller - Vector3f target_vel_ef{blimp.pid_pos_xy.update_all(target_pos, blimp.pos_ned, dt, {0,0,0}), 0}; - target_vel_ef.z = blimp.pid_pos_z.update_all(target_pos.z, blimp.pos_ned.z, dt); - float yaw_ef = blimp.ahrs.get_yaw(); - float target_vel_yaw = blimp.pid_pos_yaw.update_error(wrap_PI(target_yaw - yaw_ef), dt); - blimp.pid_pos_yaw.set_target_rate(target_yaw); - blimp.pid_pos_yaw.set_actual_rate(yaw_ef); - - Vector3f target_vel_ef_c{constrain_float(target_vel_ef.x, -g.max_vel_xy, g.max_vel_xy), - constrain_float(target_vel_ef.y, -g.max_vel_xy, g.max_vel_xy), - constrain_float(target_vel_ef.z, -g.max_vel_z, g.max_vel_z)}; - float target_vel_yaw_c = constrain_float(target_vel_yaw, -g.max_vel_yaw, g.max_vel_yaw); - - Vector2f actuator = blimp.pid_vel_xy.update_all(target_vel_ef_c, blimp.vel_ned_filtd, dt, {0,0,0}); - float act_down = blimp.pid_vel_z.update_all(target_vel_ef_c.z, blimp.vel_ned_filtd.z, dt); - blimp.rotate_NE_to_BF(actuator); - float act_yaw = blimp.pid_vel_yaw.update_all(target_vel_yaw_c, blimp.vel_yaw_filtd, dt); - if(!(blimp.g.dis_mask & (1<<(2-1)))){ - motors->front_out = actuator.x; + if (fabsf(target_pos.x-blimp.pos_ned.x) < (g.max_pos_xy*POS_LAG)) { + target_pos.x += pilot.x; } - if(!(blimp.g.dis_mask & (1<<(1-1)))){ - motors->right_out = actuator.y; + if (fabsf(target_pos.y-blimp.pos_ned.y) < (g.max_pos_xy*POS_LAG)) { + target_pos.y += pilot.y; } - if(!(blimp.g.dis_mask & (1<<(3-1)))){ - motors->down_out = act_down; + if (fabsf(target_pos.z-blimp.pos_ned.z) < (g.max_pos_z*POS_LAG)) { + target_pos.z += pilot.z; } - if(!(blimp.g.dis_mask & (1<<(4-1)))){ - motors->yaw_out = act_yaw; + if (fabsf(wrap_PI(target_yaw-ahrs.get_yaw())) < (g.max_pos_yaw*POS_LAG)) { + target_yaw = wrap_PI(target_yaw + pilot_yaw); } - AP::logger().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); - AP::logger().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); - AP::logger().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); + blimp.loiter->run(target_pos, target_yaw, Vector4b{false,false,false,false}); } diff --git a/Blimp/mode_manual.cpp b/Blimp/mode_manual.cpp index 1183b4bd7a1ad1..30a9eb7bbaffff 100644 --- a/Blimp/mode_manual.cpp +++ b/Blimp/mode_manual.cpp @@ -6,8 +6,11 @@ // Runs the main manual controller void ModeManual::run() { - motors->right_out = channel_right->get_control_in() / float(RC_SCALE); - motors->front_out = channel_front->get_control_in() / float(RC_SCALE); - motors->yaw_out = channel_yaw->get_control_in() / float(RC_SCALE); - motors->down_out = channel_down->get_control_in() / float(RC_SCALE); + Vector3f pilot; + float pilot_yaw; + get_pilot_input(pilot, pilot_yaw); + motors->right_out = pilot.y; + motors->front_out = pilot.x; + motors->yaw_out = pilot_yaw; + motors->down_out = pilot.z; } diff --git a/Blimp/mode_rtl.cpp b/Blimp/mode_rtl.cpp new file mode 100644 index 00000000000000..c1b593cd9c9331 --- /dev/null +++ b/Blimp/mode_rtl.cpp @@ -0,0 +1,20 @@ +#include "Blimp.h" +/* + * Init and run calls for rtl flight mode + */ + +//Number of seconds of movement that the target position can be ahead of actual position. +#define POS_LAG 1 + +bool ModeRTL::init(bool ignore_checks) +{ + return true; +} + +//Runs the main rtl controller +void ModeRTL::run() +{ + Vector3f target_pos = {0,0,0}; + float target_yaw = 0; + blimp.loiter->run(target_pos, target_yaw, Vector4b{false,false,false,false}); +} diff --git a/Blimp/mode_velocity.cpp b/Blimp/mode_velocity.cpp index a333d6cbc29440..ae6011c619fb48 100644 --- a/Blimp/mode_velocity.cpp +++ b/Blimp/mode_velocity.cpp @@ -8,34 +8,17 @@ // Runs the main velocity controller void ModeVelocity::run() { - const float dt = blimp.scheduler.get_last_loop_time_s(); - Vector3f target_vel; - target_vel.x = channel_front->get_control_in() / float(RC_SCALE) * g.max_vel_xy; - target_vel.y = channel_right->get_control_in() / float(RC_SCALE) * g.max_vel_xy; - blimp.rotate_BF_to_NE(target_vel.xy()); - target_vel.z = channel_down->get_control_in() / float(RC_SCALE) * g.max_vel_z; - float target_vel_yaw = channel_yaw->get_control_in() / float(RC_SCALE) * g.max_vel_yaw; - - Vector2f actuator = blimp.pid_vel_xy.update_all(target_vel, blimp.vel_ned_filtd, dt, {0,0,0}); - blimp.rotate_NE_to_BF(actuator); - float act_down = blimp.pid_vel_z.update_all(target_vel.z, blimp.vel_ned_filtd.z, dt); - float act_yaw = blimp.pid_vel_yaw.update_all(target_vel_yaw, blimp.vel_yaw_filtd, dt); - - if(!(blimp.g.dis_mask & (1<<(2-1)))){ - motors->front_out = actuator.x; - } - if(!(blimp.g.dis_mask & (1<<(1-1)))){ - motors->right_out = actuator.y; - } - if(!(blimp.g.dis_mask & (1<<(3-1)))){ - motors->down_out = act_down; - } - if(!(blimp.g.dis_mask & (1<<(4-1)))){ - motors->yaw_out = act_yaw; + float target_vel_yaw; + get_pilot_input(target_vel, target_vel_yaw); + target_vel.x *= g.max_vel_xy; + target_vel.y *= g.max_vel_xy; + if (g.simple_mode == 0) { + //If simple mode is disabled, input is in body-frame, thus needs to be rotated. + blimp.rotate_BF_to_NE(target_vel.xy()); } + target_vel.z *= g.max_vel_z; + target_vel_yaw *= g.max_vel_yaw; - AP::logger().Write_PSCN(0.0, blimp.pos_ned.x * 100.0, 0.0, 0.0, blimp.vel_ned_filtd.x * 100.0, 0.0, 0.0, 0.0); - AP::logger().Write_PSCE(0.0, blimp.pos_ned.y * 100.0, 0.0, 0.0, blimp.vel_ned_filtd.y * 100.0, 0.0, 0.0, 0.0); - AP::logger().Write_PSCD(0.0, -blimp.pos_ned.z * 100.0, 0.0, 0.0, -blimp.vel_ned_filtd.z * 100.0, 0.0, 0.0, 0.0); + blimp.loiter->run_vel(target_vel, target_vel_yaw, Vector4b{false,false,false,false}); } diff --git a/Blimp/motors.cpp b/Blimp/motors.cpp index c2034774880f41..35ba08b90cce93 100644 --- a/Blimp/motors.cpp +++ b/Blimp/motors.cpp @@ -18,7 +18,7 @@ void Blimp::arm_motors_check() } // ensure throttle is down - if (channel_down->get_control_in() > 0) { //MIR what dow we do with this? + if (channel_up->get_control_in() > 0) { //MIR what dow we do with this? arming_counter = 0; return; } diff --git a/Blimp/radio.cpp b/Blimp/radio.cpp index e7640c44c2aa96..861c057820a5fc 100644 --- a/Blimp/radio.cpp +++ b/Blimp/radio.cpp @@ -8,23 +8,23 @@ void Blimp::default_dead_zones() { channel_right->set_default_dead_zone(20); channel_front->set_default_dead_zone(20); - channel_down->set_default_dead_zone(30); + channel_up->set_default_dead_zone(30); channel_yaw->set_default_dead_zone(20); rc().channel(CH_6)->set_default_dead_zone(0); } void Blimp::init_rc_in() { - channel_right = rc().channel(rcmap.roll()-1); - channel_front = rc().channel(rcmap.pitch()-1); - channel_down = rc().channel(rcmap.throttle()-1); - channel_yaw = rc().channel(rcmap.yaw()-1); + 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); // set rc channel ranges channel_right->set_angle(RC_SCALE); channel_front->set_angle(RC_SCALE); channel_yaw->set_angle(RC_SCALE); - channel_down->set_angle(RC_SCALE); + channel_up->set_angle(RC_SCALE); // set default dead zones default_dead_zones(); @@ -58,14 +58,14 @@ void Blimp::read_radio() if (rc().read_input()) { ap.new_radio_frame = true; - set_throttle_and_failsafe(channel_down->get_radio_in()); - set_throttle_zero_flag(channel_down->get_control_in()); + set_throttle_and_failsafe(channel_up->get_radio_in()); + set_throttle_zero_flag(channel_up->get_control_in()); // RC receiver must be attached if we've just got input ap.rc_receiver_present = true; const float dt = (tnow_ms - last_radio_update_ms)*1.0e-3f; - rc_throttle_control_in_filter.apply(channel_down->get_control_in(), dt); + rc_throttle_control_in_filter.apply(channel_up->get_control_in(), dt); last_radio_update_ms = tnow_ms; return; } diff --git a/Blimp/system.cpp b/Blimp/system.cpp index 5a2092911d4a64..f3d8bdc08e69f1 100644 --- a/Blimp/system.cpp +++ b/Blimp/system.cpp @@ -46,6 +46,7 @@ void Blimp::init_ardupilot() // allocate the motors class allocate_motors(); + loiter = new 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); diff --git a/Blimp/wscript b/Blimp/wscript index a45b13a3137502..34cb8c170490e0 100644 --- a/Blimp/wscript +++ b/Blimp/wscript @@ -7,9 +7,7 @@ def build(bld): name=vehicle + '_libs', ap_vehicle=vehicle, ap_libraries=bld.ap_common_vehicle_libraries() + [ - 'AC_AttitudeControl', 'AC_InputManager', - 'AC_WPNav', 'AP_InertialNav', 'AP_RCMapper', 'AP_Avoidance', @@ -27,5 +25,4 @@ def build(bld): program_name='blimp', program_groups=['bin', 'blimp'], use=vehicle + '_libs', - defines=['FRAME_CONFIG=MULTICOPTER_FRAME'], ) diff --git a/Dockerfile b/Dockerfile index 6c128335de6099..495c843488054b 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,4 +1,6 @@ -FROM ubuntu:22.04 +ARG BASE_IMAGE="ubuntu" +ARG TAG="22.04" +FROM ${BASE_IMAGE}:${TAG} WORKDIR /ardupilot ARG DEBIAN_FRONTEND=noninteractive diff --git a/README.md b/README.md index 36994430d4fcbc..7b603fc1632425 100644 --- a/README.md +++ b/README.md @@ -77,7 +77,7 @@ It is continually being expanded to provide support for new emerging vehicle typ The ArduPilot project is licensed under the GNU General Public License, version 3. -- [Overview of license](https://dev.ardupilot.com/wiki/license-gplv3) +- [Overview of license](https://ardupilot.org/dev/docs/license-gplv3.html) - [Full Text](https://github.com/ArduPilot/ardupilot/blob/master/COPYING.txt) diff --git a/Rover/AP_Rally.cpp b/Rover/AP_Rally.cpp index 1a836159645eff..b0daf506f10856 100644 --- a/Rover/AP_Rally.cpp +++ b/Rover/AP_Rally.cpp @@ -13,11 +13,13 @@ along with this program. If not, see . */ -#include +#include "AP_Rally.h" + +#if HAL_RALLY_ENABLED #include "Rover.h" -#include "AP_Rally.h" +#include bool AP_Rally_Rover::is_valid(const Location &rally_point) const { @@ -28,3 +30,5 @@ bool AP_Rally_Rover::is_valid(const Location &rally_point) const #endif return true; } + +#endif // HAL_RALLY_ENABLED diff --git a/Rover/AP_Rally.h b/Rover/AP_Rally.h index 0055dcb1e5e93e..197d6c92797fff 100644 --- a/Rover/AP_Rally.h +++ b/Rover/AP_Rally.h @@ -15,7 +15,8 @@ #pragma once #include -#include + +#if HAL_RALLY_ENABLED class AP_Rally_Rover : public AP_Rally { @@ -28,3 +29,5 @@ class AP_Rally_Rover : public AP_Rally private: bool is_valid(const Location &rally_point) const override; }; + +#endif // HAL_RALLY_ENABLED diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 92d17426514e46..24a41058cf756a 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -53,7 +53,7 @@ MAV_MODE GCS_MAVLINK_Rover::base_mode() const uint32_t GCS_Rover::custom_mode() const { - return rover.control_mode->mode_number(); + return (uint32_t)rover.control_mode->mode_number(); } MAV_STATE GCS_MAVLINK_Rover::vehicle_system_status() const @@ -398,8 +398,10 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) void GCS_MAVLINK_Rover::packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) { +#if AP_FOLLOW_ENABLED // pass message to follow library rover.g2.follow.handle_msg(msg); +#endif GCS_MAVLINK::packetReceived(status, msg); } @@ -529,7 +531,9 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_GPS2_RAW, MSG_GPS2_RTK, MSG_NAV_CONTROLLER_OUTPUT, +#if AP_FENCE_ENABLED MSG_FENCE_STATUS, +#endif MSG_POSITION_TARGET_GLOBAL_INT, }; static const ap_message STREAM_POSITION_msgs[] = { @@ -562,8 +566,10 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_BATTERY_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_OPTICAL_FLOW, +#if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, +#endif MSG_EKF_STATUS_REPORT, MSG_VIBRATION, #if AP_RPM_ENABLED @@ -608,15 +614,15 @@ bool GCS_MAVLINK_Rover::handle_guided_request(AP_Mission::Mission_Command &cmd) return rover.mode_guided.set_desired_location(cmd.content.location); } -MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { - if (is_equal(packet.param6, 1.0f)) { + if (packet.y == 1) { if (rover.g2.windvane.start_direction_calibration()) { return MAV_RESULT_ACCEPTED; } else { return MAV_RESULT_FAILED; } - } else if (is_equal(packet.param6, 2.0f)) { + } else if (packet.y == 2) { if (rover.g2.windvane.start_speed_calibration()) { return MAV_RESULT_ACCEPTED; } else { @@ -635,7 +641,7 @@ bool GCS_MAVLINK_Rover::set_home(const Location& loc, bool _lock) { return rover.set_home(loc, _lock); } -MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_int_t &packet) +MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch (packet.command) { @@ -655,45 +661,46 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in rover.control_mode->set_reversed(is_equal(packet.param1,1.0f)); return MAV_RESULT_ACCEPTED; - default: - return GCS_MAVLINK::handle_command_int_packet(packet); - } -} - -MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_long_t &packet) -{ - switch (packet.command) { - case MAV_CMD_NAV_RETURN_TO_LAUNCH: if (rover.set_mode(rover.mode_rtl, ModeReason::GCS_COMMAND)) { return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED; + case MAV_CMD_DO_MOTOR_TEST: + // param1 : motor sequence number (a number from 1 to max number of motors on the vehicle) + // param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) + // param3 : throttle (range depends upon param2) + // param4 : timeout (in seconds) + return rover.mavlink_motor_test_start(*this, + (AP_MotorsUGV::motor_test_order)packet.param1, + static_cast(packet.param2), + static_cast(packet.param3), + packet.param4); + case MAV_CMD_MISSION_START: if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) { return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED; - case MAV_CMD_DO_CHANGE_SPEED: - // param1 : unused - // param2 : new speed in m/s - if (!rover.control_mode->set_desired_speed(packet.param2)) { - return MAV_RESULT_FAILED; - } - return MAV_RESULT_ACCEPTED; +#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED + case MAV_CMD_NAV_SET_YAW_SPEED: + send_received_message_deprecation_warning("MAV_CMD_NAV_SET_YAW_SPEED"); + return handle_command_nav_set_yaw_speed(packet, msg); +#endif - case MAV_CMD_DO_SET_REVERSE: - // param1 : Direction (0=Forward, 1=Reverse) - rover.control_mode->set_reversed(is_equal(packet.param1,1.0f)); - return MAV_RESULT_ACCEPTED; + default: + return GCS_MAVLINK::handle_command_int_packet(packet, msg); + } +} - case MAV_CMD_NAV_SET_YAW_SPEED: - { - // param1 : yaw angle to adjust direction by in centidegress - // param2 : Speed - normalized to 0 .. 1 - // param3 : 0 = absolute, 1 = relative +#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED +MAV_RESULT GCS_MAVLINK_Rover::handle_command_nav_set_yaw_speed(const mavlink_command_int_t &packet, const mavlink_message_t &msg) +{ + // param1 : yaw angle (may be absolute or relative) + // param2 : Speed - in metres/second + // param3 : 0 = param1 is absolute, 1 = param1 is relative // exit if vehicle is not in Guided mode if (!rover.control_mode->in_guided_mode()) { @@ -709,23 +716,8 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l rover.mode_guided.set_desired_heading_and_speed(packet.param1 * 100.0f, packet.param2); } return MAV_RESULT_ACCEPTED; - } - - case MAV_CMD_DO_MOTOR_TEST: - // param1 : motor sequence number (a number from 1 to max number of motors on the vehicle) - // param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum) - // param3 : throttle (range depends upon param2) - // param4 : timeout (in seconds) - return rover.mavlink_motor_test_start(*this, - (AP_MotorsUGV::motor_test_order)packet.param1, - static_cast(packet.param2), - static_cast(packet.param3), - packet.param4); - - default: - return GCS_MAVLINK::handle_command_long_packet(packet); - } } +#endif MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_command_int_t &packet) { diff --git a/Rover/GCS_Mavlink.h b/Rover/GCS_Mavlink.h index 028c92f497a6b4..f628bfa530bc4e 100644 --- a/Rover/GCS_Mavlink.h +++ b/Rover/GCS_Mavlink.h @@ -2,6 +2,11 @@ #include + // 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 +#endif + class GCS_MAVLINK_Rover : public GCS_MAVLINK { public: @@ -15,10 +20,10 @@ class GCS_MAVLINK_Rover : public GCS_MAVLINK uint8_t sysid_my_gcs() const override; bool sysid_enforce() const override; - MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; - MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override; - MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; + MAV_RESULT _handle_command_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); + MAV_RESULT handle_command_nav_set_yaw_speed(const mavlink_command_int_t &packet, const mavlink_message_t &msg); void send_position_target_global_int() override; diff --git a/Rover/Log.cpp b/Rover/Log.cpp index 6f40ceae0bf599..c8c18d8ee9ec1e 100644 --- a/Rover/Log.cpp +++ b/Rover/Log.cpp @@ -241,7 +241,7 @@ void Rover::Log_Write_RC(void) void Rover::Log_Write_Vehicle_Startup_Messages() { // only 200(?) bytes are guaranteed by AP_Logger - logger.Write_Mode(control_mode->mode_number(), control_mode_reason); + logger.Write_Mode((uint8_t)control_mode->mode_number(), control_mode_reason); ahrs.Log_Write_Home_And_Origin(); gps.Write_AP_Logger_Log_Startup_messages(); } diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 5fb3ebf7078eef..313cec0c21dc62 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -29,7 +29,7 @@ const AP_Param::Info Rover::var_info[] = { // @Description: This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver. Usually used in combination with when AUTO_TRIGGER_PIN or AUTO_KICKSTART. // @CopyValuesFrom: MODE1 // @User: Advanced - GSCALAR(initial_mode, "INITIAL_MODE", Mode::Number::MANUAL), + GSCALAR(initial_mode, "INITIAL_MODE", (int8_t)Mode::Number::MANUAL), // @Param: SYSID_THISMAV // @DisplayName: MAVLink system ID of this vehicle @@ -109,7 +109,7 @@ const AP_Param::Info Rover::var_info[] = { // @Description: What to do on a failsafe event // @Values: 0:Nothing,1:RTL,2:Hold,3:SmartRTL or RTL,4:SmartRTL or Hold // @User: Standard - GSCALAR(fs_action, "FS_ACTION", Failsafe_Action_Hold), + GSCALAR(fs_action, "FS_ACTION", (int8_t)FailsafeAction::Hold), // @Param: FS_TIMEOUT // @DisplayName: Failsafe timeout @@ -174,38 +174,38 @@ const AP_Param::Info Rover::var_info[] = { // @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,8:Dock,9:Circle,10:Auto,11:RTL,12:SmartRTL,15:Guided // @User: Standard // @Description: Driving mode for switch position 1 (910 to 1230 and above 2049) - GSCALAR(mode1, "MODE1", Mode::Number::MANUAL), + GSCALAR(mode1, "MODE1", (int8_t)Mode::Number::MANUAL), // @Param: MODE2 // @DisplayName: Mode2 // @Description: Driving mode for switch position 2 (1231 to 1360) // @CopyValuesFrom: MODE1 // @User: Standard - GSCALAR(mode2, "MODE2", Mode::Number::MANUAL), + GSCALAR(mode2, "MODE2", (int8_t)Mode::Number::MANUAL), // @Param: MODE3 // @CopyFieldsFrom: MODE1 // @DisplayName: Mode3 // @Description: Driving mode for switch position 3 (1361 to 1490) - GSCALAR(mode3, "MODE3", Mode::Number::MANUAL), + GSCALAR(mode3, "MODE3", (int8_t)Mode::Number::MANUAL), // @Param: MODE4 // @CopyFieldsFrom: MODE1 // @DisplayName: Mode4 // @Description: Driving mode for switch position 4 (1491 to 1620) - GSCALAR(mode4, "MODE4", Mode::Number::MANUAL), + GSCALAR(mode4, "MODE4", (int8_t)Mode::Number::MANUAL), // @Param: MODE5 // @CopyFieldsFrom: MODE1 // @DisplayName: Mode5 // @Description: Driving mode for switch position 5 (1621 to 1749) - GSCALAR(mode5, "MODE5", Mode::Number::MANUAL), + GSCALAR(mode5, "MODE5", (int8_t)Mode::Number::MANUAL), // @Param: MODE6 // @CopyFieldsFrom: MODE1 // @DisplayName: Mode6 // @Description: Driving mode for switch position 6 (1750 to 2049) - GSCALAR(mode6, "MODE6", Mode::Number::MANUAL), + GSCALAR(mode6, "MODE6", (int8_t)Mode::Number::MANUAL), // variables not in the g class which contain EEPROM saved variables @@ -517,9 +517,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @User: Standard AP_GROUPINFO("CRASH_ANGLE", 22, ParametersG2, crash_angle, 0), +#if AP_FOLLOW_ENABLED // @Group: FOLL // @Path: ../libraries/AP_Follow/AP_Follow.cpp AP_SUBGROUPINFO(follow, "FOLL", 23, ParametersG2, AP_Follow), +#endif // @Param: FRAME_TYPE // @DisplayName: Frame Type @@ -546,7 +548,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Path: ../libraries/AP_WheelEncoder/AP_WheelRateControl.cpp AP_SUBGROUPINFO(wheel_rate_control, "WRC", 27, ParametersG2, AP_WheelRateControl), -#if AP_RALLY == ENABLED +#if HAL_RALLY_ENABLED // @Group: RALLY_ // @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp AP_SUBGROUPINFO(rally, "RALLY_", 28, ParametersG2, AP_Rally_Rover), @@ -752,7 +754,9 @@ ParametersG2::ParametersG2(void) proximity(), #endif avoid(), +#if AP_FOLLOW_ENABLED follow(), +#endif windvane(), pos_control(attitude_control), wp_nav(attitude_control, pos_control), diff --git a/Rover/Parameters.h b/Rover/Parameters.h index e93bc5bc0866a3..035d16f4d0ffb4 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -316,13 +316,13 @@ class ParametersG2 { AP_Beacon beacon; #endif - // Motor library - AP_MotorsUGV motors; - // wheel encoders AP_WheelEncoder wheel_encoder; AP_WheelRateControl wheel_rate_control; + // Motor library + AP_MotorsUGV motors; + // steering and throttle controller AR_AttitudeControl attitude_control; @@ -360,8 +360,10 @@ class ParametersG2 { // pitch/roll angle for crash check AP_Int8 crash_angle; +#if AP_FOLLOW_ENABLED // follow mode library AP_Follow follow; +#endif // frame type for vehicle (used for vectored motor vehicles and custom motor configs) AP_Int8 frame_type; @@ -379,8 +381,10 @@ class ParametersG2 { AP_Gripper gripper; #endif +#if HAL_RALLY_ENABLED // Rally point library AP_Rally_Rover rally; +#endif // Simple mode types AP_Int8 simple_type; diff --git a/Rover/RC_Channel.cpp b/Rover/RC_Channel.cpp index 3d27b926294dec..e799f38a70fd24 100644 --- a/Rover/RC_Channel.cpp +++ b/Rover/RC_Channel.cpp @@ -214,10 +214,12 @@ bool RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit do_aux_function_change_mode(rover.mode_loiter, ch_flag); break; +#if MODE_FOLLOW_ENABLED == ENABLED // Set mode to Follow case AUX_FUNC::FOLLOW: do_aux_function_change_mode(rover.mode_follow, ch_flag); break; +#endif // set mode to Simple case AUX_FUNC::SIMPLE: diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index 2a429dd5556f37..4b6497382b48dd 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -207,6 +207,14 @@ bool Rover::set_steering_and_throttle(float steering, float throttle) return true; } +// get steering and throttle (-1 to +1) (for use by scripting) +bool Rover::get_steering_and_throttle(float& steering, float& throttle) +{ + steering = g2.motors.get_steering() / 4500.0; + throttle = g2.motors.get_throttle() * 0.01; + return true; +} + // set desired turn rate (degrees/sec) and speed (m/s). Used for scripting bool Rover::set_desired_turn_rate_and_speed(float turn_rate, float speed) { @@ -421,6 +429,11 @@ void Rover::update_logging2(void) gyro_fft.write_log_messages(); #endif } +#if HAL_MOUNT_ENABLED + if (should_log(MASK_LOG_CAMERA)) { + camera_mount.write_log(); + } +#endif } diff --git a/Rover/Rover.h b/Rover/Rover.h index d3ad64aad72fa5..a15d086b4d1609 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -43,6 +43,11 @@ #include #include #include +#include +#include +#if AP_EXTERNAL_CONTROL_ENABLED +#include +#endif // Configuration #include "defines.h" @@ -91,7 +96,9 @@ class Rover : public AP_Vehicle { friend class ModeManual; friend class ModeRTL; friend class ModeSmartRTL; +#if MODE_FOLLOW_ENABLED == ENABLED friend class ModeFollow; +#endif friend class ModeSimple; #if MODE_DOCK_ENABLED == ENABLED friend class ModeDock; @@ -140,6 +147,11 @@ class Rover : public AP_Vehicle { // Arming/Disarming management class AP_Arming_Rover arming; + // dummy external control implementation +#if AP_EXTERNAL_CONTROL_ENABLED + AP_ExternalControl external_control; +#endif + #if AP_OPTICALFLOW_ENABLED AP_OpticalFlow optflow; #endif @@ -236,7 +248,9 @@ class Rover : public AP_Vehicle { ModeSteering mode_steering; ModeRTL mode_rtl; ModeSmartRTL mode_smartrtl; +#if MODE_FOLLOW_ENABLED == ENABLED ModeFollow mode_follow; +#endif ModeSimple mode_simple; #if MODE_DOCK_ENABLED == ENABLED ModeDock mode_dock; @@ -258,6 +272,7 @@ class Rover : public AP_Vehicle { bool set_target_location(const Location& target_loc) override; 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; // set desired turn rate (degrees/sec) and speed (m/s). Used for scripting bool set_desired_turn_rate_and_speed(float turn_rate, float speed) override; bool set_desired_speed(float speed) override; @@ -363,6 +378,7 @@ class Rover : public AP_Vehicle { bool gcs_mode_enabled(const Mode::Number mode_num) const; bool set_mode(Mode &new_mode, ModeReason reason); bool set_mode(const uint8_t new_mode, ModeReason reason) override; + bool set_mode(Mode::Number new_mode, ModeReason reason); uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); } bool current_mode_requires_mission() const override { return control_mode == &mode_auto; @@ -379,13 +395,13 @@ class Rover : public AP_Vehicle { bool get_wp_bearing_deg(float &bearing) const override; bool get_wp_crosstrack_error_m(float &xtrack_error) const override; - enum Failsafe_Action { - Failsafe_Action_None = 0, - Failsafe_Action_RTL = 1, - Failsafe_Action_Hold = 2, - Failsafe_Action_SmartRTL = 3, - Failsafe_Action_SmartRTL_Hold = 4, - Failsafe_Action_Terminate = 5 + enum class FailsafeAction: int8_t { + None = 0, + RTL = 1, + Hold = 2, + SmartRTL = 3, + SmartRTL_Hold = 4, + Terminate = 5 }; enum class Failsafe_Options : uint32_t { @@ -393,12 +409,12 @@ class Rover : public AP_Vehicle { }; static constexpr int8_t _failsafe_priorities[] = { - Failsafe_Action_Terminate, - Failsafe_Action_Hold, - Failsafe_Action_RTL, - Failsafe_Action_SmartRTL_Hold, - Failsafe_Action_SmartRTL, - Failsafe_Action_None, + (int8_t)FailsafeAction::Terminate, + (int8_t)FailsafeAction::Hold, + (int8_t)FailsafeAction::RTL, + (int8_t)FailsafeAction::SmartRTL_Hold, + (int8_t)FailsafeAction::SmartRTL, + (int8_t)FailsafeAction::None, -1 // the priority list must end with a sentinel of -1 }; static_assert(_failsafe_priorities[ARRAY_SIZE(_failsafe_priorities) - 1] == -1, diff --git a/Rover/afs_rover.cpp b/Rover/afs_rover.cpp index e0349eefc0ea87..4265a20887ebb2 100644 --- a/Rover/afs_rover.cpp +++ b/Rover/afs_rover.cpp @@ -29,4 +29,9 @@ AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Rover::afs_mode(void) return AP_AdvancedFailsafe::AFS_STABILIZED; } +//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); + } #endif // ADVANCED_FAILSAFE diff --git a/Rover/afs_rover.h b/Rover/afs_rover.h index 36dd0a0aa9f2f1..aa3473ddc39d54 100644 --- a/Rover/afs_rover.h +++ b/Rover/afs_rover.h @@ -38,6 +38,9 @@ class AP_AdvancedFailsafe_Rover : public AP_AdvancedFailsafe // return the AFS mapped control mode enum control_mode afs_mode(void) override; + + //to force entering auto mode when datalink loss + void set_mode_auto(void) override; }; #endif // ADVANCED_FAILSAFE diff --git a/Rover/config.h b/Rover/config.h index 77b2981c5fbcc5..7a280e88f3497a 100644 --- a/Rover/config.h +++ b/Rover/config.h @@ -31,13 +31,6 @@ #error XXX #endif -////////////////////////////////////////////////////////////////////////////// -// RALLY POINTS -// -#ifndef AP_RALLY - #define AP_RALLY ENABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // NAVL1 // @@ -67,6 +60,12 @@ # define MODE_DOCK_ENABLED AC_PRECLAND_ENABLED #endif +////////////////////////////////////////////////////////////////////////////// +// Follow mode - allows vehicle to follow target +#ifndef MODE_FOLLOW_ENABLED +# define MODE_FOLLOW_ENABLED AP_FOLLOW_ENABLED +#endif + ////////////////////////////////////////////////////////////////////////////// // Developer Items diff --git a/Rover/failsafe.cpp b/Rover/failsafe.cpp index 2520c73f663345..da877c2bb7482a 100644 --- a/Rover/failsafe.cpp +++ b/Rover/failsafe.cpp @@ -80,29 +80,30 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool o // continue with mission in auto mode gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe - Continuing Auto Mode"); } else { - switch (g.fs_action) { - case Failsafe_Action_None: + switch ((FailsafeAction)g.fs_action.get()) { + case FailsafeAction::None: break; - case Failsafe_Action_RTL: - if (!set_mode(mode_rtl, ModeReason::FAILSAFE)) { - set_mode(mode_hold, ModeReason::FAILSAFE); + case FailsafeAction::SmartRTL: + if (set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) { + break; } - break; - case Failsafe_Action_Hold: - set_mode(mode_hold, ModeReason::FAILSAFE); - break; - case Failsafe_Action_SmartRTL: - if (!set_mode(mode_smartrtl, ModeReason::FAILSAFE)) { - if (!set_mode(mode_rtl, ModeReason::FAILSAFE)) { - set_mode(mode_hold, ModeReason::FAILSAFE); - } + FALLTHROUGH; + case FailsafeAction::RTL: + if (set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE)) { + break; } + FALLTHROUGH; + case FailsafeAction::Hold: + set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE); break; - case Failsafe_Action_SmartRTL_Hold: + case FailsafeAction::SmartRTL_Hold: if (!set_mode(mode_smartrtl, ModeReason::FAILSAFE)) { set_mode(mode_hold, ModeReason::FAILSAFE); } break; + case FailsafeAction::Terminate: + arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE); + break; } } } @@ -110,28 +111,28 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool o void Rover::handle_battery_failsafe(const char* type_str, const int8_t action) { - switch ((Failsafe_Action)action) { - case Failsafe_Action_None: + switch ((FailsafeAction)action) { + case FailsafeAction::None: break; - case Failsafe_Action_SmartRTL: + case FailsafeAction::SmartRTL: if (set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) { break; } FALLTHROUGH; - case Failsafe_Action_RTL: + case FailsafeAction::RTL: if (set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE)) { break; } FALLTHROUGH; - case Failsafe_Action_Hold: + case FailsafeAction::Hold: set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE); break; - case Failsafe_Action_SmartRTL_Hold: + case FailsafeAction::SmartRTL_Hold: if (!set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) { set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE); } break; - case Failsafe_Action_Terminate: + case FailsafeAction::Terminate: #if ADVANCED_FAILSAFE == ENABLED char battery_type_str[17]; snprintf(battery_type_str, 17, "%s battery", type_str); diff --git a/Rover/fence.cpp b/Rover/fence.cpp index fba0706bdefd6a..7150c88c467ccc 100644 --- a/Rover/fence.cpp +++ b/Rover/fence.cpp @@ -18,32 +18,33 @@ void Rover::fence_check() // if there is a new breach take action if (new_breaches) { // if the user wants some kind of response and motors are armed - if (fence.get_action() != Failsafe_Action_None) { + if ((FailsafeAction)fence.get_action() != FailsafeAction::None) { // if within 100m of the fence, it will take the action specified by the FENCE_ACTION parameter if (fence.get_breach_distance(new_breaches) <= AC_FENCE_GIVE_UP_DISTANCE) { - switch (fence.get_action()) { - case Failsafe_Action_None: + switch ((FailsafeAction)fence.get_action()) { + case FailsafeAction::None: break; - case Failsafe_Action_RTL: - if (!set_mode(mode_rtl, ModeReason::FENCE_BREACHED)) { - set_mode(mode_hold, ModeReason::FENCE_BREACHED); + case FailsafeAction::SmartRTL: + if (set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) { + break; } - break; - case Failsafe_Action_Hold: - set_mode(mode_hold, ModeReason::FENCE_BREACHED); - break; - case Failsafe_Action_SmartRTL: - if (!set_mode(mode_smartrtl, ModeReason::FENCE_BREACHED)) { - if (!set_mode(mode_rtl, ModeReason::FENCE_BREACHED)) { - set_mode(mode_hold, ModeReason::FENCE_BREACHED); - } + FALLTHROUGH; + case FailsafeAction::RTL: + if (set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE)) { + break; } + FALLTHROUGH; + case FailsafeAction::Hold: + set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE); break; - case Failsafe_Action_SmartRTL_Hold: + case FailsafeAction::SmartRTL_Hold: if (!set_mode(mode_smartrtl, ModeReason::FENCE_BREACHED)) { set_mode(mode_hold, ModeReason::FENCE_BREACHED); } break; + case FailsafeAction::Terminate: + arming.disarm(AP_Arming::Method::FENCEBREACH); + break; } } else { // if more than 100m outside the fence just force to HOLD diff --git a/Rover/mode.cpp b/Rover/mode.cpp index 5f70481c191eb0..842789c1006698 100644 --- a/Rover/mode.cpp +++ b/Rover/mode.cpp @@ -531,9 +531,11 @@ Mode *Rover::mode_from_mode_num(const enum Mode::Number num) case Mode::Number::LOITER: ret = &mode_loiter; break; +#if MODE_FOLLOW_ENABLED == ENABLED case Mode::Number::FOLLOW: ret = &mode_follow; break; +#endif case Mode::Number::SIMPLE: ret = &mode_simple; break; diff --git a/Rover/mode.h b/Rover/mode.h index 0ac0c4c4097e77..fb9a57514dbe4c 100644 --- a/Rover/mode.h +++ b/Rover/mode.h @@ -11,7 +11,7 @@ class Mode // Auto Pilot modes // ---------------- - enum Number : uint8_t { + enum class Number : uint8_t { MANUAL = 0, ACRO = 1, STEERING = 3, @@ -43,7 +43,7 @@ class Mode void exit(); // returns a unique number specific to this mode - virtual uint32_t mode_number() const = 0; + virtual Number mode_number() const = 0; // returns short text name (up to 4 bytes) virtual const char *name4() const = 0; @@ -218,7 +218,7 @@ class ModeAcro : public Mode { public: - uint32_t mode_number() const override { return ACRO; } + Number mode_number() const override { return Number::ACRO; } const char *name4() const override { return "ACRO"; } // methods that affect movement of the vehicle in this mode @@ -240,7 +240,7 @@ class ModeAuto : public Mode { public: - uint32_t mode_number() const override { return AUTO; } + Number mode_number() const override { return Number::AUTO; } const char *name4() const override { return "AUTO"; } // methods that affect movement of the vehicle in this mode @@ -251,7 +251,7 @@ class ModeAuto : public Mode bool is_autopilot_mode() const override { return true; } // return if external control is allowed in this mode (Guided or Guided-within-Auto) - bool in_guided_mode() const override { return _submode == Auto_Guided || _submode == Auto_NavScriptTime; } + bool in_guided_mode() const override { return _submode == SubMode::Guided || _submode == SubMode::NavScriptTime; } // return heading (in degrees) and cross track error (in meters) for reporting to ground station (NAV_CONTROLLER_OUTPUT message) float wp_bearing() const override; @@ -294,15 +294,15 @@ class ModeAuto : public Mode bool _enter() override; void _exit() override; - enum AutoSubMode { - Auto_WP, // drive to a given location - Auto_HeadingAndSpeed, // turn to a given heading - Auto_RTL, // perform RTL within auto mode - Auto_Loiter, // perform Loiter within auto mode - Auto_Guided, // handover control to external navigation system from within auto mode - Auto_Stop, // stop the vehicle as quickly as possible - Auto_NavScriptTime, // accept targets from lua scripts while NAV_SCRIPT_TIME commands are executing - Auto_Circle, // circle a given location + enum SubMode: uint8_t { + WP, // drive to a given location + HeadingAndSpeed, // turn to a given heading + RTL, // perform RTL within auto mode + Loiter, // perform Loiter within auto mode + Guided, // handover control to external navigation system from within auto mode + Stop, // stop the vehicle as quickly as possible + NavScriptTime, // accept targets from lua scripts while NAV_SCRIPT_TIME commands are executing + Circle, // circle a given location } _submode; private: @@ -405,7 +405,7 @@ class ModeCircle : public Mode // Does not allow copies CLASS_NO_COPY(ModeCircle); - uint32_t mode_number() const override { return CIRCLE; } + Number mode_number() const override { return Number::CIRCLE; } const char *name4() const override { return "CIRC"; } // initialise with specific center location, radius (in meters) and direction @@ -489,7 +489,7 @@ class ModeGuided : public Mode { public: - uint32_t mode_number() const override { return GUIDED; } + Number mode_number() const override { return Number::GUIDED; } const char *name4() const override { return "GUID"; } // methods that affect movement of the vehicle in this mode @@ -544,13 +544,13 @@ class ModeGuided : public Mode protected: - enum GuidedMode { - Guided_WP, - Guided_HeadingAndSpeed, - Guided_TurnRateAndSpeed, - Guided_Loiter, - Guided_SteeringAndThrottle, - Guided_Stop + enum class SubMode: uint8_t { + WP, + HeadingAndSpeed, + TurnRateAndSpeed, + Loiter, + SteeringAndThrottle, + Stop }; // enum for GUID_OPTIONS parameter @@ -564,7 +564,7 @@ class ModeGuided : public Mode // scurves provide path planning and object avoidance but cannot handle fast updates to the destination (for fast updates use position controller input shaping) bool use_scurves_for_navigation() const; - GuidedMode _guided_mode; // stores which GUIDED mode the vehicle is in + SubMode _guided_mode; // stores which GUIDED mode the vehicle is in // attitude control bool have_attitude_target; // true if we have a valid attitude target @@ -593,7 +593,7 @@ class ModeHold : public Mode { public: - uint32_t mode_number() const override { return HOLD; } + Number mode_number() const override { return Number::HOLD; } const char *name4() const override { return "HOLD"; } // methods that affect movement of the vehicle in this mode @@ -611,7 +611,7 @@ class ModeLoiter : public Mode { public: - uint32_t mode_number() const override { return LOITER; } + Number mode_number() const override { return Number::LOITER; } const char *name4() const override { return "LOIT"; } // methods that affect movement of the vehicle in this mode @@ -643,7 +643,7 @@ class ModeManual : public Mode { public: - uint32_t mode_number() const override { return MANUAL; } + Number mode_number() const override { return Number::MANUAL; } const char *name4() const override { return "MANU"; } // methods that affect movement of the vehicle in this mode @@ -667,7 +667,7 @@ class ModeRTL : public Mode { public: - uint32_t mode_number() const override { return RTL; } + Number mode_number() const override { return Number::RTL; } const char *name4() const override { return "RTL"; } // methods that affect movement of the vehicle in this mode @@ -702,7 +702,7 @@ class ModeSmartRTL : public Mode { public: - uint32_t mode_number() const override { return SMART_RTL; } + Number mode_number() const override { return Number::SMART_RTL; } const char *name4() const override { return "SRTL"; } // methods that affect movement of the vehicle in this mode @@ -719,7 +719,7 @@ class ModeSmartRTL : public Mode // return distance (in meters) to destination float get_distance_to_destination() const override { return _distance_to_destination; } - bool reached_destination() const override { return smart_rtl_state == SmartRTL_StopAtHome; } + bool reached_destination() const override { return smart_rtl_state == SmartRTLState::StopAtHome; } // set desired speed in m/s bool set_desired_speed(float speed) override; @@ -730,11 +730,11 @@ class ModeSmartRTL : public Mode protected: // Safe RTL states - enum SmartRTLState { - SmartRTL_WaitForPathCleanup, - SmartRTL_PathFollow, - SmartRTL_StopAtHome, - SmartRTL_Failure + enum class SmartRTLState: uint8_t { + WaitForPathCleanup, + PathFollow, + StopAtHome, + Failure } smart_rtl_state; bool _enter() override; @@ -748,7 +748,7 @@ class ModeSteering : public Mode { public: - uint32_t mode_number() const override { return STEERING; } + Number mode_number() const override { return Number::STEERING; } const char *name4() const override { return "STER"; } // methods that affect movement of the vehicle in this mode @@ -773,7 +773,7 @@ class ModeInitializing : public Mode { public: - uint32_t mode_number() const override { return INITIALISING; } + Number mode_number() const override { return Number::INITIALISING; } const char *name4() const override { return "INIT"; } // methods that affect movement of the vehicle in this mode @@ -789,11 +789,12 @@ class ModeInitializing : public Mode bool _enter() override { return false; }; }; +#if MODE_FOLLOW_ENABLED == ENABLED class ModeFollow : public Mode { public: - uint32_t mode_number() const override { return FOLLOW; } + Number mode_number() const override { return Number::FOLLOW; } const char *name4() const override { return "FOLL"; } // methods that affect movement of the vehicle in this mode @@ -823,12 +824,13 @@ class ModeFollow : public Mode float _desired_speed; // desired speed in m/s }; +#endif class ModeSimple : public Mode { public: - uint32_t mode_number() const override { return SIMPLE; } + Number mode_number() const override { return Number::SIMPLE; } const char *name4() const override { return "SMPL"; } // methods that affect movement of the vehicle in this mode @@ -858,7 +860,7 @@ class ModeDock : public Mode // Does not allow copies CLASS_NO_COPY(ModeDock); - uint32_t mode_number() const override { return DOCK; } + Number mode_number() const override { return Number::DOCK; } const char *name4() const override { return "DOCK"; } // methods that affect movement of the vehicle in this mode diff --git a/Rover/mode_auto.cpp b/Rover/mode_auto.cpp index 5be1d1eba0a7c1..439f4a014b034e 100644 --- a/Rover/mode_auto.cpp +++ b/Rover/mode_auto.cpp @@ -66,7 +66,7 @@ void ModeAuto::update() // check for mission changes if (mis_change_detector.check_for_mission_change()) { // if mission is running restart the current command if it is a waypoint command - if ((mission.state() == AP_Mission::MISSION_RUNNING) && (_submode == AutoSubMode::Auto_WP)) { + if ((mission.state() == AP_Mission::MISSION_RUNNING) && (_submode == SubMode::WP)) { if (mission.restart_current_nav_cmd()) { gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto mission changed, restarted command"); } else { @@ -80,7 +80,7 @@ void ModeAuto::update() } switch (_submode) { - case Auto_WP: + case SubMode::WP: { // check if we've reached the destination if (!g2.wp_nav.reached_destination() || g2.wp_nav.is_fast_waypoint()) { @@ -101,7 +101,7 @@ void ModeAuto::update() break; } - case Auto_HeadingAndSpeed: + case SubMode::HeadingAndSpeed: { if (!_reached_heading) { // run steering and throttle controllers @@ -122,15 +122,15 @@ void ModeAuto::update() break; } - case Auto_RTL: + case SubMode::RTL: rover.mode_rtl.update(); break; - case Auto_Loiter: + case SubMode::Loiter: rover.mode_loiter.update(); break; - case Auto_Guided: + case SubMode::Guided: { // send location target to offboard navigation system send_guided_position_target(); @@ -138,15 +138,15 @@ void ModeAuto::update() break; } - case Auto_Stop: + case SubMode::Stop: stop_vehicle(); break; - case Auto_NavScriptTime: + case SubMode::NavScriptTime: rover.mode_guided.update(); break; - case Auto_Circle: + case SubMode::Circle: rover.g2.mode_circle.update(); break; } @@ -166,19 +166,19 @@ void ModeAuto::calc_throttle(float target_speed, bool avoidance_enabled) float ModeAuto::wp_bearing() const { switch (_submode) { - case Auto_WP: + case SubMode::WP: return g2.wp_nav.wp_bearing_cd() * 0.01f; - case Auto_HeadingAndSpeed: - case Auto_Stop: + case SubMode::HeadingAndSpeed: + case SubMode::Stop: return 0.0f; - case Auto_RTL: + case SubMode::RTL: return rover.mode_rtl.wp_bearing(); - case Auto_Loiter: + case SubMode::Loiter: return rover.mode_loiter.wp_bearing(); - case Auto_Guided: - case Auto_NavScriptTime: + case SubMode::Guided: + case SubMode::NavScriptTime: return rover.mode_guided.wp_bearing(); - case Auto_Circle: + case SubMode::Circle: return rover.g2.mode_circle.wp_bearing(); } @@ -190,19 +190,19 @@ float ModeAuto::wp_bearing() const float ModeAuto::nav_bearing() const { switch (_submode) { - case Auto_WP: + case SubMode::WP: return g2.wp_nav.nav_bearing_cd() * 0.01f; - case Auto_HeadingAndSpeed: - case Auto_Stop: + case SubMode::HeadingAndSpeed: + case SubMode::Stop: return 0.0f; - case Auto_RTL: + case SubMode::RTL: return rover.mode_rtl.nav_bearing(); - case Auto_Loiter: + case SubMode::Loiter: return rover.mode_loiter.nav_bearing(); - case Auto_Guided: - case Auto_NavScriptTime: + case SubMode::Guided: + case SubMode::NavScriptTime: return rover.mode_guided.nav_bearing(); - case Auto_Circle: + case SubMode::Circle: return rover.g2.mode_circle.nav_bearing(); } @@ -214,19 +214,19 @@ float ModeAuto::nav_bearing() const float ModeAuto::crosstrack_error() const { switch (_submode) { - case Auto_WP: + case SubMode::WP: return g2.wp_nav.crosstrack_error(); - case Auto_HeadingAndSpeed: - case Auto_Stop: + case SubMode::HeadingAndSpeed: + case SubMode::Stop: return 0.0f; - case Auto_RTL: + case SubMode::RTL: return rover.mode_rtl.crosstrack_error(); - case Auto_Loiter: + case SubMode::Loiter: return rover.mode_loiter.crosstrack_error(); - case Auto_Guided: - case Auto_NavScriptTime: + case SubMode::Guided: + case SubMode::NavScriptTime: return rover.mode_guided.crosstrack_error(); - case Auto_Circle: + case SubMode::Circle: return rover.g2.mode_circle.crosstrack_error(); } @@ -238,19 +238,19 @@ float ModeAuto::crosstrack_error() const float ModeAuto::get_desired_lat_accel() const { switch (_submode) { - case Auto_WP: + case SubMode::WP: return g2.wp_nav.get_lat_accel(); - case Auto_HeadingAndSpeed: - case Auto_Stop: + case SubMode::HeadingAndSpeed: + case SubMode::Stop: return 0.0f; - case Auto_RTL: + case SubMode::RTL: return rover.mode_rtl.get_desired_lat_accel(); - case Auto_Loiter: + case SubMode::Loiter: return rover.mode_loiter.get_desired_lat_accel(); - case Auto_Guided: - case Auto_NavScriptTime: + case SubMode::Guided: + case SubMode::NavScriptTime: return rover.mode_guided.get_desired_lat_accel(); - case Auto_Circle: + case SubMode::Circle: return rover.g2.mode_circle.get_desired_lat_accel(); } @@ -262,20 +262,20 @@ float ModeAuto::get_desired_lat_accel() const float ModeAuto::get_distance_to_destination() const { switch (_submode) { - case Auto_WP: + case SubMode::WP: return _distance_to_destination; - case Auto_HeadingAndSpeed: - case Auto_Stop: + case SubMode::HeadingAndSpeed: + case SubMode::Stop: // no valid distance so return zero return 0.0f; - case Auto_RTL: + case SubMode::RTL: return rover.mode_rtl.get_distance_to_destination(); - case Auto_Loiter: + case SubMode::Loiter: return rover.mode_loiter.get_distance_to_destination(); - case Auto_Guided: - case Auto_NavScriptTime: + case SubMode::Guided: + case SubMode::NavScriptTime: return rover.mode_guided.get_distance_to_destination(); - case Auto_Circle: + case SubMode::Circle: return rover.g2.mode_circle.get_distance_to_destination(); } @@ -287,24 +287,24 @@ float ModeAuto::get_distance_to_destination() const bool ModeAuto::get_desired_location(Location& destination) const { switch (_submode) { - case Auto_WP: + case SubMode::WP: if (g2.wp_nav.is_destination_valid()) { destination = g2.wp_nav.get_oa_destination(); return true; } return false; - case Auto_HeadingAndSpeed: - case Auto_Stop: + case SubMode::HeadingAndSpeed: + case SubMode::Stop: // no desired location for this submode return false; - case Auto_RTL: + case SubMode::RTL: return rover.mode_rtl.get_desired_location(destination); - case Auto_Loiter: + case SubMode::Loiter: return rover.mode_loiter.get_desired_location(destination); - case Auto_Guided: - case Auto_NavScriptTime: + case SubMode::Guided: + case SubMode::NavScriptTime: return rover.mode_guided.get_desired_location(destination); - case Auto_Circle: + case SubMode::Circle: return rover.g2.mode_circle.get_desired_location(destination); } @@ -320,7 +320,7 @@ bool ModeAuto::set_desired_location(const Location &destination, Location next_d return false; } - _submode = Auto_WP; + _submode = SubMode::WP; return true; } @@ -329,24 +329,24 @@ bool ModeAuto::set_desired_location(const Location &destination, Location next_d bool ModeAuto::reached_destination() const { switch (_submode) { - case Auto_WP: + case SubMode::WP: return g2.wp_nav.reached_destination(); break; - case Auto_HeadingAndSpeed: - case Auto_Stop: + case SubMode::HeadingAndSpeed: + case SubMode::Stop: // always return true because this is the safer option to allow missions to continue return true; break; - case Auto_RTL: + case SubMode::RTL: return rover.mode_rtl.reached_destination(); break; - case Auto_Loiter: + case SubMode::Loiter: return rover.mode_loiter.reached_destination(); break; - case Auto_Guided: - case Auto_NavScriptTime: + case SubMode::Guided: + case SubMode::NavScriptTime: return rover.mode_guided.reached_destination(); - case Auto_Circle: + case SubMode::Circle: return rover.g2.mode_circle.reached_destination(); } @@ -358,20 +358,20 @@ bool ModeAuto::reached_destination() const bool ModeAuto::set_desired_speed(float speed) { switch (_submode) { - case Auto_WP: - case Auto_Stop: + case SubMode::WP: + case SubMode::Stop: return g2.wp_nav.set_speed_max(speed); - case Auto_HeadingAndSpeed: + case SubMode::HeadingAndSpeed: _desired_speed = speed; return true; - case Auto_RTL: + case SubMode::RTL: return rover.mode_rtl.set_desired_speed(speed); - case Auto_Loiter: + case SubMode::Loiter: return rover.mode_loiter.set_desired_speed(speed); - case Auto_Guided: - case Auto_NavScriptTime: + case SubMode::Guided: + case SubMode::NavScriptTime: return rover.mode_guided.set_desired_speed(speed); - case Auto_Circle: + case SubMode::Circle: return rover.g2.mode_circle.set_desired_speed(speed); } return false; @@ -381,7 +381,7 @@ bool ModeAuto::set_desired_speed(float speed) void ModeAuto::start_RTL() { if (rover.mode_rtl.enter()) { - _submode = Auto_RTL; + _submode = SubMode::RTL; } } @@ -389,7 +389,7 @@ void ModeAuto::start_RTL() bool ModeAuto::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4) { #if AP_SCRIPTING_ENABLED - if (_submode == AutoSubMode::Auto_NavScriptTime) { + if (_submode == SubMode::NavScriptTime) { id = nav_scripting.id; cmd = nav_scripting.command; arg1 = nav_scripting.arg1; @@ -406,7 +406,7 @@ bool ModeAuto::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &a void ModeAuto::nav_script_time_done(uint16_t id) { #if AP_SCRIPTING_ENABLED - if ((_submode == AutoSubMode::Auto_NavScriptTime) && (id == nav_scripting.id)) { + if ((_submode == SubMode::NavScriptTime) && (id == nav_scripting.id)) { nav_scripting.done = true; } #endif @@ -458,7 +458,7 @@ bool ModeAuto::check_trigger(void) bool ModeAuto::start_loiter() { if (rover.mode_loiter.enter()) { - _submode = Auto_Loiter; + _submode = SubMode::Loiter; return true; } return false; @@ -468,7 +468,7 @@ bool ModeAuto::start_loiter() void ModeAuto::start_guided(const Location& loc) { if (rover.mode_guided.enter()) { - _submode = Auto_Guided; + _submode = SubMode::Guided; // initialise guided start time and position as reference for limit checking rover.mode_guided.limit_init_time_and_location(); @@ -487,7 +487,7 @@ void ModeAuto::start_guided(const Location& loc) // start stopping vehicle as quickly as possible void ModeAuto::start_stop() { - _submode = Auto_Stop; + _submode = SubMode::Stop; } // send latest position target to offboard navigation system @@ -788,7 +788,11 @@ void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd) nav_delay_time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds } else { // absolute delay to utc time +#if AP_RTC_ENABLED nav_delay_time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0); +#else + nav_delay_time_max_ms = 0; +#endif } gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000)); } @@ -820,7 +824,7 @@ void ModeAuto::do_nav_set_yaw_speed(const AP_Mission::Mission_Command& cmd) _desired_speed = constrain_float(cmd.content.set_yaw_speed.speed, -speed_max, speed_max); _desired_yaw_cd = desired_heading_cd; _reached_heading = false; - _submode = Auto_HeadingAndSpeed; + _submode = SubMode::HeadingAndSpeed; } /********************************************************************************/ @@ -896,7 +900,7 @@ bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd) { // if we failed to enter guided or this command disables guided // return true so we move to next command - if (_submode != Auto_Guided || cmd.p1 == 0) { + if (_submode != SubMode::Guided || cmd.p1 == 0) { return true; } @@ -914,7 +918,7 @@ bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd) // verify_yaw - return true if we have reached the desired heading bool ModeAuto::verify_nav_set_yaw_speed() { - if (_submode == Auto_HeadingAndSpeed) { + if (_submode == SubMode::HeadingAndSpeed) { return _reached_heading; } // we should never reach here but just in case, return true to allow missions to continue @@ -937,7 +941,7 @@ bool ModeAuto::do_circle(const AP_Mission::Mission_Command& cmd) // initialise circle mode if (g2.mode_circle.set_center(circle_center, circle_radius_m, cmd.content.location.loiter_ccw)) { - _submode = Auto_Circle; + _submode = SubMode::Circle; return true; } return false; @@ -1031,7 +1035,7 @@ void ModeAuto::do_nav_script_time(const AP_Mission::Mission_Command& cmd) { // call regular guided flight mode initialisation if (rover.mode_guided.enter()) { - _submode = AutoSubMode::Auto_NavScriptTime; + _submode = SubMode::NavScriptTime; nav_scripting.done = false; nav_scripting.id++; nav_scripting.start_ms = millis(); diff --git a/Rover/mode_follow.cpp b/Rover/mode_follow.cpp index 437cb53deb8445..964a81a102a6ba 100644 --- a/Rover/mode_follow.cpp +++ b/Rover/mode_follow.cpp @@ -1,5 +1,6 @@ #include "Rover.h" +#if MODE_FOLLOW_ENABLED // initialize follow mode bool ModeFollow::_enter() { @@ -94,3 +95,5 @@ bool ModeFollow::set_desired_speed(float speed) _desired_speed = speed; return true; } + +#endif // MODE_FOLLOW_ENABLED diff --git a/Rover/mode_guided.cpp b/Rover/mode_guided.cpp index 76f34367607bb6..a1d18cf92d006d 100644 --- a/Rover/mode_guided.cpp +++ b/Rover/mode_guided.cpp @@ -22,7 +22,7 @@ bool ModeGuided::_enter() void ModeGuided::update() { switch (_guided_mode) { - case Guided_WP: + case SubMode::WP: { // check if we've reached the destination if (!g2.wp_nav.reached_destination()) { @@ -49,7 +49,7 @@ void ModeGuided::update() break; } - case Guided_HeadingAndSpeed: + case SubMode::HeadingAndSpeed: { // stop vehicle if target not updated within 3 seconds if (have_attitude_target && (millis() - _des_att_time_ms) > 3000) { @@ -73,7 +73,7 @@ void ModeGuided::update() break; } - case Guided_TurnRateAndSpeed: + case SubMode::TurnRateAndSpeed: { // stop vehicle if target not updated within 3 seconds if (have_attitude_target && (millis() - _des_att_time_ms) > 3000) { @@ -101,13 +101,13 @@ void ModeGuided::update() break; } - case Guided_Loiter: + case SubMode::Loiter: { rover.mode_loiter.update(); break; } - case Guided_SteeringAndThrottle: + case SubMode::SteeringAndThrottle: { // handle timeout if (_have_strthr && (AP_HAL::millis() - _strthr_time_ms) > 3000) { @@ -131,7 +131,7 @@ void ModeGuided::update() break; } - case Guided_Stop: + case SubMode::Stop: stop_vehicle(); break; @@ -145,15 +145,15 @@ void ModeGuided::update() float ModeGuided::wp_bearing() const { switch (_guided_mode) { - case Guided_WP: + case SubMode::WP: return g2.wp_nav.wp_bearing_cd() * 0.01f; - case Guided_HeadingAndSpeed: - case Guided_TurnRateAndSpeed: + case SubMode::HeadingAndSpeed: + case SubMode::TurnRateAndSpeed: return 0.0f; - case Guided_Loiter: + case SubMode::Loiter: return rover.mode_loiter.wp_bearing(); - case Guided_SteeringAndThrottle: - case Guided_Stop: + case SubMode::SteeringAndThrottle: + case SubMode::Stop: return 0.0f; } @@ -164,15 +164,15 @@ float ModeGuided::wp_bearing() const float ModeGuided::nav_bearing() const { switch (_guided_mode) { - case Guided_WP: + case SubMode::WP: return g2.wp_nav.nav_bearing_cd() * 0.01f; - case Guided_HeadingAndSpeed: - case Guided_TurnRateAndSpeed: + case SubMode::HeadingAndSpeed: + case SubMode::TurnRateAndSpeed: return 0.0f; - case Guided_Loiter: + case SubMode::Loiter: return rover.mode_loiter.nav_bearing(); - case Guided_SteeringAndThrottle: - case Guided_Stop: + case SubMode::SteeringAndThrottle: + case SubMode::Stop: return 0.0f; } @@ -183,15 +183,15 @@ float ModeGuided::nav_bearing() const float ModeGuided::crosstrack_error() const { switch (_guided_mode) { - case Guided_WP: + case SubMode::WP: return g2.wp_nav.crosstrack_error(); - case Guided_HeadingAndSpeed: - case Guided_TurnRateAndSpeed: + case SubMode::HeadingAndSpeed: + case SubMode::TurnRateAndSpeed: return 0.0f; - case Guided_Loiter: + case SubMode::Loiter: return rover.mode_loiter.crosstrack_error(); - case Guided_SteeringAndThrottle: - case Guided_Stop: + case SubMode::SteeringAndThrottle: + case SubMode::Stop: return 0.0f; } @@ -202,15 +202,15 @@ float ModeGuided::crosstrack_error() const float ModeGuided::get_desired_lat_accel() const { switch (_guided_mode) { - case Guided_WP: + case SubMode::WP: return g2.wp_nav.get_lat_accel(); - case Guided_HeadingAndSpeed: - case Guided_TurnRateAndSpeed: + case SubMode::HeadingAndSpeed: + case SubMode::TurnRateAndSpeed: return 0.0f; - case Guided_Loiter: + case SubMode::Loiter: return rover.mode_loiter.get_desired_lat_accel(); - case Guided_SteeringAndThrottle: - case Guided_Stop: + case SubMode::SteeringAndThrottle: + case SubMode::Stop: return 0.0f; } @@ -222,15 +222,15 @@ float ModeGuided::get_desired_lat_accel() const float ModeGuided::get_distance_to_destination() const { switch (_guided_mode) { - case Guided_WP: + case SubMode::WP: return _distance_to_destination; - case Guided_HeadingAndSpeed: - case Guided_TurnRateAndSpeed: + case SubMode::HeadingAndSpeed: + case SubMode::TurnRateAndSpeed: return 0.0f; - case Guided_Loiter: + case SubMode::Loiter: return rover.mode_loiter.get_distance_to_destination(); - case Guided_SteeringAndThrottle: - case Guided_Stop: + case SubMode::SteeringAndThrottle: + case SubMode::Stop: return 0.0f; } @@ -242,13 +242,13 @@ float ModeGuided::get_distance_to_destination() const bool ModeGuided::reached_destination() const { switch (_guided_mode) { - case Guided_WP: + case SubMode::WP: return g2.wp_nav.reached_destination(); - case Guided_HeadingAndSpeed: - case Guided_TurnRateAndSpeed: - case Guided_Loiter: - case Guided_SteeringAndThrottle: - case Guided_Stop: + case SubMode::HeadingAndSpeed: + case SubMode::TurnRateAndSpeed: + case SubMode::Loiter: + case SubMode::SteeringAndThrottle: + case SubMode::Stop: return true; } @@ -260,16 +260,16 @@ bool ModeGuided::reached_destination() const bool ModeGuided::set_desired_speed(float speed) { switch (_guided_mode) { - case Guided_WP: + case SubMode::WP: return g2.wp_nav.set_speed_max(speed); - case Guided_HeadingAndSpeed: - case Guided_TurnRateAndSpeed: + case SubMode::HeadingAndSpeed: + case SubMode::TurnRateAndSpeed: // speed is set from mavlink message return false; - case Guided_Loiter: + case SubMode::Loiter: return rover.mode_loiter.set_desired_speed(speed); - case Guided_SteeringAndThrottle: - case Guided_Stop: + case SubMode::SteeringAndThrottle: + case SubMode::Stop: // no speed control return false; } @@ -280,21 +280,21 @@ bool ModeGuided::set_desired_speed(float speed) bool ModeGuided::get_desired_location(Location& destination) const { switch (_guided_mode) { - case Guided_WP: + case SubMode::WP: if (g2.wp_nav.is_destination_valid()) { destination = g2.wp_nav.get_oa_destination(); return true; } return false; - case Guided_HeadingAndSpeed: - case Guided_TurnRateAndSpeed: + case SubMode::HeadingAndSpeed: + case SubMode::TurnRateAndSpeed: // not supported in these submodes return false; - case Guided_Loiter: + case SubMode::Loiter: // get destination from loiter return rover.mode_loiter.get_desired_location(destination); - case Guided_SteeringAndThrottle: - case Guided_Stop: + case SubMode::SteeringAndThrottle: + case SubMode::Stop: // no desired location in this submode break; } @@ -320,9 +320,9 @@ bool ModeGuided::set_desired_location(const Location &destination, Location next } // handle guided specific initialisation and logging - _guided_mode = ModeGuided::Guided_WP; + _guided_mode = SubMode::WP; send_notification = true; - rover.Log_Write_GuidedTarget(_guided_mode, Vector3f(destination.lat, destination.lng, 0), Vector3f(g2.wp_nav.get_speed_max(), 0.0f, 0.0f)); + rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(destination.lat, destination.lng, 0), Vector3f(g2.wp_nav.get_speed_max(), 0.0f, 0.0f)); return true; } @@ -330,7 +330,7 @@ bool ModeGuided::set_desired_location(const Location &destination, Location next void ModeGuided::set_desired_heading_and_speed(float yaw_angle_cd, float target_speed) { // initialisation and logging - _guided_mode = ModeGuided::Guided_HeadingAndSpeed; + _guided_mode = SubMode::HeadingAndSpeed; _des_att_time_ms = AP_HAL::millis(); // record targets @@ -339,14 +339,14 @@ void ModeGuided::set_desired_heading_and_speed(float yaw_angle_cd, float target_ have_attitude_target = true; // log new target - rover.Log_Write_GuidedTarget(_guided_mode, Vector3f(_desired_yaw_cd, 0.0f, 0.0f), Vector3f(_desired_speed, 0.0f, 0.0f)); + rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(_desired_yaw_cd, 0.0f, 0.0f), Vector3f(_desired_speed, 0.0f, 0.0f)); } void ModeGuided::set_desired_heading_delta_and_speed(float yaw_delta_cd, float target_speed) { // handle initialisation - if (_guided_mode != ModeGuided::Guided_HeadingAndSpeed) { - _guided_mode = ModeGuided::Guided_HeadingAndSpeed; + if (_guided_mode != SubMode::HeadingAndSpeed) { + _guided_mode = SubMode::HeadingAndSpeed; _desired_yaw_cd = ahrs.yaw_sensor; } set_desired_heading_and_speed(wrap_180_cd(_desired_yaw_cd + yaw_delta_cd), target_speed); @@ -356,7 +356,7 @@ void ModeGuided::set_desired_heading_delta_and_speed(float yaw_delta_cd, float t void ModeGuided::set_desired_turn_rate_and_speed(float turn_rate_cds, float target_speed) { // handle initialisation - _guided_mode = ModeGuided::Guided_TurnRateAndSpeed; + _guided_mode = SubMode::TurnRateAndSpeed; _des_att_time_ms = AP_HAL::millis(); // record targets @@ -365,13 +365,13 @@ void ModeGuided::set_desired_turn_rate_and_speed(float turn_rate_cds, float targ have_attitude_target = true; // log new target - rover.Log_Write_GuidedTarget(_guided_mode, Vector3f(_desired_yaw_rate_cds, 0.0f, 0.0f), Vector3f(_desired_speed, 0.0f, 0.0f)); + rover.Log_Write_GuidedTarget((uint8_t)_guided_mode, Vector3f(_desired_yaw_rate_cds, 0.0f, 0.0f), Vector3f(_desired_speed, 0.0f, 0.0f)); } // set steering and throttle (both in the range -1 to +1) void ModeGuided::set_steering_and_throttle(float steering, float throttle) { - _guided_mode = ModeGuided::Guided_SteeringAndThrottle; + _guided_mode = SubMode::SteeringAndThrottle; _strthr_time_ms = AP_HAL::millis(); _strthr_steering = constrain_float(steering, -1.0f, 1.0f); _strthr_throttle = constrain_float(throttle, -1.0f, 1.0f); @@ -381,7 +381,7 @@ void ModeGuided::set_steering_and_throttle(float steering, float throttle) bool ModeGuided::start_loiter() { if (rover.mode_loiter.enter()) { - _guided_mode = Guided_Loiter; + _guided_mode = SubMode::Loiter; return true; } return false; @@ -391,7 +391,7 @@ bool ModeGuided::start_loiter() // start stopping vehicle as quickly as possible void ModeGuided::start_stop() { - _guided_mode = Guided_Stop; + _guided_mode = SubMode::Stop; } // set guided timeout and movement limits diff --git a/Rover/mode_rtl.cpp b/Rover/mode_rtl.cpp index b9a8ee49649e17..e896c5151fc878 100644 --- a/Rover/mode_rtl.cpp +++ b/Rover/mode_rtl.cpp @@ -11,7 +11,7 @@ bool ModeRTL::_enter() g2.wp_nav.init(MAX(0, g2.rtl_speed)); // set target to the closest rally point or home -#if AP_RALLY == ENABLED +#if HAL_RALLY_ENABLED if (!g2.wp_nav.set_desired_location(g2.rally.calc_best_rally_or_home_location(rover.current_loc, ahrs.get_home().alt))) { return false; } diff --git a/Rover/mode_smart_rtl.cpp b/Rover/mode_smart_rtl.cpp index 0d083965e4b32d..0080d3569fd8cd 100644 --- a/Rover/mode_smart_rtl.cpp +++ b/Rover/mode_smart_rtl.cpp @@ -22,7 +22,7 @@ bool ModeSmartRTL::_enter() } // init state - smart_rtl_state = SmartRTL_WaitForPathCleanup; + smart_rtl_state = SmartRTLState::WaitForPathCleanup; _loitering = false; return true; @@ -31,24 +31,24 @@ bool ModeSmartRTL::_enter() void ModeSmartRTL::update() { switch (smart_rtl_state) { - case SmartRTL_WaitForPathCleanup: + case SmartRTLState::WaitForPathCleanup: // check if return path is computed and if yes, begin journey home if (g2.smart_rtl.request_thorough_cleanup()) { - smart_rtl_state = SmartRTL_PathFollow; + smart_rtl_state = SmartRTLState::PathFollow; _load_point = true; } // Note: this may lead to an unnecessary 20ms slow down of the vehicle (but it is unlikely) stop_vehicle(); break; - case SmartRTL_PathFollow: + case SmartRTLState::PathFollow: // load point if required if (_load_point) { Vector3f dest_NED; if (!g2.smart_rtl.pop_point(dest_NED)) { // if not more points, we have reached home gcs().send_text(MAV_SEVERITY_INFO, "Reached destination"); - smart_rtl_state = SmartRTL_StopAtHome; + smart_rtl_state = SmartRTLState::StopAtHome; break; } else { // peek at the next point. this can fail if the IO task currently has the path semaphore @@ -57,7 +57,7 @@ void ModeSmartRTL::update() if (!g2.wp_nav.set_desired_location_NED(dest_NED, next_dest_NED)) { // this should never happen because the EKF origin should already be set gcs().send_text(MAV_SEVERITY_INFO, "SmartRTL: failed to set destination"); - smart_rtl_state = SmartRTL_Failure; + smart_rtl_state = SmartRTLState::Failure; INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); } } else { @@ -65,7 +65,7 @@ void ModeSmartRTL::update() if (!g2.wp_nav.set_desired_location_NED(dest_NED)) { // this should never happen because the EKF origin should already be set gcs().send_text(MAV_SEVERITY_INFO, "SmartRTL: failed to set destination"); - smart_rtl_state = SmartRTL_Failure; + smart_rtl_state = SmartRTLState::Failure; INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); } } @@ -81,8 +81,8 @@ void ModeSmartRTL::update() } break; - case SmartRTL_StopAtHome: - case SmartRTL_Failure: + case SmartRTLState::StopAtHome: + case SmartRTLState::Failure: _reached_destination = true; // we have reached the destination // boats loiters, rovers stop @@ -107,16 +107,16 @@ void ModeSmartRTL::update() bool ModeSmartRTL::get_desired_location(Location& destination) const { switch (smart_rtl_state) { - case SmartRTL_WaitForPathCleanup: + case SmartRTLState::WaitForPathCleanup: return false; - case SmartRTL_PathFollow: + case SmartRTLState::PathFollow: if (g2.wp_nav.is_destination_valid()) { destination = g2.wp_nav.get_destination(); return true; } return false; - case SmartRTL_StopAtHome: - case SmartRTL_Failure: + case SmartRTLState::StopAtHome: + case SmartRTLState::Failure: return false; } // should never reach here but just in case diff --git a/Rover/release-notes.txt b/Rover/release-notes.txt index b82ad0c150c262..e6957078113187 100644 --- a/Rover/release-notes.txt +++ b/Rover/release-notes.txt @@ -1,5 +1,85 @@ Rover Release Notes: ------------------------------------------------------------------ +Rover 4.4.0-beta8 13-Oct-2023 +Changes from 4.4.0-beta7 +1) Autopilot related enhancements and fixes + - BETAFPV-F405 support + - MambaF405v2 battery and serial setup corrected + - mRo Control Zero OEM H7 bdshot support + - SpeedyBee-F405-Wing gets VTX power control + - SpeedyBee-F405-Mini support + - T-Motor H743 Mini support +2) EKF3 supports baroless boards +3) GPS-for-yaw allows base GPS to update at only 3Hz +4) INA battery monitor supports config of shunt resistor used (see BATTx_SHUNT) +5) Log VER message includes vehicle type +6) OpenDroneId option to auto-store IDs in persistent flash +7) RC SBUS protection against invalid data in first 4 channels +8) Bug fixes + - BMI088 IMU error value handling fixed to avoid occasional negative spike + - Dev environment CI autotest stability improvements + - OSD correct DisplayPort BF MSP symbols + - OSD option to correct direction arrows for BF font set + - Sensor status reporting to GCS fixed for baroless boards +------------------------------------------------------------------ +Rover 4.4.0-beta7 14-Sep-2023 +Changes from 4.4.0-beta6 +1) Autopilot related enhancements + - H750 external flash optimisations for to lower CPU load + - MambaF405Mini fixes to match manufacturer's recommended wiring + - RADIX2 HD support + - YJUAV_A6SE support +2) Bug fixes + - Airbotf4 features minimised to build for 4.4 + - ChibiOS clock fix for 480Mhz H7 boards (affected FDCAN) + - RPI hardware version check fix +------------------------------------------------------------------ +Rover 4.4.0-beta6 05-Sep-2023 +Changes from 4.4.0-beta5 +1) Autopilot related fixes and enhancements + - KakuteH7-wing get 8 bit directional dshot channel support + - Luminousbee5 boards defaults updated + - Navigator autopilot GPIOs fix (PWM output was broken) + - Pixhawk6C Serial RTS lines pulled low on startup + - QiotekZealotF427 and QiotekZealotH743 battery monitor default fixed + - SDMODELH7V1 supporta +2) Driver enhancements + - DroneCAN battery monitors allow reset of battery SoC + - Himark DroneCAN servo support + - Hobbywing DroneCAN ESC support +3) Asymmetrical thrust support for skid steering rovers (see MOT_THST_ASYM) +4) EKF3 high vibration handling improved with EK3_GLITCH_RADIUS option +5) Custom build server gets mission storage on SDCard selection +6) SITL default parameter handling bug fix +------------------------------------------------------------------ +Rover 4.4.0-beta5 12-Aug-2023 +Changes from 4.4.0-beta4 +1) Autopilots specific changes + - SIYI N7 support +2) Bug fixes + - DroneCAN airspeed sensor fix to handle missing packets + - DroneCAN GPS RTK injection fix + - Notch filter gyro glitch caused by race condition fixed +------------------------------------------------------------------ +Rover 4.4.0-beta4 27-July-2023 +Changes from 4.4.0-beta3 +1) Autopilots specific changes + - Diatone-Mamba-MK4-H743v2 uses SPL06 baro (was DPS280) + - DMA for I2C disabled on F7 and H7 boards + - Foxeer H743v1 default serial protocol config fixes + - HeeWing-F405 and F405v2 support + - iFlight BlitzF7 support +2) Rover specific enhancements + - QuikTune Lua script + - Circle mode safety improvements including handling when CIRC_SPEED set too high + - Velocity controller I-term build-up avoided when steering reaches limits +3) Bug fixes + - BLHeli returns battery status requested via MSP (avoids hang when using esc-configurator) + - CRSFv3 rescans at baudrates to avoid RX loss + - EK3_ABIAS_P_NSE param range fix + - Scripting restart memory corruption bug fixed + - Siyi A8/ZR10 driver fix to avoid crash if serial port not configured +------------------------------------------------------------------ Rover 4.4.0-beta3 03-July-2023 Changes from 4.4.0-beta2 1) Autopilots specific changes @@ -21,7 +101,6 @@ Changes from 4.4.0-beta2 - SERVOx_PROTOCOL "SToRM32 Gimbal Serial" value renamed to "Gimbal" because also used by Siyi - SERIALx_OPTION "Swap" renamed to "SwapTXRX" for clarity - SBF GPS ellipsoid height fixed - - Scripting restart memory corruption bug fixed - Ublox M10S GPS auto configuration fixed ------------------------------------------------------------------ Rover 4.4.0-beta2 05-Jun-2023 @@ -227,6 +306,14 @@ Changes from 4.3.0-beta12 - Webots 2023a simulator support - XPlane support for wider range of aircraft ------------------------------------------------------------------ +Rover 4.3.0-beta14 12-Aug-2023 +Changes from 4.3.0-beta13 +1) Bug fixes + - DroneCAN GPS RTK injection fix + - INAxxx battery monitors allow for battery reset remaining + - Notch filter gyro glitch caused by race condition fixed + - Scripting restart memory corruption bug fixed +------------------------------------------------------------------ Rover 4.3.0-beta13 27-Mar-2023 Changes from 4.3.0-beta12 1) Bug fixes diff --git a/Rover/system.cpp b/Rover/system.cpp index 10cc4a975ba34d..492463e8a2345a 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -281,7 +281,7 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason) old_mode.exit(); control_mode_reason = reason; - logger.Write_Mode(control_mode->mode_number(), control_mode_reason); + logger.Write_Mode((uint8_t)control_mode->mode_number(), control_mode_reason); gcs().send_message(MSG_HEARTBEAT); notify_mode(control_mode); @@ -291,9 +291,14 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason) bool Rover::set_mode(const uint8_t new_mode, ModeReason reason) { static_assert(sizeof(Mode::Number) == sizeof(new_mode), "The new mode can't be mapped to the vehicles mode number"); - Mode *mode = rover.mode_from_mode_num((enum Mode::Number)new_mode); + return rover.set_mode(static_cast(new_mode), reason); +} + +bool Rover::set_mode(Mode::Number new_mode, ModeReason reason) +{ + Mode *mode = rover.mode_from_mode_num(new_mode); if (mode == nullptr) { - notify_no_such_mode(new_mode); + notify_no_such_mode((uint8_t)new_mode); return false; } return rover.set_mode(*mode, reason); @@ -317,7 +322,7 @@ void Rover::startup_INS_ground(void) void Rover::notify_mode(const Mode *mode) { AP_Notify::flags.autopilot_mode = mode->is_autopilot_mode(); - notify.flags.flight_mode = mode->mode_number(); + notify.flags.flight_mode = (uint8_t)mode->mode_number(); notify.set_flight_mode_str(mode->name4()); } diff --git a/Tools/AP_Bootloader/AP_Bootloader.cpp b/Tools/AP_Bootloader/AP_Bootloader.cpp index 4f3edcfe69c3aa..f42271208073ba 100644 --- a/Tools/AP_Bootloader/AP_Bootloader.cpp +++ b/Tools/AP_Bootloader/AP_Bootloader.cpp @@ -63,6 +63,8 @@ AP_FlashIface_JEDEC ext_flash; int main(void) { + custom_startup(); + #ifdef STM32F427xx if (BOARD_FLASH_SIZE > 1024 && check_limit_flash_1M()) { board_info.fw_size = (1024 - (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB))*1024; diff --git a/Tools/AP_Bootloader/bl_protocol.cpp b/Tools/AP_Bootloader/bl_protocol.cpp index 28004b66aaadb1..5bc0df7b2877f7 100644 --- a/Tools/AP_Bootloader/bl_protocol.cpp +++ b/Tools/AP_Bootloader/bl_protocol.cpp @@ -240,6 +240,10 @@ do_jump(uint32_t stacktop, uint32_t entrypoint) #define APP_START_ADDRESS (FLASH_LOAD_ADDRESS + (FLASH_BOOTLOADER_LOAD_KB + APP_START_OFFSET_KB)*1024U) #endif +#if !defined(STM32_OTG2_IS_OTG1) +#define STM32_OTG2_IS_OTG1 0 +#endif + void jump_to_app() { @@ -324,7 +328,7 @@ jump_to_app() #endif rccDisableAPB2(~0); #if HAL_USE_SERIAL_USB == TRUE -#if !defined(STM32_OTG2_IS_OTG1) +#if !STM32_OTG2_IS_OTG1 rccResetOTG_FS(); #endif #if defined(rccResetOTG_HS) @@ -630,7 +634,7 @@ bootloader(unsigned timeout) led_set(LED_OFF); // erase all sectors - for (uint8_t i = 0; flash_func_sector_size(i) != 0; i++) { + for (uint16_t i = 0; flash_func_sector_size(i) != 0; i++) { #if defined(STM32F7) || defined(STM32H7) if (!flash_func_erase_sector(i, c == PROTO_CHIP_FULL_ERASE)) { #else diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index 956b1027b164fd..ab5b3fa8bde839 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -233,6 +233,24 @@ AP_HW_HEEWING_F405 1119 AP_HW_PodmanH7 1120 AP_HW_mRo-M10053 1121 AP_HW_mRo-M10044 1122 +AP_HW_SIYI_N7 1123 +AP_HW_mRoCZOEM_revG 1124 +AP_HW_BETAFPV_F405 1125 +AP_HW_QioTekAdeptH743 1126 +AP_HW_YJUAV_A6SE 1127 +AP_HW_QioTekAdept_6C 1128 + +AP_HW_PixFlamingoL4R5_V2 1129 +AP_HW_PixFlamingoF427_V1 1130 +AP_HW_PixFlamingoF767_V1 1131 +AP_HW_PixFlamingoH743I 1132 +AP_HW_PixFlamingoH743V 1133 + +AP_HW_AR-F407SmartBat 1134 +AP_HW_SPEEDYBEEF4MINI 1135 +AP_HW_SPEEDYBEEF4V4 1136 +AP_HW_FlywooF405Pro 1137 +AP_HW_TMOTORH7 1138 AP_HW_ESP32_PERIPH 1205 AP_HW_ESP32S3_PERIPH 1206 @@ -242,7 +260,14 @@ AP_HW_CUBEBLACK_PERIPH 1401 AP_HW_PIXRACER_PERIPH 1402 AP_HW_SWBOOMBOARD_PERIPH 1403 -# IDs 5000-5100 reserved for Carbonix +AP_HW_VIMDRONES_FLOW 1404 +AP_HW_VIMDRONES_MOSAIC_X5 1405 +AP_HW_VIMDRONES_MOSAIC_H 1406 +AP_HW_VIMDRONES_PERIPH 1407 + +# IDs 5000-5099 reserved for Carbonix +# IDs 5100-5199 reserved for SYPAQ Systems +# IDs 6000-6099 reserved for SpektreWorks # OpenDroneID enabled boards. Use 10000 + the base board ID AP_HW_CubeOrange_ODID 10140 diff --git a/Tools/AP_Bootloader/can.cpp b/Tools/AP_Bootloader/can.cpp index 715070edc69729..24ed583284eba6 100644 --- a/Tools/AP_Bootloader/can.cpp +++ b/Tools/AP_Bootloader/can.cpp @@ -47,18 +47,20 @@ static CANConfig cancfg = { CAN_MCR_ABOM | CAN_MCR_AWUM | CAN_MCR_TXFP, 0 // filled in below }; +// 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]; #endif #ifndef CAN_APP_VERSION_MAJOR -#define CAN_APP_VERSION_MAJOR 1 +#define CAN_APP_VERSION_MAJOR 2 #endif #ifndef CAN_APP_VERSION_MINOR #define CAN_APP_VERSION_MINOR 0 #endif #ifndef CAN_APP_NODE_NAME -#define CAN_APP_NODE_NAME "org.ardupilot.ap_periph" +#define CAN_APP_NODE_NAME "org.ardupilot." CHIBIOS_BOARD_NAME #endif static uint8_t node_id_allocation_transfer_id; @@ -66,14 +68,30 @@ static uavcan_protocol_NodeStatus node_status; static uint32_t send_next_node_id_allocation_request_at_ms; static uint8_t node_id_allocation_unique_id_offset; +static void processTx(void); + +// keep up to 4 transfers in progress +#ifndef FW_UPDATE_PIPELINE_LEN +#define FW_UPDATE_PIPELINE_LEN 4 +#endif + static struct { - uint64_t ofs; - uint32_t last_ms; + uint32_t rtt_ms; + uint32_t ofs; uint8_t node_id; - uint8_t transfer_id; uint8_t path[sizeof(uavcan_protocol_file_Path::path.data)+1]; uint8_t sector; uint32_t sector_ofs; + uint8_t transfer_id; + uint8_t idx; + struct { + uint8_t tx_id; + uint32_t sent_ms; + uint32_t offset; + bool have_reply; + uavcan_protocol_file_ReadResponse pkt; + } reads[FW_UPDATE_PIPELINE_LEN]; + uint16_t erased_to; } fw_update; /* @@ -150,87 +168,184 @@ static void handle_get_node_info(CanardInstance* ins, /* send a read for a fw update */ -static void send_fw_read(void) +static bool send_fw_read(uint8_t idx) { - uint32_t now = AP_HAL::millis(); - if (now - fw_update.last_ms < 750) { - // the server may still be responding - return; - } - fw_update.last_ms = now; + auto &r = fw_update.reads[idx]; + r.tx_id = fw_update.transfer_id; + r.have_reply = false; + + uavcan_protocol_file_ReadRequest pkt {}; + pkt.path.path.len = strlen((const char *)fw_update.path); + pkt.offset = r.offset; + memcpy(pkt.path.path.data, fw_update.path, pkt.path.path.len); uint8_t buffer[UAVCAN_PROTOCOL_FILE_READ_REQUEST_MAX_SIZE]; - canardEncodeScalar(buffer, 0, 40, &fw_update.ofs); - uint32_t offset = 40; - uint8_t len = strlen((const char *)fw_update.path); - for (uint8_t i=0; i 0) { + // mark it as having been sent + r.sent_ms = AP_HAL::millis(); + return true; + } + return false; } /* - handle response to file read for fw update + send a read for a fw update */ -static void handle_file_read_response(CanardInstance* ins, CanardRxTransfer* transfer) +static void send_fw_reads(void) { - if ((transfer->transfer_id+1)%256 != fw_update.transfer_id || - transfer->source_node_id != fw_update.node_id) { - return; + const uint32_t now = AP_HAL::millis(); + + for (uint8_t i=0; ipayload_len - 2; +} - uint32_t offset = 16; - uint32_t buf32[(len+3)/4]; - uint8_t *buf = (uint8_t *)&buf32[0]; - for (uint16_t i=0; isource_node_id != fw_update.node_id) { + return; } - if (fw_update.sector_ofs+len > sector_size) { - flash_func_erase_sector(fw_update.sector+1); + /* + match the response to a sent request + */ + uint8_t idx = 0; + bool found = false; + for (idx=0; idxtransfer_id) { + found = true; + break; + } } - for (uint16_t i=0; i= flash_func_sector_size(fw_update.sector)) { - fw_update.sector++; - fw_update.sector_ofs -= sector_size; + if (uavcan_protocol_file_ReadResponse_decode(transfer, &fw_update.reads[idx].pkt)) { + return; } - if (len < sizeof(uavcan_protocol_file_ReadResponse::data.data)) { - fw_update.node_id = 0; - flash_write_flush(); - const auto ok = check_good_firmware(); - node_status.vendor_specific_status_code = uint8_t(ok); - if (ok == check_fw_result_t::CHECK_FW_OK) { - jump_to_app(); + fw_update.reads[idx].have_reply = true; + uint32_t rtt = MIN(3000,MAX(AP_HAL::millis() - fw_update.reads[idx].sent_ms, 25)); + fw_update.rtt_ms = uint32_t(0.9 * fw_update.rtt_ms + 0.1 * rtt); + + while (fw_update.reads[fw_update.idx].have_reply) { + auto &r = fw_update.reads[fw_update.idx]; + if (r.offset != fw_update.ofs) { + // bad sequence + r.have_reply = false; + r.sent_ms = 0; + break; + } + const auto &pkt = r.pkt; + const uint16_t len = pkt.data.len; + const uint16_t len_words = (len+3U)/4U; + const uint8_t *buf = (uint8_t *)pkt.data.data; + uint32_t buf32[len_words] {}; + memcpy((uint8_t*)buf32, buf, len); + + if (fw_update.ofs == 0) { + flash_set_keep_unlocked(true); + } + + const uint32_t sector_size = flash_func_sector_size(fw_update.sector); + if (sector_size == 0) { + // firmware is too big + fw_update.node_id = 0; + flash_write_flush(); + flash_set_keep_unlocked(false); + node_status.vendor_specific_status_code = uint8_t(check_fw_result_t::FAIL_REASON_BAD_LENGTH_APP); + break; + } + if (fw_update.sector_ofs == 0) { + erase_to(fw_update.sector); + } + if (fw_update.sector_ofs+len > sector_size) { + erase_to(fw_update.sector+1); + } + if (!flash_write_buffer(fw_update.ofs, buf32, len_words)) { + continue; + } + + fw_update.ofs += len; + fw_update.sector_ofs += len; + if (fw_update.sector_ofs >= flash_func_sector_size(fw_update.sector)) { + fw_update.sector++; + fw_update.sector_ofs -= sector_size; + } + + if (len < sizeof(uavcan_protocol_file_ReadResponse::data.data)) { + fw_update.node_id = 0; + flash_write_flush(); + flash_set_keep_unlocked(false); + const auto ok = check_good_firmware(); + node_status.vendor_specific_status_code = uint8_t(ok); + if (ok == check_fw_result_t::CHECK_FW_OK) { + jump_to_app(); + } + return; } + + r.have_reply = false; + r.sent_ms = 0; + r.offset += FW_UPDATE_PIPELINE_LEN*sizeof(uavcan_protocol_file_ReadResponse::data.data); + send_fw_read(fw_update.idx); + processTx(); + + fw_update.idx = (fw_update.idx + 1) % FW_UPDATE_PIPELINE_LEN; } // show offset number we are flashing in kbyte as crude progress indicator node_status.vendor_specific_status_code = 1 + (fw_update.ofs / 1024U); - - fw_update.last_ms = 0; } /* @@ -238,23 +353,21 @@ static void handle_file_read_response(CanardInstance* ins, CanardRxTransfer* tra */ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* transfer) { - // manual decoding due to TAO bug in libcanard generated code - if (transfer->payload_len < 1 || transfer->payload_len > sizeof(fw_update.path)+1) { - return; - } - if (fw_update.node_id == 0) { - uint32_t offset = 0; - canardDecodeScalar(transfer, 0, 8, false, (void*)&fw_update.node_id); - offset += 8; - for (uint8_t i=0; ipayload_len-1; i++) { - canardDecodeScalar(transfer, offset, 8, false, (void*)&fw_update.path[i]); - offset += 8; + uavcan_protocol_file_BeginFirmwareUpdateRequest pkt; + if (uavcan_protocol_file_BeginFirmwareUpdateRequest_decode(transfer, &pkt)) { + return; } - fw_update.ofs = 0; - fw_update.last_ms = 0; - fw_update.sector = 0; - fw_update.sector_ofs = 0; + if (pkt.image_file_remote_path.path.len > sizeof(fw_update.path)-1) { + return; + } + memset(&fw_update, 0, sizeof(fw_update)); + for (uint8_t i=0; isource_node_id; } @@ -274,8 +387,6 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* CanardResponse, &buffer[0], total_size); - - send_fw_read(); } static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* transfer) @@ -291,35 +402,28 @@ static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* tr return; } - // Copying the unique ID from the message - static const uint8_t UniqueIDBitOffset = 8; - uint8_t received_unique_id[sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)]; - uint8_t received_unique_id_len = 0; - for (; received_unique_id_len < (transfer->payload_len - (UniqueIDBitOffset / 8U)); received_unique_id_len++) { - const uint8_t bit_offset = (uint8_t)(UniqueIDBitOffset + received_unique_id_len * 8U); - (void) canardDecodeScalar(transfer, bit_offset, 8, false, &received_unique_id[received_unique_id_len]); + struct uavcan_protocol_dynamic_node_id_Allocation msg; + if (uavcan_protocol_dynamic_node_id_Allocation_decode(transfer, &msg)) { + return; } - + // Obtaining the local unique ID uint8_t my_unique_id[sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)]; readUniqueID(my_unique_id); // Matching the received UID against the local one - if (memcmp(received_unique_id, my_unique_id, received_unique_id_len) != 0) { + if (memcmp(msg.unique_id.data, my_unique_id, msg.unique_id.len) != 0) { node_id_allocation_unique_id_offset = 0; return; // No match, return } - if (received_unique_id_len < sizeof(uavcan_protocol_dynamic_node_id_Allocation::unique_id.data)) { + if (msg.unique_id.len < sizeof(msg.unique_id.data)) { // The allocator has confirmed part of unique ID, switching to the next stage and updating the timeout. - node_id_allocation_unique_id_offset = received_unique_id_len; + 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 { // Allocation complete - copying the allocated node ID from the message - uint8_t allocated_node_id = 0; - (void) canardDecodeScalar(transfer, 0, 7, false, &allocated_node_id); - - canardSetLocalNodeID(ins, allocated_node_id); + canardSetLocalNodeID(ins, msg.node_id); } } @@ -617,6 +721,9 @@ bool can_check_update(void) if (comms->magic == APP_BOOTLOADER_COMMS_MAGIC) { can_set_node_id(comms->my_node_id); fw_update.node_id = comms->server_node_id; + for (uint8_t i=0; ipath, sizeof(uavcan_protocol_file_Path::path.data)+1); ret = true; // clear comms region @@ -704,8 +811,8 @@ void can_start() void can_update() { - // do one loop of CAN support. If we are doing a few update then - // loop until it is finished + // do one loop of CAN support. If we are doing a firmware update + // then loop until it is finished do { processTx(); processRx(); @@ -717,8 +824,12 @@ void can_update() process1HzTasks(AP_HAL::micros64()); } if (fw_update.node_id != 0) { - send_fw_read(); + send_fw_reads(); } +#if CH_CFG_ST_FREQUENCY >= 1000000 + // give a bit of time for background processing + chThdSleepMicroseconds(200); +#endif } while (fw_update.node_id != 0); } diff --git a/Tools/AP_Bootloader/custom.cpp b/Tools/AP_Bootloader/custom.cpp new file mode 100644 index 00000000000000..ef5f7ef434d38b --- /dev/null +++ b/Tools/AP_Bootloader/custom.cpp @@ -0,0 +1,52 @@ +/* + custom code for specific boards + */ +#include +#include "ch.h" +#include "hal.h" +#include "support.h" + +#ifdef AP_BOOTLOADER_CUSTOM_HERE4 +/* + reset here4 LEDs +*/ +static void bootloader_custom_Here4(void) +{ + for (uint8_t n=0; n<10; n++) { + const uint8_t num_leds = 4; + const uint32_t min_bits = num_leds*25+50; + const uint8_t num_leading_zeros = 8-min_bits%8 + 50; + const uint32_t output_stream_byte_length = (min_bits+7)/8; + palSetLineMode(HAL_GPIO_PIN_LED_DI, PAL_MODE_OUTPUT_PUSHPULL); + palSetLineMode(HAL_GPIO_PIN_LED_SCK, PAL_MODE_OUTPUT_PUSHPULL); + int l = 100; + while (l--) { + for (uint32_t i=0; i 0) { + // don't sleep more than 65 at a time, to cope with 16 bit + // timer + const uint32_t dt = ms > 65? 65: ms; + chThdSleepMilliseconds(dt); + ms -= dt; + } +} + // generate a pulse sequence forever, for debugging void led_pulses(uint8_t npulses) { @@ -355,11 +371,11 @@ void led_pulses(uint8_t npulses) while (true) { for (uint8_t i=0; i= 0) { auto *uart = hal.serial(g.proximity_port); if (uart != nullptr) { @@ -265,6 +273,10 @@ void AP_Periph_FW::init() nmea.init(); #endif +#ifdef HAL_PERIPH_ENABLE_RPM + rpm_sensor.init(); +#endif + #ifdef HAL_PERIPH_ENABLE_NOTIFY notify.init(); #endif @@ -272,7 +284,7 @@ void AP_Periph_FW::init() #if AP_SCRIPTING_ENABLED scripting.init(); #endif - start_ms = AP_HAL::native_millis(); + start_ms = AP_HAL::millis(); } #if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY) @@ -290,7 +302,7 @@ void AP_Periph_FW::update_rainbow() if (rainbow_done) { return; } - uint32_t now = AP_HAL::native_millis(); + uint32_t now = AP_HAL::millis(); if (now - start_ms > 1500) { rainbow_done = true; #if defined (HAL_PERIPH_ENABLE_NOTIFY) @@ -374,7 +386,7 @@ void AP_Periph_FW::update() #endif static uint32_t last_led_ms; - uint32_t now = AP_HAL::native_millis(); + uint32_t now = AP_HAL::millis(); if (now - last_led_ms > 1000) { last_led_ms = now; #ifdef HAL_GPIO_PIN_LED @@ -410,10 +422,8 @@ void AP_Periph_FW::update() rcout_init_1Hz(); #endif -#if HAL_GCS_ENABLED - gcs().send_message(MSG_HEARTBEAT); - gcs().send_message(MSG_SYS_STATUS); -#endif + GCS_SEND_MESSAGE(MSG_HEARTBEAT); + GCS_SEND_MESSAGE(MSG_SYS_STATUS); } static uint32_t last_error_ms; @@ -445,10 +455,18 @@ void AP_Periph_FW::update() if (now - battery.last_read_ms >= 100) { // update battery at 10Hz battery.last_read_ms = now; - battery.lib.read(); + battery_lib.read(); } #endif +#ifdef HAL_PERIPH_ENABLE_RCIN + rcin_update(); +#endif + +#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE + batt_balance_update(); +#endif + static uint32_t fiftyhz_last_update_ms; if (now - fiftyhz_last_update_ms >= 20) { // update at 50Hz @@ -470,12 +488,23 @@ void AP_Periph_FW::update() temperature_sensor.update(); #endif +#ifdef HAL_PERIPH_ENABLE_RPM + if (now - rpm_last_update_ms >= 100) { + rpm_last_update_ms = now; + rpm_sensor.update(); + } +#endif + #if HAL_LOGGING_ENABLED logger.periodic_tasks(); #endif can_update(); +#ifdef HAL_PERIPH_ENABLE_NETWORKING + networking.update(); +#endif + #if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY) update_rainbow(); #endif diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 085a4263f8a8c0..2723d589e0aa17 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -1,6 +1,7 @@ #pragma once #include +#include #include #include #include @@ -25,11 +26,16 @@ #include #include #include +#include +#include #include #include #if HAL_WITH_ESC_TELEM #include #endif +#include +#include "rc_in.h" +#include "batt_balance.h" #include #if HAL_NMEA_OUTPUT_ENABLED && !(HAL_GCS_ENABLED && defined(HAL_PERIPH_ENABLE_GPS)) @@ -62,6 +68,14 @@ #endif #endif +#ifndef AP_PERIPH_SAFETY_SWITCH_ENABLED +#define AP_PERIPH_SAFETY_SWITCH_ENABLED defined(HAL_PERIPH_ENABLE_RC_OUT) +#endif + +#ifndef HAL_PERIPH_CAN_MIRROR +#define HAL_PERIPH_CAN_MIRROR 0 +#endif + #include "Parameters.h" #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -80,6 +94,20 @@ void can_printf(const char *fmt, ...) FMT_PRINTF(1,2); struct CanardInstance; struct CanardRxTransfer; +#define MAKE_TRANSFER_DESCRIPTOR(data_type_id, transfer_type, src_node_id, dst_node_id) \ + (((uint32_t)(data_type_id)) | (((uint32_t)(transfer_type)) << 16U) | \ + (((uint32_t)(src_node_id)) << 18U) | (((uint32_t)(dst_node_id)) << 25U)) + +#ifndef HAL_CAN_POOL_SIZE +#if HAL_CANFD_SUPPORTED + #define HAL_CAN_POOL_SIZE 16000 +#elif GPS_MOVING_BASELINE + #define HAL_CAN_POOL_SIZE 8000 +#else + #define HAL_CAN_POOL_SIZE 4000 +#endif +#endif + class AP_Periph_FW { public: AP_Periph_FW(); @@ -109,7 +137,11 @@ class AP_Periph_FW { void can_airspeed_update(); void can_rangefinder_update(); void can_battery_update(); + void can_battery_send_cells(uint8_t instance); void can_proximity_update(); + void can_buzzer_update(void); + void can_safety_button_update(void); + void can_safety_LED_update(void); void load_parameters(); void prepare_reboot(); @@ -158,11 +190,15 @@ class AP_Periph_FW { AP_Baro baro; #endif -#ifdef HAL_PERIPH_ENABLE_BATTERY - struct AP_Periph_Battery { - void handle_battery_failsafe(const char* type_str, const int8_t action) { } - AP_BattMonitor lib{0, FUNCTOR_BIND_MEMBER(&AP_Periph_FW::AP_Periph_Battery::handle_battery_failsafe, void, const char*, const int8_t), nullptr}; +#ifdef HAL_PERIPH_ENABLE_RPM + AP_RPM rpm_sensor; + uint32_t rpm_last_update_ms; +#endif +#ifdef HAL_PERIPH_ENABLE_BATTERY + void handle_battery_failsafe(const char* type_str, const int8_t action) { } + AP_BattMonitor battery_lib{0, FUNCTOR_BIND_MEMBER(&AP_Periph_FW::handle_battery_failsafe, void, const char*, const int8_t), nullptr}; + struct { uint32_t last_read_ms; uint32_t last_can_send_ms; } battery; @@ -200,6 +236,7 @@ class AP_Periph_FW { struct { mavlink_message_t msg; mavlink_status_t status; + uint32_t last_heartbeat_ms; } adsb; #endif @@ -212,7 +249,7 @@ class AP_Periph_FW { uint32_t last_sample_ms; #endif -#if HAL_PROXIMITY_ENABLED +#ifdef HAL_PERIPH_ENABLE_PROXIMITY AP_Proximity proximity; #endif @@ -271,6 +308,21 @@ class AP_Periph_FW { void rcout_handle_safety_state(uint8_t safety_state); #endif +#ifdef HAL_PERIPH_ENABLE_RCIN + void rcin_init(); + void rcin_update(); + void can_send_RCInput(uint8_t quality, uint16_t *values, uint8_t nvalues, bool in_failsafe, bool quality_valid); + bool rcin_initialised; + uint32_t rcin_last_sent_RCInput_ms; + const char *rcin_rc_protocol; // protocol currently being decoded + Parameters_RCIN g_rcin; +#endif + +#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE + void batt_balance_update(); + BattBalance battery_balance; +#endif + #if AP_TEMPERATURE_SENSOR_ENABLED AP_TemperatureSensor temperature_sensor; #endif @@ -303,6 +355,14 @@ class AP_Periph_FW { AP_Logger logger; #endif +#ifdef HAL_PERIPH_ENABLE_NETWORKING + AP_Networking networking; +#endif + +#ifdef HAL_PERIPH_ENABLE_RTC + AP_RTC rtc; +#endif + #if HAL_GCS_ENABLED GCS_Periph _gcs; #endif @@ -338,14 +398,22 @@ class AP_Periph_FW { static bool no_iface_finished_dna; static constexpr auto can_printf = ::can_printf; - static bool canard_broadcast(uint64_t data_type_signature, - uint16_t data_type_id, - uint8_t priority, - const void* payload, - uint16_t payload_len); - + bool canard_broadcast(uint64_t data_type_signature, + uint16_t data_type_id, + uint8_t priority, + const void* payload, + uint16_t payload_len); + + void onTransferReceived(CanardInstance* canard_instance, + CanardRxTransfer* transfer); + bool shouldAcceptTransfer(const CanardInstance* canard_instance, + uint64_t* out_data_type_signature, + uint16_t data_type_id, + CanardTransferType transfer_type, + uint8_t source_node_id); + #if AP_UART_MONITOR_ENABLED - void handle_tunnel_Targetted(CanardInstance* ins, CanardRxTransfer* transfer); + void handle_tunnel_Targetted(CanardInstance* canard_instance, CanardRxTransfer* transfer); void send_serial_monitor_data(); int8_t get_default_tunnel_serial_port(void) const; @@ -360,8 +428,67 @@ class AP_Periph_FW { bool locked; } uart_monitor; #endif + + // handlers for incoming messages + void handle_get_node_info(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_param_getset(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_param_executeopcode(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_begin_firmware_update(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_allocation_response(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_safety_state(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_arming_status(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_RTCMStream(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_MovingBaselineData(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_esc_rawcommand(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_act_command(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_beep_command(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_lightscommand(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer); + + void process1HzTasks(uint64_t timestamp_usec); + void processTx(void); + void processRx(void); +#if HAL_PERIPH_CAN_MIRROR + void processMirror(void); +#endif // HAL_PERIPH_CAN_MIRROR + void cleanup_stale_transactions(uint64_t ×tamp_usec); + void update_rx_protocol_stats(int16_t res); + void node_status_send(void); + bool can_do_dna(); + uint8_t *get_tid_ptr(uint32_t transfer_desc); + uint16_t pool_peak_percent(); + void set_rgb_led(uint8_t red, uint8_t green, uint8_t blue); + + struct dronecan_protocol_t { + CanardInstance canard; + uint32_t canard_memory_pool[HAL_CAN_POOL_SIZE/sizeof(uint32_t)]; + struct tid_map { + uint32_t transfer_desc; + uint8_t tid; + tid_map *next; + } *tid_map_head; + /* + * Variables used for dynamic node ID allocation. + * RTFM at http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation + */ + uint32_t send_next_node_id_allocation_request_at_ms; ///< When the next node ID allocation request should be sent + uint8_t node_id_allocation_unique_id_offset; ///< Depends on the stage of the next request + uint8_t tx_fail_count; + uint8_t dna_interface = 1; + } dronecan; + +#if AP_SIM_ENABLED + SITL::SIM sitl; +#endif +#if AP_AHRS_ENABLED + AP_AHRS ahrs; +#endif }; +#ifndef CAN_APP_NODE_NAME +#define CAN_APP_NODE_NAME "org.ardupilot." CHIBIOS_BOARD_NAME +#endif + namespace AP { AP_Periph_FW& periph(); diff --git a/Tools/AP_Periph/GCS_MAVLink.cpp b/Tools/AP_Periph/GCS_MAVLink.cpp index 07bc1484048db0..55020876783077 100644 --- a/Tools/AP_Periph/GCS_MAVLink.cpp +++ b/Tools/AP_Periph/GCS_MAVLink.cpp @@ -67,7 +67,7 @@ uint8_t GCS_Periph::sysid_this_mav() const return periph.g.sysid_this_mav; } -MAV_RESULT GCS_MAVLINK_Periph::handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK_Periph::handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { hal.scheduler->delay(10); periph.prepare_reboot(); diff --git a/Tools/AP_Periph/GCS_MAVLink.h b/Tools/AP_Periph/GCS_MAVLink.h index 98f39b885256ae..ce1f17b1ba2ed7 100644 --- a/Tools/AP_Periph/GCS_MAVLink.h +++ b/Tools/AP_Periph/GCS_MAVLink.h @@ -31,7 +31,7 @@ class GCS_MAVLINK_Periph : public GCS_MAVLINK uint32_t telem_delay() const override { return 0; } void handleMessage(const mavlink_message_t &msg) override { handle_common_message(msg); } bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return true; } - MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override; + MAV_RESULT handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; uint8_t sysid_my_gcs() const override; protected: diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 187fceba15cf86..80b3ae7d44a219 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -43,6 +43,10 @@ extern const AP_HAL::HAL &hal; #define AP_PERIPH_BARO_ENABLE_DEFAULT 1 #endif +#ifndef HAL_PERIPH_BATT_HIDE_MASK_DEFAULT +#define HAL_PERIPH_BATT_HIDE_MASK_DEFAULT 0 +#endif + #ifndef AP_PERIPH_EFI_PORT_DEFAULT #define AP_PERIPH_EFI_PORT_DEFAULT 3 #endif @@ -171,7 +175,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Param: DEBUG // @DisplayName: Debug // @Description: Debug - // @Bitmask: 0:Disabled, 1:Show free stack space, 2:Auto Reboot after 15sec, 3:Enable sending stats + // @Bitmask: 0:Show free stack space, 1:Auto Reboot after 15sec, 2:Enable sending stats // @User: Advanced GSCALAR(debug, "DEBUG", 0), @@ -223,7 +227,14 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { #ifdef HAL_PERIPH_ENABLE_BATTERY // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp - GOBJECT(battery, "BATT", AP_BattMonitor), + GOBJECT(battery_lib, "BATT", AP_BattMonitor), + + // @Param: BATT_HIDE_MASK + // @DisplayName: Battery hide mask + // @Description: Instance mask of local battery index(es) to prevent transmitting their status over CAN. This is useful for hiding a "battery" instance that is used locally in the peripheral but don't want them to be treated as a battery source(s) to the autopilot. For example, an AP_Periph battery monitor with multiple batteries that monitors each locally for diagnostic or other purposes, but only reports as a single SUM battery monitor to the autopilot. + // @Bitmask: 0:BATT, 1:BATT2, 2:BATT3, 3:BATT4, 4:BATT5, 5:BATT6, 6:BATT7, 7:BATT8, 8:BATT9, 9:BATTA, 10:BATTB, 11:BATTC, 12:BATTD, 13:BATTE, 14:BATTF, 15:BATTG + // @User: Advanced + GSCALAR(battery_hide_mask, "BATT_HIDE_MASK", HAL_PERIPH_BATT_HIDE_MASK_DEFAULT), #endif #ifdef HAL_PERIPH_ENABLE_MAG @@ -475,7 +486,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GOBJECT(efi, "EFI", AP_EFI), #endif -#if HAL_PROXIMITY_ENABLED +#ifdef HAL_PERIPH_ENABLE_PROXIMITY // @Param: PRX_BAUDRATE // @DisplayName: Proximity Sensor serial baudrate // @Description: Proximity Sensor serial baudrate. @@ -507,7 +518,7 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Group: PRX // @Path: ../libraries/AP_Proximity/AP_Proximity.cpp GOBJECT(proximity, "PRX", AP_Proximity), -#endif // HAL_PROXIMITY_ENABLED +#endif // HAL_PERIPH_ENABLE_PROXIMITY #if HAL_NMEA_OUTPUT_ENABLED // @Group: NMEA_ @@ -551,6 +562,58 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { #endif #endif +#ifdef HAL_PERIPH_ENABLE_NETWORKING + // @Group: NET_ + // @Path: ../libraries/AP_Networking/AP_Networking.cpp + GOBJECT(networking, "NET_", AP_Networking), +#endif + +#ifdef HAL_PERIPH_ENABLE_RPM + // @Group: RPM + // @Path: ../libraries/AP_RPM/AP_RPM.cpp + GOBJECT(rpm_sensor, "RPM", AP_RPM), +#endif + +#ifdef HAL_PERIPH_ENABLE_RCIN + // @Group: RC + // @Path: rc_in.cpp + GOBJECT(g_rcin, "RC", Parameters_RCIN), +#endif + +#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE + // @Group: BAL + // @Path: batt_balance.cpp + GOBJECT(battery_balance, "BAL", BattBalance), +#endif + + // NOTE: sim parameters should go last +#if AP_SIM_ENABLED + // @Group: SIM_ + // @Path: ../libraries/SITL/SITL.cpp + GOBJECT(sitl, "SIM_", SITL::SIM), + +#if AP_AHRS_ENABLED + // @Group: AHRS_ + // @Path: ../libraries/AP_AHRS/AP_AHRS.cpp + GOBJECT(ahrs, "AHRS_", AP_AHRS), +#endif +#endif // AP_SIM_ENABLED + +#if HAL_PERIPH_CAN_MIRROR + // @Param: CAN_MIRROR_PORTS + // @DisplayName: CAN ports to mirror traffic between + // @Description: Any set ports will participate in blindly mirroring traffic from one port to the other. It is the users responsibility to ensure that no loops exist that cause traffic to be infinitly repeated, and both ports must be running the same baud rates. + // @Bitmask: 0:CAN1, 1:CAN2, 2:CAN3 + // @User: Advanced + GSCALAR(can_mirror_ports, "CAN_MIRROR_PORTS", 0), +#endif // HAL_PERIPH_CAN_MIRROR + +#ifdef HAL_PERIPH_ENABLE_RTC + // @Group: RTC + // @Path: ../libraries/AP_RTC/AP_RTC.cpp + GOBJECT(rtc, "RTC", AP_RTC), +#endif + AP_VAREND }; diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index 698833f73cdc2c..fb4a628b021099 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -31,7 +31,7 @@ class Parameters { k_param_hardpoint_rate, k_param_baro_enable, k_param_esc_number0, - k_param_battery, + k_param_battery_lib, k_param_debug, k_param_serial_number, k_param_adsb_port, @@ -76,6 +76,15 @@ class Parameters { k_param_esc_number1, k_param_pole_count1, k_param_esc_serial_port1, + k_param_networking, + k_param_rpm_sensor, + k_param_g_rcin, + k_param_sitl, + k_param_ahrs, + k_param_battery_balance, + k_param_battery_hide_mask, + k_param_can_mirror_ports, + k_param_rtc, }; AP_Int16 format_version; @@ -109,7 +118,7 @@ class Parameters { AP_Int16 rangefinder_max_rate; #endif -#if HAL_PROXIMITY_ENABLED +#ifdef HAL_PERIPH_ENABLE_PROXIMITY AP_Int32 proximity_baud; AP_Int8 proximity_port; AP_Int16 proximity_max_rate; @@ -177,10 +186,18 @@ class Parameters { AP_Int16 sysid_this_mav; #endif +#ifdef HAL_PERIPH_ENABLE_BATTERY + AP_Int32 battery_hide_mask; +#endif + #ifdef HAL_PERIPH_ENABLE_EFI AP_Int32 efi_baudrate; AP_Int8 efi_port; #endif + +#if HAL_PERIPH_CAN_MIRROR + AP_Int8 can_mirror_ports; +#endif // HAL_PERIPH_CAN_MIRROR #if HAL_CANFD_SUPPORTED AP_Int8 can_fdmode; diff --git a/Tools/AP_Periph/README.md b/Tools/AP_Periph/README.md index 90e5a62cd05b04..67aba113d923d5 100644 --- a/Tools/AP_Periph/README.md +++ b/Tools/AP_Periph/README.md @@ -1,42 +1,50 @@ -# AP_Periph UAVCAN Peripheral Firmware +# AP_Periph DroneCAN Peripheral Firmware -This is an ArduPilot based UAVCAN peripheral firmware. This firmware +This is an ArduPilot based DroneCAN peripheral firmware. This firmware takes advantage of the wide range of sensor drivers in ArduPilot to -make building a UAVCAN peripheral firmware easy. +make building a DroneCAN peripheral firmware easy. The AP_Periph firmware is based on the same ChibiOS hwdef.dat system that is used to define pinouts for STM32 based flight controllers supported by ArduPilot. That means you can add support for a new -UAVCAN peripheral based on the STM32 by just writing a simple +DroneCAN peripheral based on the STM32 by just writing a simple hwdef.dat that defines the pinout of your device. -Currently we have four targets building for AP_Periph firmwares: +We have over 60 build targets building for AP_Periph firmwares. All +ArduPilot supported MCUs can be used, including: - - A STM32F103 128k flash part made by mRobotics (target f103-GPS) - - A STM32F412 512k flash part made by CUAV (target CUAV_GPS) - - A STM32F105 256k flash part (used in ZubaxGNSSv2) - - A STM32F303 256k flash part made by mRobotics (target f303-GPS) + - STM32F1xx + - STM32F3xx + - STM32F4xx + - STM32F7xx + - STM32H7xx + - STM32L4xx + - STM32G4xx More can be added using the hwdef.dat system # Features The AP_Periph firmware can be configured to enable a wide range of -UAVCAN sensor types. Support is included for: +DroneCAN sensor types. Support is included for: - GPS modules (including RTK GPS) - Magnetometers (SPI or I2C) - Barometers (SPI or I2C) - Airspeed sensors (I2C) - Rangefinders (UART or I2C) - - ADSB (Ping ADSB receiver on UART) + - ADSB (uAvionix compatible Ping ADSB receiver on UART) - Battery Monitor (Analog, I2C/SMBus, UART) - LEDs (GPIO, I2C or WS2812 serial) - Safety LED and Safety Switch - Buzzer (tonealarm or simple GPIO) - RC Output (All standard RCOutput protocols) + - RC input + - battery balance monitor + - EFI engines + - Proximity sensors -An AP_Periph UAVCAN firmware supports these UAVCAN features: +An AP_Periph DroneCAN firmware supports these DroneCAN features: - dynamic or static CAN node allocation - firmware upload @@ -56,8 +64,8 @@ Using f103-GPS as an example, build the main firmware like this: - ./waf AP_Periph that will build a file build/f103-GPS/bin/AP_Periph.bin. You can -now load that using the CAN bootloader and either uavcan_gui_tool or -MissionPlanner SLCAN support. +now load that using the CAN bootloader and either dronecan_gui_tool or +MissionPlanner DroneCAN support. # Flashing @@ -87,95 +95,32 @@ the resulting bootloader will be in Tools/bootloaders Firmware targets are automatically built and distributed on the ArduPilot firmware server on firmware.ardupilot.org. These firmwares -can be loaded using Mission Planner or the UAVCAN GUI Tool. Parameters -for peripherals can be changed using the Mission Planner SLCAN support -or using UAVCAN GUI Tools. +can be loaded using Mission Planner or the DroneCAN GUI Tool. Parameters +for peripherals can be changed using the Mission Planner DroneCAN support +or using DroneCAN GUI Tools. # User Bootloader Update The bootloader is automatically stored in ROMFS in the main -firmware. End users can update the bootloader by setting the UAVCAN +firmware. End users can update the bootloader by setting the DroneCAN parameter "FLASH_BOOTLOADER" to 1. After setting it to 1 the node will -respond with a debug text message which can be seen in the UAVCAN GUI +respond with a debug text message which can be seen in the DroneCAN GUI tool to show the result of the flash. # SITL Testing -Currently GPS peripheral build is supported under linux environment, -we simulate a UAVCAN GPS Peripheral on SocketCAN. - -Setup can be done as follows, this is on top of usual setup required -to build ardupilot: - -``` -sudo dpkg --add-architecture i386 -sudo apt-get update -sudo apt-get install -y gcc-multilib g++-multilib -sudo apt-get update -sudo apt-get -y install can-utils iproute2 linux-modules-extra-$(uname -r) -sudo modprobe vcan -sudo ip link add dev vcan0 type vcan -sudo ip link set up vcan0 -``` -Build Commands: -``` -./waf configure --board sitl_periph_gps -./waf AP_Periph -``` -Autotest Command: -``` -Tools/autotest/autotest.py -v Copter build.SITLPeriphGPS test.CAN -``` - - ---- -**Note** - -To run valgrind on AP_Periph binary you might need to get 32 bit version of libc6-dbg which can be simply get using following command for Ubuntu machines: `sudo apt-get install libc6-dbg:i386` - ---- - - -https://github.com/linux-can/can-utils contains a nice set of utility to do CAN related testings on Linux system. I used Ubuntu for this development, for Ubuntu systems you can simply download this tool using `sudo apt-get install can-utils` - -Following are the common commands that can be used while testing or developing: -* Create Virtual CAN Interface: -``` -sudo modprobe vcan -sudo ip link add dev vcan0 type vcan -sudo ip link set up vcan0 -sudo ip link add dev vcan1 type vcan -sudo ip link set up vcan1 -``` -* Route one CANSocket to another -``` -sudo modprobe can-gw -sudo cangw -A -s vcan0 -d vcan1 -e -sudo cangw -A -s vcan1 -d vcan0 -e -``` -* Delete routes -``` -sudo cangw -D -s vcan0 -d vcan1 -e -sudo cangw -D -s vcan1 -d vcan0 -e -``` -* Route SLCAN to VCAN, this allows connecting CAN devices to SITL run via CAN Adapter like the one running in Ardupilot itself. -``` -sudo modprobe slcan -sudo modprobe can-gw -sudo slcan_attach -f -s8 -o /dev/ttyACM0 -sudo slcand ttyACM0 slcan0 -sudo ifconfig slcan0 up -sudo cangw -A -s vcan0 -d slcan0 -e -sudo cangw -A -s slcan0 -d vcan0 -e -``` -* Dump can messages: -``` -sudo candump vcan0 -``` +A wide range of DroneCAN peripherals are supported in the SITL +simulation system. The simplest way of starting a DroneCAN enabled +simulated vehicle is to use sim_vehicle.py. + +For a quadplane use: sim_vehicle.py with the option -f quadplane-can + +For a quadcopter use: sim_vehicle.py with the option -f quad-can # Discussion and Feedback Please join the discussions at these locations: - - https://discuss.ardupilot.org/t/ap-periph-1-0-0-stable-released/49049 - - https://gitter.im/ArduPilot/CANBUS + - https://discuss.ardupilot.org/ + - https://ardupilot.org/discord + diff --git a/Tools/AP_Periph/ReleaseNotes.txt b/Tools/AP_Periph/ReleaseNotes.txt index 76666579839791..252044e1efceb7 100644 --- a/Tools/AP_Periph/ReleaseNotes.txt +++ b/Tools/AP_Periph/ReleaseNotes.txt @@ -1,3 +1,32 @@ +Release 1.6.0 8th September 2023 +-------------------------------- + +This is a major release with the following changes: + + - much faster CAN bootloader for faster firmware update + - improved handling of peripherals with 2 or more CAN interfaces + - support most AP_Periph features in SITL testing + - added RC input support + - added battery balance plug support + - support sending RPM over DroneCAN + - support for pitot temperature reporting + +Release 1.5.1 23rd July 2023 +--------------------------- + +This is a major release with the following changes: + +- support serial tunnelling over DroneCAN +- raised CAN priority of MovingBaseline data +- support APD ESC telemetry +- support DroneCAN and CAN statistics reporting +- support KDECAN to DroneCAN translation + +The serial tunnelling support allows for uCenter to be used over +DroneCAN with the serial tunnelling panel in the DroneCAN GUI +tool. This allows for monitoring of uBlox GPS over a telemetry link, +and update of F9P firmware over DroneCAN + Release 1.5.0 27th Mar 2023 --------------------------- diff --git a/Tools/AP_Periph/adsb.cpp b/Tools/AP_Periph/adsb.cpp index fe80b39081ec89..1a1229826bee6e 100644 --- a/Tools/AP_Periph/adsb.cpp +++ b/Tools/AP_Periph/adsb.cpp @@ -27,18 +27,6 @@ extern const AP_HAL::HAL &hal; -# if !HAL_GCS_ENABLED - -#include "include/mavlink/v2.0/protocol.h" -#include "include/mavlink/v2.0/mavlink_types.h" -#include "include/mavlink/v2.0/all/mavlink.h" -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wmissing-declarations" -#include "include/mavlink/v2.0/mavlink_helpers.h" -#pragma GCC diagnostic pop - -#endif - /* init ADSB support */ @@ -53,16 +41,6 @@ void AP_Periph_FW::adsb_init(void) } } -static mavlink_message_t chan_buffer; -mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) { - return &chan_buffer; -} - -static mavlink_status_t chan_status; -mavlink_status_t* mavlink_get_channel_status(uint8_t chan) { - return &chan_status; -} - /* update ADSB subsystem */ @@ -83,7 +61,7 @@ void AP_Periph_FW::adsb_update(void) const uint8_t c = (uint8_t)uart->read(); // Try to get a new message - if (mavlink_parse_char(MAVLINK_COMM_0, c, &adsb.msg, &adsb.status)) { + if (mavlink_frame_char_buffer(&adsb.msg, &adsb.status, c, &adsb.msg, &adsb.status) == MAVLINK_FRAMING_OK) { if (adsb.msg.msgid == MAVLINK_MSG_ID_ADSB_VEHICLE) { // decode and send as UAVCAN TrafficReport static mavlink_adsb_vehicle_t msg; @@ -92,6 +70,24 @@ void AP_Periph_FW::adsb_update(void) } } } + + /* + some ADSB devices need a heartbeat to get the system ID + */ + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - adsb.last_heartbeat_ms >= 1000) { + adsb.last_heartbeat_ms = now_ms; + mavlink_heartbeat_t heartbeat {}; + mavlink_message_t msg; + heartbeat.type = MAV_TYPE_GENERIC; + heartbeat.autopilot = MAV_AUTOPILOT_ARDUPILOTMEGA; + auto len = mavlink_msg_heartbeat_encode_status(1, + MAV_COMP_ID_PERIPHERAL, + &adsb.status, + &msg, &heartbeat); + + uart->write((uint8_t*)&msg.magic, len); + } } /* diff --git a/Tools/AP_Periph/airspeed.cpp b/Tools/AP_Periph/airspeed.cpp new file mode 100644 index 00000000000000..17a4da160731c5 --- /dev/null +++ b/Tools/AP_Periph/airspeed.cpp @@ -0,0 +1,85 @@ +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_AIRSPEED + +/* + airspeed support + */ + +#include + +#ifndef AP_PERIPH_PROBE_CONTINUOUS +#define AP_PERIPH_PROBE_CONTINUOUS 0 +#endif + +/* + update CAN airspeed + */ +void AP_Periph_FW::can_airspeed_update(void) +{ + if (!airspeed.enabled()) { + return; + } +#if AP_PERIPH_PROBE_CONTINUOUS + if (!airspeed.healthy()) { + uint32_t now = AP_HAL::millis(); + static uint32_t last_probe_ms; + if (now - last_probe_ms >= 1000) { + last_probe_ms = now; + airspeed.allocate(); + } + } +#endif + uint32_t now = AP_HAL::millis(); + if (now - last_airspeed_update_ms < 50) { + // max 20Hz data + return; + } + last_airspeed_update_ms = now; + airspeed.update(); + if (!airspeed.healthy()) { + // don't send any data + return; + } + const float press = airspeed.get_corrected_pressure(); + float temp; + if (!airspeed.get_temperature(temp)) { + temp = nanf(""); + } else { + temp = C_TO_KELVIN(temp); + } + + uavcan_equipment_air_data_RawAirData pkt {}; + + // unfilled elements are NaN + pkt.static_pressure = nanf(""); + pkt.static_pressure_sensor_temperature = nanf(""); + pkt.differential_pressure_sensor_temperature = nanf(""); + pkt.pitot_temperature = nanf(""); + + // populate the elements we have + pkt.differential_pressure = press; + pkt.static_air_temperature = temp; + + // if a Pitot tube temperature sensor is available, use it +#if AP_TEMPERATURE_SENSOR_ENABLED + for (uint8_t i=0; i + +/* + update CAN baro + */ +void AP_Periph_FW::can_baro_update(void) +{ + if (!periph.g.baro_enable) { + return; + } + baro.update(); + if (last_baro_update_ms == baro.get_last_update()) { + return; + } + + last_baro_update_ms = baro.get_last_update(); + if (!baro.healthy()) { + // don't send any data + return; + } + const float press = baro.get_pressure(); + const float temp = baro.get_temperature(); + + { + uavcan_equipment_air_data_StaticPressure pkt {}; + 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] {}; + uint16_t total_size = uavcan_equipment_air_data_StaticPressure_encode(&pkt, buffer, !periph.canfdout()); + + canard_broadcast(UAVCAN_EQUIPMENT_AIR_DATA_STATICPRESSURE_SIGNATURE, + UAVCAN_EQUIPMENT_AIR_DATA_STATICPRESSURE_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + } + + { + uavcan_equipment_air_data_StaticTemperature pkt {}; + 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] {}; + uint16_t total_size = uavcan_equipment_air_data_StaticTemperature_encode(&pkt, buffer, !periph.canfdout()); + + canard_broadcast(UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_SIGNATURE, + UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + } +} + +#endif // HAL_PERIPH_ENABLE_BARO diff --git a/Tools/AP_Periph/batt_balance.cpp b/Tools/AP_Periph/batt_balance.cpp new file mode 100644 index 00000000000000..86c7c7a11cd7c4 --- /dev/null +++ b/Tools/AP_Periph/batt_balance.cpp @@ -0,0 +1,138 @@ +/* + 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_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE + +#include + +extern const AP_HAL::HAL &hal; + +#ifndef AP_PERIPH_BATTERY_BALANCE_NUMCELLS_DEFAULT +#define AP_PERIPH_BATTERY_BALANCE_NUMCELLS_DEFAULT 0 +#endif + +#ifndef AP_PERIPH_BATTERY_BALANCE_RATE_DEFAULT +#define AP_PERIPH_BATTERY_BALANCE_RATE_DEFAULT 1 +#endif + +#ifndef AP_PERIPH_BATTERY_BALANCE_CELL1_PIN_DEFAULT +#define AP_PERIPH_BATTERY_BALANCE_CELL1_PIN_DEFAULT 1 +#endif + +#ifndef AP_PERIPH_BATTERY_BALANCE_ID_DEFAULT +#define AP_PERIPH_BATTERY_BALANCE_ID_DEFAULT 0 +#endif + + +const AP_Param::GroupInfo BattBalance::var_info[] { + // @Param: _NUM_CELLS + // @DisplayName: Number of battery cells + // @Description: Number of battery cells to monitor + // @Range: 0 64 + AP_GROUPINFO("_NUM_CELLS", 1, BattBalance, num_cells, AP_PERIPH_BATTERY_BALANCE_NUMCELLS_DEFAULT), + + // @Param: _ID + // @DisplayName: Battery ID + // @Description: Battery ID to match against other batteries + // @Range: 0 127 + AP_GROUPINFO("_ID", 2, BattBalance, id, AP_PERIPH_BATTERY_BALANCE_ID_DEFAULT), + + // @Param: _RATE + // @DisplayName: Send Rate + // @Description: Rate to send cell information + // @Range: 0 20 + AP_GROUPINFO("_RATE", 3, BattBalance, rate, AP_PERIPH_BATTERY_BALANCE_RATE_DEFAULT), + + // @Param: _CELL1_PIN + // @DisplayName: First analog pin + // @Description: Analog pin of the first cell. Later cells must be sequential + // @Range: 0 127 + AP_GROUPINFO("_CELL1_PIN", 4, BattBalance, cell1_pin, AP_PERIPH_BATTERY_BALANCE_CELL1_PIN_DEFAULT), + + AP_GROUPEND +}; + +BattBalance::BattBalance(void) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +void AP_Periph_FW::batt_balance_update() +{ + const int8_t ncell = battery_balance.num_cells; + if (ncell <= 0) { + return; + } + + // allocate cell sources if needed + if (battery_balance.cells == nullptr) { + battery_balance.cells = new AP_HAL::AnalogSource*[ncell]; + if (battery_balance.cells == nullptr) { + return; + } + battery_balance.cells_allocated = ncell; + for (uint8_t i=0; ichannel(battery_balance.cell1_pin + i); + } + } + + const uint32_t now = AP_HAL::millis(); + if (now - battery_balance.last_send_ms < 1000.0/battery_balance.rate.get()) { + return; + } + battery_balance.last_send_ms = now; + + // 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]; + if (pkt == nullptr || buffer == nullptr) { + delete pkt; + delete [] buffer; + return; + } + + pkt->voltage_cell.len = battery_balance.cells_allocated; + float last_cell = 0; + for (uint8_t i=0; ivoltage_average(); + pkt->voltage_cell.data[i] = v - last_cell; + last_cell = v; + } + pkt->max_current = nanf(""); + pkt->nominal_voltage = nanf(""); + pkt->battery_id = uint8_t(battery_balance.id); + + // encode and send message: + const uint16_t total_size = ardupilot_equipment_power_BatteryInfoAux_encode(pkt, buffer, !periph.canfdout()); + + canard_broadcast(ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_SIGNATURE, + ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_ID, + CANARD_TRANSFER_PRIORITY_LOW, + buffer, + total_size); + + delete pkt; + delete [] buffer; +} + +#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE + diff --git a/Tools/AP_Periph/batt_balance.h b/Tools/AP_Periph/batt_balance.h new file mode 100644 index 00000000000000..961875c660ab71 --- /dev/null +++ b/Tools/AP_Periph/batt_balance.h @@ -0,0 +1,24 @@ +#pragma once + +#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE + +class BattBalance { +public: + friend class AP_Periph_FW; + BattBalance(void); + + static const struct AP_Param::GroupInfo var_info[]; + +private: + AP_Int8 num_cells; + AP_Int8 id; + AP_Int8 cell1_pin; + AP_Float rate; + uint32_t last_send_ms; + + AP_HAL::AnalogSource **cells; + uint8_t cells_allocated; +}; + +#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE + diff --git a/Tools/AP_Periph/battery.cpp b/Tools/AP_Periph/battery.cpp new file mode 100644 index 00000000000000..8f07834d22e66c --- /dev/null +++ b/Tools/AP_Periph/battery.cpp @@ -0,0 +1,128 @@ +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_BATTERY + +/* + battery support + */ + +#include + +extern const AP_HAL::HAL &hal; + +#ifndef AP_PERIPH_BATTERY_MODEL_NAME +#define AP_PERIPH_BATTERY_MODEL_NAME CAN_APP_NODE_NAME +#endif + +/* + update CAN battery monitor + */ +void AP_Periph_FW::can_battery_update(void) +{ + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - battery.last_can_send_ms < 100) { + return; + } + battery.last_can_send_ms = now_ms; + + const uint8_t battery_instances = battery_lib.num_instances(); + for (uint8_t i=0; i= 0) ? serial_number : i+1; + + pkt.voltage = battery_lib.voltage(i); + + float current; + if (battery_lib.current_amps(current, i)) { + pkt.current = current; + } + float temperature; + if (battery_lib.get_temperature(temperature, i)) { + // Battery lib reports temperature in Celsius. + // Convert Celsius to Kelvin for transmission on CAN. + pkt.temperature = C_TO_KELVIN(temperature); + } + + pkt.state_of_health_pct = UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN; + uint8_t percentage = 0; + if (battery_lib.capacity_remaining_pct(percentage, i)) { + pkt.state_of_charge_pct = percentage; + } + pkt.model_instance_id = i+1; + +#if !defined(HAL_PERIPH_BATTERY_SKIP_NAME) + // example model_name: "org.ardupilot.ap_periph SN 123" + hal.util->snprintf((char*)pkt.model_name.data, sizeof(pkt.model_name.data), "%s %ld", AP_PERIPH_BATTERY_MODEL_NAME, (long int)serial_number); + 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] {}; + const uint16_t total_size = uavcan_equipment_power_BatteryInfo_encode(&pkt, buffer, !periph.canfdout()); + + canard_broadcast(UAVCAN_EQUIPMENT_POWER_BATTERYINFO_SIGNATURE, + UAVCAN_EQUIPMENT_POWER_BATTERYINFO_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + + // Send individual cell information if available + if (battery_lib.has_cell_voltages(i)) { + can_battery_send_cells(i); + } + } +} + +/* + send individual cell voltages if available + */ +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]; + if (pkt == nullptr || buffer == nullptr) { + delete pkt; + delete [] buffer; + return; + } + const auto &cell_voltages = battery_lib.get_cell_voltages(instance); + + for (uint8_t i = 0; i < ARRAY_SIZE(cell_voltages.cells); i++) { + if (cell_voltages.cells[i] == 0xFFFFU) { + break; + } + pkt->voltage_cell.data[i] = cell_voltages.cells[i]*0.001; + pkt->voltage_cell.len = i+1; + } + + pkt->max_current = nanf(""); + pkt->nominal_voltage = nanf(""); + + // encode and send message: + const uint16_t total_size = ardupilot_equipment_power_BatteryInfoAux_encode(pkt, buffer, !periph.canfdout()); + + canard_broadcast(ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_SIGNATURE, + ARDUPILOT_EQUIPMENT_POWER_BATTERYINFOAUX_ID, + CANARD_TRANSFER_PRIORITY_LOW, + buffer, + total_size); + + // Delete temporary buffers + delete pkt; + delete [] buffer; +} + +#endif // HAL_PERIPH_ENABLE_BATTERY + diff --git a/Tools/AP_Periph/buzzer.cpp b/Tools/AP_Periph/buzzer.cpp new file mode 100644 index 00000000000000..c5285e3612d375 --- /dev/null +++ b/Tools/AP_Periph/buzzer.cpp @@ -0,0 +1,55 @@ +#include "AP_Periph.h" + +#if defined(HAL_PERIPH_ENABLE_NOTIFY) || defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) + +/* + buzzer support + */ + +#include + +extern const AP_HAL::HAL &hal; + +static uint32_t buzzer_start_ms; +static uint32_t buzzer_len_ms; + +/* + handle BeepCommand + */ +void AP_Periph_FW::handle_beep_command(CanardInstance* canard_instance, CanardRxTransfer* transfer) +{ + uavcan_equipment_indication_BeepCommand req; + if (uavcan_equipment_indication_BeepCommand_decode(transfer, &req)) { + return; + } + static bool initialised; + if (!initialised) { + initialised = true; + hal.rcout->init(); + hal.util->toneAlarm_init(AP_Notify::Notify_Buzz_Builtin); + } + buzzer_start_ms = AP_HAL::millis(); + buzzer_len_ms = req.duration*1000; +#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY + float volume = constrain_float(periph.g.buzz_volume/100.0f, 0, 1); +#elif defined(HAL_PERIPH_ENABLE_NOTIFY) + float volume = constrain_float(periph.notify.get_buzz_volume()/100.0f, 0, 1); +#endif + hal.util->toneAlarm_set_buzzer_tone(req.frequency, volume, uint32_t(req.duration*1000)); +} + +/* + update buzzer + */ +void AP_Periph_FW::can_buzzer_update(void) +{ + if (buzzer_start_ms != 0) { + uint32_t now = AP_HAL::millis(); + if (now - buzzer_start_ms > buzzer_len_ms) { + hal.util->toneAlarm_set_buzzer_tone(0, 0, 0); + buzzer_start_ms = 0; + } + } +} + +#endif // (HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || (HAL_PERIPH_ENABLE_NOTIFY) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index e4cccc9a68f059..deadcd03f36f71 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -20,8 +20,6 @@ #include #include #include "AP_Periph.h" -#include -#include #include #include #include @@ -38,7 +36,7 @@ #include #endif -#define IFACE_ALL ((1U<<(HAL_NUM_CAN_IFACES+1U))-1U) +#define IFACE_ALL ((1U<<(HAL_NUM_CAN_IFACES))-1U) #include "i2c.h" #include @@ -47,7 +45,6 @@ #include #endif - #if CONFIG_HAL_BOARD == HAL_BOARD_SITL extern const HAL_SITL &hal; #else @@ -56,16 +53,6 @@ extern const AP_HAL::HAL &hal; extern AP_Periph_FW periph; -#ifndef HAL_CAN_POOL_SIZE -#if HAL_CANFD_SUPPORTED - #define HAL_CAN_POOL_SIZE 16000 -#elif GPS_MOVING_BASELINE - #define HAL_CAN_POOL_SIZE 8000 -#else - #define HAL_CAN_POOL_SIZE 4000 -#endif -#endif - #ifndef HAL_PERIPH_LOOP_DELAY_US // delay between can loop updates. This needs to be longer on F4 #if defined(STM32H7) @@ -75,17 +62,13 @@ extern AP_Periph_FW periph; #endif #endif -#ifndef AP_PERIPH_MAG_MAX_RATE -#define AP_PERIPH_MAG_MAX_RATE 25U -#endif - -#define DEBUG_PRINTS 0 #define DEBUG_PKTS 0 -#if DEBUG_PRINTS - # define Debug(fmt, args ...) do {can_printf(fmt "\n", ## args);} while(0) -#else - # define Debug(fmt, args ...) -#endif + +#if HAL_PERIPH_CAN_MIRROR + #ifndef HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE + #define HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE 64 + #endif +#endif //HAL_PERIPH_CAN_MIRROR #ifndef HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF // When enabled, can_printf() strings longer than the droneCAN max text length (90 chars) @@ -104,27 +87,18 @@ static struct instance_t { #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL HALSITL::CANIface* iface; #endif + +#if HAL_PERIPH_CAN_MIRROR + #if HAL_NUM_CAN_IFACES < 2 + #error "Can't use HAL_PERIPH_CAN_MIRROR if there are not at least 2 HAL_NUM_CAN_IFACES" + #endif + ObjectBuffer *mirror_queue; + uint8_t mirror_fail_count; +#endif // HAL_PERIPH_CAN_MIRROR } instances[HAL_NUM_CAN_IFACES]; -static struct dronecan_protocol_t { - CanardInstance canard; - uint32_t canard_memory_pool[HAL_CAN_POOL_SIZE/sizeof(uint32_t)]; - struct tid_map { - uint32_t transfer_desc; - uint8_t tid; - tid_map *next; - } *tid_map_head; - /* - * Variables used for dynamic node ID allocation. - * RTFM at http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation - */ - uint32_t send_next_node_id_allocation_request_at_ms; ///< When the next node ID allocation request should be sent - uint8_t node_id_allocation_unique_id_offset; ///< Depends on the stage of the next request - uint8_t tx_fail_count; - uint8_t dna_interface = 1; -} dronecan; - -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(HAL_GPIO_PIN_TERMCAN1) + +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(HAL_GPIO_PIN_TERMCAN1) && (HAL_NUM_CAN_IFACES >= 2) static ioline_t can_term_lines[] = { HAL_GPIO_PIN_TERMCAN1 @@ -147,19 +121,11 @@ HAL_GPIO_PIN_TERMCAN1 }; #endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(HAL_GPIO_PIN_TERMCAN1) -#ifndef CAN_APP_NODE_NAME -#define CAN_APP_NODE_NAME "org.ardupilot.ap_periph" -#endif - #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; -#ifndef AP_PERIPH_BATTERY_MODEL_NAME -#define AP_PERIPH_BATTERY_MODEL_NAME CAN_APP_NODE_NAME -#endif - #ifndef AP_PERIPH_PROBE_CONTINUOUS #define AP_PERIPH_PROBE_CONTINUOUS 0 #endif @@ -208,13 +174,13 @@ static void readUniqueID(uint8_t* out_uid) /* handle a GET_NODE_INFO request */ -static void handle_get_node_info(CanardInstance* ins, - CanardRxTransfer* transfer) +void AP_Periph_FW::handle_get_node_info(CanardInstance* canard_instance, + CanardRxTransfer* transfer) { uint8_t buffer[UAVCAN_PROTOCOL_GETNODEINFO_RESPONSE_MAX_SIZE] {}; uavcan_protocol_GetNodeInfoResponse pkt {}; - node_status.uptime_sec = AP_HAL::native_millis() / 1000U; + node_status.uptime_sec = AP_HAL::millis() / 1000U; pkt.status = node_status; pkt.software_version.major = AP::fwversion().major; @@ -232,16 +198,16 @@ static void handle_get_node_info(CanardInstance* ins, pkt.hardware_version.major = APJ_BOARD_ID >> 8; pkt.hardware_version.minor = APJ_BOARD_ID & 0xFF; - if (periph.g.serial_number > 0) { - hal.util->snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s(%u)", CAN_APP_NODE_NAME, (unsigned)periph.g.serial_number); + if (g.serial_number > 0) { + hal.util->snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s(%u)", CAN_APP_NODE_NAME, (unsigned)g.serial_number); } else { hal.util->snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s", CAN_APP_NODE_NAME); } pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data)); - uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer, !periph.canfdout()); + uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer, !canfdout()); - const int16_t resp_res = canardRequestOrRespond(ins, + const int16_t resp_res = canardRequestOrRespond(canard_instance, transfer->source_node_id, UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE, UAVCAN_PROTOCOL_GETNODEINFO_ID, @@ -254,7 +220,7 @@ static void handle_get_node_info(CanardInstance* ins, , IFACE_ALL #endif #if HAL_CANFD_SUPPORTED - , periph.canfdout() + , canfdout() #endif ); if (resp_res <= 0) { @@ -265,7 +231,7 @@ static void handle_get_node_info(CanardInstance* ins, /* handle parameter GetSet request */ -static void handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer) +void AP_Periph_FW::handle_param_getset(CanardInstance* canard_instance, CanardRxTransfer* transfer) { // param fetch all can take a long time, so pat watchdog stm32_watchdog_pat(); @@ -348,9 +314,9 @@ static void handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer) } uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE] {}; - uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer, !periph.canfdout()); + uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer, !canfdout()); - canardRequestOrRespond(ins, + canardRequestOrRespond(canard_instance, transfer->source_node_id, UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE, UAVCAN_PROTOCOL_PARAM_GETSET_ID, @@ -363,7 +329,7 @@ static void handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer) , IFACE_ALL #endif #if HAL_CANFD_SUPPORTED - ,periph.canfdout() + ,canfdout() #endif ); @@ -372,7 +338,7 @@ static void handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer) /* handle parameter executeopcode request */ -static void handle_param_executeopcode(CanardInstance* ins, CanardRxTransfer* transfer) +void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, CanardRxTransfer* transfer) { uavcan_protocol_param_ExecuteOpcodeRequest req; if (uavcan_protocol_param_ExecuteOpcodeRequest_decode(transfer, &req)) { @@ -384,22 +350,22 @@ static void handle_param_executeopcode(CanardInstance* ins, CanardRxTransfer* tr AP_Param::load_all(); AP_Param::setup_sketch_defaults(); #ifdef HAL_PERIPH_ENABLE_GPS - AP_Param::setup_object_defaults(&periph.gps, periph.gps.var_info); + AP_Param::setup_object_defaults(&gps, gps.var_info); #endif #ifdef HAL_PERIPH_ENABLE_BATTERY - AP_Param::setup_object_defaults(&periph.battery, periph.battery.lib.var_info); + AP_Param::setup_object_defaults(&battery, battery_lib.var_info); #endif #ifdef HAL_PERIPH_ENABLE_MAG - AP_Param::setup_object_defaults(&periph.compass, periph.compass.var_info); + AP_Param::setup_object_defaults(&compass, compass.var_info); #endif #ifdef HAL_PERIPH_ENABLE_BARO - AP_Param::setup_object_defaults(&periph.baro, periph.baro.var_info); + AP_Param::setup_object_defaults(&baro, baro.var_info); #endif #ifdef HAL_PERIPH_ENABLE_AIRSPEED - AP_Param::setup_object_defaults(&periph.airspeed, periph.airspeed.var_info); + AP_Param::setup_object_defaults(&airspeed, airspeed.var_info); #endif #ifdef HAL_PERIPH_ENABLE_RANGEFINDER - AP_Param::setup_object_defaults(&periph.rangefinder, periph.rangefinder.var_info); + AP_Param::setup_object_defaults(&rangefinder, rangefinder.var_info); #endif } @@ -408,9 +374,9 @@ static void handle_param_executeopcode(CanardInstance* ins, CanardRxTransfer* tr pkt.ok = true; uint8_t buffer[UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE] {}; - uint16_t total_size = uavcan_protocol_param_ExecuteOpcodeResponse_encode(&pkt, buffer, !periph.canfdout()); + uint16_t total_size = uavcan_protocol_param_ExecuteOpcodeResponse_encode(&pkt, buffer, !canfdout()); - canardRequestOrRespond(ins, + canardRequestOrRespond(canard_instance, transfer->source_node_id, UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE, UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID, @@ -423,15 +389,12 @@ static void handle_param_executeopcode(CanardInstance* ins, CanardRxTransfer* tr , IFACE_ALL #endif #if HAL_CANFD_SUPPORTED - ,periph.canfdout() + ,canfdout() #endif ); } -static void processTx(void); -static void processRx(void); - -static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* transfer) +void AP_Periph_FW::handle_begin_firmware_update(CanardInstance* canard_instance, CanardRxTransfer* transfer) { #if HAL_RAM_RESERVE_START >= 256 // setup information on firmware request at start of ram @@ -449,14 +412,14 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* comms->server_node_id = transfer->source_node_id; } memcpy(comms->path, req.image_file_remote_path.path.data, req.image_file_remote_path.path.len); - comms->my_node_id = canardGetLocalNodeID(ins); + comms->my_node_id = canardGetLocalNodeID(canard_instance); uint8_t buffer[UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_MAX_SIZE] {}; uavcan_protocol_file_BeginFirmwareUpdateResponse reply {}; reply.error = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK; - uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer, !periph.canfdout()); - canardRequestOrRespond(ins, + uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer, !canfdout()); + canardRequestOrRespond(canard_instance, transfer->source_node_id, UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE, UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID, @@ -469,7 +432,7 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* ,IFACE_ALL #endif #if HAL_CANFD_SUPPORTED - ,periph.canfdout() + ,canfdout() #endif ); uint8_t count = 50; @@ -481,18 +444,18 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer* // instant reboot, with backup register used to give bootloader // the node_id - periph.prepare_reboot(); + prepare_reboot(); #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - set_fast_reboot((rtc_boot_magic)(RTC_BOOT_CANBL | canardGetLocalNodeID(ins))); + set_fast_reboot((rtc_boot_magic)(RTC_BOOT_CANBL | canardGetLocalNodeID(canard_instance))); NVIC_SystemReset(); #endif } -static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* transfer) +void AP_Periph_FW::handle_allocation_response(CanardInstance* canard_instance, CanardRxTransfer* transfer) { // Rule C - updating the randomized time interval dronecan.send_next_node_id_allocation_request_at_ms = - AP_HAL::native_millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS + + AP_HAL::millis() + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MIN_REQUEST_PERIOD_MS + get_random_range(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_MAX_FOLLOWUP_DELAY_MS); if (transfer->source_node_id == CANARD_BROADCAST_NODE_ID) @@ -526,19 +489,19 @@ static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* tr printf("Matching allocation response: %d\n", msg.unique_id.len); } else { // Allocation complete - copying the allocated node ID from the message - canardSetLocalNodeID(ins, msg.node_id); + canardSetLocalNodeID(canard_instance, msg.node_id); printf("IF%d Node ID allocated: %d\n", dronecan.dna_interface, msg.node_id); #if defined(HAL_PERIPH_ENABLE_GPS) && (HAL_NUM_CAN_IFACES >= 2) && GPS_MOVING_BASELINE - if (periph.g.gps_mb_only_can_port) { + if (g.gps_mb_only_can_port) { // we need to assign the unallocated port to be used for Moving Baseline only - periph.gps_mb_can_port = (dronecan.dna_interface+1)%HAL_NUM_CAN_IFACES; + gps_mb_can_port = (dronecan.dna_interface+1)%HAL_NUM_CAN_IFACES; if (canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) { // copy node id from the primary iface canardSetLocalNodeID(&dronecan.canard, msg.node_id); #ifdef HAL_GPIO_PIN_TERMCAN1 // also terminate the line as we don't have any other device on this port - palWriteLine(can_term_lines[periph.gps_mb_can_port], 1); + palWriteLine(can_term_lines[gps_mb_can_port], 1); #endif } } @@ -546,48 +509,6 @@ static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* tr } } -#if defined(HAL_PERIPH_ENABLE_NOTIFY) || defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) -static uint32_t buzzer_start_ms; -static uint32_t buzzer_len_ms; -/* - handle BeepCommand - */ -static void handle_beep_command(CanardInstance* ins, CanardRxTransfer* transfer) -{ - uavcan_equipment_indication_BeepCommand req; - if (uavcan_equipment_indication_BeepCommand_decode(transfer, &req)) { - return; - } - static bool initialised; - if (!initialised) { - initialised = true; - hal.rcout->init(); - hal.util->toneAlarm_init(AP_Notify::Notify_Buzz_Builtin); - } - buzzer_start_ms = AP_HAL::native_millis(); - buzzer_len_ms = req.duration*1000; -#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY - float volume = constrain_float(periph.g.buzz_volume/100.0f, 0, 1); -#elif defined(HAL_PERIPH_ENABLE_NOTIFY) - float volume = constrain_float(periph.notify.get_buzz_volume()/100.0f, 0, 1); -#endif - hal.util->toneAlarm_set_buzzer_tone(req.frequency, volume, uint32_t(req.duration*1000)); -} - -/* - update buzzer - */ -static void can_buzzer_update(void) -{ - if (buzzer_start_ms != 0) { - uint32_t now = AP_HAL::native_millis(); - if (now - buzzer_start_ms > buzzer_len_ms) { - hal.util->toneAlarm_set_buzzer_tone(0, 0, 0); - buzzer_start_ms = 0; - } - } -} -#endif // (HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || (HAL_PERIPH_ENABLE_NOTIFY) #if defined(HAL_GPIO_PIN_SAFE_LED) || defined(HAL_PERIPH_ENABLE_RC_OUT) static uint8_t safety_state; @@ -595,15 +516,15 @@ static uint8_t safety_state; /* handle SafetyState */ -static void handle_safety_state(CanardInstance* ins, CanardRxTransfer* transfer) +void AP_Periph_FW::handle_safety_state(CanardInstance* canard_instance, CanardRxTransfer* transfer) { ardupilot_indication_SafetyState req; if (ardupilot_indication_SafetyState_decode(transfer, &req)) { return; } safety_state = req.status; -#ifdef HAL_PERIPH_ENABLE_RC_OUT - periph.rcout_handle_safety_state(safety_state); +#if AP_PERIPH_SAFETY_SWITCH_ENABLED + rcout_handle_safety_state(safety_state); #endif } #endif // HAL_GPIO_PIN_SAFE_LED @@ -611,7 +532,7 @@ static void handle_safety_state(CanardInstance* ins, CanardRxTransfer* transfer) /* handle ArmingStatus */ -static void handle_arming_status(CanardInstance* ins, CanardRxTransfer* transfer) +void AP_Periph_FW::handle_arming_status(CanardInstance* canard_instance, CanardRxTransfer* transfer) { uavcan_equipment_safety_ArmingStatus req; if (uavcan_equipment_safety_ArmingStatus_decode(transfer, &req)) { @@ -620,44 +541,15 @@ static void handle_arming_status(CanardInstance* ins, CanardRxTransfer* transfer hal.util->set_soft_armed(req.status == UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_STATUS_FULLY_ARMED); } -#ifdef HAL_PERIPH_ENABLE_GPS -/* - handle gnss::RTCMStream - */ -static void handle_RTCMStream(CanardInstance* ins, CanardRxTransfer* transfer) -{ - uavcan_equipment_gnss_RTCMStream req; - if (uavcan_equipment_gnss_RTCMStream_decode(transfer, &req)) { - return; - } - periph.gps.handle_gps_rtcm_fragment(0, req.data.data, req.data.len); -} - -/* - handle gnss::MovingBaselineData -*/ -#if GPS_MOVING_BASELINE -static void handle_MovingBaselineData(CanardInstance* ins, CanardRxTransfer* transfer) -{ - ardupilot_gnss_MovingBaselineData msg; - if (ardupilot_gnss_MovingBaselineData_decode(transfer, &msg)) { - return; - } - periph.gps.inject_MBL_data(msg.data.data, msg.data.len); - Debug("MovingBaselineData: len=%u\n", msg.data.len); -} -#endif // GPS_MOVING_BASELINE - -#endif // HAL_PERIPH_ENABLE_GPS #if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NOTIFY) -static void set_rgb_led(uint8_t red, uint8_t green, uint8_t blue) +void AP_Periph_FW::set_rgb_led(uint8_t red, uint8_t green, uint8_t blue) { #ifdef HAL_PERIPH_ENABLE_NOTIFY - periph.notify.handle_rgb(red, green, blue); + notify.handle_rgb(red, green, blue); #ifdef HAL_PERIPH_ENABLE_RC_OUT - periph.rcout_has_new_data_to_update = true; + rcout_has_new_data_to_update = true; #endif // HAL_PERIPH_ENABLE_RC_OUT #endif // HAL_PERIPH_ENABLE_NOTIFY @@ -736,7 +628,7 @@ static void set_rgb_led(uint8_t red, uint8_t green, uint8_t blue) /* handle lightscommand */ -static void handle_lightscommand(CanardInstance* ins, CanardRxTransfer* transfer) +void AP_Periph_FW::handle_lightscommand(CanardInstance* canard_instance, CanardRxTransfer* transfer) { uavcan_equipment_indication_LightsCommand req; if (uavcan_equipment_indication_LightsCommand_decode(transfer, &req)) { @@ -750,9 +642,9 @@ static void handle_lightscommand(CanardInstance* ins, CanardRxTransfer* transfer uint8_t green = (cmd.color.green>>1U)<<3U; uint8_t blue = cmd.color.blue<<3U; #ifdef HAL_PERIPH_ENABLE_NOTIFY - const int8_t brightness = periph.notify.get_rgb_led_brightness_percent(); + const int8_t brightness = notify.get_rgb_led_brightness_percent(); #elif defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) - const int8_t brightness = periph.g.led_brightness; + const int8_t brightness = g.led_brightness; #endif if (brightness != 100 && brightness >= 0) { const float scale = brightness * 0.01; @@ -766,20 +658,20 @@ static void handle_lightscommand(CanardInstance* ins, CanardRxTransfer* transfer #endif // AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY #ifdef HAL_PERIPH_ENABLE_RC_OUT -static void handle_esc_rawcommand(CanardInstance* ins, CanardRxTransfer* transfer) +void AP_Periph_FW::handle_esc_rawcommand(CanardInstance* canard_instance, CanardRxTransfer* transfer) { uavcan_equipment_esc_RawCommand cmd; if (uavcan_equipment_esc_RawCommand_decode(transfer, &cmd)) { return; } - periph.rcout_esc(cmd.cmd.data, cmd.cmd.len); + rcout_esc(cmd.cmd.data, cmd.cmd.len); // Update internal copy for disabling output to ESC when CAN packets are lost - periph.last_esc_num_channels = cmd.cmd.len; - periph.last_esc_raw_command_ms = AP_HAL::millis(); + last_esc_num_channels = cmd.cmd.len; + last_esc_raw_command_ms = AP_HAL::millis(); } -static void handle_act_command(CanardInstance* ins, CanardRxTransfer* transfer) +void AP_Periph_FW::handle_act_command(CanardInstance* canard_instance, CanardRxTransfer* transfer) { uavcan_equipment_actuator_ArrayCommand cmd; if (uavcan_equipment_actuator_ArrayCommand_decode(transfer, &cmd)) { @@ -790,10 +682,10 @@ static void handle_act_command(CanardInstance* ins, CanardRxTransfer* transfer) const auto &c = cmd.commands.data[i]; switch (c.command_type) { case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_UNITLESS: - periph.rcout_srv_unitless(c.actuator_id, c.command_value); + rcout_srv_unitless(c.actuator_id, c.command_value); break; case UAVCAN_EQUIPMENT_ACTUATOR_COMMAND_COMMAND_TYPE_PWM: - periph.rcout_srv_PWM(c.actuator_id, c.command_value); + rcout_srv_PWM(c.actuator_id, c.command_value); break; } } @@ -801,7 +693,7 @@ static void handle_act_command(CanardInstance* ins, CanardRxTransfer* transfer) #endif // HAL_PERIPH_ENABLE_RC_OUT #if defined(HAL_PERIPH_ENABLE_NOTIFY) -static void handle_notify_state(CanardInstance* ins, CanardRxTransfer* transfer) +void AP_Periph_FW::handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer) { ardupilot_indication_NotifyState msg; if (ardupilot_indication_NotifyState_decode(transfer, &msg)) { @@ -810,10 +702,10 @@ static void handle_notify_state(CanardInstance* ins, CanardRxTransfer* transfer) if (msg.aux_data.len == 2 && msg.aux_data_type == ARDUPILOT_INDICATION_NOTIFYSTATE_VEHICLE_YAW_EARTH_CENTIDEGREES) { uint16_t tmp = 0; memcpy(&tmp, msg.aux_data.data, sizeof(tmp)); - periph.yaw_earth = radians((float)tmp * 0.01f); + yaw_earth = radians((float)tmp * 0.01f); } - periph.vehicle_state = msg.vehicle_state; - periph.last_vehicle_state = AP_HAL::millis(); + vehicle_state = msg.vehicle_state; + last_vehicle_state = AP_HAL::millis(); } #endif // HAL_PERIPH_ENABLE_NOTIFY @@ -821,7 +713,7 @@ static void handle_notify_state(CanardInstance* ins, CanardRxTransfer* transfer) /* update safety LED */ -static void can_safety_LED_update(void) +void AP_Periph_FW::can_safety_LED_update(void) { static uint32_t last_update_ms; switch (safety_state) { @@ -829,7 +721,7 @@ static void can_safety_LED_update(void) palWriteLine(HAL_GPIO_PIN_SAFE_LED, SAFE_LED_ON); break; case ARDUPILOT_INDICATION_SAFETYSTATE_STATUS_SAFETY_ON: { - uint32_t now = AP_HAL::native_millis(); + uint32_t now = AP_HAL::millis(); if (now - last_update_ms > 100) { last_update_ms = now; static uint8_t led_counter; @@ -854,11 +746,11 @@ static void can_safety_LED_update(void) /* update safety button */ -static void can_safety_button_update(void) +void AP_Periph_FW::can_safety_button_update(void) { static uint32_t last_update_ms; static uint8_t counter; - uint32_t now = AP_HAL::native_millis(); + uint32_t now = AP_HAL::millis(); // send at 10Hz when pressed if (palReadLine(HAL_GPIO_PIN_SAFE_BUTTON) != HAL_SAFE_BUTTON_ON) { counter = 0; @@ -877,9 +769,9 @@ static void can_safety_button_update(void) pkt.press_time = counter; uint8_t buffer[ARDUPILOT_INDICATION_BUTTON_MAX_SIZE] {}; - uint16_t total_size = ardupilot_indication_Button_encode(&pkt, buffer, !periph.canfdout()); + uint16_t total_size = ardupilot_indication_Button_encode(&pkt, buffer, !canfdout()); - periph.canard_broadcast(ARDUPILOT_INDICATION_BUTTON_SIGNATURE, + canard_broadcast(ARDUPILOT_INDICATION_BUTTON_SIGNATURE, ARDUPILOT_INDICATION_BUTTON_ID, CANARD_TRANSFER_PRIORITY_LOW, &buffer[0], @@ -890,8 +782,8 @@ static void can_safety_button_update(void) /** * This callback is invoked by the library when a new message or request or response is received. */ -static void onTransferReceived(CanardInstance* ins, - CanardRxTransfer* transfer) +void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance, + CanardRxTransfer* transfer) { #ifdef HAL_GPIO_PIN_LED_CAN1 palToggleLine(HAL_GPIO_PIN_LED_CAN1); @@ -906,27 +798,27 @@ static void onTransferReceived(CanardInstance* ins, * Dynamic node ID allocation protocol. * Taking this branch only if we don't have a node ID, ignoring otherwise. */ - if (canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID) { + if (canardGetLocalNodeID(canard_instance) == CANARD_BROADCAST_NODE_ID) { if (transfer->transfer_type == CanardTransferTypeBroadcast && transfer->data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID) { - handle_allocation_response(ins, transfer); + handle_allocation_response(canard_instance, transfer); } return; } switch (transfer->data_type_id) { case UAVCAN_PROTOCOL_GETNODEINFO_ID: - handle_get_node_info(ins, transfer); + handle_get_node_info(canard_instance, transfer); break; case UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID: - handle_begin_firmware_update(ins, transfer); + handle_begin_firmware_update(canard_instance, transfer); break; case UAVCAN_PROTOCOL_RESTARTNODE_ID: printf("RestartNode\n"); hal.scheduler->delay(10); - periph.prepare_reboot(); + prepare_reboot(); #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS NVIC_SystemReset(); #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -935,71 +827,81 @@ static void onTransferReceived(CanardInstance* ins, break; case UAVCAN_PROTOCOL_PARAM_GETSET_ID: - handle_param_getset(ins, transfer); + handle_param_getset(canard_instance, transfer); break; case UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID: - handle_param_executeopcode(ins, transfer); + handle_param_executeopcode(canard_instance, transfer); break; #if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY) case UAVCAN_EQUIPMENT_INDICATION_BEEPCOMMAND_ID: - handle_beep_command(ins, transfer); + handle_beep_command(canard_instance, transfer); break; #endif #if defined(HAL_GPIO_PIN_SAFE_LED) || defined(HAL_PERIPH_ENABLE_RC_OUT) case ARDUPILOT_INDICATION_SAFETYSTATE_ID: - handle_safety_state(ins, transfer); + handle_safety_state(canard_instance, transfer); break; #endif case UAVCAN_EQUIPMENT_SAFETY_ARMINGSTATUS_ID: - handle_arming_status(ins, transfer); + handle_arming_status(canard_instance, transfer); break; #ifdef HAL_PERIPH_ENABLE_GPS case UAVCAN_EQUIPMENT_GNSS_RTCMSTREAM_ID: - handle_RTCMStream(ins, transfer); + handle_RTCMStream(canard_instance, transfer); break; #if GPS_MOVING_BASELINE case ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID: - handle_MovingBaselineData(ins, transfer); + handle_MovingBaselineData(canard_instance, transfer); break; #endif #endif // HAL_PERIPH_ENABLE_GPS #if AP_UART_MONITOR_ENABLED case UAVCAN_TUNNEL_TARGETTED_ID: - periph.handle_tunnel_Targetted(ins, transfer); + handle_tunnel_Targetted(canard_instance, transfer); break; #endif #if defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_NOTIFY) case UAVCAN_EQUIPMENT_INDICATION_LIGHTSCOMMAND_ID: - handle_lightscommand(ins, transfer); + handle_lightscommand(canard_instance, transfer); break; #endif #ifdef HAL_PERIPH_ENABLE_RC_OUT case UAVCAN_EQUIPMENT_ESC_RAWCOMMAND_ID: - handle_esc_rawcommand(ins, transfer); + handle_esc_rawcommand(canard_instance, transfer); break; case UAVCAN_EQUIPMENT_ACTUATOR_ARRAYCOMMAND_ID: - handle_act_command(ins, transfer); + handle_act_command(canard_instance, transfer); break; #endif #ifdef HAL_PERIPH_ENABLE_NOTIFY case ARDUPILOT_INDICATION_NOTIFYSTATE_ID: - handle_notify_state(ins, transfer); + handle_notify_state(canard_instance, transfer); break; #endif } } +/** + * This callback is invoked by the library when a new message or request or response is received. + */ +static void onTransferReceived_trampoline(CanardInstance* canard_instance, + CanardRxTransfer* transfer) +{ + AP_Periph_FW *fw = (AP_Periph_FW *)canard_instance->user_reference; + fw->onTransferReceived(canard_instance, transfer); +} + /** * This callback is invoked by the library when it detects beginning of a new transfer on the bus that can be received @@ -1008,15 +910,15 @@ static void onTransferReceived(CanardInstance* ins, * If the callback returns false, the library will ignore the transfer. * All transfers that are addressed to other nodes are always ignored. */ -static bool shouldAcceptTransfer(const CanardInstance* ins, - uint64_t* out_data_type_signature, - uint16_t data_type_id, - CanardTransferType transfer_type, - uint8_t source_node_id) +bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance, + uint64_t* out_data_type_signature, + uint16_t data_type_id, + CanardTransferType transfer_type, + uint8_t source_node_id) { (void)source_node_id; - if (canardGetLocalNodeID(ins) == CANARD_BROADCAST_NODE_ID) + if (canardGetLocalNodeID(canard_instance) == CANARD_BROADCAST_NODE_ID) { /* * If we're in the process of allocation of dynamic node ID, accept only relevant transfers. @@ -1103,16 +1005,22 @@ static bool shouldAcceptTransfer(const CanardInstance* ins, return false; } -static void cleanup_stale_transactions(uint64_t ×tamp_usec) +static bool shouldAcceptTransfer_trampoline(const CanardInstance* canard_instance, + uint64_t* out_data_type_signature, + uint16_t data_type_id, + CanardTransferType transfer_type, + uint8_t source_node_id) { - canardCleanupStaleTransfers(&dronecan.canard, timestamp_usec); + AP_Periph_FW *fw = (AP_Periph_FW *)canard_instance->user_reference; + return fw->shouldAcceptTransfer(canard_instance, out_data_type_signature, data_type_id, transfer_type, source_node_id); } -#define MAKE_TRANSFER_DESCRIPTOR(data_type_id, transfer_type, src_node_id, dst_node_id) \ - (((uint32_t)(data_type_id)) | (((uint32_t)(transfer_type)) << 16U) | \ - (((uint32_t)(src_node_id)) << 18U) | (((uint32_t)(dst_node_id)) << 25U)) +void AP_Periph_FW::cleanup_stale_transactions(uint64_t ×tamp_usec) +{ + canardCleanupStaleTransfers(&dronecan.canard, timestamp_usec); +} -static uint8_t* get_tid_ptr(uint32_t transfer_desc) +uint8_t *AP_Periph_FW::get_tid_ptr(uint32_t transfer_desc) { // check head if (!dronecan.tid_map_head) { @@ -1172,7 +1080,7 @@ bool AP_Periph_FW::canard_broadcast(uint64_t data_type_signature, , IFACE_ALL // send over all ifaces #endif #if HAL_CANFD_SUPPORTED - , periph.canfdout() + , canfdout() #endif ); @@ -1191,9 +1099,9 @@ bool AP_Periph_FW::canard_broadcast(uint64_t data_type_signature, return res > 0; } -static void processTx(void) +void AP_Periph_FW::processTx(void) { - for (const CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&dronecan.canard)) != NULL;) { + for (CanardCANFrame* txf = NULL; (txf = canardPeekTxQueue(&dronecan.canard)) != NULL;) { AP_HAL::CANFrame txmsg {}; txmsg.dlc = AP_HAL::CANFrame::dataLengthToDlc(txf->data_len); memcpy(txmsg.data, txf->data, txf->data_len); @@ -1203,24 +1111,39 @@ static void processTx(void) #endif // push message with 1s timeout bool sent = true; - const uint64_t deadline = AP_HAL::native_micros64() + 1000000; + const uint64_t now_us = AP_HAL::micros64(); + const uint64_t deadline = now_us + 1000000U; // try sending to all interfaces - for (auto &ins : instances) { - if (ins.iface == NULL) { + for (auto &_ins : instances) { + if (_ins.iface == NULL) { continue; } #if CANARD_MULTI_IFACE - if (!(txf->iface_mask & (1U<iface_mask & (1U<<_ins.index))) { continue; } #endif #if HAL_NUM_CAN_IFACES >= 2 - if (periph.can_protocol_cached[ins.index] != AP_CAN::Protocol::DroneCAN) { + if (can_protocol_cached[_ins.index] != AP_CAN::Protocol::DroneCAN) { continue; } #endif - if (ins.iface->send(txmsg, deadline, 0) <= 0) { - sent = false; + if (_ins.iface->send(txmsg, deadline, 0) <= 0) { + /* + We were not able to queue the frame for + sending. Only mark the send as failing if the + interface is active. We consider an interface as + active if it has had a successful transmit in the + last 2 seconds + */ + const auto *stats = _ins.iface->get_statistics(); + if (stats == nullptr || now_us - stats->last_transmit_us < 2000000UL) { + sent = false; + } + } else { +#if CANARD_MULTI_IFACE + txf->iface_mask &= ~(1U<<_ins.index); +#endif } } if (sent) { @@ -1243,7 +1166,7 @@ static void processTx(void) } #if HAL_ENABLE_SENDING_STATS -static void update_rx_protocol_stats(int16_t res) +void AP_Periph_FW::update_rx_protocol_stats(int16_t res) { switch (res) { case CANARD_OK: @@ -1287,7 +1210,7 @@ static void update_rx_protocol_stats(int16_t res) } #endif -static void processRx(void) +void AP_Periph_FW::processRx(void) { AP_HAL::CANFrame rxmsg; for (auto &ins : instances) { @@ -1295,7 +1218,7 @@ static void processRx(void) continue; } #if HAL_NUM_CAN_IFACES >= 2 - if (periph.can_protocol_cached[ins.index] != AP_CAN::Protocol::DroneCAN) { + if (can_protocol_cached[ins.index] != AP_CAN::Protocol::DroneCAN) { continue; } #endif @@ -1314,6 +1237,17 @@ static void processRx(void) if (ins.iface->receive(rxmsg, timestamp, flags) <= 0) { break; } +#if HAL_PERIPH_CAN_MIRROR + for (auto &other_instance : instances) { + if (other_instance.mirror_queue == nullptr) { // we aren't mirroring here, or failed on memory + continue; + } + if (other_instance.index == ins.index) { // don't self add + continue; + } + other_instance.mirror_queue->push(rxmsg); + } +#endif // HAL_PERIPH_CAN_MIRROR rx_frame.data_len = AP_HAL::CANFrame::dlcToDataLength(rxmsg.dlc); memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len); #if HAL_CANFD_SUPPORTED @@ -1348,14 +1282,48 @@ static void processRx(void) } } -static uint16_t pool_peak_percent() +#if HAL_PERIPH_CAN_MIRROR +void AP_Periph_FW::processMirror(void) +{ + const uint64_t deadline = AP_HAL::micros64() + 1000000; + + for (auto &ins : instances) { + if (ins.iface == nullptr || ins.mirror_queue == nullptr) { // can't send on a null interface + continue; + } + + const uint32_t pending = ins.mirror_queue->available(); + for (uint32_t i = 0; i < pending; i++) { // limit how long we can loop + AP_HAL::CANFrame txmsg {}; + + if (!ins.mirror_queue->peek(txmsg)) { + break; + } + + if (ins.iface->send(txmsg, deadline, 0) <= 0) { + if (ins.mirror_fail_count < 8) { + ins.mirror_fail_count++; + } else { + ins.mirror_queue->pop(); + } + break; + } else { + ins.mirror_fail_count = 0; + ins.mirror_queue->pop(); + } + } + } +} +#endif // HAL_PERIPH_CAN_MIRROR + +uint16_t AP_Periph_FW::pool_peak_percent() { const CanardPoolAllocatorStatistics stats = canardGetPoolAllocatorStatistics(&dronecan.canard); const uint16_t peak_percent = (uint16_t)(100U * stats.peak_usage_blocks / stats.capacity_blocks); return peak_percent; } -static void node_status_send(void) +void AP_Periph_FW::node_status_send(void) { { uint8_t buffer[UAVCAN_PROTOCOL_NODESTATUS_MAX_SIZE]; @@ -1363,20 +1331,20 @@ static void node_status_send(void) node_status.vendor_specific_status_code = hal.util->available_memory(); - uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer, !periph.canfdout()); + uint32_t len = uavcan_protocol_NodeStatus_encode(&node_status, buffer, !canfdout()); - periph.canard_broadcast(UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, + canard_broadcast(UAVCAN_PROTOCOL_NODESTATUS_SIGNATURE, UAVCAN_PROTOCOL_NODESTATUS_ID, CANARD_TRANSFER_PRIORITY_LOW, buffer, len); } #if HAL_ENABLE_SENDING_STATS - if (periph.debug_option_is_set(AP_Periph_FW::DebugOptions::ENABLE_STATS)) { + if (debug_option_is_set(AP_Periph_FW::DebugOptions::ENABLE_STATS)) { { uint8_t buffer[DRONECAN_PROTOCOL_STATS_MAX_SIZE]; - uint32_t len = dronecan_protocol_Stats_encode(&protocol_stats, buffer, !periph.canfdout()); - periph.canard_broadcast(DRONECAN_PROTOCOL_STATS_SIGNATURE, + uint32_t len = dronecan_protocol_Stats_encode(&protocol_stats, buffer, !canfdout()); + canard_broadcast(DRONECAN_PROTOCOL_STATS_SIGNATURE, DRONECAN_PROTOCOL_STATS_ID, CANARD_TRANSFER_PRIORITY_LOWEST, buffer, @@ -1400,8 +1368,8 @@ static void node_status_send(void) can_stats.rx_overflow = bus_stats->rx_overflow; can_stats.rx_errors = bus_stats->rx_errors; can_stats.busoff_errors = bus_stats->num_busoff_err; - uint32_t len = dronecan_protocol_CanStats_encode(&can_stats, buffer, !periph.canfdout()); - periph.canard_broadcast(DRONECAN_PROTOCOL_CANSTATS_SIGNATURE, + uint32_t len = dronecan_protocol_CanStats_encode(&can_stats, buffer, !canfdout()); + canard_broadcast(DRONECAN_PROTOCOL_CANSTATS_SIGNATURE, DRONECAN_PROTOCOL_CANSTATS_ID, CANARD_TRANSFER_PRIORITY_LOWEST, buffer, @@ -1415,7 +1383,7 @@ static void node_status_send(void) /** * This function is called at 1 Hz rate from the main loop. */ -static void process1HzTasks(uint64_t timestamp_usec) +void AP_Periph_FW::process1HzTasks(uint64_t timestamp_usec) { /* * Purging transfers that are no longer transmitted. This will occasionally free up some memory. @@ -1442,9 +1410,9 @@ static void process1HzTasks(uint64_t timestamp_usec) node_status_send(); #if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT) - if (periph.g.flash_bootloader.get()) { - const uint8_t flash_bl = periph.g.flash_bootloader.get(); - periph.g.flash_bootloader.set_and_save_ifchanged(0); + if (g.flash_bootloader.get()) { + const uint8_t flash_bl = g.flash_bootloader.get(); + g.flash_bootloader.set_and_save_ifchanged(0); if (flash_bl == 42) { // magic developer value to test watchdog support with main loop lockup while (true) { @@ -1493,12 +1461,12 @@ static void process1HzTasks(uint64_t timestamp_usec) #if 0 // test code for watchdog reset - if (AP_HAL::native_millis() > 15000) { + if (AP_HAL::millis() > 15000) { while (true) ; } #endif #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - if (AP_HAL::native_millis() > 30000) { + if (AP_HAL::millis() > 30000) { // use RTC to mark that we have been running fine for // 30s. This is used along with watchdog resets to ensure the // user has a chance to load a fixed firmware @@ -1511,14 +1479,15 @@ static void process1HzTasks(uint64_t timestamp_usec) wait for dynamic allocation of node ID */ bool AP_Periph_FW::no_iface_finished_dna = true; -static bool can_do_dna() + +bool AP_Periph_FW::can_do_dna() { if (canardGetLocalNodeID(&dronecan.canard) != CANARD_BROADCAST_NODE_ID) { AP_Periph_FW::no_iface_finished_dna = false; return true; } - const uint32_t now = AP_HAL::native_millis(); + const uint32_t now = AP_HAL::millis(); static uint8_t node_id_allocation_transfer_id = 0; @@ -1583,14 +1552,14 @@ void AP_Periph_FW::can_start() { node_status.health = UAVCAN_PROTOCOL_NODESTATUS_HEALTH_OK; node_status.mode = UAVCAN_PROTOCOL_NODESTATUS_MODE_INITIALIZATION; - node_status.uptime_sec = AP_HAL::native_millis() / 1000U; + node_status.uptime_sec = AP_HAL::millis() / 1000U; if (g.can_node >= 0 && g.can_node < 128) { PreferredNodeID = g.can_node; } #if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT) - periph.g.flash_bootloader.set_and_save_ifchanged(0); + g.flash_bootloader.set_and_save_ifchanged(0); #endif #if AP_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz && HAL_NUM_CAN_IFACES >= 2 @@ -1614,6 +1583,11 @@ void AP_Periph_FW::can_start() #endif instances[i].iface = can_iface_periph[i]; instances[i].index = i; +#if HAL_PERIPH_CAN_MIRROR + if ((g.can_mirror_ports & (1U << i)) != 0) { + instances[i].mirror_queue = new ObjectBuffer (HAL_PERIPH_CAN_MIRROR_QUEUE_SIZE); + } +#endif //HAL_PERIPH_CAN_MIRROR #if HAL_NUM_CAN_IFACES >= 2 can_protocol_cached[i] = g.can_protocol[i]; CANSensor::set_periph(i, can_protocol_cached[i], can_iface_periph[i]); @@ -1634,100 +1608,20 @@ void AP_Periph_FW::can_start() instances[slcan_selected_index].iface = (AP_HAL::CANIface*)&slcan_interface; // ensure there's a serial port mapped to SLCAN - if (!periph.serial_manager.have_serial(AP_SerialManager::SerialProtocol_SLCAN, 0)) { - periph.serial_manager.set_protocol_and_baud(SERIALMANAGER_NUM_PORTS-1, AP_SerialManager::SerialProtocol_SLCAN, 1500000); + if (!serial_manager.have_serial(AP_SerialManager::SerialProtocol_SLCAN, 0)) { + serial_manager.set_protocol_and_baud(SERIALMANAGER_NUM_PORTS-1, AP_SerialManager::SerialProtocol_SLCAN, 1500000); } } #endif canardInit(&dronecan.canard, (uint8_t *)dronecan.canard_memory_pool, sizeof(dronecan.canard_memory_pool), - onTransferReceived, shouldAcceptTransfer, NULL); + onTransferReceived_trampoline, shouldAcceptTransfer_trampoline, this); if (PreferredNodeID != CANARD_BROADCAST_NODE_ID) { canardSetLocalNodeID(&dronecan.canard, PreferredNodeID); } } -#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT -void AP_Periph_FW::pwm_hardpoint_init() -{ - hal.gpio->attach_interrupt( - PWM_HARDPOINT_PIN, - FUNCTOR_BIND_MEMBER(&AP_Periph_FW::pwm_irq_handler, void, uint8_t, bool, uint32_t), AP_HAL::GPIO::INTERRUPT_BOTH); - -} - -/* - called on PWM pin transition - */ -void AP_Periph_FW::pwm_irq_handler(uint8_t pin, bool pin_state, uint32_t timestamp) -{ - if (pin_state == 0 && pwm_hardpoint.last_state == 1 && pwm_hardpoint.last_ts_us != 0) { - uint32_t width = timestamp - pwm_hardpoint.last_ts_us; - if (width > 500 && width < 2500) { - pwm_hardpoint.pwm_value = width; - if (width > pwm_hardpoint.highest_pwm) { - pwm_hardpoint.highest_pwm = width; - } - } - } - pwm_hardpoint.last_state = pin_state; - pwm_hardpoint.last_ts_us = timestamp; -} - -void AP_Periph_FW::pwm_hardpoint_update() -{ - uint32_t now = AP_HAL::native_millis(); - // send at 10Hz - void *save = hal.scheduler->disable_interrupts_save(); - uint16_t value = pwm_hardpoint.highest_pwm; - pwm_hardpoint.highest_pwm = 0; - hal.scheduler->restore_interrupts(save); - float rate = g.hardpoint_rate; - rate = constrain_float(rate, 10, 100); - if (value > 0 && now - pwm_hardpoint.last_send_ms >= 1000U/rate) { - pwm_hardpoint.last_send_ms = now; - uavcan_equipment_hardpoint_Command cmd {}; - cmd.hardpoint_id = g.hardpoint_id; - cmd.command = value; - - uint8_t buffer[UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_hardpoint_Command_encode(&cmd, buffer, !periph.canfdout()); - canard_broadcast(UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_SIGNATURE, - UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); - } -} -#endif // HAL_PERIPH_ENABLE_PWM_HARDPOINT - -#ifdef HAL_PERIPH_ENABLE_HWESC -void AP_Periph_FW::hwesc_telem_update() -{ - if (!hwesc_telem.update()) { - return; - } - const HWESC_Telem::HWESC &t = hwesc_telem.get_telem(); - - uavcan_equipment_esc_Status pkt {}; - pkt.esc_index = g.esc_number[0]; // only supports a single ESC - pkt.voltage = t.voltage; - pkt.current = t.current; - pkt.temperature = C_TO_KELVIN(MAX(t.mos_temperature, t.cap_temperature)); - pkt.rpm = t.rpm; - pkt.power_rating_pct = t.phase_current; - pkt.error_count = t.error_count; - - uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !periph.canfdout()); - canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE, - UAVCAN_EQUIPMENT_ESC_STATUS_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); -} -#endif // HAL_PERIPH_ENABLE_HWESC #ifdef HAL_PERIPH_ENABLE_RC_OUT #if HAL_WITH_ESC_TELEM @@ -1773,7 +1667,7 @@ void AP_Periph_FW::esc_telem_update() pkt.error_count = 0; uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !periph.canfdout()); + uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE, UAVCAN_EQUIPMENT_ESC_STATUS_ID, CANARD_TRANSFER_PRIORITY_LOW, @@ -1806,7 +1700,7 @@ void AP_Periph_FW::apd_esc_telem_update() pkt.error_count = t.error_count; uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !periph.canfdout()); + uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE, UAVCAN_EQUIPMENT_ESC_STATUS_ID, CANARD_TRANSFER_PRIORITY_LOW, @@ -1821,7 +1715,7 @@ void AP_Periph_FW::apd_esc_telem_update() void AP_Periph_FW::can_update() { - const uint32_t now = AP_HAL::native_millis(); + const uint32_t now = AP_HAL::millis(); const uint32_t led_pattern = 0xAAAA; const uint32_t led_change_period = 50; static uint8_t led_idx = 0; @@ -1849,23 +1743,37 @@ void AP_Periph_FW::can_update() static uint32_t last_1Hz_ms; if (now - last_1Hz_ms >= 1000) { last_1Hz_ms = now; - process1HzTasks(AP_HAL::native_micros64()); + process1HzTasks(AP_HAL::micros64()); } #if CONFIG_HAL_BOARD == HAL_BOARD_SITL if (!hal.run_in_maintenance_mode()) #endif { +#ifdef HAL_PERIPH_ENABLE_MAG can_mag_update(); +#endif +#ifdef HAL_PERIPH_ENABLE_GPS can_gps_update(); +#endif #if AP_UART_MONITOR_ENABLED send_serial_monitor_data(); #endif +#ifdef HAL_PERIPH_ENABLE_BATTERY can_battery_update(); +#endif +#ifdef HAL_PERIPH_ENABLE_BARO can_baro_update(); +#endif +#ifdef HAL_PERIPH_ENABLE_AIRSPEED can_airspeed_update(); +#endif +#ifdef HAL_PERIPH_ENABLE_RANGEFINDER can_rangefinder_update(); +#endif +#ifdef HAL_PERIPH_ENABLE_PROXIMITY can_proximity_update(); +#endif #if defined(HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY) || defined (HAL_PERIPH_ENABLE_NOTIFY) can_buzzer_update(); #endif @@ -1900,865 +1808,17 @@ void AP_Periph_FW::can_update() #if HAL_CANFD_SUPPORTED // allow for user enabling/disabling CANFD at runtime - dronecan.canard.tao_disabled = periph.g.can_fdmode == 1; + dronecan.canard.tao_disabled = g.can_fdmode == 1; #endif processTx(); processRx(); +#if HAL_PERIPH_CAN_MIRROR + processMirror(); +#endif // HAL_PERIPH_CAN_MIRROR } } -/* - update CAN magnetometer - */ -void AP_Periph_FW::can_mag_update(void) -{ -#ifdef HAL_PERIPH_ENABLE_MAG - if (!compass.available()) { - return; - } - -#if AP_PERIPH_MAG_MAX_RATE > 0 - // don't flood the bus with very high rate magnetometers - const uint32_t now_ms = AP_HAL::millis(); - if (now_ms - last_mag_update_ms < (1000U / AP_PERIPH_MAG_MAX_RATE)) { - return; - } -#endif - - compass.read(); -#if AP_PERIPH_PROBE_CONTINUOUS - if (compass.get_count() == 0) { - static uint32_t last_probe_ms; - uint32_t now = AP_HAL::native_millis(); - if (now - last_probe_ms >= 1000) { - last_probe_ms = now; - compass.init(); - } - } -#endif - - if (last_mag_update_ms == compass.last_update_ms()) { - return; - } - if (!compass.healthy()) { - return; - } - - last_mag_update_ms = compass.last_update_ms(); - const Vector3f &field = compass.get_field(); - uavcan_equipment_ahrs_MagneticFieldStrength pkt {}; - - // the canard dsdl compiler doesn't understand float16 - for (uint8_t i=0; i<3; i++) { - pkt.magnetic_field_ga[i] = field[i] * 0.001; - } - - 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, - UAVCAN_EQUIPMENT_AHRS_MAGNETICFIELDSTRENGTH_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); -#endif // HAL_PERIPH_ENABLE_MAG -} - -/* - update CAN battery monitor - */ -void AP_Periph_FW::can_battery_update(void) -{ -#ifdef HAL_PERIPH_ENABLE_BATTERY - const uint32_t now_ms = AP_HAL::native_millis(); - if (now_ms - battery.last_can_send_ms < 100) { - return; - } - battery.last_can_send_ms = now_ms; - - const uint8_t battery_instances = battery.lib.num_instances(); - for (uint8_t i=0; i= 0) ? serial_number : i+1; - - pkt.voltage = battery.lib.voltage(i); - - float current; - if (battery.lib.current_amps(current, i)) { - pkt.current = current; - } - float temperature; - if (battery.lib.get_temperature(temperature, i)) { - // Battery lib reports temperature in Celsius. - // Convert Celsius to Kelvin for transmission on CAN. - pkt.temperature = C_TO_KELVIN(temperature); - } - - pkt.state_of_health_pct = UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN; - uint8_t percentage = 0; - if (battery.lib.capacity_remaining_pct(percentage, i)) { - pkt.state_of_charge_pct = percentage; - } - pkt.model_instance_id = i+1; - -#if !defined(HAL_PERIPH_BATTERY_SKIP_NAME) - // example model_name: "org.ardupilot.ap_periph SN 123" - hal.util->snprintf((char*)pkt.model_name.data, sizeof(pkt.model_name.data), "%s %ld", AP_PERIPH_BATTERY_MODEL_NAME, (long int)serial_number); - 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] {}; - const uint16_t total_size = uavcan_equipment_power_BatteryInfo_encode(&pkt, buffer, !periph.canfdout()); - - canard_broadcast(UAVCAN_EQUIPMENT_POWER_BATTERYINFO_SIGNATURE, - UAVCAN_EQUIPMENT_POWER_BATTERYINFO_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); - } -#endif -} - -#ifdef HAL_PERIPH_ENABLE_GPS -/* - convert large values to NaN for float16 - */ -static void check_float16_range(float *v, uint8_t len) -{ - for (uint8_t i=0; i= f16max) { - v[i] = nanf(""); - } - } -} -#endif - -/* - update CAN GPS - */ -void AP_Periph_FW::can_gps_update(void) -{ -#ifdef HAL_PERIPH_ENABLE_GPS - if (gps.get_type(0) == AP_GPS::GPS_Type::GPS_TYPE_NONE) { - return; - } - gps.update(); - send_moving_baseline_msg(); - send_relposheading_msg(); - if (last_gps_update_ms == gps.last_message_time_ms()) { - return; - } - last_gps_update_ms = gps.last_message_time_ms(); - - { - /* - send Fix2 packet - */ - uavcan_equipment_gnss_Fix2 pkt {}; - const Location &loc = gps.location(); - const Vector3f &vel = gps.velocity(); - if (gps.status() < AP_GPS::GPS_OK_FIX_2D && !saw_gps_lock_once) { - pkt.timestamp.usec = AP_HAL::micros64(); - pkt.gnss_timestamp.usec = 0; - } else { - saw_gps_lock_once = true; - pkt.timestamp.usec = gps.time_epoch_usec(); - pkt.gnss_timestamp.usec = gps.last_message_epoch_usec(); - } - if (pkt.gnss_timestamp.usec == 0) { - pkt.gnss_time_standard = UAVCAN_EQUIPMENT_GNSS_FIX_GNSS_TIME_STANDARD_NONE; - } else { - pkt.gnss_time_standard = UAVCAN_EQUIPMENT_GNSS_FIX_GNSS_TIME_STANDARD_UTC; - } - pkt.longitude_deg_1e8 = uint64_t(loc.lng) * 10ULL; - pkt.latitude_deg_1e8 = uint64_t(loc.lat) * 10ULL; - pkt.height_ellipsoid_mm = loc.alt * 10; - pkt.height_msl_mm = loc.alt * 10; - float undulation; - if (gps.get_undulation(undulation)) { - pkt.height_ellipsoid_mm -= undulation*1000; - } - for (uint8_t i=0; i<3; i++) { - pkt.ned_velocity[i] = vel[i]; - } - pkt.sats_used = gps.num_sats(); - switch (gps.status()) { - case AP_GPS::GPS_Status::NO_GPS: - case AP_GPS::GPS_Status::NO_FIX: - pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_NO_FIX; - pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE; - pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER; - break; - case AP_GPS::GPS_Status::GPS_OK_FIX_2D: - pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_2D_FIX; - pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE; - pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER; - break; - case AP_GPS::GPS_Status::GPS_OK_FIX_3D: - pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; - pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE; - pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER; - break; - case AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS: - pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; - pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_DGPS; - pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_SBAS; - break; - case AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT: - pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; - pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK; - pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FLOAT; - break; - case AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED: - pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; - pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK; - pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FIXED; - break; - } - - pkt.covariance.len = 6; - - float hacc; - if (gps.horizontal_accuracy(hacc)) { - pkt.covariance.data[0] = pkt.covariance.data[1] = sq(hacc); - } - - float vacc; - if (gps.vertical_accuracy(vacc)) { - pkt.covariance.data[2] = sq(vacc); - } - - float sacc; - if (gps.speed_accuracy(sacc)) { - float vc3 = sq(sacc); - pkt.covariance.data[3] = pkt.covariance.data[4] = pkt.covariance.data[5] = vc3; - } - - check_float16_range(pkt.covariance.data, pkt.covariance.len); - - uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_FIX2_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_gnss_Fix2_encode(&pkt, buffer, !periph.canfdout()); - - canard_broadcast(UAVCAN_EQUIPMENT_GNSS_FIX2_SIGNATURE, - UAVCAN_EQUIPMENT_GNSS_FIX2_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); - } - - /* - send aux packet - */ - { - uavcan_equipment_gnss_Auxiliary aux {}; - aux.hdop = gps.get_hdop() * 0.01; - aux.vdop = gps.get_vdop() * 0.01; - - uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_AUXILIARY_MAX_SIZE] {}; - uint16_t total_size = uavcan_equipment_gnss_Auxiliary_encode(&aux, buffer, !periph.canfdout()); - canard_broadcast(UAVCAN_EQUIPMENT_GNSS_AUXILIARY_SIGNATURE, - UAVCAN_EQUIPMENT_GNSS_AUXILIARY_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); - } - - // send the gnss status packet - { - ardupilot_gnss_Status status {}; - - status.healthy = gps.is_healthy(); - if (gps.logging_present() && gps.logging_enabled() && !gps.logging_failed()) { - status.status |= ARDUPILOT_GNSS_STATUS_STATUS_LOGGING; - } - uint8_t idx; // unused - if (status.healthy && !gps.first_unconfigured_gps(idx)) { - status.status |= ARDUPILOT_GNSS_STATUS_STATUS_ARMABLE; - } - - uint32_t error_codes; - if (gps.get_error_codes(error_codes)) { - status.error_codes = error_codes; - } - - uint8_t buffer[ARDUPILOT_GNSS_STATUS_MAX_SIZE] {}; - const uint16_t total_size = ardupilot_gnss_Status_encode(&status, buffer, !periph.canfdout()); - canard_broadcast(ARDUPILOT_GNSS_STATUS_SIGNATURE, - ARDUPILOT_GNSS_STATUS_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); - - } - - // send Heading message if we are not sending RelPosHeading messages and have yaw - if (gps.have_gps_yaw() && last_relposheading_ms == 0) { - float yaw_deg, yaw_acc_deg; - uint32_t yaw_time_ms; - if (gps.gps_yaw_deg(yaw_deg, yaw_acc_deg, yaw_time_ms) && yaw_time_ms != last_gps_yaw_ms) { - last_gps_yaw_ms = yaw_time_ms; - - ardupilot_gnss_Heading heading {}; - heading.heading_valid = true; - 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] {}; - const uint16_t total_size = ardupilot_gnss_Heading_encode(&heading, buffer, !periph.canfdout()); - canard_broadcast(ARDUPILOT_GNSS_HEADING_SIGNATURE, - ARDUPILOT_GNSS_HEADING_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); - } - } -#endif // HAL_PERIPH_ENABLE_GPS -} - - -void AP_Periph_FW::send_moving_baseline_msg() -{ -#if defined(HAL_PERIPH_ENABLE_GPS) && GPS_MOVING_BASELINE - const uint8_t *data = nullptr; - uint16_t len = 0; - if (!gps.get_RTCMV3(data, len)) { - return; - } - if (len == 0 || data == nullptr) { - return; - } - // send the packet from Moving Base to be used RelPosHeading calc by GPS module - ardupilot_gnss_MovingBaselineData mbldata {}; - // get the data from the moving base - static_assert(sizeof(ardupilot_gnss_MovingBaselineData::data.data) == RTCM3_MAX_PACKET_LEN, "Size of Moving Base data is wrong"); - mbldata.data.len = len; - memcpy(mbldata.data.data, data, len); - uint8_t buffer[ARDUPILOT_GNSS_MOVINGBASELINEDATA_MAX_SIZE] {}; - const uint16_t total_size = ardupilot_gnss_MovingBaselineData_encode(&mbldata, buffer, !periph.canfdout()); - -#if HAL_NUM_CAN_IFACES >= 2 - if (gps_mb_can_port != -1 && (gps_mb_can_port < HAL_NUM_CAN_IFACES)) { - uint8_t *tid_ptr = get_tid_ptr(MAKE_TRANSFER_DESCRIPTOR(ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE, ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID, 0, CANARD_BROADCAST_NODE_ID)); - canardBroadcast(&dronecan.canard, - ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE, - ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID, - tid_ptr, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size -#if CANARD_MULTI_IFACE - ,(1U<= 1000) { - last_probe_ms = now; - airspeed.allocate(); - } - } -#endif - uint32_t now = AP_HAL::native_millis(); - if (now - last_airspeed_update_ms < 50) { - // max 20Hz data - return; - } - last_airspeed_update_ms = now; - airspeed.update(); - if (!airspeed.healthy()) { - // don't send any data - return; - } - const float press = airspeed.get_corrected_pressure(); - float temp; - if (!airspeed.get_temperature(temp)) { - temp = nanf(""); - } else { - temp = C_TO_KELVIN(temp); - } - - uavcan_equipment_air_data_RawAirData pkt {}; - pkt.differential_pressure = press; - pkt.static_air_temperature = temp; - - // unfilled elements are NaN - pkt.static_pressure = nanf(""); - pkt.static_pressure_sensor_temperature = nanf(""); - pkt.differential_pressure_sensor_temperature = nanf(""); - pkt.pitot_temperature = nanf(""); - - 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, - UAVCAN_EQUIPMENT_AIR_DATA_RAWAIRDATA_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); -#endif // HAL_PERIPH_ENABLE_AIRSPEED -} - - -/* - update CAN rangefinder - */ -void AP_Periph_FW::can_rangefinder_update(void) -{ -#ifdef HAL_PERIPH_ENABLE_RANGEFINDER - if (rangefinder.get_type(0) == RangeFinder::Type::NONE) { - return; - } -#if AP_PERIPH_PROBE_CONTINUOUS - if (rangefinder.num_sensors() == 0) { - uint32_t now = AP_HAL::native_millis(); - static uint32_t last_probe_ms; - if (now - last_probe_ms >= 1000) { - last_probe_ms = now; - rangefinder.init(ROTATION_NONE); - } - } -#endif - uint32_t now = AP_HAL::native_millis(); - static uint32_t last_update_ms; - if (g.rangefinder_max_rate > 0 && - now - last_update_ms < 1000/g.rangefinder_max_rate) { - // limit to max rate - return; - } - last_update_ms = now; - 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; - - 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 -} - - -void AP_Periph_FW::can_proximity_update() -{ -#if HAL_PROXIMITY_ENABLED - if (proximity.get_type(0) == AP_Proximity::Type::None) { - return; - } - - uint32_t now = AP_HAL::native_millis(); - static uint32_t last_update_ms; - if (g.proximity_max_rate > 0 && - now - last_update_ms < 1000/g.proximity_max_rate) { - // limit to max rate - return; - } - last_update_ms = now; - proximity.update(); - AP_Proximity::Status status = proximity.get_status(); - if (status <= AP_Proximity::Status::NoData) { - // don't send any data - return; - } - - ardupilot_equipment_proximity_sensor_Proximity pkt {}; - - const uint8_t obstacle_count = proximity.get_obstacle_count(); - - // if no objects return - if (obstacle_count == 0) { - return; - } - - // calculate maximum roll, pitch values from objects - for (uint8_t i=0; i + +#ifndef AP_PERIPH_MAG_MAX_RATE +#define AP_PERIPH_MAG_MAX_RATE 25U +#endif + +#ifndef AP_PERIPH_PROBE_CONTINUOUS +#define AP_PERIPH_PROBE_CONTINUOUS 0 +#endif + +/* + update CAN magnetometer + */ +void AP_Periph_FW::can_mag_update(void) +{ + if (!compass.available()) { + return; + } + +#if AP_PERIPH_MAG_MAX_RATE > 0 + // don't flood the bus with very high rate magnetometers + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - last_mag_update_ms < (1000U / AP_PERIPH_MAG_MAX_RATE)) { + return; + } +#endif + + compass.read(); + +#if AP_PERIPH_PROBE_CONTINUOUS + if (compass.get_count() == 0) { + static uint32_t last_probe_ms; + uint32_t now = AP_HAL::millis(); + if (now - last_probe_ms >= 1000) { + last_probe_ms = now; + compass.init(); + } + } +#endif + + if (last_mag_update_ms == compass.last_update_ms()) { + return; + } + if (!compass.healthy()) { + return; + } + + last_mag_update_ms = compass.last_update_ms(); + const Vector3f &field = compass.get_field(); + uavcan_equipment_ahrs_MagneticFieldStrength pkt {}; + + // the canard dsdl compiler doesn't understand float16 + for (uint8_t i=0; i<3; i++) { + pkt.magnetic_field_ga[i] = field[i] * 0.001; + } + + 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, + UAVCAN_EQUIPMENT_AHRS_MAGNETICFIELDSTRENGTH_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); +} + +#endif // HAL_PERIPH_ENABLE_MAG diff --git a/Tools/AP_Periph/efi.cpp b/Tools/AP_Periph/efi.cpp new file mode 100644 index 00000000000000..5d84adbfd72cd2 --- /dev/null +++ b/Tools/AP_Periph/efi.cpp @@ -0,0 +1,193 @@ +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_EFI + +/* + EFI support + */ + +#include + +/* + update CAN EFI + */ +void AP_Periph_FW::can_efi_update(void) +{ + if (!efi.enabled()) { + return; + } + efi.update(); + const uint32_t update_ms = efi.get_last_update_ms(); + if (!efi.is_healthy() || efi_update_ms == update_ms) { + return; + } + efi_update_ms = update_ms; + EFI_State state; + efi.get_state(state); + + { + /* + send status packet + */ + uavcan_equipment_ice_reciprocating_Status pkt {}; + + // state maps 1:1 from Engine_State + pkt.state = uint8_t(state.engine_state); + + switch (state.crankshaft_sensor_status) { + case Crankshaft_Sensor_Status::NOT_SUPPORTED: + break; + case Crankshaft_Sensor_Status::OK: + pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED; + break; + case Crankshaft_Sensor_Status::ERROR: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_CRANKSHAFT_SENSOR_ERROR; + break; + } + + switch (state.temperature_status) { + case Temperature_Status::NOT_SUPPORTED: + break; + case Temperature_Status::OK: + pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED; + break; + case Temperature_Status::BELOW_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_BELOW_NOMINAL; + break; + case Temperature_Status::ABOVE_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_ABOVE_NOMINAL; + break; + case Temperature_Status::OVERHEATING: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_OVERHEATING; + break; + case Temperature_Status::EGT_ABOVE_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_EGT_ABOVE_NOMINAL; + break; + } + + switch (state.fuel_pressure_status) { + case Fuel_Pressure_Status::NOT_SUPPORTED: + break; + case Fuel_Pressure_Status::OK: + pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_SUPPORTED; + break; + case Fuel_Pressure_Status::BELOW_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_BELOW_NOMINAL; + break; + case Fuel_Pressure_Status::ABOVE_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_ABOVE_NOMINAL; + break; + } + + switch (state.oil_pressure_status) { + case Oil_Pressure_Status::NOT_SUPPORTED: + break; + case Oil_Pressure_Status::OK: + pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_SUPPORTED; + break; + case Oil_Pressure_Status::BELOW_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_BELOW_NOMINAL; + break; + case Oil_Pressure_Status::ABOVE_NOMINAL: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_ABOVE_NOMINAL; + break; + } + + switch (state.detonation_status) { + case Detonation_Status::NOT_SUPPORTED: + break; + case Detonation_Status::NOT_OBSERVED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DETONATION_SUPPORTED; + break; + case Detonation_Status::OBSERVED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DETONATION_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DETONATION_OBSERVED; + break; + } + + switch (state.misfire_status) { + case Misfire_Status::NOT_SUPPORTED: + break; + case Misfire_Status::NOT_OBSERVED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_MISFIRE_SUPPORTED; + break; + case Misfire_Status::OBSERVED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_MISFIRE_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_MISFIRE_OBSERVED; + break; + } + + switch (state.debris_status) { + case Debris_Status::NOT_SUPPORTED: + break; + case Debris_Status::NOT_DETECTED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DEBRIS_SUPPORTED; + break; + case Debris_Status::DETECTED: + pkt.flags |= + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DEBRIS_SUPPORTED | + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DEBRIS_DETECTED; + break; + } + + pkt.engine_load_percent = state.engine_load_percent; + pkt.engine_speed_rpm = state.engine_speed_rpm; + pkt.spark_dwell_time_ms = state.spark_dwell_time_ms; + pkt.atmospheric_pressure_kpa = state.atmospheric_pressure_kpa; + pkt.intake_manifold_pressure_kpa = state.intake_manifold_pressure_kpa; + pkt.intake_manifold_temperature = state.intake_manifold_temperature; + pkt.coolant_temperature = state.coolant_temperature; + pkt.oil_pressure = state.oil_pressure; + pkt.oil_temperature = state.oil_temperature; + pkt.fuel_pressure = state.fuel_pressure; + pkt.fuel_consumption_rate_cm3pm = state.fuel_consumption_rate_cm3pm; + pkt.estimated_consumed_fuel_volume_cm3 = state.estimated_consumed_fuel_volume_cm3; + pkt.throttle_position_percent = state.throttle_position_percent; + pkt.ecu_index = state.ecu_index; + pkt.spark_plug_usage = uint8_t(state.spark_plug_usage); + + // assume single set of cylinder status + pkt.cylinder_status.len = 1; + auto &c = pkt.cylinder_status.data[0]; + const auto &state_c = state.cylinder_status; + c.ignition_timing_deg = state_c.ignition_timing_deg; + c.injection_time_ms = state_c.injection_time_ms; + c.cylinder_head_temperature = state_c.cylinder_head_temperature; + c.exhaust_gas_temperature = state_c.exhaust_gas_temperature; + c.lambda_coefficient = state_c.lambda_coefficient; + + uint8_t buffer[UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_MAX_SIZE] {}; + const uint16_t total_size = uavcan_equipment_ice_reciprocating_Status_encode(&pkt, buffer, !canfdout()); + + canard_broadcast(UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_SIGNATURE, + UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + } +} + +#endif // HAL_PERIPH_ENABLE_EFI diff --git a/Tools/AP_Periph/esc_apd_telem.cpp b/Tools/AP_Periph/esc_apd_telem.cpp index fccc2663312bbb..ed438d60f36c5d 100644 --- a/Tools/AP_Periph/esc_apd_telem.cpp +++ b/Tools/AP_Periph/esc_apd_telem.cpp @@ -48,7 +48,7 @@ bool ESC_APD_Telem::update() { // valid packet, copy the data we need and reset length decoded.voltage = le16toh(received.packet.voltage) * 1e-2f; decoded.temperature = convert_temperature(le16toh(received.packet.temperature)); - decoded.current = le16toh(received.packet.bus_current) * (1 / 12.5f); + decoded.current = ((int16_t)le16toh(received.packet.bus_current)) * (1 / 12.5f); decoded.rpm = le32toh(received.packet.erpm) / pole_count; decoded.power_rating_pct = le16toh(received.packet.motor_duty) * 1e-2f; ret = true; diff --git a/Tools/AP_Periph/gps.cpp b/Tools/AP_Periph/gps.cpp new file mode 100644 index 00000000000000..e8262e2efb4345 --- /dev/null +++ b/Tools/AP_Periph/gps.cpp @@ -0,0 +1,322 @@ +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_GPS + +/* + GPS support + */ + +#include +#include + +#define DEBUG_PRINTS 0 + +#if DEBUG_PRINTS + # define Debug(fmt, args ...) do {can_printf(fmt "\n", ## args);} while(0) +#else + # define Debug(fmt, args ...) +#endif + +/* + handle gnss::RTCMStream + */ +void AP_Periph_FW::handle_RTCMStream(CanardInstance* canard_instance, CanardRxTransfer* transfer) +{ + uavcan_equipment_gnss_RTCMStream req; + if (uavcan_equipment_gnss_RTCMStream_decode(transfer, &req)) { + return; + } + gps.handle_gps_rtcm_fragment(0, req.data.data, req.data.len); +} + +/* + handle gnss::MovingBaselineData +*/ +#if GPS_MOVING_BASELINE +void AP_Periph_FW::handle_MovingBaselineData(CanardInstance* canard_instance, CanardRxTransfer* transfer) +{ + ardupilot_gnss_MovingBaselineData msg; + if (ardupilot_gnss_MovingBaselineData_decode(transfer, &msg)) { + return; + } + gps.inject_MBL_data(msg.data.data, msg.data.len); + Debug("MovingBaselineData: len=%u\n", msg.data.len); +} +#endif // GPS_MOVING_BASELINE + +/* + convert large values to NaN for float16 + */ +static void check_float16_range(float *v, uint8_t len) +{ + for (uint8_t i=0; i= f16max) { + v[i] = nanf(""); + } + } +} + +/* + update CAN GPS + */ +void AP_Periph_FW::can_gps_update(void) +{ + if (gps.get_type(0) == AP_GPS::GPS_Type::GPS_TYPE_NONE) { + return; + } + gps.update(); + send_moving_baseline_msg(); + send_relposheading_msg(); + if (last_gps_update_ms == gps.last_message_time_ms()) { + return; + } + last_gps_update_ms = gps.last_message_time_ms(); + + { + /* + send Fix2 packet + */ + uavcan_equipment_gnss_Fix2 pkt {}; + const Location &loc = gps.location(); + const Vector3f &vel = gps.velocity(); + if (gps.status() < AP_GPS::GPS_OK_FIX_2D && !saw_gps_lock_once) { + pkt.timestamp.usec = AP_HAL::micros64(); + pkt.gnss_timestamp.usec = 0; + } else { + saw_gps_lock_once = true; + pkt.timestamp.usec = gps.time_epoch_usec(); + pkt.gnss_timestamp.usec = gps.last_message_epoch_usec(); + } + if (pkt.gnss_timestamp.usec == 0) { + pkt.gnss_time_standard = UAVCAN_EQUIPMENT_GNSS_FIX_GNSS_TIME_STANDARD_NONE; + } else { + pkt.gnss_time_standard = UAVCAN_EQUIPMENT_GNSS_FIX_GNSS_TIME_STANDARD_UTC; + } + pkt.longitude_deg_1e8 = uint64_t(loc.lng) * 10ULL; + pkt.latitude_deg_1e8 = uint64_t(loc.lat) * 10ULL; + pkt.height_ellipsoid_mm = loc.alt * 10; + pkt.height_msl_mm = loc.alt * 10; + float undulation; + if (gps.get_undulation(undulation)) { + pkt.height_ellipsoid_mm -= undulation*1000; + } + for (uint8_t i=0; i<3; i++) { + pkt.ned_velocity[i] = vel[i]; + } + pkt.sats_used = gps.num_sats(); + switch (gps.status()) { + case AP_GPS::GPS_Status::NO_GPS: + case AP_GPS::GPS_Status::NO_FIX: + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_NO_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER; + break; + case AP_GPS::GPS_Status::GPS_OK_FIX_2D: + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_2D_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER; + break; + case AP_GPS::GPS_Status::GPS_OK_FIX_3D: + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_SINGLE; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_OTHER; + break; + case AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS: + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_DGPS; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_DGPS_SBAS; + break; + case AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT: + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FLOAT; + break; + case AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED: + pkt.status = UAVCAN_EQUIPMENT_GNSS_FIX2_STATUS_3D_FIX; + pkt.mode = UAVCAN_EQUIPMENT_GNSS_FIX2_MODE_RTK; + pkt.sub_mode = UAVCAN_EQUIPMENT_GNSS_FIX2_SUB_MODE_RTK_FIXED; + break; + } + + pkt.covariance.len = 6; + + float hacc; + if (gps.horizontal_accuracy(hacc)) { + pkt.covariance.data[0] = pkt.covariance.data[1] = sq(hacc); + } + + float vacc; + if (gps.vertical_accuracy(vacc)) { + pkt.covariance.data[2] = sq(vacc); + } + + float sacc; + if (gps.speed_accuracy(sacc)) { + float vc3 = sq(sacc); + pkt.covariance.data[3] = pkt.covariance.data[4] = pkt.covariance.data[5] = vc3; + } + + check_float16_range(pkt.covariance.data, pkt.covariance.len); + + uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_FIX2_MAX_SIZE] {}; + uint16_t total_size = uavcan_equipment_gnss_Fix2_encode(&pkt, buffer, !canfdout()); + + canard_broadcast(UAVCAN_EQUIPMENT_GNSS_FIX2_SIGNATURE, + UAVCAN_EQUIPMENT_GNSS_FIX2_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + } + + /* + send aux packet + */ + { + uavcan_equipment_gnss_Auxiliary aux {}; + aux.hdop = gps.get_hdop() * 0.01; + aux.vdop = gps.get_vdop() * 0.01; + + uint8_t buffer[UAVCAN_EQUIPMENT_GNSS_AUXILIARY_MAX_SIZE] {}; + uint16_t total_size = uavcan_equipment_gnss_Auxiliary_encode(&aux, buffer, !canfdout()); + canard_broadcast(UAVCAN_EQUIPMENT_GNSS_AUXILIARY_SIGNATURE, + UAVCAN_EQUIPMENT_GNSS_AUXILIARY_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + } + + // send the gnss status packet + { + ardupilot_gnss_Status status {}; + + status.healthy = gps.is_healthy(); + if (gps.logging_present() && gps.logging_enabled() && !gps.logging_failed()) { + status.status |= ARDUPILOT_GNSS_STATUS_STATUS_LOGGING; + } + uint8_t idx; // unused + if (status.healthy && !gps.first_unconfigured_gps(idx)) { + status.status |= ARDUPILOT_GNSS_STATUS_STATUS_ARMABLE; + } + + uint32_t error_codes; + if (gps.get_error_codes(error_codes)) { + status.error_codes = error_codes; + } + + 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, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + + } + + // send Heading message if we are not sending RelPosHeading messages and have yaw + if (gps.have_gps_yaw() && last_relposheading_ms == 0) { + float yaw_deg, yaw_acc_deg; + uint32_t yaw_time_ms; + if (gps.gps_yaw_deg(yaw_deg, yaw_acc_deg, yaw_time_ms) && yaw_time_ms != last_gps_yaw_ms) { + last_gps_yaw_ms = yaw_time_ms; + + ardupilot_gnss_Heading heading {}; + heading.heading_valid = true; + 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] {}; + const uint16_t total_size = ardupilot_gnss_Heading_encode(&heading, buffer, !canfdout()); + canard_broadcast(ARDUPILOT_GNSS_HEADING_SIGNATURE, + ARDUPILOT_GNSS_HEADING_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + } + } +} + + +void AP_Periph_FW::send_moving_baseline_msg() +{ +#if GPS_MOVING_BASELINE + const uint8_t *data = nullptr; + uint16_t len = 0; + if (!gps.get_RTCMV3(data, len)) { + return; + } + if (len == 0 || data == nullptr) { + return; + } + // send the packet from Moving Base to be used RelPosHeading calc by GPS module + ardupilot_gnss_MovingBaselineData mbldata {}; + // get the data from the moving base + static_assert(sizeof(ardupilot_gnss_MovingBaselineData::data.data) == RTCM3_MAX_PACKET_LEN, "Size of Moving Base data is wrong"); + mbldata.data.len = len; + memcpy(mbldata.data.data, data, len); + uint8_t buffer[ARDUPILOT_GNSS_MOVINGBASELINEDATA_MAX_SIZE] {}; + const uint16_t total_size = ardupilot_gnss_MovingBaselineData_encode(&mbldata, buffer, !canfdout()); + +#if HAL_NUM_CAN_IFACES >= 2 + if (gps_mb_can_port != -1 && (gps_mb_can_port < HAL_NUM_CAN_IFACES)) { + uint8_t *tid_ptr = get_tid_ptr(MAKE_TRANSFER_DESCRIPTOR(ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE, ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID, 0, CANARD_BROADCAST_NODE_ID)); + canardBroadcast(&dronecan.canard, + ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE, + ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID, + tid_ptr, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size +#if CANARD_MULTI_IFACE + ,(1U< + +extern const AP_HAL::HAL &hal; + +/* + hardpoint support + */ + +#include + +void AP_Periph_FW::pwm_hardpoint_init() +{ + hal.gpio->attach_interrupt( + PWM_HARDPOINT_PIN, + FUNCTOR_BIND_MEMBER(&AP_Periph_FW::pwm_irq_handler, void, uint8_t, bool, uint32_t), AP_HAL::GPIO::INTERRUPT_BOTH); +} + +/* + called on PWM pin transition + */ +void AP_Periph_FW::pwm_irq_handler(uint8_t pin, bool pin_state, uint32_t timestamp) +{ + if (pin_state == 0 && pwm_hardpoint.last_state == 1 && pwm_hardpoint.last_ts_us != 0) { + uint32_t width = timestamp - pwm_hardpoint.last_ts_us; + if (width > 500 && width < 2500) { + pwm_hardpoint.pwm_value = width; + if (width > pwm_hardpoint.highest_pwm) { + pwm_hardpoint.highest_pwm = width; + } + } + } + pwm_hardpoint.last_state = pin_state; + pwm_hardpoint.last_ts_us = timestamp; +} + +void AP_Periph_FW::pwm_hardpoint_update() +{ + uint32_t now = AP_HAL::millis(); + // send at 10Hz + void *save = hal.scheduler->disable_interrupts_save(); + uint16_t value = pwm_hardpoint.highest_pwm; + pwm_hardpoint.highest_pwm = 0; + hal.scheduler->restore_interrupts(save); + float rate = g.hardpoint_rate; + rate = constrain_float(rate, 10, 100); + if (value > 0 && now - pwm_hardpoint.last_send_ms >= 1000U/rate) { + pwm_hardpoint.last_send_ms = now; + uavcan_equipment_hardpoint_Command cmd {}; + cmd.hardpoint_id = g.hardpoint_id; + cmd.command = value; + + 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, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); + } +} + +#endif // HAL_PERIPH_ENABLE_PWM_HARDPOINT diff --git a/Tools/AP_Periph/hwing_esc.cpp b/Tools/AP_Periph/hwing_esc.cpp index a79862f3cf6d0e..871c2e0517c45f 100644 --- a/Tools/AP_Periph/hwing_esc.cpp +++ b/Tools/AP_Periph/hwing_esc.cpp @@ -6,8 +6,11 @@ This protocol only allows for one ESC per UART RX line, so using a CAN node per ESC works well. */ + +#include "AP_Periph.h" #include "hwing_esc.h" #include +#include #ifdef HAL_PERIPH_ENABLE_HWESC @@ -39,7 +42,7 @@ bool HWESC_Telem::update() } // we expect at least 50ms idle between frames - uint32_t now = AP_HAL::native_millis(); + uint32_t now = AP_HAL::millis(); bool frame_gap = (now - last_read_ms) > 10; last_read_ms = now; @@ -143,5 +146,30 @@ bool HWESC_Telem::parse_packet(void) return true; } +void AP_Periph_FW::hwesc_telem_update() +{ + if (!hwesc_telem.update()) { + return; + } + const HWESC_Telem::HWESC &t = hwesc_telem.get_telem(); + + uavcan_equipment_esc_Status pkt {}; + pkt.esc_index = g.esc_number[0]; // only supports a single ESC + pkt.voltage = t.voltage; + pkt.current = t.current; + pkt.temperature = C_TO_KELVIN(MAX(t.mos_temperature, t.cap_temperature)); + pkt.rpm = t.rpm; + pkt.power_rating_pct = t.phase_current; + pkt.error_count = t.error_count; + + uint8_t buffer[UAVCAN_EQUIPMENT_ESC_STATUS_MAX_SIZE] {}; + uint16_t total_size = uavcan_equipment_esc_Status_encode(&pkt, buffer, !canfdout()); + canard_broadcast(UAVCAN_EQUIPMENT_ESC_STATUS_SIGNATURE, + UAVCAN_EQUIPMENT_ESC_STATUS_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); +} + #endif // HAL_PERIPH_ENABLE_HWESC diff --git a/Tools/AP_Periph/proximity.cpp b/Tools/AP_Periph/proximity.cpp new file mode 100644 index 00000000000000..2c88d3fc0f98af --- /dev/null +++ b/Tools/AP_Periph/proximity.cpp @@ -0,0 +1,75 @@ +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_PROXIMITY + +/* + proximity support + */ + +#include + +void AP_Periph_FW::can_proximity_update() +{ + if (proximity.get_type(0) == AP_Proximity::Type::None) { + return; + } + + uint32_t now = AP_HAL::millis(); + static uint32_t last_update_ms; + if (g.proximity_max_rate > 0 && + now - last_update_ms < 1000/g.proximity_max_rate) { + // limit to max rate + return; + } + last_update_ms = now; + proximity.update(); + AP_Proximity::Status status = proximity.get_status(); + if (status <= AP_Proximity::Status::NoData) { + // don't send any data + return; + } + + ardupilot_equipment_proximity_sensor_Proximity pkt {}; + + const uint8_t obstacle_count = proximity.get_obstacle_count(); + + // if no objects return + if (obstacle_count == 0) { + return; + } + + // calculate maximum roll, pitch values from objects + for (uint8_t i=0; i + +#ifndef AP_PERIPH_PROBE_CONTINUOUS +#define AP_PERIPH_PROBE_CONTINUOUS 0 +#endif + +/* + update CAN rangefinder + */ +void AP_Periph_FW::can_rangefinder_update(void) +{ + if (rangefinder.get_type(0) == RangeFinder::Type::NONE) { + return; + } +#if AP_PERIPH_PROBE_CONTINUOUS + if (rangefinder.num_sensors() == 0) { + uint32_t now = AP_HAL::millis(); + static uint32_t last_probe_ms; + if (now - last_probe_ms >= 1000) { + last_probe_ms = now; + rangefinder.init(ROTATION_NONE); + } + } +#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)) { + // limit to max rate + return; + } + last_update_ms = now; + 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; + + 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 new file mode 100644 index 00000000000000..83f691bda2816b --- /dev/null +++ b/Tools/AP_Periph/rc_in.cpp @@ -0,0 +1,180 @@ +/* + 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 + +#ifdef HAL_PERIPH_ENABLE_RCIN + +#ifndef AP_PERIPH_RC1_PORT_DEFAULT +#define AP_PERIPH_RC1_PORT_DEFAULT -1 +#endif + +#ifndef AP_PERIPH_RC1_PORT_OPTIONS_DEFAULT +#define AP_PERIPH_RC1_PORT_OPTIONS_DEFAULT 0 +#endif + +#include +#include "AP_Periph.h" +#include + +extern const AP_HAL::HAL &hal; + +const AP_Param::GroupInfo Parameters_RCIN::var_info[] { + // RC_PROTOCOLS copied from RC_Channel/RC_Channels_Varinfo.h + // @Param: RC_PROTOCOLS + // @DisplayName: RC protocols enabled + // @Description: Bitmask of enabled RC protocols. Allows narrowing the protocol detection to only specific types of RC receivers which can avoid issues with incorrect detection. Set to 1 to enable all protocols. + // @User: Advanced + // @Bitmask: 0:All,1:PPM,2:IBUS,3:SBUS,4:SBUS_NI,5:DSM,6:SUMD,7:SRXL,8:SRXL2,9:CRSF,10:ST24,11:FPORT,12:FPORT2,13:FastSBUS + AP_GROUPINFO("_PROTOCOLS", 1, Parameters_RCIN, rcin_protocols, 1), + + // RC_PROTOCOLS copied from RC_Channel/RC_Channels_Varinfo.h + // @Param: RC_MSGRATE + // @DisplayName: DroneCAN RC Message rate + // @Description: Rate at which RC input is sent via DroneCAN + // @User: Advanced + // @Increment: 1 + // @Range: 0 255 + // @Units: Hz + AP_GROUPINFO("_MSGRATE", 2, Parameters_RCIN, rcin_rate_hz, 50), + + // @Param: RC1_PORT + // @DisplayName: RC input port + // @Description: This is the serial port number where SERIALx_PROTOCOL will be set to RC input. + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced + // @RebootRequired: True + AP_GROUPINFO("_PORT", 3, Parameters_RCIN, rcin1_port, AP_PERIPH_RC1_PORT_DEFAULT), + + // @Param: RC1_PORT_OPTIONS + // @DisplayName: RC input port serial options + // @Description: This is the serial port number where SERIALx_PROTOCOL will be set to RC input. + // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards. + // @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:SwapTXRX, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA, 10: Don't forward mavlink to/from, 11: DisableFIFO, 12: Ignore Streamrate + AP_GROUPINFO("1_PORT_OPTIONS", 4, Parameters_RCIN, rcin1_port_options, AP_PERIPH_RC1_PORT_OPTIONS_DEFAULT), + // @RebootRequired: True + + AP_GROUPEND +}; + +Parameters_RCIN::Parameters_RCIN(void) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +void AP_Periph_FW::rcin_init() +{ + if (g_rcin.rcin1_port < 0) { + return; + } + + // init uart for serial RC + auto *uart = hal.serial(g_rcin.rcin1_port); + if (uart == nullptr) { + return; + } + + uart->set_options(g_rcin.rcin1_port_options); + + serial_manager.set_protocol_and_baud( + g_rcin.rcin1_port, + AP_SerialManager::SerialProtocol_RCIN, + 115200 // baud doesn't matter; RC Protocol autobauds + ); + + auto &rc = AP::RC(); + rc.init(); + rc.set_rc_protocols(g_rcin.rcin_protocols); + rc.add_uart(uart); + + rcin_initialised = true; +} + +void AP_Periph_FW::rcin_update() +{ + if (!rcin_initialised) { + return; + } + + auto &rc = AP::RC(); + if (!rc.new_input()) { + return; + } + + // log discovered protocols: + auto new_rc_protocol = rc.protocol_name(); + if (new_rc_protocol != rcin_rc_protocol) { + can_printf("Decoding (%s)", new_rc_protocol); + rcin_rc_protocol = new_rc_protocol; + } + + // decimate the input to a parameterized rate + const uint8_t rate_hz = g_rcin.rcin_rate_hz; + if (rate_hz == 0) { + return; + } + + const auto now_ms = AP_HAL::millis(); + const auto interval_ms = 1000U / rate_hz; + if (now_ms - rcin_last_sent_RCInput_ms < interval_ms) { + return; + } + rcin_last_sent_RCInput_ms = now_ms; + + // extract data and send CAN packet: + const uint8_t num_channels = rc.num_channels(); + uint16_t channels[MAX_RCIN_CHANNELS]; + rc.read(channels, num_channels); + const int16_t rssi = rc.get_RSSI(); + + can_send_RCInput((uint8_t)rssi, channels, num_channels, rc.failsafe_active(), rssi > 0 && rssi <256); +} + +/* + send an RCInput CAN message + */ +void AP_Periph_FW::can_send_RCInput(uint8_t quality, uint16_t *values, uint8_t nvalues, bool in_failsafe, bool quality_valid) +{ + uint16_t status = 0; + if (quality_valid) { + status |= DRONECAN_SENSORS_RC_RCINPUT_STATUS_QUALITY_VALID; + } + if (in_failsafe) { + status |= DRONECAN_SENSORS_RC_RCINPUT_STATUS_FAILSAFE; + } + + // assemble packet + dronecan_sensors_rc_RCInput pkt {}; + pkt.quality = quality; + pkt.status = status; + pkt.rcin.len = nvalues; + for (uint8_t i=0; iforce_safety_on(); +#else + hal.rcout->force_safety_off(); +#endif #if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED if (g.esc_telem_port >= 0) { @@ -132,7 +136,8 @@ void AP_Periph_FW::rcout_update() const bool has_esc_rawcommand_timed_out = esc_timeout_ms != 0 && ((now_ms - last_esc_raw_command_ms) >= esc_timeout_ms); if (last_esc_num_channels > 0 && has_esc_rawcommand_timed_out) { // If we've seen ESCs previously, and a timeout has occurred, then zero the outputs - int16_t esc_output[last_esc_num_channels] {}; + int16_t esc_output[last_esc_num_channels]; + memset(esc_output, 0, sizeof(esc_output)); rcout_esc(esc_output, last_esc_num_channels); // register that the output has been changed diff --git a/Tools/AP_Periph/serial_tunnel.cpp b/Tools/AP_Periph/serial_tunnel.cpp index f7ab4c1d21b51a..a1becc8aff65a3 100644 --- a/Tools/AP_Periph/serial_tunnel.cpp +++ b/Tools/AP_Periph/serial_tunnel.cpp @@ -58,7 +58,7 @@ int8_t AP_Periph_FW::get_default_tunnel_serial_port(void) const uart_num = g.adsb_port; } #endif -#if HAL_PROXIMITY_ENABLED +#ifdef HAL_PERIPH_ENABLE_PROXIMITY if (uart_num == -1) { uart_num = g.proximity_port; } @@ -69,13 +69,13 @@ int8_t AP_Periph_FW::get_default_tunnel_serial_port(void) const /* handle tunnel data */ -void AP_Periph_FW::handle_tunnel_Targetted(CanardInstance* ins, CanardRxTransfer* transfer) +void AP_Periph_FW::handle_tunnel_Targetted(CanardInstance* canard_ins, CanardRxTransfer* transfer) { uavcan_tunnel_Targetted pkt; if (uavcan_tunnel_Targetted_decode(transfer, &pkt)) { return; } - if (pkt.target_node != canardGetLocalNodeID(ins)) { + if (pkt.target_node != canardGetLocalNodeID(canard_ins)) { return; } if (uart_monitor.buffer == nullptr) { diff --git a/Tools/AP_Periph/version.h b/Tools/AP_Periph/version.h index 2cd4fb5bf0ab7d..090841e1d57fdc 100644 --- a/Tools/AP_Periph/version.h +++ b/Tools/AP_Periph/version.h @@ -2,15 +2,16 @@ #include -#define THISFIRMWARE "AP_Periph V1.5.0" +#define THISFIRMWARE "AP_Periph V1.7.0-dev" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 1,5,0,FIRMWARE_VERSION_TYPE_OFFICIAL +#define FIRMWARE_VERSION 1,7,0,FIRMWARE_VERSION_TYPE_DEV #define FW_MAJOR 1 -#define FW_MINOR 5 +#define FW_MINOR 7 #define FW_PATCH 0 -#define FW_TYPE FIRMWARE_VERSION_TYPE_OFFICIAL +#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV + diff --git a/Tools/AP_Periph/wscript b/Tools/AP_Periph/wscript index ce5a3c4ba9ea13..8f238ce14b0d50 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_Networking', 'AP_SerialManager', 'AP_RTC', 'AP_Compass', @@ -69,8 +70,19 @@ def build(bld): 'AP_Stats', 'AP_EFI', 'AP_CheckFirmware', + 'AP_RPM', 'AP_Proximity', + 'AP_RCProtocol', + 'AP_AHRS', + 'AP_Terrain', + 'AP_Torqeedo', + 'AP_Volz_Protocol', + 'AP_SBusOut', + 'AP_RobotisServo', + 'AP_FETtecOneWire', + 'GCS_MAVLink', ] + bld.ap_stlib( name= 'AP_Periph_libs', dynamic_source='modules/DroneCAN/libcanard/dsdlc_generated/src/**.c', diff --git a/Tools/CPUInfo/output-PixFlamingo.txt b/Tools/CPUInfo/output-PixFlamingo.txt old mode 100755 new mode 100644 diff --git a/Tools/GIT_Test/GIT_Success.txt b/Tools/GIT_Test/GIT_Success.txt index fc7d6db5d721b6..54dfab7eb55bac 100644 --- a/Tools/GIT_Test/GIT_Success.txt +++ b/Tools/GIT_Test/GIT_Success.txt @@ -175,3 +175,5 @@ Yacine Thabet - 57 Greg Poulos Torre Orazio seba czapnik +Ramy Gad +Matthew R. Cunningham \ No newline at end of file diff --git a/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin new file mode 100755 index 00000000000000..83a7e2b6299695 Binary files /dev/null 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 new file mode 100755 index 00000000000000..dbc520edd07a61 Binary files /dev/null and b/Tools/IO_Firmware/iofirmware_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 519b96d3bc1b1c..a722bc5bd2ee92 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 ec72fd7814beec..cdb40f2fab870f 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 new file mode 100755 index 00000000000000..3d993264ce8699 Binary files /dev/null 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 new file mode 100755 index 00000000000000..ef5755a62abef3 Binary files /dev/null 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 new file mode 100755 index 00000000000000..89d0449fb12566 Binary files /dev/null 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 new file mode 100755 index 00000000000000..2179b5cbc5efb9 Binary files /dev/null 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 943d1a36c681b8..4e2b62dec6a670 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 fa9a372b5b8a25..3ba40363bcd4a8 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 index 38fc82b21943db..a96cca589cecd5 100644 --- a/Tools/LogAnalyzer/DataflashLog.py +++ b/Tools/LogAnalyzer/DataflashLog.py @@ -169,7 +169,7 @@ def to_class(self): _pack_=True, ) - if type(self.types[0]) == str: + if isinstance(self.types[0], str): fieldtypes = [i for i in self.types] else: fieldtypes = [chr(i) for i in self.types] @@ -756,7 +756,7 @@ def read_text(self, f, ignoreBadlines): else: raise Exception("") else: - if not tokens[0] in self.formats: + 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) diff --git a/Tools/Replay/check_replay.py b/Tools/Replay/check_replay.py index 32a49ea5556a1a..dbb0a0bf0203ca 100755 --- a/Tools/Replay/check_replay.py +++ b/Tools/Replay/check_replay.py @@ -40,7 +40,7 @@ def check_log(logfile, progress=print, ekf2_only=False, ekf3_only=False, verbose if not hasattr(m,'C'): continue mtype = m.get_type() - if not mtype in counts: + if mtype not in counts: counts[mtype] = 0 base_counts[mtype] = 0 core = m.C diff --git a/Tools/ardupilotwaf/ap_library.py b/Tools/ardupilotwaf/ap_library.py index 9c7b42f7749890..b49010ae06001c 100644 --- a/Tools/ardupilotwaf/ap_library.py +++ b/Tools/ardupilotwaf/ap_library.py @@ -270,11 +270,15 @@ def double_precision_check(tasks): double_tasks.append([library, s]) src = str(t.inputs[0]).split('/')[-2:] - if src in double_tasks: - single_precision_option='-fsingle-precision-constant' + double_library = t.env.DOUBLE_PRECISION_LIBRARIES.get(src[0],False) + + if double_library or src in double_tasks: t.env.CXXFLAGS = t.env.CXXFLAGS[:] - if single_precision_option in t.env.CXXFLAGS: - t.env.CXXFLAGS.remove(single_precision_option) + for opt in ['-fsingle-precision-constant', '-cl-single-precision-constant']: + try: + t.env.CXXFLAGS.remove(opt) + except ValueError: + pass t.env.CXXFLAGS.append("-DALLOW_DOUBLE_MATH_FUNCTIONS") @@ -321,3 +325,4 @@ def configure(cfg): cfg.env.AP_LIB_EXTRA_CXXFLAGS = dict() cfg.env.AP_LIB_EXTRA_CFLAGS = dict() cfg.env.DOUBLE_PRECISION_SOURCES = dict() + cfg.env.DOUBLE_PRECISION_LIBRARIES = dict() diff --git a/Tools/ardupilotwaf/ardupilotwaf.py b/Tools/ardupilotwaf/ardupilotwaf.py index c3363fcff86752..75c9975b826bd7 100644 --- a/Tools/ardupilotwaf/ardupilotwaf.py +++ b/Tools/ardupilotwaf/ardupilotwaf.py @@ -64,6 +64,7 @@ 'AP_Module', 'AP_Button', 'AP_ICEngine', + 'AP_Networking', 'AP_Frsky_Telem', 'AP_FlashStorage', 'AP_Relay', @@ -114,6 +115,7 @@ 'AP_AIS', 'AP_OpenDroneID', 'AP_CheckFirmware', + 'AP_ExternalControl', ] def get_legacy_defines(sketch_name, bld): @@ -303,6 +305,8 @@ def ap_program(bld, for group in program_groups: _grouped_programs.setdefault(group, {}).update({tg.name : tg}) + return tg + @conf def ap_example(bld, **kw): @@ -354,7 +358,7 @@ def ap_stlib_target(self): self.target = '#%s' % os.path.join('lib', self.target) @conf -def ap_find_tests(bld, use=[]): +def ap_find_tests(bld, use=[], DOUBLE_PRECISION_SOURCES=[]): if not bld.env.HAS_GTEST: return @@ -368,7 +372,7 @@ def ap_find_tests(bld, use=[]): includes = [bld.srcnode.abspath() + '/tests/'] for f in bld.path.ant_glob(incl='*.cpp'): - ap_program( + t = ap_program( bld, features=features, includes=includes, @@ -379,6 +383,16 @@ def ap_find_tests(bld, use=[]): use_legacy_defines=False, cxxflags=['-Wno-undef'], ) + filename = os.path.basename(f.abspath()) + if filename in DOUBLE_PRECISION_SOURCES: + t.env.CXXFLAGS = t.env.CXXFLAGS[:] + single_precision_option='-fsingle-precision-constant' + if single_precision_option in t.env.CXXFLAGS: + t.env.CXXFLAGS.remove(single_precision_option) + single_precision_option='-cl-single-precision-constant' + if single_precision_option in t.env.CXXFLAGS: + t.env.CXXFLAGS.remove(single_precision_option) + t.env.CXXFLAGS.append("-DALLOW_DOUBLE_MATH_FUNCTIONS") _versions = [] diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 98005453a60618..faf500cc24ee30 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -243,16 +243,20 @@ def configure_env(self, cfg, env): if 'clang' in cfg.env.COMPILER_CC: env.CFLAGS += [ '-fcolor-diagnostics', - '-Wno-gnu-designator', '-Wno-inconsistent-missing-override', '-Wno-mismatched-tags', '-Wno-gnu-variable-sized-type-not-at-end', '-Werror=implicit-fallthrough', + '-cl-single-precision-constant', + ] + env.CXXFLAGS += [ + '-cl-single-precision-constant', ] else: env.CFLAGS += [ '-Wno-format-contains-nul', + '-fsingle-precision-constant', # force const vals to be float , not double. so 100.0 means 100.0f ] if self.cc_version_gte(cfg, 7, 4): env.CXXFLAGS += [ @@ -260,6 +264,7 @@ def configure_env(self, cfg, env): ] env.CXXFLAGS += [ '-fcheck-new', + '-fsingle-precision-constant', ] if cfg.env.DEBUG: @@ -609,7 +614,7 @@ def get_board(ctx): ''' % ctx.env.BOARD) boards = _board_classes.keys() - if not ctx.env.BOARD in boards: + if ctx.env.BOARD not in boards: ctx.fatal("Invalid board '%s': choices are %s" % (ctx.env.BOARD, ', '.join(sorted(boards, key=str.lower)))) _board = _board_classes[ctx.env.BOARD]() return _board @@ -621,10 +626,7 @@ def get_board(ctx): class sitl(Board): def __init__(self): - if Utils.unversioned_sys_platform().startswith("linux"): - self.with_can = True - else: - self.with_can = False + self.with_can = True def configure_env(self, cfg, env): super(sitl, self).configure_env(cfg, env) @@ -649,7 +651,16 @@ def configure_env(self, cfg, env): cfg.define('HAL_NUM_CAN_IFACES', 2) env.DEFINES.update(CANARD_MULTI_IFACE=1, CANARD_IFACE_ALL = 0x3, - CANARD_ENABLE_CANFD = 1) + CANARD_ENABLE_CANFD = 1, + CANARD_ENABLE_ASSERTS = 1) + if not cfg.options.force_32bit: + # needed for cygwin + env.CXXFLAGS += [ '-DCANARD_64_BIT=1' ] + env.CFLAGS += [ '-DCANARD_64_BIT=1' ] + if Utils.unversioned_sys_platform().startswith("linux"): + cfg.define('HAL_CAN_WITH_SOCKETCAN', 1) + else: + cfg.define('HAL_CAN_WITH_SOCKETCAN', 0) env.CXXFLAGS += [ '-Werror=float-equal', @@ -700,10 +711,9 @@ def configure_env(self, cfg, env): 'AP_CSVReader', ] - if not cfg.env.AP_PERIPH: - env.AP_LIBRARIES += [ - 'SITL', - ] + env.AP_LIBRARIES += [ + 'SITL', + ] if cfg.options.enable_sfml: if not cfg.check_SFML(env): @@ -773,22 +783,31 @@ def configure_env(self, cfg, env): # whitelist of compilers which we should build with -Werror gcc_whitelist = frozenset([ ('11','3','0'), + ('12','1','0'), ]) - werr_enabled_default = bool('g++' == cfg.env.COMPILER_CXX and cfg.env.CC_VERSION in gcc_whitelist) + # initialise werr_enabled from defaults: + werr_enabled = bool('g++' in cfg.env.COMPILER_CXX and cfg.env.CC_VERSION in gcc_whitelist) - if werr_enabled_default or cfg.options.Werror: - if not cfg.options.disable_Werror: - cfg.msg("Enabling -Werror", "yes") - if '-Werror' not in env.CXXFLAGS: - env.CXXFLAGS += [ '-Werror' ] - else: - cfg.msg("Enabling -Werror", "no") - if '-Werror' in env.CXXFLAGS: - env.CXXFLAGS.remove('-Werror') - else: + # now process overrides to that default: + if (cfg.options.Werror is not None and + cfg.options.Werror == cfg.options.disable_Werror): + cfg.fatal("Asked to both enable and disable Werror") + + if cfg.options.Werror is not None: + werr_enabled = cfg.options.Werror + elif cfg.options.disable_Werror is not None: + werr_enabled = not cfg.options.disable_Werror + + if werr_enabled: cfg.msg("Enabling -Werror", "yes") - + if '-Werror' not in env.CXXFLAGS: + env.CXXFLAGS += [ '-Werror' ] + else: + cfg.msg("Enabling -Werror", "no") + if '-Werror' in env.CXXFLAGS: + env.CXXFLAGS.remove('-Werror') + def get_name(self): return self.__class__.__name__ @@ -800,14 +819,26 @@ def configure_env(self, cfg, env): env.DEFINES.update( HAL_BUILD_AP_PERIPH = 1, PERIPH_FW = 1, - CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_gps"', - AP_AIRSPEED_ENABLED = 0, + CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph"', HAL_PERIPH_ENABLE_GPS = 1, + HAL_PERIPH_ENABLE_AIRSPEED = 1, + HAL_PERIPH_ENABLE_MAG = 1, + HAL_PERIPH_ENABLE_BARO = 1, + HAL_PERIPH_ENABLE_RANGEFINDER = 1, + HAL_PERIPH_ENABLE_BATTERY = 1, + HAL_PERIPH_ENABLE_EFI = 1, + HAL_PERIPH_ENABLE_RPM = 1, + HAL_PERIPH_ENABLE_RC_OUT = 1, + HAL_PERIPH_ENABLE_ADSB = 1, + AP_AIRSPEED_ENABLED = 1, + AP_AIRSPEED_AUTOCAL_ENABLE = 0, + AP_AHRS_ENABLED = 1, AP_UART_MONITOR_ENABLED = 1, HAL_CAN_DEFAULT_NODE_ID = 0, HAL_RAM_RESERVE_START = 0, APJ_BOARD_ID = 100, HAL_GCS_ENABLED = 0, + HAL_MAVLINK_BINDINGS_ENABLED = 1, HAL_LOGGING_ENABLED = 0, HAL_LOGGING_MAVLINK_ENABLED = 0, AP_MISSION_ENABLED = 0, @@ -821,7 +852,7 @@ def configure_env(self, cfg, env): COMPASS_CAL_ENABLED = 0, COMPASS_MOT_ENABLED = 0, COMPASS_LEARN_ENABLED = 0, - AP_BATTERY_ESC_ENABLED = 0, + AP_BATTERY_ESC_ENABLED = 1, HAL_EXTERNAL_AHRS_ENABLED = 0, HAL_GENERATOR_ENABLED = 0, AP_STATS_ENABLED = 0, @@ -829,7 +860,11 @@ def configure_env(self, cfg, env): AP_CAN_SLCAN_ENABLED = 0, HAL_PROXIMITY_ENABLED = 0, AP_SCRIPTING_ENABLED = 0, - AP_AHRS_ENABLED = 0, + HAL_NAVEKF2_AVAILABLE = 0, + HAL_NAVEKF3_AVAILABLE = 0, + HAL_PWM_COUNT = 32, + HAL_WITH_ESC_TELEM = 1, + AP_RTC_ENABLED = 0, ) @@ -868,7 +903,6 @@ def expand_path(p): env.CFLAGS += [ '-fno-inline-functions', '-mlongcalls', - '-fsingle-precision-constant', ] env.CFLAGS.remove('-Werror=undef') @@ -884,7 +918,6 @@ def expand_path(p): '-Wno-sign-compare', '-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'] env.CXXFLAGS.remove('-Werror=undef') @@ -947,7 +980,6 @@ def configure_env(self, cfg, env): env.CFLAGS += cfg.env.CPU_FLAGS + [ '-Wlogical-op', '-Wframe-larger-than=1300', - '-fsingle-precision-constant', '-Wno-attributes', '-fno-exceptions', '-Wall', diff --git a/Tools/ardupilotwaf/build_summary.py b/Tools/ardupilotwaf/build_summary.py index 6a0abacc827f7c..82f76367565185 100644 --- a/Tools/ardupilotwaf/build_summary.py +++ b/Tools/ardupilotwaf/build_summary.py @@ -190,7 +190,7 @@ def _parse_size_output(s, s_all, totals=False): lines = s.splitlines()[1:] l = [] for line in lines: - if pattern.match(line) or totals==False: + if pattern.match(line) or totals is False: row = line.strip().split() # check if crash_log wasn't found diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index 83c41cb81dba7f..819b3474c540f1 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -31,7 +31,7 @@ def _load_dynamic_env_data(bld): # relative paths from the make build are relative to BUILDROOT d = os.path.join(bld.env.BUILDROOT, d) d = os.path.normpath(d) - if not d in idirs2: + if d not in idirs2: idirs2.append(d) _dynamic_env_data['include_dirs'] = idirs2 @@ -98,7 +98,7 @@ def wsl2_prereq_checks(self): except subprocess.CalledProcessError: #if where.exe can't find the file it returns a non-zero result which throws this exception where_python = "" - if not where_python or not "\Python\Python" in where_python or "python.exe" not in where_python: + if not where_python or "\Python\Python" not in where_python or "python.exe" not in where_python: print(self.get_full_wsl2_error_msg("Windows python.exe not found")) return False return True @@ -578,6 +578,8 @@ def bldpath(path): load_env_vars(cfg.env) if env.HAL_NUM_CAN_IFACES and not env.AP_PERIPH: setup_canmgr_build(cfg) + if env.HAL_NUM_CAN_IFACES and env.AP_PERIPH and int(env.HAL_NUM_CAN_IFACES)>1 and not env.BOOTLOADER: + env.DEFINES += [ 'CANARD_MULTI_IFACE=1' ] setup_optimization(cfg.env) def generate_hwdef_h(env): diff --git a/Tools/ardupilotwaf/cmake.py b/Tools/ardupilotwaf/cmake.py index 9ec9691c150ae1..0616de6128ed6f 100644 --- a/Tools/ardupilotwaf/cmake.py +++ b/Tools/ardupilotwaf/cmake.py @@ -23,7 +23,7 @@ the configuration to set a minimum version required for cmake. Example:: def configure(cfg): - cfg.CMAKE_MIN_VERSION = '3.5.2' + cfg.env.CMAKE_MIN_VERSION = '3.5.2' cfg.load('cmake') Usage example:: diff --git a/Tools/ardupilotwaf/mavgen.py b/Tools/ardupilotwaf/mavgen.py index 5af076ac3f4b48..f246d768d5a3fa 100644 --- a/Tools/ardupilotwaf/mavgen.py +++ b/Tools/ardupilotwaf/mavgen.py @@ -44,7 +44,7 @@ def scan(self): node.parent.path_from(entry_point.parent), path ) - if not path in names: + if path not in names: names.append(path) return nodes, names diff --git a/Tools/ardupilotwaf/toolchain.py b/Tools/ardupilotwaf/toolchain.py index 5d242a4fc6c385..eb86084307cb29 100644 --- a/Tools/ardupilotwaf/toolchain.py +++ b/Tools/ardupilotwaf/toolchain.py @@ -119,7 +119,7 @@ def _set_pkgconfig_crosscompilation_wrapper(cfg): @conf def new_validate_cfg(kw): - if not 'path' in kw: + if 'path' not in kw: if not cfg.env.PKGCONFIG: cfg.find_program('%s-pkg-config' % cfg.env.TOOLCHAIN, var='PKGCONFIG') kw['path'] = cfg.env.PKGCONFIG diff --git a/Tools/autotest/ArduCopter_Tests/PayLoadPlaceMission/copter_payload_place.txt b/Tools/autotest/ArduCopter_Tests/PayloadPlaceMission/copter_payload_place.txt similarity index 100% rename from Tools/autotest/ArduCopter_Tests/PayLoadPlaceMission/copter_payload_place.txt rename to Tools/autotest/ArduCopter_Tests/PayloadPlaceMission/copter_payload_place.txt diff --git a/Tools/autotest/ArduPlane_Tests/GUIDEDToAUTO/mission.txt b/Tools/autotest/ArduPlane_Tests/GUIDEDToAUTO/mission.txt new file mode 100644 index 00000000000000..12bb5ed5f65e6b --- /dev/null +++ b/Tools/autotest/ArduPlane_Tests/GUIDEDToAUTO/mission.txt @@ -0,0 +1,36 @@ +QGC WPL 110 +0 0 0 16 0.000000 0.000000 0.000000 0.000000 -27.272924 151.290848 10.000000 1 +1 0 10 84 0.000000 0.000000 0.000000 0.000000 -27.272924 151.290848 10.000000 1 +2 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.272705 151.298172 100.000000 1 +3 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.277561 151.337250 100.000000 1 +4 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.281748 151.335953 100.000000 1 +5 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.275724 151.289932 100.000000 1 +6 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.297457 151.285629 100.000000 1 +7 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.308109 151.354279 100.000000 1 +8 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.330292 151.374268 90.000000 1 +9 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.330435 151.375977 70.000000 1 +10 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.332638 151.376099 70.000000 1 +11 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.334694 151.376144 70.000000 1 +12 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.333776 151.374146 70.000000 1 +13 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.331438 151.378159 70.000000 1 +14 0 0 177 9.000000 4.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 +15 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.334566 151.375366 40.000000 1 +16 0 0 178 0.000000 20.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 +17 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.334840 151.377234 40.000000 1 +18 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.333933 151.376849 35.000000 1 +19 0 10 85 0.000000 0.000000 0.000000 0.000000 -27.332676 151.376511 0.000000 1 +20 0 10 84 0.000000 0.000000 0.000000 0.000000 -27.332659 151.376511 35.000000 1 +21 0 0 178 0.000000 24.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 +22 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.332201 151.376511 100.000000 1 +23 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.330381 151.374191 100.000000 1 +24 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.308224 151.354538 100.000000 1 +25 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.297340 151.285385 100.000000 1 +26 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.275724 151.289932 100.000000 1 +27 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.281631 151.335953 100.000000 1 +28 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.277679 151.337128 100.000000 1 +29 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.272587 151.298294 100.000000 1 +30 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.271564 151.291473 30.000000 1 +31 0 0 178 0.000000 20.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 +32 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.271054 151.290211 25.000000 1 +33 0 10 16 0.000000 0.000000 0.000000 0.000000 -27.273310 151.290222 15.000000 1 +34 0 10 85 0.000000 0.000000 0.000000 0.000000 -27.274887 151.289918 0.000000 1 diff --git a/Tools/autotest/ArduPlane_Tests/MAV_CMD_DO_GO_AROUND/mission.txt b/Tools/autotest/ArduPlane_Tests/MAV_CMD_DO_GO_AROUND/mission.txt new file mode 100644 index 00000000000000..41e2938f9c9d60 --- /dev/null +++ b/Tools/autotest/ArduPlane_Tests/MAV_CMD_DO_GO_AROUND/mission.txt @@ -0,0 +1,8 @@ +QGC WPL 110 +0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165238 584.089966 1 +1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.361438 149.165031 50.000000 1 +2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.361505 149.163723 50.000000 1 +3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.365845 149.164175 52.219997 1 +4 0 3 189 0.000000 0.000000 0.000000 0.000000 -35.368656 149.165976 54.410000 1 +5 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.366148 149.165741 50.849998 1 +6 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.362920 149.165127 50.000000 1 diff --git a/Tools/autotest/ArduPlane_Tests/LordEAHRS/ap1.txt b/Tools/autotest/ArduPlane_Tests/MicroStrainEAHRS5/ap1.txt similarity index 100% rename from Tools/autotest/ArduPlane_Tests/LordEAHRS/ap1.txt rename to Tools/autotest/ArduPlane_Tests/MicroStrainEAHRS5/ap1.txt diff --git a/Tools/autotest/Generic_Missions/QuadPlaneDalbyRTL.txt b/Tools/autotest/Generic_Missions/QuadPlaneDalbyRTL.txt new file mode 100644 index 00000000000000..e88bb0c7fd6c0a --- /dev/null +++ b/Tools/autotest/Generic_Missions/QuadPlaneDalbyRTL.txt @@ -0,0 +1,6 @@ +QGC WPL 110 +0 0 0 16 0.000000 0.000000 0.000000 0.000000 -27.274439 151.290064 343.209991 1 +1 0 3 189 0.000000 0.000000 0.000000 0.000000 -27.270617 151.283268 28.590000 1 +2 0 3 16 0.000000 0.000000 0.000000 0.000000 -27.272859 151.286018 28.789999 1 +3 0 3 16 0.000000 0.000000 0.000000 0.000000 -27.273316 151.288023 30.000000 1 +4 0 3 85 0.000000 0.000000 0.000000 0.000000 -27.273771 151.289905 0.000000 1 diff --git a/Tools/autotest/antennatracker.py b/Tools/autotest/antennatracker.py index cea2a37fa09ba5..a4cdf01a460d28 100644 --- a/Tools/autotest/antennatracker.py +++ b/Tools/autotest/antennatracker.py @@ -116,28 +116,36 @@ def MANUAL(self): self.set_rc(chan, pwm) self.wait_servo_channel_value(chan, pwm) - def SERVOTEST(self): + def MAV_CMD_DO_SET_SERVO(self): '''Test SERVOTEST mode''' self.change_mode(0) # "MANUAL" # magically changes to SERVOTEST (3) - for value in 1900, 1200: - channel = 1 - self.run_cmd( - mavutil.mavlink.MAV_CMD_DO_SET_SERVO, - p1=channel, - p2=value, - timeout=1, - ) - self.wait_servo_channel_value(channel, value) - for value in 1300, 1670: - channel = 2 - self.run_cmd( - mavutil.mavlink.MAV_CMD_DO_SET_SERVO, - p1=channel, - p2=value, - timeout=1, - ) - self.wait_servo_channel_value(channel, value) + for method in self.run_cmd, self.run_cmd_int: + for value in 1900, 1200: + channel = 1 + method( + mavutil.mavlink.MAV_CMD_DO_SET_SERVO, + p1=channel, + p2=value, + timeout=1, + ) + self.wait_servo_channel_value(channel, value) + for value in 1300, 1670: + channel = 2 + method( + mavutil.mavlink.MAV_CMD_DO_SET_SERVO, + p1=channel, + p2=value, + timeout=1, + ) + self.wait_servo_channel_value(channel, value) + + def MAV_CMD_MISSION_START(self): + '''test MAV_CMD_MISSION_START mavlink command''' + for method in self.run_cmd, self.run_cmd_int: + self.change_mode(0) # "MANUAL" + method(mavutil.mavlink.MAV_CMD_MISSION_START) + self.wait_mode("AUTO") def SCAN(self): '''Test SCAN mode''' @@ -166,7 +174,8 @@ def tests(self): ret.extend([ self.GUIDED, self.MANUAL, - self.SERVOTEST, + self.MAV_CMD_DO_SET_SERVO, + self.MAV_CMD_MISSION_START, self.NMEAOutput, self.SCAN, ]) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 366d13ca6bb1ea..aeada6db195109 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -123,14 +123,6 @@ def get_disarm_delay(self): def set_autodisarm_delay(self, delay): self.set_parameter("DISARM_DELAY", delay) - def user_takeoff(self, alt_min=30, timeout=30, max_err=5): - '''takeoff using mavlink takeoff command''' - self.run_cmd( - mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, - p7=alt_min, - ) - self.wait_for_alt(alt_min, timeout=timeout, max_err=max_err) - def takeoff(self, alt_min=30, takeoff_throttle=1700, @@ -149,17 +141,10 @@ def takeoff(self, self.user_takeoff(alt_min=alt_min, timeout=timeout, max_err=max_err) else: self.set_rc(3, takeoff_throttle) - self.wait_for_alt(alt_min=alt_min, timeout=timeout, max_err=max_err) + self.wait_altitude(alt_min-1, alt_min+max_err, relative=True, timeout=timeout) self.hover() self.progress("TAKEOFF COMPLETE") - def wait_for_alt(self, alt_min=30, timeout=30, max_err=5): - """Wait for minimum altitude to be reached.""" - self.wait_altitude(alt_min - 1, - (alt_min + max_err), - relative=True, - timeout=timeout) - def land_and_disarm(self, timeout=60): """Land the quad.""" self.progress("STARTING LANDING") @@ -171,7 +156,7 @@ def wait_landed_and_disarmed(self, min_alt=6, timeout=60): m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) alt = m.relative_alt / 1000.0 # mm -> m if alt > min_alt: - self.wait_for_alt(min_alt, timeout=timeout) + self.wait_altitude(min_alt-1, min_alt+5, relative=True, timeout=timeout) # self.wait_statustext("SIM Hit ground", timeout=timeout) self.wait_disarmed() @@ -703,6 +688,47 @@ def ThrottleFailsafe(self, side=60, timeout=360): self.set_parameter('FS_THR_ENABLE', 0) self.reboot_sitl() + def ThrottleFailsafePassthrough(self): + '''check servo passthrough on RC failsafe. Make sure it doesn't glitch to the bad RC input value''' + channel = 7 + trim_value = 1450 + self.set_parameters({ + 'RC%u_MIN' % channel: 1000, + 'RC%u_MAX' % channel: 2000, + 'SERVO%u_MIN' % channel: 1000, + 'SERVO%u_MAX' % channel: 2000, + 'SERVO%u_TRIM' % channel: trim_value, + 'SERVO%u_FUNCTION' % channel: 146, # scaled passthrough for channel 7 + 'FS_THR_ENABLE': 1, + 'RC_FS_TIMEOUT': 10, + 'SERVO_RC_FS_MSK': 1 << (channel-1), + }) + + self.reboot_sitl() + + self.context_set_message_rate_hz('SERVO_OUTPUT_RAW', 200) + + self.set_rc(channel, 1799) + expected_servo_output_value = 1778 # 1778 because of weird trim + self.wait_servo_channel_value(channel, expected_servo_output_value) + # receiver goes into failsafe with wild override values: + + def ensure_SERVO_values_never_input(mav, m): + if m.get_type() != "SERVO_OUTPUT_RAW": + return + value = getattr(m, "servo%u_raw" % channel) + if value != expected_servo_output_value and value != trim_value: + raise NotAchievedException("Bad servo value %u received" % value) + + self.install_message_hook_context(ensure_SERVO_values_never_input) + self.progress("Forcing receiver into failsafe") + self.set_rc_from_map({ + 3: 800, + channel: 1300, + }) + self.wait_servo_channel_value(channel, trim_value) + self.delay_sim_time(10) + # Tests all actions and logic behind the GCS failsafe def GCSFailsafe(self, side=60, timeout=360): '''Test GCS Failsafe''' @@ -1114,7 +1140,7 @@ def VibrationFailsafe(self): self.change_mode("LAND") # check vehicle descends to 2m or less within 40 seconds - self.wait_altitude(-5, 2, timeout=40, relative=True) + self.wait_altitude(-5, 2, timeout=50, relative=True) # force disarm of vehicle (it will likely not automatically disarm) self.disarm_vehicle(force=True) @@ -2100,7 +2126,7 @@ def ModeFlip(self): self.progress("Regaining altitude") self.change_mode('ALT_HOLD') - self.wait_for_alt(20, max_err=40) + self.wait_altitude(19, 60, relative=True) self.progress("Flipping in pitch") self.set_rc(2, 1700) @@ -2440,7 +2466,7 @@ def AutoTuneSwitch(self): raise NotAchievedException("AUTOTUNE gains not present in pilot testing") # land without changing mode self.set_rc(3, 1000) - self.wait_for_alt(0) + 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 @@ -2594,7 +2620,23 @@ def CANGPSCopterMission(self): "CAN_P1_DRIVER": 1, "GPS_TYPE": 9, "GPS_TYPE2": 9, - "SIM_GPS2_DISABLE": 0, + # disable simulated GPS, so only via DroneCAN + "SIM_GPS_DISABLE": 1, + "SIM_GPS2_DISABLE": 1, + # this ensures we use DroneCAN baro and compass + "SIM_BARO_COUNT" : 0, + "SIM_MAG1_DEVID" : 0, + "SIM_MAG2_DEVID" : 0, + "SIM_MAG3_DEVID" : 0, + "COMPASS_USE2" : 0, + "COMPASS_USE3" : 0, + # use DroneCAN rangefinder + "RNGFND1_TYPE" : 24, + "RNGFND1_MAX_CM" : 11000, + # use DroneCAN battery monitoring, and enforce with a arming voltage + "BATT_MONITOR" : 8, + "BATT_ARM_VOLT" : 12.0, + "SIM_SPEEDUP": 2, }) self.context_push() @@ -2692,6 +2734,17 @@ def CANGPSCopterMission(self): self.start_sup_program(instance=1) self.context_stop_collecting('STATUSTEXT') self.context_pop() + + self.set_parameters({ + # use DroneCAN ESCs for flight + "CAN_D1_UC_ESC_BM" : 0x0f, + # this stops us using local servo output, guaranteeing we are + # flying on DroneCAN ESCs + "SIM_CAN_SRV_MSK" : 0xFF, + # we can do the flight faster + "SIM_SPEEDUP" : 5, + }) + self.CopterMission() def TakeoffAlt(self): @@ -3613,8 +3666,8 @@ def test_rangefinder_switchover(self): if ex is not None: raise ex - def Parachute(self): - '''Test Parachute Functionality''' + def _Parachute(self, command): + '''Test Parachute Functionality using specific mavlink command''' self.set_rc(9, 1000) self.set_parameters({ "CHUTE_ENABLED": 1, @@ -3637,7 +3690,7 @@ def Parachute(self): self.progress("Test triggering with mavlink message") self.takeoff(20) - self.run_cmd( + command( mavutil.mavlink.MAV_CMD_DO_PARACHUTE, p1=2, # release ) @@ -3658,7 +3711,7 @@ def Parachute(self): self.progress("Test mavlink triggering") self.takeoff(20) - self.run_cmd( + command( mavutil.mavlink.MAV_CMD_DO_PARACHUTE, p1=mavutil.mavlink.PARACHUTE_DISABLE, ) @@ -3669,7 +3722,7 @@ def Parachute(self): ok = True if not ok: raise NotAchievedException("Disabled parachute fired") - self.run_cmd( + command( mavutil.mavlink.MAV_CMD_DO_PARACHUTE, p1=mavutil.mavlink.PARACHUTE_ENABLE, ) @@ -3687,7 +3740,7 @@ def Parachute(self): # parachute should not fire if you go from disabled to release: self.takeoff(20) - self.run_cmd( + command( mavutil.mavlink.MAV_CMD_DO_PARACHUTE, p1=mavutil.mavlink.PARACHUTE_RELEASE, ) @@ -3700,11 +3753,11 @@ def Parachute(self): raise NotAchievedException("Parachute fired when going straight from disabled to release") # now enable then release parachute: - self.run_cmd( + command( mavutil.mavlink.MAV_CMD_DO_PARACHUTE, p1=mavutil.mavlink.PARACHUTE_ENABLE, ) - self.run_cmd( + command( mavutil.mavlink.MAV_CMD_DO_PARACHUTE, p1=mavutil.mavlink.PARACHUTE_RELEASE, ) @@ -3747,49 +3800,10 @@ def Parachute(self): self.disarm_vehicle(force=True) self.reboot_sitl() - def MotorTest(self, timeout=60): - '''Run Motor Tests''' - self.start_subtest("Testing PWM output") - pwm_in = 1300 - # default frame is "+" - start motor of 2 is "B", which is - # motor 1... see - # https://ardupilot.org/copter/docs/connect-escs-and-motors.html - self.run_cmd( - mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST, - p1=2, # start motor - p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM, - p3=pwm_in, # pwm-to-output - p4=2, # timeout in seconds - p5=2, # number of motors to output - p6=0, # compass learning - timeout=timeout, - ) - # long timeouts here because there's a pause before we start motors - self.wait_servo_channel_value(1, pwm_in, timeout=10) - self.wait_servo_channel_value(4, pwm_in, timeout=10) - self.wait_statustext("finished motor test") - self.end_subtest("Testing PWM output") - - self.start_subtest("Testing percentage output") - percentage = 90.1 - # since MOT_SPIN_MIN and MOT_SPIN_MAX are not set, the RC3 - # min/max are used. - expected_pwm = 1000 + (self.get_parameter("RC3_MAX") - self.get_parameter("RC3_MIN")) * percentage/100.0 - self.progress("expected pwm=%f" % expected_pwm) - self.run_cmd( - mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST, - p1=2, # start motor - p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PERCENT, - p3=percentage, # pwm-to-output - p4=2, # timeout in seconds - p5=2, # number of motors to output - p6=0, # compass learning - timeout=timeout, - ) - self.wait_servo_channel_value(1, expected_pwm, timeout=10) - self.wait_servo_channel_value(4, expected_pwm, timeout=10) - self.wait_statustext("finished motor test") - self.end_subtest("Testing percentage output") + def Parachute(self): + '''Test Parachute Functionality''' + self._Parachute(self.run_cmd) + self._Parachute(self.run_cmd_int) def PrecisionLanding(self): """Use PrecLand backends precision messages to land aircraft.""" @@ -3833,7 +3847,7 @@ def PrecisionLanding(self): new_pos = self.mav.location() delta = self.get_distance(target, new_pos) self.progress("Landed %f metres from target position" % delta) - max_delta = 1 + max_delta = 1.5 if delta > max_delta: raise NotAchievedException("Did not land close enough to target position (%fm > %fm" % (delta, max_delta)) @@ -4352,7 +4366,7 @@ def fly_guided_move_local(self, x, y, z_up, timeout=100): MAV_POS_TARGET_TYPE_MASK.POS_ONLY | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE, # mask specifying use-only-x-y-z x, # x y, # y - -z_up,# z + -z_up, # z 0, # vx 0, # vy 0, # vz @@ -4550,7 +4564,7 @@ def precision_loiter_to_pos(self, x, y, z, timeout=40): # determine if we've successfully navigated to close to # where we should be: dist = math.sqrt(delta_ef.x * delta_ef.x + delta_ef.y * delta_ef.y) - dist_max = 0.15 + dist_max = 1 self.progress("dist=%f want <%f" % (dist, dist_max)) if dist < dist_max: # success! We've gotten within our target distance @@ -4585,7 +4599,7 @@ def precision_loiter_to_pos(self, x, y, z, timeout=40): 0.01 # size of target in radians, Y-axis ) - def PayLoadPlaceMission(self): + def PayloadPlaceMission(self): """Test payload placing in auto.""" self.context_push() @@ -4628,6 +4642,7 @@ def PayLoadPlaceMission(self): except Exception as e: self.print_exception_caught(e) + self.disarm_vehicle(force=True) ex = e self.context_pop() @@ -4681,6 +4696,74 @@ def Weathervane(self): self.wait_heading(100, accuracy=8, timeout=100) self.do_RTL() + def _DO_WINCH(self, command): + self.context_push() + self.load_default_params_file("copter-winch.parm") + self.reboot_sitl() + self.wait_ready_to_arm() + + self.start_subtest("starts relaxed") + self.wait_servo_channel_value(9, 0) + + self.start_subtest("rate control") + command( + mavutil.mavlink.MAV_CMD_DO_WINCH, + p1=1, # instance number + p2=mavutil.mavlink.WINCH_RATE_CONTROL, # command + p3=0, # length to release + p4=1, # rate in m/s + ) + self.wait_servo_channel_value(9, 1900) + + self.start_subtest("relax") + command( + mavutil.mavlink.MAV_CMD_DO_WINCH, + p1=1, # instance number + p2=mavutil.mavlink.WINCH_RELAXED, # command + p3=0, # length to release + p4=1, # rate in m/s + ) + self.wait_servo_channel_value(9, 0) + + self.start_subtest("hold but zero output") + command( + mavutil.mavlink.MAV_CMD_DO_WINCH, + p1=1, # instance number + p2=mavutil.mavlink.WINCH_RATE_CONTROL, # command + p3=0, # length to release + p4=0, # rate in m/s + ) + self.wait_servo_channel_value(9, 1500) + + self.start_subtest("relax") + command( + mavutil.mavlink.MAV_CMD_DO_WINCH, + p1=1, # instance number + p2=mavutil.mavlink.WINCH_RELAXED, # command + p3=0, # length to release + p4=1, # rate in m/s + ) + self.wait_servo_channel_value(9, 0) + + self.start_subtest("position") + command( + mavutil.mavlink.MAV_CMD_DO_WINCH, + p1=1, # instance number + p2=mavutil.mavlink.WINCH_RELATIVE_LENGTH_CONTROL, # command + p3=2, # length to release + p4=1, # rate in m/s + ) + self.wait_servo_channel_value(9, 1900) + self.wait_servo_channel_value(9, 1500, timeout=60) + + self.context_pop() + self.reboot_sitl() + + def DO_WINCH(self): + '''test mavlink DO_WINCH command''' + self._DO_WINCH(self.run_cmd_int) + self._DO_WINCH(self.run_cmd) + def GuidedSubModeChange(self): """"Ensure we can move around in guided after a takeoff command.""" @@ -4825,8 +4908,7 @@ def test_mount_pitch(self, despitch, despitch_tolerance, mount_mode, timeout=10, (mount_pitch, despitch)) if success_start == 0: success_start = now - continue - if now - success_start > hold: + if now - success_start >= hold: self.progress("Mount pitch achieved") return @@ -4879,6 +4961,12 @@ def get_mount_roll_pitch_yaw_deg(self): def set_mount_mode(self, mount_mode): '''set mount mode''' + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_DO_MOUNT_CONFIGURE, + p1=mount_mode, + p2=0, # stabilize roll (unsupported) + p3=0, # stabilize pitch (unsupported) + ) self.run_cmd( mavutil.mavlink.MAV_CMD_DO_MOUNT_CONFIGURE, p1=mount_mode, @@ -4886,6 +4974,95 @@ def set_mount_mode(self, mount_mode): p3=0, # stabilize pitch (unsupported) ) + def test_mount_rc_targetting(self): + '''called in multipleplaces to make sure that mount RC targetting works''' + try: + self.context_push() + self.set_parameters({ + 'RC6_OPTION': 0, + 'RC11_OPTION': 212, # MOUNT1_ROLL + 'RC12_OPTION': 213, # MOUNT1_PITCH + 'RC13_OPTION': 214, # MOUNT1_YAW + 'RC12_MIN': 1100, + 'RC12_MAX': 1900, + 'RC12_TRIM': 1500, + 'MNT1_PITCH_MIN': -45, + 'MNT1_PITCH_MAX': 45, + }) + self.progress("Testing RC angular control") + # default RC min=1100 max=1900 + self.set_rc_from_map({ + 11: 1500, + 12: 1500, + 13: 1500, + }) + self.test_mount_pitch(0, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.progress("Testing RC input down 1/4 of its range in the output, should be down 1/4 range in output") + rc12_in = 1400 + rc12_min = 1100 # default + rc12_max = 1900 # default + mpitch_min = -45.0 + mpitch_max = 45.0 + expected_pitch = (float(rc12_in-rc12_min)/float(rc12_max-rc12_min) * (mpitch_max-mpitch_min)) + mpitch_min + self.progress("expected mount pitch: %f" % expected_pitch) + if expected_pitch != -11.25: + raise NotAchievedException("Calculation wrong - defaults changed?!") + self.set_rc(12, rc12_in) + self.test_mount_pitch(-11.25, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.set_rc(12, 1800) + self.test_mount_pitch(33.75, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.set_rc_from_map({ + 11: 1500, + 12: 1500, + 13: 1500, + }) + + try: + self.context_push() + self.set_parameters({ + "RC12_MIN": 1000, + "RC12_MAX": 2000, + "MNT1_PITCH_MIN": -90, + "MNT1_PITCH_MAX": 10, + }) + self.set_rc(12, 1000) + self.test_mount_pitch(-90.00, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.set_rc(12, 2000) + self.test_mount_pitch(10.00, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.set_rc(12, 1500) + self.test_mount_pitch(-40.00, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + finally: + self.context_pop() + + self.set_rc(12, 1500) + + self.progress("Testing RC rate control") + self.set_parameter('MNT1_RC_RATE', 10) + self.test_mount_pitch(0, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.set_rc(12, 1300) + self.test_mount_pitch(-5, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + 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.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.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 @@ -4950,17 +5127,18 @@ def Mount(self): self.do_pitch(0) # level vehicle self.wait_pitch(0, despitch_tolerance) self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING) - self.run_cmd( - mavutil.mavlink.MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW, - p1=-20, # pitch angle in degrees - p2=0, # yaw angle in degrees - p3=0, # pitch rate in degrees (NaN to ignore) - p4=0, # yaw rate in degrees (NaN to ignore) - p5=0, # flags (0=Body-frame, 16/GIMBAL_MANAGER_FLAGS_YAW_LOCK=Earth Frame) - p6=0, # unused - p7=0, # gimbal id - ) - self.test_mount_pitch(-20, 1, mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING) + for (method, angle) in (self.run_cmd, -20), (self.run_cmd_int, -30): + method( + mavutil.mavlink.MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW, + p1=angle, # pitch angle in degrees + p2=0, # yaw angle in degrees + p3=0, # pitch rate in degrees (NaN to ignore) + p4=0, # yaw rate in degrees (NaN to ignore) + p5=0, # flags (0=Body-frame, 16/GIMBAL_MANAGER_FLAGS_YAW_LOCK=Earth Frame) + p6=0, # unused + p7=0, # gimbal id + ) + 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)") @@ -4988,9 +5166,6 @@ def Mount(self): ) self.test_mount_pitch(-52, 5, mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT) - # now test RC targetting - self.progress("Testing mount RC targetting") - # this is a one-off; ArduCopter *will* time out this directive! self.progress("Levelling aircraft") self.mav.mav.set_attitude_target_send( @@ -5004,94 +5179,13 @@ def Mount(self): 0, # yaw rate (rad/s) 0.5) # thrust, 0 to 1, translated to a climb/descent rate - self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - - try: - self.context_push() - self.set_parameters({ - 'RC6_OPTION': 0, - 'RC11_OPTION': 212, # MOUNT1_ROLL - 'RC12_OPTION': 213, # MOUNT1_PITCH - 'RC13_OPTION': 214, # MOUNT1_YAW - 'RC12_MIN': 1100, - 'RC12_MAX': 1900, - 'RC12_TRIM': 1500, - 'MNT1_PITCH_MIN': -45, - 'MNT1_PITCH_MAX': 45, - }) - self.progress("Testing RC angular control") - # default RC min=1100 max=1900 - self.set_rc_from_map({ - 11: 1500, - 12: 1500, - 13: 1500, - }) - self.test_mount_pitch(0, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.progress("Testing RC input down 1/4 of its range in the output, should be down 1/4 range in output") - rc12_in = 1400 - rc12_min = 1100 # default - rc12_max = 1900 # default - mpitch_min = -45.0 - mpitch_max = 45.0 - expected_pitch = (float(rc12_in-rc12_min)/float(rc12_max-rc12_min) * (mpitch_max-mpitch_min)) + mpitch_min - self.progress("expected mount pitch: %f" % expected_pitch) - if expected_pitch != -11.25: - raise NotAchievedException("Calculation wrong - defaults changed?!") - self.set_rc(12, rc12_in) - self.test_mount_pitch(-11.25, 0.01, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.set_rc(12, 1800) - self.test_mount_pitch(33.75, 0.01, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.set_rc_from_map({ - 11: 1500, - 12: 1500, - 13: 1500, - }) - - try: - self.context_push() - self.set_parameters({ - "RC12_MIN": 1000, - "RC12_MAX": 2000, - "MNT1_PITCH_MIN": -90, - "MNT1_PITCH_MAX": 10, - }) - self.set_rc(12, 1000) - self.test_mount_pitch(-90.00, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.set_rc(12, 2000) - self.test_mount_pitch(10.00, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.set_rc(12, 1500) - self.test_mount_pitch(-40.00, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - finally: - self.context_pop() - - self.set_rc(12, 1500) - - self.progress("Testing RC rate control") - self.set_parameter('MNT1_RC_RATE', 10) - self.test_mount_pitch(0, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - self.set_rc(12, 1300) - self.test_mount_pitch(-5, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) - 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.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.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.wait_groundspeed(0, 1) - self.context_pop() + # now test RC targetting + self.progress("Testing mount RC targetting") - except Exception as e: - self.print_exception_caught(e) - self.context_pop() - raise e + self.set_mount_mode(mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.test_mount_rc_targetting() self.progress("Testing mount ROI behaviour") self.test_mount_pitch(0, 0.1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) @@ -5213,6 +5307,11 @@ def Mount(self): ) self.test_mount_pitch(-89, 5, mavutil.mavlink.MAV_MOUNT_MODE_SYSID_TARGET, hold=2) + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_ROI_NONE) + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_DO_SET_ROI_SYSID, + p1=self.mav.source_system, + ) self.mav.mav.global_position_int_send( 0, # time boot ms int(roi_lat * 1e7), @@ -5242,6 +5341,193 @@ def Mount(self): if ex is not None: raise ex + 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() + 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" % + (name, want, got)) + + def neutralise_gimbal(self): + '''put mount into neutralise mode, assert it is at zero angles''' + self.run_cmd( + mavutil.mavlink.MAV_CMD_DO_MOUNT_CONTROL, + p7=mavutil.mavlink.MAV_MOUNT_MODE_NEUTRAL, + ) + self.test_mount_pitch(0, 0, mavutil.mavlink.MAV_MOUNT_MODE_RETRACT) + + def MAV_CMD_DO_MOUNT_CONTROL(self): + '''test MAV_CMD_DO_MOUNT_CONTROL mavlink command''' + + # setup mount parameters + self.context_push() + self.setup_servo_mount() + self.reboot_sitl() # to handle MNT_TYPE changing + + takeoff_loc = self.mav.location() + + self.takeoff(20, mode='GUIDED') + self.guided_achieve_heading(315) + + self.run_cmd( + mavutil.mavlink.MAV_CMD_DO_MOUNT_CONTROL, + p7=mavutil.mavlink.MAV_MOUNT_MODE_RETRACT, + ) + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_DO_MOUNT_CONTROL, + p7=mavutil.mavlink.MAV_MOUNT_MODE_RETRACT, + ) + + for method in self.run_cmd, self.run_cmd_int: + self.start_subtest("MAV_MOUNT_MODE_GPS_POINT") + + self.progress("start=%s" % str(takeoff_loc)) + t = self.offset_location_ne(takeoff_loc, 20, 0) + self.progress("targetting=%s" % str(t)) + + # this command is *weird* as the lat/lng is *always* 1e7, + # even when transported via COMMAND_LONG! + x = int(t.lat * 1e7) + y = int(t.lng * 1e7) + method( + mavutil.mavlink.MAV_CMD_DO_MOUNT_CONTROL, + p4=0, # this is a relative altitude! + p5=x, + p6=y, + p7=mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT, + ) + self.test_mount_pitch(-45, 5, mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT) + self.neutralise_gimbal() + + self.start_subtest("MAV_MOUNT_MODE_HOME_LOCATION") + method( + mavutil.mavlink.MAV_CMD_DO_MOUNT_CONTROL, + p7=mavutil.mavlink.MAV_MOUNT_MODE_HOME_LOCATION, + ) + self.test_mount_pitch(-90, 5, mavutil.mavlink.MAV_MOUNT_MODE_HOME_LOCATION) + self.neutralise_gimbal() + + # try an invalid mount mode. Note that this is asserting we + # are receiving a result code which is actually incorrect; + # this should be MAV_RESULT_DENIED + self.start_subtest("Invalid mode") + method( + mavutil.mavlink.MAV_CMD_DO_MOUNT_CONTROL, + p7=87, + want_result=mavutil.mavlink.MAV_RESULT_FAILED, + ) + + self.start_subtest("MAV_MOUNT_MODE_MAVLINK_TARGETING") + r = 15 + p = 20 + y = 30 + method( + mavutil.mavlink.MAV_CMD_DO_MOUNT_CONTROL, + p1=p, + p2=r, + p3=y, + p7=mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING, + ) + self.delay_sim_time(2) + self.assert_mount_rpy(r, p, y) + self.neutralise_gimbal() + + self.start_subtest("MAV_MOUNT_MODE_RC_TARGETING") + method( + mavutil.mavlink.MAV_CMD_DO_MOUNT_CONTROL, + p7=mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, + ) + self.test_mount_rc_targetting() + + self.start_subtest("MAV_MOUNT_MODE_RETRACT") + self.context_push() + retract_r = 13 + retract_p = 23 + retract_y = 33 + self.set_parameters({ + "MNT1_RETRACT_X": retract_r, + "MNT1_RETRACT_Y": retract_p, + "MNT1_RETRACT_Z": retract_y, + }) + method( + mavutil.mavlink.MAV_CMD_DO_MOUNT_CONTROL, + p7=mavutil.mavlink.MAV_MOUNT_MODE_RETRACT, + ) + self.delay_sim_time(3) + self.assert_mount_rpy(retract_r, retract_p, retract_y) + self.context_pop() + + 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, + p1=37, + p2=38, + ) + self.assert_received_message_field_values('GIMBAL_MANAGER_STATUS', { + "gimbal_device_id": 1, + "primary_control_sysid": 37, + "primary_control_compid": 38, + }) + + self.start_subtest("leave unchanged") + method(mavutil.mavlink.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE, p1=-1) + self.assert_received_message_field_values('GIMBAL_MANAGER_STATUS', { + "gimbal_device_id": 1, + "primary_control_sysid": 37, + "primary_control_compid": 38, + }) + + # ardupilot currently handles this incorrectly: + # self.start_subtest("self-controlled") + # method(mavutil.mavlink.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE, p1=-2) + # self.assert_received_message_field_values('GIMBAL_MANAGER_STATUS', { + # "gimbal_device_id": 1, + # "primary_control_sysid": 1, + # "primary_control_compid": 1, + # }) + + self.start_subtest("release control") + method( + mavutil.mavlink.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE, + p1=self.mav.source_system, + p2=self.mav.source_component, + ) + self.assert_received_message_field_values('GIMBAL_MANAGER_STATUS', { + "gimbal_device_id": 1, + "primary_control_sysid": self.mav.source_system, + "primary_control_compid": self.mav.source_component, + }) + method(mavutil.mavlink.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE, p1=-3) + self.assert_received_message_field_values('GIMBAL_MANAGER_STATUS', { + "gimbal_device_id": 1, + "primary_control_sysid": 0, + "primary_control_compid": 0, + }) + + self.context_pop() + self.reboot_sitl() + def MountYawVehicleForMountROI(self): '''Test Camera/Antenna Mount vehicle yawing for ROI''' self.context_push() @@ -6811,6 +7097,7 @@ def ProximitySensors(self): failed = False wants = [] gots = [] + epsilon = 20 while True: if self.get_sim_time_cached() - tstart > 30: raise AutoTestTimeoutException("Failed to get distances") @@ -6823,7 +7110,7 @@ def ProximitySensors(self): want = expected_distances_copy[m.orientation] wants.append(want) gots.append(got) - if abs(want - got) > 5: + if abs(want - got) > epsilon: failed = True del expected_distances_copy[m.orientation] if failed: @@ -6891,7 +7178,7 @@ def shove(a, b): if self.get_sim_time_cached() - tstart > 10: break vel = self.get_body_frame_velocity() - if vel.length() > 0.3: + if vel.length() > 0.5: raise NotAchievedException("Moved too much (%s)" % (str(vel),)) shove(None, None) @@ -7388,6 +7675,38 @@ def AuxFunctionsInMission(self): self.change_mode('AUTO') self.wait_rtl_complete() + def MAV_CMD_AIRFRAME_CONFIGURATION(self): + '''deploy/retract landing gear using mavlink command''' + self.context_push() + self.set_parameters({ + "LGR_ENABLE": 1, + "SERVO10_FUNCTION": 29, + "SERVO10_MIN": 1001, + "SERVO10_MAX": 1999, + }) + self.reboot_sitl() + + # starts loose: + self.wait_servo_channel_value(10, 0) + + # 0 is down: + self.start_subtest("Put gear down") + self.run_cmd(mavutil.mavlink.MAV_CMD_AIRFRAME_CONFIGURATION, p2=0) + self.wait_servo_channel_value(10, 1999) + + # 1 is up: + self.start_subtest("Put gear up") + self.run_cmd_int(mavutil.mavlink.MAV_CMD_AIRFRAME_CONFIGURATION, p2=1) + self.wait_servo_channel_value(10, 1001) + + # 0 is down: + self.start_subtest("Put gear down") + self.run_cmd(mavutil.mavlink.MAV_CMD_AIRFRAME_CONFIGURATION, p2=0) + self.wait_servo_channel_value(10, 1999) + + self.context_pop() + self.reboot_sitl() + def WatchAlts(self): '''Ensure we can monitor different altitudes''' self.takeoff(30, mode='GUIDED') @@ -7682,29 +8001,19 @@ def fly_rangefinder_mavlink_distance_sensor(self): def GSF(self): '''test the Gaussian Sum filter''' - ex = None self.context_push() - try: - self.set_parameter("EK2_ENABLE", 1) - self.reboot_sitl() - self.takeoff(20, mode='LOITER') - self.set_rc(2, 1400) - self.delay_sim_time(5) - self.set_rc(2, 1500) - self.progress("Path: %s" % self.current_onboard_log_filepath()) - dfreader = self.dfreader_for_current_onboard_log() - self.do_RTL() - except Exception as e: - self.progress("Caught exception: %s" % - self.get_exception_stacktrace(e)) - ex = e - + self.set_parameter("EK2_ENABLE", 1) + self.reboot_sitl() + self.takeoff(20, mode='LOITER') + self.set_rc(2, 1400) + self.delay_sim_time(5) + self.set_rc(2, 1500) + self.progress("Path: %s" % self.current_onboard_log_filepath()) + dfreader = self.dfreader_for_current_onboard_log() + self.do_RTL() self.context_pop() self.reboot_sitl() - if ex is not None: - raise ex - # ensure log messages present want = set(["XKY0", "XKY1", "NKY0", "NKY1"]) still_want = want @@ -7714,6 +8023,46 @@ def GSF(self): raise NotAchievedException("Did not get %s" % want) still_want.remove(m.get_type()) + def GSF_reset(self): + '''test the Gaussian Sum filter based Emergency reset''' + self.context_push() + self.set_parameters({ + "COMPASS_ORIENT": 4, # yaw 180 + "COMPASS_USE2": 0, # disable backup compasses to avoid pre-arm failures + "COMPASS_USE3": 0, + }) + self.reboot_sitl() + self.change_mode('GUIDED') + self.wait_ready_to_arm() + + # record starting position + startpos = self.mav.recv_match(type='LOCAL_POSITION_NED', blocking=True) + self.progress("startpos=%s" % str(startpos)) + + # arm vehicle and takeoff to at least 5m + self.arm_vehicle() + expected_alt = 5 + self.user_takeoff(alt_min=expected_alt) + + # watch for emergency yaw reset + self.wait_text("EKF3 IMU. emergency yaw reset", timeout=5, regex=True) + + # record how far vehicle flew off + endpos = self.mav.recv_match(type='LOCAL_POSITION_NED', blocking=True) + delta_x = endpos.x - startpos.x + delta_y = endpos.y - startpos.y + dist_m = math.sqrt(delta_x*delta_x + delta_y*delta_y) + self.progress("GSF yaw reset triggered at %f meters" % dist_m) + + self.do_RTL() + self.context_pop() + self.reboot_sitl() + + # ensure vehicle did not fly too far + dist_m_max = 8 + if dist_m > dist_m_max: + raise NotAchievedException("GSF reset failed, vehicle flew too far (%f > %f)" % (dist_m, dist_m_max)) + def fly_rangefinder_mavlink(self): self.fly_rangefinder_mavlink_distance_sensor() @@ -8269,6 +8618,7 @@ def FlyEachFrame(self): 'heli': "wrong binary, different takeoff regime", 'heli-gas': "wrong binary, different takeoff regime", 'heli-blade360': "wrong binary, different takeoff regime", + "quad-can" : "needs CAN periph", } for frame in sorted(copter_vinfo_options["frames"].keys()): self.start_subtest("Testing frame (%s)" % str(frame)) @@ -8287,7 +8637,7 @@ def FlyEachFrame(self): # to carry the path to the JSON. actual_model = model.split(":")[0] defaults = self.model_defaults_filepath(actual_model) - if type(defaults) != list: + if not isinstance(defaults, list): defaults = [defaults] self.customise_SITL_commandline( ["--defaults", ','.join(defaults), ], @@ -8299,7 +8649,7 @@ def FlyEachFrame(self): def verify_yaw(mav, m): if m.get_type() != 'ATTITUDE': return - yawspeed_thresh_rads = math.radians(10) + yawspeed_thresh_rads = math.radians(20) if m.yawspeed > yawspeed_thresh_rads: raise NotAchievedException("Excessive yaw on takeoff: %f deg/s > %f deg/s (frame=%s)" % (math.degrees(m.yawspeed), math.degrees(yawspeed_thresh_rads), frame)) @@ -8659,7 +9009,7 @@ def GroundEffectCompensation_takeOffExpected(self): raise NotAchievedException("Was expecting takeoff for longer than expected; got=%f want<=%f" % (duration, want_lt)) - def MAV_CMD_CONDITION_YAW_absolute(self): + def _MAV_CMD_CONDITION_YAW(self, command): self.start_subtest("absolute") self.takeoff(20, mode='GUIDED') @@ -8668,7 +9018,7 @@ def MAV_CMD_CONDITION_YAW_absolute(self): self.progress("Ensuring initial heading is steady") target = initial_heading - self.run_cmd( + command( mavutil.mavlink.MAV_CMD_CONDITION_YAW, p1=target, # target angle p2=10, # degrees/second @@ -8676,6 +9026,7 @@ def MAV_CMD_CONDITION_YAW_absolute(self): p4=0, # 1 for relative, 0 for absolute ) self.wait_heading(target, minimum_duration=2, timeout=50) + self.wait_yaw_speed(0) degsecond = 2 @@ -8689,7 +9040,7 @@ def rate_watcher(mav, m): self.progress("Yaw CW 60 degrees") target = initial_heading + 60 part_way_target = initial_heading + 10 - self.run_cmd( + command( mavutil.mavlink.MAV_CMD_CONDITION_YAW, p1=target, # target angle p2=degsecond, # degrees/second @@ -8702,7 +9053,7 @@ def rate_watcher(mav, m): self.progress("Yaw CCW 60 degrees") target = initial_heading part_way_target = initial_heading + 30 - self.run_cmd( + command( mavutil.mavlink.MAV_CMD_CONDITION_YAW, p1=target, # target angle p2=degsecond, # degrees/second @@ -8712,15 +9063,17 @@ def rate_watcher(mav, m): self.wait_heading(part_way_target) self.wait_heading(target, minimum_duration=2) - self.do_RTL() - - def MAV_CMD_CONDITION_YAW_relative(self): - pass + self.disarm_vehicle(force=True) + self.reboot_sitl() def MAV_CMD_CONDITION_YAW(self): - '''Test response to MAV_CMD_CONDITION_YAW''' - self.MAV_CMD_CONDITION_YAW_absolute() - self.MAV_CMD_CONDITION_YAW_relative() + '''Test response to MAV_CMD_CONDITION_YAW via mavlink''' + self.context_push() + self._MAV_CMD_CONDITION_YAW(self.run_cmd_int) + self.context_pop() + self.context_push() + self._MAV_CMD_CONDITION_YAW(self.run_cmd) + self.context_pop() def GroundEffectCompensation_touchDownExpected(self): '''Test EKF's handling of touchdown-expected''' @@ -9527,7 +9880,7 @@ def tests1a(self): self.GuidedSubModeChange, self.MAV_CMD_CONDITION_YAW, self.LoiterToAlt, - self.PayLoadPlaceMission, + self.PayloadPlaceMission, self.PrecisionLoiterCompanion, self.Landing, self.PrecisionLanding, @@ -9548,6 +9901,7 @@ def tests1b(self): self.BrakeMode, self.RecordThenPlayMission, self.ThrottleFailsafe, + self.ThrottleFailsafePassthrough, self.GCSFailsafe, self.CustomController, ]) @@ -9619,6 +9973,8 @@ def tests1e(self): self.RTLSpeed, self.Mount, self.MountYawVehicleForMountROI, + self.MAV_CMD_DO_MOUNT_CONTROL, + self.MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE, self.Button, self.ShipTakeoff, self.RangeFinder, @@ -9643,6 +9999,10 @@ def tests1e(self): self.IE24, self.MAVLandedStateTakeoff, self.Weathervane, + self.MAV_CMD_AIRFRAME_CONFIGURATION, + self.MAV_CMD_NAV_LOITER_UNLIM, + self.MAV_CMD_NAV_RETURN_TO_LAUNCH, + self.MAV_CMD_NAV_VTOL_LAND, ]) return ret @@ -9836,6 +10196,178 @@ def RPLidarA1(self): self.test_rplidar("rplidara1", expected_distances) + def BrakeZ(self): + '''check jerk limit correct in Brake mode''' + self.set_parameter('PSC_JERK_Z', 3) + self.takeoff(50, mode='GUIDED') + vx, vy, vz_up = (0, 0, -1) + self.test_guided_local_velocity_target(vx=vx, vy=vy, vz_up=vz_up, timeout=10) + + self.wait_for_local_velocity(vx=vx, vy=vy, vz_up=vz_up, timeout=10) + self.change_mode('BRAKE') + self.wait_for_local_velocity(vx=0, vy=0, vz_up=0, timeout=10) + self.land_and_disarm() + + def MISSION_START(self): + '''test mavlink command MAV_CMD_MISSION_START''' + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 200), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + for command in self.run_cmd, self.run_cmd_int: + self.change_mode('LOITER') + self.set_current_waypoint(1) + self.wait_ready_to_arm() + self.arm_vehicle() + self.change_mode('AUTO') + command(mavutil.mavlink.MAV_CMD_MISSION_START) + self.wait_altitude(20, 1000, relative=True) + self.change_mode('RTL') + self.wait_disarmed() + + def DO_CHANGE_SPEED_in_guided(self): + '''test Copter DO_CHANGE_SPEED handling in guided mode''' + self.takeoff(20, mode='GUIDED') + + new_loc = self.mav.location() + new_loc_offset_n = 2000 + new_loc_offset_e = 0 + self.location_offset_ne(new_loc, new_loc_offset_n, new_loc_offset_e) + + second_loc_offset_n = -1000 + second_loc_offset_e = 0 + second_loc = self.mav.location() + self.location_offset_ne(second_loc, second_loc_offset_n, second_loc_offset_e) + + # for run_cmd we fly away from home + for (tloc, command) in (new_loc, self.run_cmd), (second_loc, self.run_cmd_int): + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_DO_REPOSITION, + p1=-1, # "default" + p2=0, # flags; none supplied here + p3=0, # loiter radius for planes, zero ignored + p4=float("nan"), # nan means do whatever you want to do + p5=int(tloc.lat * 1e7), + p6=int(tloc.lng * 1e7), + p7=tloc.alt, + frame=mavutil.mavlink.MAV_FRAME_GLOBAL, + ) + for speed in [2, 10, 4]: + command( + mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, + p1=1, # groundspeed, + p2=speed, + p3=-1, # throttle, -1 is no-change + p4=0, # absolute value, not relative + ) + self.wait_groundspeed(speed-0.2, speed+0.2, minimum_duration=10, timeout=20) + + # we've made random changes to vehicle guided speeds above; + # reboot vehicle to reset those: + self.disarm_vehicle(force=True) + self.reboot_sitl() + + def _MAV_CMD_DO_FLIGHTTERMINATION(self, command): + self.set_parameters({ + "SYSID_MYGCS": self.mav.source_system, + "DISARM_DELAY": 0, + }) + self.wait_ready_to_arm() + self.arm_vehicle() + self.context_collect('STATUSTEXT') + command(mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION, p1=1) + self.wait_disarmed() + self.reboot_sitl() + + def MAV_CMD_DO_FLIGHTTERMINATION(self): + '''test MAV_CMD_DO_FLIGHTTERMINATION works on Copter''' + self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd) + self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd_int) + + def MAV_CMD_NAV_LOITER_UNLIM(self): + '''ensure MAV_CMD_NAV_LOITER_UNLIM via mavlink works''' + for command in self.run_cmd, self.run_cmd_int: + self.change_mode('STABILIZE') + command(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM) + self.wait_mode('LOITER') + + def MAV_CMD_NAV_RETURN_TO_LAUNCH(self): + '''ensure MAV_CMD_NAV_RETURN_TO_LAUNCH via mavlink works''' + for command in self.run_cmd, self.run_cmd_int: + self.change_mode('STABILIZE') + command(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH) + self.wait_mode('RTL') + + def MAV_CMD_NAV_VTOL_LAND(self): + '''ensure MAV_CMD_NAV_LAND via mavlink works''' + for command in self.run_cmd, self.run_cmd_int: + self.change_mode('STABILIZE') + command(mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND) + self.wait_mode('LAND') + self.change_mode('STABILIZE') + command(mavutil.mavlink.MAV_CMD_NAV_LAND) + self.wait_mode('LAND') + + def start_flying_simple_rehome_mission(self, items): + '''uploads items, changes mode to auto, waits ready to arm and arms + vehicle. If the first item it a takeoff you can expect the + vehicle to fly after this method returns + ''' + + self.upload_simple_relhome_mission(items) + + self.set_parameter("AUTO_OPTIONS", 3) + self.change_mode('AUTO') + self.wait_ready_to_arm() + + self.arm_vehicle() + + def _MAV_CMD_DO_LAND_START(self, run_cmd): + alt = 5 + self.start_flying_simple_rehome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, alt), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 200, 0, alt), + (mavutil.mavlink.MAV_CMD_NAV_LAND, 0, 0, 0), + (mavutil.mavlink.MAV_CMD_DO_LAND_START, 0, 0, alt), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 200, 2000, alt), + (mavutil.mavlink.MAV_CMD_NAV_LAND, 0, 0, 0), + ]) + + self.wait_current_waypoint(2) + run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START) + self.wait_current_waypoint(5) + # we pretend to be in RTL mode while doing this: + self.wait_mode("AUTO_RTL") + self.do_RTL() + + def MAV_CMD_DO_LAND_START(self): + '''test handling of mavlink-received MAV_CMD_DO_LAND_START command''' + self._MAV_CMD_DO_LAND_START(self.run_cmd) + self.zero_throttle() + self._MAV_CMD_DO_LAND_START(self.run_cmd_int) + + def _MAV_CMD_SET_EKF_SOURCE_SET(self, run_cmd): + run_cmd( + mavutil.mavlink.MAV_CMD_SET_EKF_SOURCE_SET, + 17, + want_result=mavutil.mavlink.MAV_RESULT_DENIED, + ) + + self.change_mode('LOITER') + self.wait_ready_to_arm() + + run_cmd(mavutil.mavlink.MAV_CMD_SET_EKF_SOURCE_SET, 2) + + self.assert_prearm_failure('Need Position Estimate') + run_cmd(mavutil.mavlink.MAV_CMD_SET_EKF_SOURCE_SET, 1) + + self.wait_ready_to_arm() + + def MAV_CMD_SET_EKF_SOURCE_SET(self): + '''test setting of source sets using mavlink command''' + self._MAV_CMD_SET_EKF_SOURCE_SET(self.run_cmd) + self._MAV_CMD_SET_EKF_SOURCE_SET(self.run_cmd_int) + def tests2b(self): # this block currently around 9.5mins here '''return list of all tests''' ret = ([ @@ -9856,6 +10388,7 @@ def tests2b(self): # this block currently around 9.5mins here self.AltEstimation, self.EKFSource, self.GSF, + self.GSF_reset, self.AP_Avoidance, self.SMART_RTL, self.RTL_TO_RALLY, @@ -9871,10 +10404,12 @@ def tests2b(self): # this block currently around 9.5mins here 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, self.DefaultIntervalsFromFiles, @@ -9892,9 +10427,14 @@ def tests2b(self): # this block currently around 9.5mins here self.AHRSTrimLand, self.GuidedYawRate, self.NoArmWithoutMissionItems, + self.DO_CHANGE_SPEED_in_guided, self.RPLidarA1, self.RPLidarA2, self.SafetySwitch, + self.BrakeZ, + self.MAV_CMD_DO_FLIGHTTERMINATION, + self.MAV_CMD_DO_LAND_START, + self.MAV_CMD_SET_EKF_SOURCE_SET, ]) return ret diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index f0de1a488f9ba5..cec10da0ae2263 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -21,8 +21,11 @@ from common import PreconditionFailedException from common import WaitModeTimeout from common import OldpymavlinkException +from common import Test + from pymavlink.rotmat import Vector3 from pysim import vehicleinfo +from pysim import util import operator @@ -91,9 +94,26 @@ def get_disarm_delay(self): def set_autodisarm_delay(self, delay): self.set_parameter("LAND_DISARMDELAY", delay) - def takeoff(self, alt=150, alt_max=None, relative=True): + def takeoff(self, alt=150, alt_max=None, relative=True, mode=None, timeout=None): """Takeoff to altitude.""" + if mode == "TAKEOFF": + return self.takeoff_in_TAKEOFF(alt=alt, relative=relative, timeout=timeout) + + return self.takeoff_in_FBWA(alt=alt, alt_max=alt_max, relative=relative, timeout=timeout) + + def takeoff_in_TAKEOFF(self, alt=150, relative=True, mode=None, alt_epsilon=2, timeout=None): + if relative is not True: + raise ValueError("Only relative alt supported ATM") + self.change_mode("TAKEOFF") + self.context_push() + self.set_parameter('TKOFF_ALT', alt) + self.wait_ready_to_arm() + self.arm_vehicle() + self.wait_altitude(alt-alt_epsilon, alt+alt_epsilon, relative=True, timeout=timeout) + self.context_pop() + + def takeoff_in_FBWA(self, alt=150, alt_max=None, relative=True, mode=None, timeout=30): if alt_max is None: alt_max = alt + 30 @@ -126,7 +146,7 @@ def takeoff(self, alt=150, alt_max=None, relative=True): }) # gain a bit of altitude - self.wait_altitude(alt, alt_max, timeout=30, relative=relative) + self.wait_altitude(alt, alt_max, timeout=timeout, relative=relative) # level off self.set_rc(2, 1500) @@ -768,18 +788,18 @@ def fly_deepstall_relative(self): self.change_mode("AUTO") self.wait_ready_to_arm() self.arm_vehicle() - self.progress("Waiting for deepstall messages") - - # note that the following two don't necessarily happen in this - # order, but at very high speedups we may miss the elevator - # PWM if we first look for the text (due to the get_sim_time() - # in wait_servo_channel_value) - self.context_collect('STATUSTEXT') + self.wait_current_waypoint(4) # assume elevator is on channel 2: self.wait_servo_channel_value(2, deepstall_elevator_pwm, timeout=240) - self.wait_text("Deepstall: Entry: ", check_context=True, timeout=60) + self.progress("Waiting for stage DEEPSTALL_STAGE_LAND") + self.assert_receive_message( + 'DEEPSTALL', + condition='DEEPSTALL.stage==6', + timeout=240, + ) + self.progress("Reached stage DEEPSTALL_STAGE_LAND") self.disarm_wait(timeout=120) self.set_current_waypoint(0, check_afterwards=False) @@ -817,18 +837,36 @@ def SmartBattery(self): if not self.current_onboard_log_contains_message("BCL2"): raise NotAchievedException("Expected BCL2 message") - def DO_CHANGE_SPEED(self): - '''Test DO_CHANGE_SPEED command/item''' + def context_push_do_change_speed(self): # the following lines ensure we revert these parameter values # - DO_CHANGE_AIRSPEED is a permanent vehicle change! + self.context_push() self.set_parameters({ "TRIM_ARSPD_CM": self.get_parameter("TRIM_ARSPD_CM"), "MIN_GNDSPD_CM": self.get_parameter("MIN_GNDSPD_CM"), + "TRIM_THROTTLE": self.get_parameter("TRIM_THROTTLE"), + }) + + def DO_CHANGE_SPEED(self): + '''Test DO_CHANGE_SPEED command/item''' + self.set_parameters({ "RTL_AUTOLAND": 1, }) - self.DO_CHANGE_SPEED_mavlink() + self.context_push_do_change_speed() + self.DO_CHANGE_SPEED_mavlink_long() + self.context_pop() + + self.set_current_waypoint(1) + self.zero_throttle() + + self.context_push_do_change_speed() + self.DO_CHANGE_SPEED_mavlink_int() + self.context_pop() + + self.context_push_do_change_speed() self.DO_CHANGE_SPEED_mission() + self.context_pop() def DO_CHANGE_SPEED_mission(self): '''test DO_CHANGE_SPEED as a mission item''' @@ -858,10 +896,16 @@ def DO_CHANGE_SPEED_mission(self): self.fly_home_land_and_disarm() - def DO_CHANGE_SPEED_mavlink(self): + def DO_CHANGE_SPEED_mavlink_int(self): + self.DO_CHANGE_SPEED_mavlink(self.run_cmd_int) + + def DO_CHANGE_SPEED_mavlink_long(self): + self.DO_CHANGE_SPEED_mavlink(self.run_cmd) + + def DO_CHANGE_SPEED_mavlink(self, run_cmd_method): '''test DO_CHANGE_SPEED as a mavlink command''' self.progress("Takeoff") - self.takeoff(alt=100) + self.takeoff(alt=100, mode="TAKEOFF", timeout=120) self.set_rc(3, 1500) # ensure we know what the airspeed is: self.progress("Entering guided and flying somewhere constant") @@ -878,24 +922,24 @@ def DO_CHANGE_SPEED_mavlink(self): timeout = 15 self.wait_airspeed(initial_speed-1, initial_speed+1, minimum_duration=5, timeout=timeout) - self.progress("Setting groundspeed") - new_target_groundspeed = initial_speed + 5 - self.run_cmd( - mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, - p1=1, # groundspeed - p2=new_target_groundspeed, - p3=-1, # throttle / no change - p4=0, # absolute values - ) - self.wait_groundspeed(new_target_groundspeed-0.5, new_target_groundspeed+0.5, timeout=40) - self.progress("Adding some wind, ensuring groundspeed holds") - self.set_parameter("SIM_WIND_SPD", 5) - self.delay_sim_time(5) - self.wait_groundspeed(new_target_groundspeed-0.5, new_target_groundspeed+0.5, timeout=40) - self.set_parameter("SIM_WIND_SPD", 0) + self.start_subtest("Setting groundspeed") + for new_target_groundspeed in initial_speed + 5, initial_speed + 2: + run_cmd_method( + mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, + p1=1, # groundspeed + p2=new_target_groundspeed, + p3=-1, # throttle / no change + p4=0, # absolute values + ) + self.wait_groundspeed(new_target_groundspeed-2, new_target_groundspeed+2, timeout=80, minimum_duration=5) + self.progress("Adding some wind, ensuring groundspeed holds") + self.set_parameter("SIM_WIND_SPD", 5) + self.delay_sim_time(5) + self.wait_groundspeed(new_target_groundspeed-2, new_target_groundspeed+2, timeout=40, minimum_duration=5) + self.set_parameter("SIM_WIND_SPD", 0) # clear target groundspeed - self.run_cmd( + run_cmd_method( mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, p1=1, # groundspeed p2=0, @@ -903,16 +947,18 @@ def DO_CHANGE_SPEED_mavlink(self): p4=0, # absolute values ) - self.progress("Setting airspeed") - new_target_airspeed = initial_speed + 5 - self.run_cmd( - mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, - p1=0, # airspeed - p2=new_target_airspeed, - p3=-1, # throttle / no change - p4=0, # absolute values - ) - self.wait_airspeed(new_target_airspeed-0.5, new_target_airspeed+0.5) + self.start_subtest("Setting airspeed") + for new_target_airspeed in initial_speed - 5, initial_speed + 5: + run_cmd_method( + mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, + p1=0, # airspeed + p2=new_target_airspeed, + p3=-1, # throttle / no change + p4=0, # absolute values + ) + self.wait_airspeed(new_target_airspeed-2, new_target_airspeed+2, minimum_duration=5) + + self.context_push() self.progress("Adding some wind, hoping groundspeed increases/decreases") self.set_parameters({ "SIM_WIND_SPD": 7, @@ -930,6 +976,39 @@ def DO_CHANGE_SPEED_mavlink(self): self.progress("groundspeed and airspeed should be different (have=%f want=%f)" % (delta, want_delta)) if delta > want_delta: break + self.context_pop() + + # cancel minimum groundspeed: + run_cmd_method( + mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, + p1=0, # groundspeed + p2=-2, # return to default + p3=0, # throttle / no change + p4=0, # absolute values + ) + # cancel airspeed: + run_cmd_method( + mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, + p1=1, # airspeed + p2=-2, # return to default + p3=0, # throttle / no change + p4=0, # absolute values + ) + + self.start_subtest("Setting throttle") + self.set_parameter('ARSPD_USE', 0) # setting throttle only effective without airspeed + for (set_throttle, expected_throttle) in (97, 79), (60, 51), (95, 77): + run_cmd_method( + mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, + p1=3, # throttle + p2=0, + p3=set_throttle, # throttle / no change + p4=0, # absolute values + ) + self.wait_message_field_values('VFR_HUD', { + "throttle": expected_throttle, + }, minimum_duration=5, epsilon=2) + self.fly_home_land_and_disarm(timeout=240) def fly_home_land_and_disarm(self, timeout=120): @@ -1127,7 +1206,7 @@ def ThrottleFailsafe(self): self.context_collect("HEARTBEAT") self.set_parameter("SIM_RC_FAIL", 2) # throttle-to-950 self.wait_mode('RTL') # long failsafe - if (not self.get_mode_from_mode_mapping("CIRCLE") in + if (self.get_mode_from_mode_mapping("CIRCLE") not in [x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]): raise NotAchievedException("Did not go via circle mode") self.progress("Ensure we've had our throttle squashed to 950") @@ -1165,7 +1244,7 @@ def ThrottleFailsafe(self): self.context_collect("HEARTBEAT") self.set_parameter("SIM_RC_FAIL", 1) # no-pulses self.wait_mode('RTL') # long failsafe - if (not self.get_mode_from_mode_mapping("CIRCLE") in + if (self.get_mode_from_mode_mapping("CIRCLE") not in [x.custom_mode for x in self.context_stop_collecting("HEARTBEAT")]): raise NotAchievedException("Did not go via circle mode") self.do_timesync_roundtrip() @@ -1302,29 +1381,28 @@ def GCSFailsafe(self): '''Ensure Long-Failsafe works on GCS loss''' self.start_subtest("Test Failsafe: RTL") self.load_sample_mission() - self.set_parameter("RTL_AUTOLAND", 1) - self.change_mode("AUTO") - self.takeoff() self.set_parameters({ "FS_GCS_ENABL": 1, "FS_LONG_ACTN": 1, + "RTL_AUTOLAND": 1, + "SYSID_MYGCS": self.mav.source_system, }) + self.takeoff() + self.change_mode('LOITER') self.progress("Disconnecting GCS") self.set_heartbeat_rate(0) - self.wait_mode("RTL", timeout=5) + self.wait_mode("RTL", timeout=10) self.set_heartbeat_rate(self.speedup) self.end_subtest("Completed RTL Failsafe test") self.start_subtest("Test Failsafe: FBWA Glide") self.set_parameters({ - "RTL_AUTOLAND": 1, "FS_LONG_ACTN": 2, }) - self.change_mode("AUTO") - self.takeoff() + self.change_mode('AUTO') self.progress("Disconnecting GCS") self.set_heartbeat_rate(0) - self.wait_mode("FBWA", timeout=5) + self.wait_mode("FBWA", timeout=10) self.set_heartbeat_rate(self.speedup) self.end_subtest("Completed FBWA Failsafe test") @@ -2571,11 +2649,6 @@ def Soaring(self): self.load_mission('CMAC-soar.txt', strict=False) - self.set_current_waypoint(1) - self.change_mode('AUTO') - self.wait_ready_to_arm() - self.arm_vehicle() - # Enable thermalling RC rc_chan = 0 for i in range(8): @@ -2589,15 +2662,22 @@ def Soaring(self): self.set_rc_from_map({ rc_chan: 1900, - 3: 1500, # Use trim airspeed. }) + self.set_parameters({ + "SOAR_VSPEED": 0.55, + "SOAR_MIN_THML_S": 25, + }) + + self.set_current_waypoint(1) + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + # Wait to detect thermal self.progress("Waiting for thermal") self.wait_mode('THERMAL', timeout=600) - self.set_parameter("SOAR_VSPEED", 0.6) - # Wait to climb to SOAR_ALT_MAX self.progress("Waiting for climb to max altitude") alt_max = self.get_parameter('SOAR_ALT_MAX') @@ -3072,7 +3152,7 @@ def WindEstimates(self): self.wait_and_maintain_wind_estimate( 5, 45, speed_tolerance=1, - timeout=20 + timeout=30 ) self.fly_home_land_and_disarm() @@ -3080,9 +3160,9 @@ def VectorNavEAHRS(self): '''Test VectorNav EAHRS support''' self.fly_external_AHRS("VectorNav", 1, "ap1.txt") - def LordEAHRS(self): - '''Test LORD Microstrain EAHRS support''' - self.fly_external_AHRS("LORD", 2, "ap1.txt") + def MicroStrainEAHRS5(self): + '''Test MicroStrain EAHRS series 5 support''' + self.fly_external_AHRS("MicroStrain5", 2, "ap1.txt") def get_accelvec(self, m): return Vector3(m.xacc, m.yacc, m.zacc) * 0.001 * 9.81 @@ -3713,29 +3793,36 @@ def attempt_fence_breached_disable(start_mode, end_mode, expected_mode, action): attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=6) attempt_fence_breached_disable(start_mode="FBWA", end_mode="FBWA", expected_mode="GUIDED", action=7) - def MAV_DO_AUX_FUNCTION(self): + def _MAV_CMD_DO_AUX_FUNCTION(self, run_cmd): '''Test triggering Auxiliary Functions via mavlink''' self.context_collect('STATUSTEXT') - self.run_auxfunc(64, 2) # 64 == reverse throttle + self.run_auxfunc(64, 2, run_cmd=run_cmd) # 64 == reverse throttle self.wait_statustext("RevThrottle: ENABLE", check_context=True) - self.run_auxfunc(64, 0) + self.run_auxfunc(64, 0, run_cmd=run_cmd) self.wait_statustext("RevThrottle: DISABLE", check_context=True) - self.run_auxfunc(65, 2) # 65 == GPS_DISABLE + self.run_auxfunc(65, 2, run_cmd=run_cmd) # 65 == GPS_DISABLE self.start_subtest("Bad auxfunc") self.run_auxfunc( 65231, 2, - want_result=mavutil.mavlink.MAV_RESULT_FAILED + want_result=mavutil.mavlink.MAV_RESULT_FAILED, + run_cmd=run_cmd, ) self.start_subtest("Bad switchpos") self.run_auxfunc( 62, 17, - want_result=mavutil.mavlink.MAV_RESULT_DENIED + want_result=mavutil.mavlink.MAV_RESULT_DENIED, + run_cmd=run_cmd, ) + def MAV_CMD_DO_AUX_FUNCTION(self): + '''Test triggering Auxiliary Functions via mavlink''' + self._MAV_CMD_DO_AUX_FUNCTION(run_cmd=self.run_cmd) + self._MAV_CMD_DO_AUX_FUNCTION(run_cmd=self.run_cmd_int) + def FlyEachFrame(self): '''Fly each supported internal frame''' vinfo = vehicleinfo.VehicleInfo() @@ -3748,6 +3835,7 @@ def FlyEachFrame(self): "quadplane-tilttrivec": "loses attitude control and crashes", "plane-ice" : "needs ICE control channel for ignition", "quadplane-ice" : "needs ICE control channel for ignition", + "quadplane-can" : "needs CAN periph", } for frame in sorted(vinfo_options["frames"].keys()): self.start_subtest("Testing frame (%s)" % str(frame)) @@ -3766,7 +3854,7 @@ def FlyEachFrame(self): # to carry the path to the JSON. actual_model = model.split(":")[0] defaults = self.model_defaults_filepath(actual_model) - if type(defaults) != list: + if not isinstance(defaults, list): defaults = [defaults] self.customise_SITL_commandline( ["--defaults", ','.join(defaults), ], @@ -3911,6 +3999,18 @@ def AUTOTUNE(self): 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) @@ -4622,6 +4722,309 @@ def AirspeedCal(self): self.reboot_sitl() + def RunMissionScript(self): + '''Test run_mission.py script''' + script = os.path.join('Tools', 'autotest', 'run_mission.py') + self.stop_SITL() + util.run_cmd([ + util.reltopdir(script), + self.binary, + 'plane', + self.generic_mission_filepath_for_filename("flaps.txt"), + ]) + self.start_SITL() + + def MAV_CMD_GUIDED_CHANGE_ALTITUDE(self): + '''test handling of MAV_CMD_GUIDED_CHANGE_ALTITUDE''' + self.takeoff(30, relative=True) + self.change_mode('GUIDED') + for alt in 50, 70: + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_GUIDED_CHANGE_ALTITUDE, + p7=alt, + frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, + ) + self.wait_altitude(alt-1, alt+1, timeout=30, relative=True) + + # test for #24535 + self.change_mode('LOITER') + self.delay_sim_time(5) + self.change_mode('GUIDED') + self.wait_altitude( + alt-3, # NOTE: reuse of alt from above loop! + alt+3, + minimum_duration=10, + timeout=30, + relative=True, + ) + self.fly_home_land_and_disarm() + + def _MAV_CMD_PREFLIGHT_CALIBRATION(self, command): + self.context_push() + self.start_subtest("Denied when armed") + self.wait_ready_to_arm() + self.arm_vehicle() + command( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p1=1, + want_result=mavutil.mavlink.MAV_RESULT_FAILED, + ) + self.disarm_vehicle() + + self.context_collect('STATUSTEXT') + + self.start_subtest("gyro cal") + command( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p1=1, + ) + + self.start_subtest("baro cal") + command( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p3=1, + ) + self.wait_statustext('Barometer calibration complete', check_context=True) + + # accelcal skipped here, it is checked elsewhere + + self.start_subtest("ins trim") + command( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p5=2, + ) + + # enforced delay between cals: + self.delay_sim_time(5) + + self.start_subtest("simple accel cal") + command( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p5=4, + ) + # simple gyro cal makes the GPS units go unhealthy as they are + # not maintaining their update rate (gyro cal is synchronous + # in the main loop). Usually ~30 seconds to recover... + self.wait_gps_sys_status_not_present_or_enabled_and_healthy(timeout=60) + + self.start_subtest("force save accels") + command( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p5=76, + ) + + self.start_subtest("force save compasses") + command( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p2=76, + ) + + self.context_pop() + + def MAV_CMD_PREFLIGHT_CALIBRATION(self): + '''test MAV_CMD_PREFLIGHT_CALIBRATION mavlink handling''' + self._MAV_CMD_PREFLIGHT_CALIBRATION(self.run_cmd) + self._MAV_CMD_PREFLIGHT_CALIBRATION(self.run_cmd_int) + + def MAV_CMD_DO_INVERTED_FLIGHT(self): + '''fly upside-down mission item''' + alt = 30 + wps = self.create_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, alt), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 400, 0, alt), + self.create_MISSION_ITEM_INT( + mavutil.mavlink.MAV_CMD_DO_INVERTED_FLIGHT, + p1=1, + ), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, alt), + self.create_MISSION_ITEM_INT( + mavutil.mavlink.MAV_CMD_DO_INVERTED_FLIGHT, + p1=0, + ), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 1200, 0, alt), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + self.check_mission_upload_download(wps) + + self.change_mode('AUTO') + self.wait_ready_to_arm() + + self.arm_vehicle() + + self.wait_current_waypoint(2) # upright flight + self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", { + "nav_roll": 0, + "nav_pitch": 0, + }, epsilon=10) + + def check_altitude(mav, m): + global initial_airspeed_threshold_reached + m_type = m.get_type() + if m_type != 'GLOBAL_POSITION_INT': + return + if abs(30 - m.relative_alt * 0.001) > 15: + raise NotAchievedException("Bad altitude while flying inverted") + + self.context_push() + self.install_message_hook_context(check_altitude) + + self.wait_current_waypoint(4) # inverted flight + self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", { + "nav_roll": 180, + "nav_pitch": 9, + }, epsilon=10,) + + self.wait_current_waypoint(6) # upright flight + self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", { + "nav_roll": 0, + "nav_pitch": 0, + }, epsilon=10) + + self.context_pop() # remove the check_altitude call + + self.wait_current_waypoint(7) + + self.fly_home_land_and_disarm() + + def MAV_CMD_DO_AUTOTUNE_ENABLE(self): + '''test enabling autotune via mavlink''' + self.context_collect('STATUSTEXT') + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_AUTOTUNE_ENABLE, p1=1) + self.wait_statustext('Started autotune', check_context=True) + self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_AUTOTUNE_ENABLE, p1=0) + self.wait_statustext('Stopped autotune', check_context=True) + + def DO_PARACHUTE(self): + '''test triggering parachute via mavlink''' + self.set_parameters({ + "CHUTE_ENABLED": 1, + "CHUTE_TYPE": 10, + "SERVO9_FUNCTION": 27, + "SIM_PARA_ENABLE": 1, + "SIM_PARA_PIN": 9, + "FS_LONG_ACTN": 3, + }) + for command in self.run_cmd, self.run_cmd_int: + self.wait_servo_channel_value(9, 1100) + self.wait_ready_to_arm() + self.arm_vehicle() + command( + mavutil.mavlink.MAV_CMD_DO_PARACHUTE, + p1=mavutil.mavlink.PARACHUTE_RELEASE, + ) + self.wait_servo_channel_value(9, 1300) + self.disarm_vehicle() + self.reboot_sitl() + + def _MAV_CMD_DO_GO_AROUND(self, command): + self.load_mission("mission.txt") + self.set_parameter("RTL_AUTOLAND", 3) + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + self.wait_current_waypoint(6) + command(mavutil.mavlink.MAV_CMD_DO_GO_AROUND, p1=150) + self.wait_current_waypoint(5) + self.wait_altitude(135, 165, relative=True) + self.wait_disarmed(timeout=300) + + def MAV_CMD_DO_GO_AROUND(self): + '''test MAV_CMD_DO_GO_AROUND as a mavlink command''' + self._MAV_CMD_DO_GO_AROUND(self.run_cmd) + self._MAV_CMD_DO_GO_AROUND(self.run_cmd_int) + + def _MAV_CMD_DO_FLIGHTTERMINATION(self, command): + self.set_parameters({ + "AFS_ENABLE": 1, + "SYSID_MYGCS": self.mav.source_system, + "AFS_TERM_ACTION": 42, + }) + self.wait_ready_to_arm() + self.arm_vehicle() + self.context_collect('STATUSTEXT') + command(mavutil.mavlink.MAV_CMD_DO_FLIGHTTERMINATION, p1=1) + self.wait_disarmed() + self.wait_text('Terminating due to GCS request', check_context=True) + self.reboot_sitl() + + def MAV_CMD_DO_FLIGHTTERMINATION(self): + '''test MAV_CMD_DO_FLIGHTTERMINATION works on Plane''' + self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd) + self._MAV_CMD_DO_FLIGHTTERMINATION(self.run_cmd_int) + + def MAV_CMD_DO_LAND_START(self): + '''test MAV_CMD_DO_LAND_START as mavlink command''' + self.set_parameters({ + "RTL_AUTOLAND": 3, + }) + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30), + (mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM, 0, 0, 30), + self.create_MISSION_ITEM_INT( + mavutil.mavlink.MAV_CMD_DO_LAND_START, + ), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0), + ]) + + self.change_mode('AUTO') + self.wait_ready_to_arm() + + self.arm_vehicle() + + self.start_subtest("DO_LAND_START as COMMAND_LONG") + self.wait_current_waypoint(2) + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_LAND_START) + self.wait_current_waypoint(4) + + self.start_subtest("DO_LAND_START as COMMAND_INT") + self.set_current_waypoint(2) + self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_LAND_START) + self.wait_current_waypoint(4) + + self.fly_home_land_and_disarm() + + def start_flying_simple_rehome_mission(self, items): + '''uploads items, changes mode to auto, waits ready to arm and arms + vehicle. If the first item it a takeoff you can expect the + vehicle to fly after this method returns + ''' + + self.upload_simple_relhome_mission(items) + + self.change_mode('AUTO') + self.wait_ready_to_arm() + + self.arm_vehicle() + + def InteractTest(self): + '''just takeoff''' + + if self.mavproxy is None: + raise NotAchievedException("Must be started with --map") + + self.start_flying_simple_rehome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 800, 0), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 400, 0), + ]) + + self.wait_current_waypoint(4) + + self.set_parameter('SIM_SPEEDUP', 1) + + self.mavproxy.interact() + + def MAV_CMD_MISSION_START(self): + '''test MAV_CMD_MISSION_START starts AUTO''' + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 800, 0, 0), + ]) + for run_cmd in self.run_cmd, self.run_cmd_int: + self.change_mode('LOITER') + run_cmd(mavutil.mavlink.MAV_CMD_MISSION_START) + self.wait_mode('AUTO') + def tests(self): '''return list of all tests''' ret = super(AutoTestPlane, self).tests() @@ -4640,6 +5043,7 @@ def tests(self): self.TestGripperMission, self.Parachute, self.ParachuteSinkRate, + self.DO_PARACHUTE, self.PitotBlockage, self.AIRSPEED_AUTOCAL, self.RangeFinder, @@ -4673,7 +5077,7 @@ def tests(self): self.TerrainMission, self.TerrainLoiter, self.VectorNavEAHRS, - self.LordEAHRS, + self.MicroStrainEAHRS5, self.Deadreckoning, self.DeadreckoningNoAirSpeed, self.EKFlaneswitch, @@ -4681,7 +5085,7 @@ def tests(self): self.RTL_CLIMB_MIN, self.ClimbBeforeTurn, self.IMUTempCal, - self.MAV_DO_AUX_FUNCTION, + self.MAV_CMD_DO_AUX_FUNCTION, self.SmartBattery, self.FlyEachFrame, self.RCDisableAirspeedUse, @@ -4692,6 +5096,7 @@ def tests(self): self.DCMFallback, self.MAVFTP, self.AUTOTUNE, + self.AutotuneFiltering, self.MegaSquirt, self.MSP_DJI, self.SpeedToFly, @@ -4701,19 +5106,30 @@ def tests(self): self.EmbeddedParamParser, self.AerobaticsScripting, self.MANUAL_CONTROL, + self.RunMissionScript, self.WindEstimates, self.AltResetBadGPS, self.AirspeedCal, self.MissionJumpTags, - self.GCSFailsafe, + Test(self.GCSFailsafe, speedup=8), self.SDCardWPTest, self.NoArmWithoutMissionItems, self.MODE_SWITCH_RESET, self.ExternalPositionEstimate, + self.MAV_CMD_GUIDED_CHANGE_ALTITUDE, + self.MAV_CMD_PREFLIGHT_CALIBRATION, + self.MAV_CMD_DO_INVERTED_FLIGHT, + self.MAV_CMD_DO_AUTOTUNE_ENABLE, + self.MAV_CMD_DO_GO_AROUND, + self.MAV_CMD_DO_FLIGHTTERMINATION, + self.MAV_CMD_DO_LAND_START, + self.InteractTest, + self.MAV_CMD_MISSION_START, ]) return ret def disabled_tests(self): return { "LandingDrift": "Flapping test. See https://github.com/ArduPilot/ardupilot/issues/20054", + "InteractTest": "requires user interaction", } diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index a6af0aba9c06c6..230bfbd1838f39 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -373,12 +373,12 @@ def SET_POSITION_TARGET_GLOBAL_INT(self): def reboot_sitl(self): """Reboot SITL instance and wait it to reconnect.""" - # out battery is reset to full on reboot. So reduce it to 10% + # our battery is reset to full on reboot. So reduce it to 10% # and wait for it to go above 50. self.run_cmd( mavutil.mavlink.MAV_CMD_BATTERY_RESET, - p1=255, # battery mask - p2=10, # percentage + p1=65535, # battery mask + p2=10, # percentage ) self.run_cmd_reboot() tstart = time.time() @@ -422,9 +422,100 @@ def disabled_tests(self): ret = super(AutoTestSub, self).disabled_tests() ret.update({ "ConfigErrorLoop": "Sub does not instantiate AP_Stats. Also see https://github.com/ArduPilot/ardupilot/issues/10247", # noqa + "MAV_CMD_DO_CHANGE_SPEED": "Doesn't work", }) return ret + def MAV_CMD_NAV_LOITER_UNLIM(self): + '''test handling of MAV_CMD_NAV_LOITER_UNLIM received via mavlink''' + for cmd in self.run_cmd, self.run_cmd_int: + self.change_mode('CIRCLE') + cmd(mavutil.mavlink.MAV_CMD_NAV_LOITER_UNLIM) + self.assert_mode('POSHOLD') + + def MAV_CMD_NAV_LAND(self): + '''test handling of MAV_CMD_NAV_LAND received via mavlink''' + for cmd in self.run_cmd, self.run_cmd_int: + self.change_mode('CIRCLE') + cmd(mavutil.mavlink.MAV_CMD_NAV_LAND) + self.assert_mode('SURFACE') + + def MAV_CMD_MISSION_START(self): + '''test handling of MAV_CMD_NAV_LAND 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), + ]) + + self.wait_ready_to_arm() + self.arm_vehicle() + for cmd in self.run_cmd, self.run_cmd_int: + self.change_mode('CIRCLE') + cmd(mavutil.mavlink.MAV_CMD_MISSION_START) + self.assert_mode('AUTO') + self.disarm_vehicle() + + def MAV_CMD_DO_CHANGE_SPEED(self): + '''ensure vehicle changes speeds when DO_CHANGE_SPEED received''' + items = [ + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 0), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ] + items = [] + for i in range(0, 2000, 10): + items.append((mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, i, 0, 0)) + self.upload_simple_relhome_mission(items) + + self.wait_ready_to_arm() + self.arm_vehicle() + self.run_cmd(mavutil.mavlink.MAV_CMD_MISSION_START) + for run_cmd in self.run_cmd, self.run_cmd_int: + for speed in [1, 2, 3, 1]: + run_cmd(mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, p2=speed) + self.wait_groundspeed(speed-0.02, speed+0.02, minimum_duration=2) + self.disarm_vehicle() + + def _MAV_CMD_CONDITION_YAW(self, run_cmd): + self.arm_vehicle() + self.change_mode('GUIDED') + for angle in 5, 30, 60, 10: + angular_rate = 10 + direction = 1 + relative_or_absolute = 0 + run_cmd( + mavutil.mavlink.MAV_CMD_CONDITION_YAW, + p1=angle, + p2=angular_rate, + p3=direction, + p4=relative_or_absolute, # 1 for relative, 0 for absolute + ) + self.wait_heading(angle, minimum_duration=2) + + self.start_subtest('Relative angle') + run_cmd( + mavutil.mavlink.MAV_CMD_CONDITION_YAW, + p1=0, + p2=10, + p3=1, + p4=0, # 1 for relative, 0 for absolute + ) + self.wait_heading(0, minimum_duration=2) + run_cmd( + mavutil.mavlink.MAV_CMD_CONDITION_YAW, + p1=20, + p2=10, + p3=1, + p4=1, # 1 for relative, 0 for absolute + ) + self.wait_heading(20, minimum_duration=2) + + self.disarm_vehicle() + + def MAV_CMD_CONDITION_YAW(self): + '''ensure vehicle yaws according to GCS command''' + self._MAV_CMD_CONDITION_YAW(self.run_cmd) + self._MAV_CMD_CONDITION_YAW(self.run_cmd_int) + def tests(self): '''return list of all tests''' ret = super(AutoTestSub, self).tests() @@ -440,6 +531,11 @@ def tests(self): self.MotorThrustHoverParameterIgnore, self.SET_POSITION_TARGET_GLOBAL_INT, self.TestLogDownloadMAVProxy, + 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, ]) return ret diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index a7e201af480f75..84c5884e070db7 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -21,6 +21,7 @@ import time import traceback +import blimp import rover import arducopter import arduplane @@ -33,7 +34,6 @@ import examples from pysim import util -from pymavlink import mavutil from pymavlink.generator import mavtemplate from common import Test @@ -58,47 +58,6 @@ def buildlogs_path(path): return os.path.join(*bits) -def get_default_params(atype, binary): - """Get default parameters.""" - # use rover simulator so SITL is not starved of input - HOME = mavutil.location(40.071374969556928, - -105.22978898137808, - 1583.702759, - 246) - if "plane" in binary or "rover" in binary: - frame = "rover" - else: - frame = "+" - - home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading) - mavproxy_master = 'tcp:127.0.0.1:5760' - sitl = util.start_SITL(binary, - wipe=True, - model=frame, - home=home, - speedup=10, - unhide_parameters=True) - mavproxy = util.start_MAVProxy_SITL(atype, - master=mavproxy_master) - print("Dumping defaults") - idx = mavproxy.expect([r'Saved [0-9]+ parameters to (\S+)']) - if idx == 0: - # we need to restart it after eeprom erase - util.pexpect_close(mavproxy) - util.pexpect_close(sitl) - sitl = util.start_SITL(binary, model=frame, home=home, speedup=10) - mavproxy = util.start_MAVProxy_SITL(atype, - master=mavproxy_master) - mavproxy.expect(r'Saved [0-9]+ parameters to (\S+)') - parmfile = mavproxy.match.group(1) - dest = buildlogs_path('%s-defaults.parm' % atype) - shutil.copy(parmfile, dest) - util.pexpect_close(mavproxy) - util.pexpect_close(sitl) - print("Saved defaults for %s to %s" % (atype, dest)) - return True - - def build_all_filepath(): """Get build_all.sh path.""" return util.reltopdir('Tools/scripts/build_all.sh') @@ -139,7 +98,7 @@ def build_binaries(): def build_examples(**kwargs): """Build examples.""" - for target in 'fmuv2', 'Pixhawk1', 'navio', 'linux': + for target in 'Pixhawk1', 'navio', 'linux': print("Running build.examples for %s" % target) try: util.build_examples(target, **kwargs) @@ -380,6 +339,7 @@ def find_specific_test_to_run(step): tester_class_map = { + "test.Blimp": blimp.AutoTestBlimp, "test.Copter": arducopter.AutoTestCopter, "test.CopterTests1a": arducopter.AutoTestCopterTests1a, # 8m43s "test.CopterTests1b": arducopter.AutoTestCopterTests1b, # 8m5s @@ -400,7 +360,8 @@ def find_specific_test_to_run(step): } supplementary_test_binary_map = { - "test.CAN": ["sitl_periph_gps.AP_Periph", "sitl_periph_gps.AP_Periph.1"], + "test.CAN": ["sitl_periph_gps:AP_Periph:0:Tools/autotest/default_params/periph.parm,Tools/autotest/default_params/quad-periph.parm", # noqa: E501 + "sitl_periph_gps:AP_Periph:1:Tools/autotest/default_params/periph.parm"], } @@ -417,7 +378,7 @@ def run_specific_test(step, *args, **kwargs): # print("Got %s" % str(tester)) for a in tester.tests(): - if type(a) != Test: + if not isinstance(a, Test): a = Test(a) print("Got %s" % (a.name)) if a.name == test: @@ -501,26 +462,25 @@ def run_step(step): binary = binary_path(step, debug=opts.debug) - if step.startswith("defaults"): - vehicle = step[9:] - return get_default_params(vehicle, binary) - # see if we need any supplementary binaries supplementary_binaries = [] for k in supplementary_test_binary_map.keys(): if step.startswith(k): # this test needs to use supplementary binaries for supplementary_test_binary in supplementary_test_binary_map[k]: - config_name = supplementary_test_binary.split('.')[0] - binary_name = supplementary_test_binary.split('.')[1] - instance_num = 0 - if len(supplementary_test_binary.split('.')) >= 3: - instance_num = int(supplementary_test_binary.split('.')[2]) - supplementary_binaries.append([util.reltopdir(os.path.join('build', - config_name, - 'bin', - binary_name)), - '-I {}'.format(instance_num)]) + a = supplementary_test_binary.split(':') + if len(a) != 4: + raise ValueError("Bad supplementary_test_binary %s" % supplementary_test_binary) + config_name = a[0] + binary_name = a[1] + instance_num = int(a[2]) + param_file = a[3].split(",") + bin_path = util.reltopdir(os.path.join('build', config_name, 'bin', binary_name)) + customisation = '-I {}'.format(instance_num) + sup_binary = {"binary" : bin_path, + "customisation" : customisation, + "param_file" : param_file} + supplementary_binaries.append(sup_binary) # we are running in conjunction with a supplementary app # can't have speedup opts.speedup = 1.0 @@ -700,9 +660,10 @@ def write_fullresults(): results.addglob("GPX track", '*.gpx') # results common to all vehicles: - vehicle_files = [('{vehicle} defaults', '{vehicle}-defaults.parm'), - ('{vehicle} core', '{vehicle}.core'), - ('{vehicle} ELF', '{vehicle}.elf'), ] + vehicle_files = [ + ('{vehicle} core', '{vehicle}.core'), + ('{vehicle} ELF', '{vehicle}.elf'), + ] vehicle_globs = [('{vehicle} log', '{vehicle}-*.BIN'), ] for vehicle in all_vehicles(): subs = {'vehicle': vehicle} @@ -723,6 +684,7 @@ def write_fullresults(): results.addglob('APM:Copter documentation', 'docs/ArduCopter/index.html') results.addglob('APM:Rover documentation', 'docs/Rover/index.html') results.addglob('APM:Sub documentation', 'docs/ArduSub/index.html') + results.addglob('APM:Blimp documentation', 'docs/Blimp/index.html') results.addglobimage("Flight Track", '*.png') write_webresults(results) @@ -758,7 +720,7 @@ def run_tests(steps): try: success = run_step(step) testinstance = None - if type(success) == tuple: + if isinstance(success, tuple): (success, testinstance) = success if success: results.add(step, 'PASSED', @@ -811,7 +773,7 @@ def run_tests(steps): return passed -vehicle_list = ['Sub', 'Copter', 'Plane', 'Tracker', 'Rover', 'QuadPlane', 'BalanceBot', 'Helicopter', 'Sailboat'] +vehicle_list = ['Sub', 'Copter', 'Plane', 'Tracker', 'Rover', 'QuadPlane', 'BalanceBot', 'Helicopter', 'Sailboat', 'Blimp'] def list_subtests(): @@ -844,7 +806,7 @@ def list_subtests_for_vehicle(vehicle_type): subtests = tester.tests() sorted_list = [] for subtest in subtests: - if type(subtest) != Test: + if not isinstance(subtest, Test): subtest = Test(subtest) sorted_list.append([subtest.name, subtest.description]) sorted_list.sort() @@ -1097,33 +1059,28 @@ def format_epilog(self, formatter): 'run.examples', 'build.Plane', - 'defaults.Plane', 'test.Plane', 'test.QuadPlane', 'build.Rover', - 'defaults.Rover', 'test.Rover', 'test.BalanceBot', 'test.Sailboat', 'build.Copter', - 'defaults.Copter', 'test.Copter', 'build.Helicopter', 'test.Helicopter', 'build.Tracker', - 'defaults.Tracker', 'test.Tracker', 'build.Sub', - 'defaults.Sub', 'test.Sub', 'build.Blimp', - 'defaults.Blimp', + 'test.Blimp', 'build.SITLPeriphGPS', 'test.CAN', @@ -1164,11 +1121,6 @@ def format_epilog(self, formatter): "drive.balancebot": "test.BalanceBot", "fly.CopterAVC": "test.Helicopter", "test.AntennaTracker": "test.Tracker", - "defaults.ArduCopter": "defaults.Copter", - "defaults.ArduPlane": "defaults.Plane", - "defaults.ArduSub": "defaults.Sub", - "defaults.APMrover2": "defaults.Rover", - "defaults.AntennaTracker": "defaults.Tracker", "fly.ArduCopterTests1a": "test.CopterTests1a", "fly.ArduCopterTests1b": "test.CopterTests1b", "fly.ArduCopterTests1c": "test.CopterTests1c", diff --git a/Tools/autotest/bisect-helper.py b/Tools/autotest/bisect-helper.py index e0aafe56587335..3858a53fb6b3a8 100755 --- a/Tools/autotest/bisect-helper.py +++ b/Tools/autotest/bisect-helper.py @@ -133,7 +133,7 @@ def run_program(self, prefix, cmd_list): # select not available on Windows... probably... time.sleep(0.1) continue - if type(x) == bytes: + if isinstance(x, bytes): x = x.decode('utf-8') self.program_output += x x = x.rstrip() diff --git a/Tools/autotest/blimp.py b/Tools/autotest/blimp.py new file mode 100644 index 00000000000000..affeec2cecd878 --- /dev/null +++ b/Tools/autotest/blimp.py @@ -0,0 +1,252 @@ +''' +Fly Blimp in SITL + +AP_FLAKE8_CLEAN +''' + +from __future__ import print_function +import os +import shutil + +from pymavlink import mavutil + +from common import AutoTest + +# get location of scripts +testdir = os.path.dirname(os.path.realpath(__file__)) +SITL_START_LOCATION = mavutil.location(-35.362938, 149.165085, 584, 0) + +# Flight mode switch positions are set-up in blimp.parm to be +# switch 1 = Land +# switch 2 = Manual +# switch 3 = Velocity +# switch 4 = Loiter +# switch 5 = Manual +# switch 6 = Manual + + +class AutoTestBlimp(AutoTest): + @staticmethod + def get_not_armable_mode_list(): + return [] + + @staticmethod + def get_not_disarmed_settable_modes_list(): + return [] + + @staticmethod + def get_no_position_not_settable_modes_list(): + return [] + + @staticmethod + def get_position_armable_modes_list(): + return [] + + @staticmethod + def get_normal_armable_modes_list(): + return [] + + def log_name(self): + return "Blimp" + + def default_mode(self): + return "MANUAL" + + def test_filepath(self): + return os.path.realpath(__file__) + + def default_speedup(self): + return 100 + + def set_current_test_name(self, name): + self.current_test_name_directory = "Blimp_Tests/" + name + "/" + + def sitl_start_location(self): + return SITL_START_LOCATION + + def sitl_streamrate(self): + return 5 + + def vehicleinfo_key(self): + return 'Blimp' + + def default_frame(self): + return "Blimp" + + def apply_defaultfile_parameters(self): + # Blimp passes in a defaults_filepath in place of applying + # parameters afterwards. + pass + + def defaults_filepath(self): + return self.model_defaults_filepath(self.frame) + + def wait_disarmed_default_wait_time(self): + return 120 + + def close(self): + super(AutoTestBlimp, self).close() + + # [2014/05/07] FC Because I'm doing a cross machine build + # (source is on host, build is on guest VM) I cannot hard link + # This flag tells me that I need to copy the data out + if self.copy_tlog: + shutil.copy(self.logfile, self.buildlog) + + def is_blimp(self): + return True + + def get_stick_arming_channel(self): + return int(self.get_parameter("RCMAP_YAW")) + + def get_disarm_delay(self): + return int(self.get_parameter("DISARM_DELAY")) + + def set_autodisarm_delay(self, delay): + self.set_parameter("DISARM_DELAY", delay) + + def FlyManual(self): + '''test manual mode''' + self.change_mode('MANUAL') + self.wait_ready_to_arm() + self.arm_vehicle() + + acc = 0.5 + + # make sure we don't drift: + bl = self.mav.location() + tl = self.offset_location_ne(location=bl, metres_north=2, metres_east=0) + ttl = self.offset_location_ne(location=bl, metres_north=4, metres_east=0) + tr = self.offset_location_ne(location=bl, metres_north=4, metres_east=2) + ttr = self.offset_location_ne(location=bl, metres_north=4, metres_east=4) + + if self.mavproxy is not None: + self.mavproxy.send(f"map icon {bl.lat} {bl.lng} flag\n") + self.mavproxy.send(f"map icon {tl.lat} {tl.lng} flag\n") + self.mavproxy.send(f"map icon {ttl.lat} {ttl.lng} flag\n") + self.mavproxy.send(f"map icon {tr.lat} {tr.lng} flag\n") + self.mavproxy.send(f"map icon {ttr.lat} {ttr.lng} flag\n") + + self.set_rc(2, 2000) + self.wait_distance_to_location(tl, 0, acc, timeout=10) + self.set_rc(2, 1500) + self.wait_distance_to_location(ttl, 0, acc, timeout=15) + self.set_rc(1, 2000) + self.wait_distance_to_location(tr, 0, acc, timeout=10) + self.set_rc(1, 1500) + self.wait_distance_to_location(ttr, 0, acc, timeout=15) + self.change_mode('RTL') + self.wait_distance_to_location(bl, 0, 0.5, timeout=30, minimum_duration=5) # make sure it can hold position + self.change_mode('MANUAL') + + self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot + + self.set_rc(3, 2000) + self.wait_altitude(5, 5.5, relative=True, timeout=15) + self.set_rc(3, 1500) + + self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot + + self.set_rc(4, 1000) + self.wait_heading(340, accuracy=5, timeout=5) # short timeout to check yawrate + self.set_rc(4, 1500) + + self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot + + self.set_rc(3, 1000) + self.wait_altitude(0, 0.5, relative=True, timeout=20) + self.set_rc(3, 1500) + + self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot + + self.set_rc(4, 2000) + self.wait_heading(135, accuracy=5, timeout=10) # short timeout to check yawrate + self.set_rc(4, 1500) + + self.wait_distance_to_location(bl, 0, acc, timeout=5) # make sure we haven't moved from the spot + + self.disarm_vehicle() + + def FlyLoiter(self): + '''test loiter mode''' + + self.change_mode('LOITER') + self.wait_ready_to_arm() + self.arm_vehicle() + + siz = 5 + tim = 60 + + # make sure we don't drift: + bl = self.mav.location() + tl = self.offset_location_ne(location=bl, metres_north=siz, metres_east=0) + tr = self.offset_location_ne(location=bl, metres_north=siz, metres_east=siz) + br = self.offset_location_ne(location=bl, metres_north=0, metres_east=siz) + + print("Locations are:") + print("bottom left ", bl.lat, bl.lng) + print("top left ", tl.lat, tl.lng) + print("top right ", tr.lat, tr.lng) + print("bottom right ", br.lat, br.lng) + + if self.mavproxy is not None: + self.mavproxy.send(f"map icon {bl.lat} {bl.lng} flag\n") + self.mavproxy.send(f"map icon {tl.lat} {tl.lng} flag\n") + self.mavproxy.send(f"map icon {tr.lat} {tr.lng} flag\n") + self.mavproxy.send(f"map icon {br.lat} {br.lng} flag\n") + + self.set_parameter("SIMPLE_MODE", 1) + + self.set_rc(2, 2000) + self.wait_distance_to_location(tl, 0, 0.2, timeout=tim) + self.set_rc(2, 1500) + + self.set_rc(1, 2000) + self.wait_distance_to_location(tr, 0, 0.5, timeout=tim) + self.set_rc(1, 1500) + + self.set_rc(2, 1000) + self.wait_distance_to_location(br, 0, 0.5, timeout=tim) + self.set_rc(2, 1500) + + self.set_rc(1, 1000) + self.wait_distance_to_location(bl, 0, 0.5, timeout=tim) + self.set_rc(1, 1500) + + fin = self.mav.location() + + self.set_rc(4, 1700) + self.wait_heading(135, accuracy=2, timeout=tim) + self.set_rc(4, 1500) + + self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot + + self.set_rc(3, 2000) + self.wait_altitude(5, 5.5, relative=True, timeout=60) + self.set_rc(3, 1000) + self.wait_altitude(0, 0.5, relative=True, timeout=60) + self.set_rc(3, 1500) + + self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot + + self.set_rc(4, 1300) + self.wait_heading(0, accuracy=2, timeout=tim) + self.set_rc(4, 1500) + + self.wait_distance_to_location(fin, 0, 0.15, timeout=5) # make sure we haven't moved from the spot + + self.disarm_vehicle() + + def tests(self): + '''return list of all tests''' + # ret = super(AutoTestBlimp, self).tests() + ret = [] + ret.extend([ + self.FlyManual, + self.FlyLoiter, + ]) + return ret + + def disabled_tests(self): + return { + } diff --git a/Tools/autotest/check_autotest_speedup.py b/Tools/autotest/check_autotest_speedup.py index 81bf13edfe064b..621726c8677c79 100755 --- a/Tools/autotest/check_autotest_speedup.py +++ b/Tools/autotest/check_autotest_speedup.py @@ -52,7 +52,7 @@ def run_program(self, prefix, cmd_list): # select not available on Windows... probably... time.sleep(0.1) continue - if type(x) == bytes: + if isinstance(x, bytes): x = x.decode('utf-8') self.program_output += x x = x.rstrip() diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index e6c862f706d050..094c76f52a30d1 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -203,6 +203,7 @@ def __init__(self): self.original_heartbeat_interval_ms = None self.installed_scripts = [] self.installed_modules = [] + self.overridden_message_rates = {} # https://stackoverflow.com/questions/616645/how-do-i-duplicate-sys-stdout-to-a-log-file-in-python @@ -226,6 +227,8 @@ def close(self): self.file = None def write(self, data): + if isinstance(data, bytes): + data = data.decode('ascii') self.file.write(data) if not self.suppress_stdout: self.stdout.write(data) @@ -1445,12 +1448,13 @@ def __init__(self, lat, lon, alt, yaw): class Test(object): '''a test definition - information about a test''' - def __init__(self, function, attempts=1, speedup=None): + def __init__(self, function, kwargs={}, attempts=1, speedup=None): self.name = function.__name__ self.description = function.__doc__ if self.description is None: raise ValueError("%s is missing a docstring" % self.name) self.function = function + self.kwargs = kwargs self.attempts = attempts self.speedup = speedup @@ -1589,6 +1593,7 @@ def __init__(self, ) self.terrain_data_messages_sent = 0 # count of messages back self.dronecan_tests = dronecan_tests + self.statustext_id = 1 def __del__(self): if self.rc_thread is not None: @@ -1888,7 +1893,7 @@ def reboot_check_valgrind_log(self): shutil.move(valgrind_log, backup_valgrind_log) def run_cmd_reboot(self): - self.run_cmd( + self.run_cmd_int( mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, p1=1, # reboot autopilot ) @@ -2135,41 +2140,11 @@ 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_BIAS_X", - "SIM_ACC1_BIAS_Y", - "SIM_ACC1_BIAS_Z", "SIM_ACC1_RND", - "SIM_ACC1_SCAL_X", - "SIM_ACC1_SCAL_Y", - "SIM_ACC1_SCAL_Z", - "SIM_ACC2_BIAS_X", - "SIM_ACC2_BIAS_Y", - "SIM_ACC2_BIAS_Z", "SIM_ACC2_RND", - "SIM_ACC2_SCAL_X", - "SIM_ACC2_SCAL_Y", - "SIM_ACC2_SCAL_Z", - "SIM_ACC3_BIAS_X", - "SIM_ACC3_BIAS_Y", - "SIM_ACC3_BIAS_Z", "SIM_ACC3_RND", - "SIM_ACC3_SCAL_X", - "SIM_ACC3_SCAL_Y", - "SIM_ACC3_SCAL_Z", "SIM_ACC4_RND", - "SIM_ACC4_SCAL_X", - "SIM_ACC4_SCAL_Y", - "SIM_ACC4_SCAL_Z", - "SIM_ACC4_BIAS_X", - "SIM_ACC4_BIAS_Y", - "SIM_ACC4_BIAS_Z", "SIM_ACC5_RND", - "SIM_ACC5_SCAL_X", - "SIM_ACC5_SCAL_Y", - "SIM_ACC5_SCAL_Z", - "SIM_ACC5_BIAS_X", - "SIM_ACC5_BIAS_Y", - "SIM_ACC5_BIAS_Z", "SIM_ACC_FILE_RW", "SIM_ACC_TRIM_X", "SIM_ACC_TRIM_Y", @@ -2178,19 +2153,10 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_ADSB_COUNT", "SIM_ADSB_RADIUS", "SIM_ADSB_TX", - "SIM_ARSPD2_FAIL", - "SIM_ARSPD2_FAILP", "SIM_ARSPD2_OFS", - "SIM_ARSPD2_PITOT", - "SIM_ARSPD2_RATIO", "SIM_ARSPD2_RND", - "SIM_ARSPD2_SIGN", - "SIM_ARSPD_FAILP", "SIM_ARSPD_OFS", - "SIM_ARSPD_PITOT", - "SIM_ARSPD_RATIO", "SIM_ARSPD_RND", - "SIM_ARSPD_SIGN", "SIM_BAR2_DELAY", "SIM_BAR2_DISABLE", "SIM_BAR2_DRIFT", @@ -2223,7 +2189,6 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_BARO_WCF_RGT", "SIM_BARO_WCF_UP", "SIM_BATT_CAP_AH", - "SIM_BATT_VOLTAGE", "SIM_BAUDLIMIT_EN", "SIM_DRIFT_SPEED", "SIM_DRIFT_TIME", @@ -2231,84 +2196,19 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_ENGINE_FAIL", "SIM_ENGINE_MUL", "SIM_ESC_ARM_RPM", - "SIM_FLOW_DELAY", - "SIM_FLOW_ENABLE", - "SIM_FLOW_POS_X", - "SIM_FLOW_POS_Y", - "SIM_FLOW_POS_Z", - "SIM_FLOW_RATE", - "SIM_FLOW_RND", "SIM_FTOWESC_ENA", "SIM_FTOWESC_POW", "SIM_GND_BEHAV", - "SIM_GPS2_ACC", - "SIM_GPS2_ALT_OFS", - "SIM_GPS2_BYTELOS", - "SIM_GPS2_DRFTALT", - "SIM_GPS2_GLTCH_X", - "SIM_GPS2_GLTCH_Y", - "SIM_GPS2_GLTCH_Z", - "SIM_GPS2_HDG", - "SIM_GPS2_HZ", - "SIM_GPS2_LAG_MS", - "SIM_GPS2_LCKTIME", - "SIM_GPS2_NOISE", - "SIM_GPS2_NUMSATS", - "SIM_GPS2_POS_X", - "SIM_GPS2_POS_Y", - "SIM_GPS2_POS_Z", - "SIM_GPS2_VERR_X", - "SIM_GPS2_VERR_Y", - "SIM_GPS2_VERR_Z", - "SIM_GPS_ACC", - "SIM_GPS_ALT_OFS", - "SIM_GPS_BYTELOSS", - "SIM_GPS_DRIFTALT", - "SIM_GPS_GLITCH_X", - "SIM_GPS_GLITCH_Y", - "SIM_GPS_GLITCH_Z", - "SIM_GPS_HDG", - "SIM_GPS_HZ", - "SIM_GPS_LAG_MS", - "SIM_GPS_LOCKTIME", - "SIM_GPS_LOG_NUM", - "SIM_GPS_NOISE", - "SIM_GPS_NUMSATS", - "SIM_GPS_POS_X", - "SIM_GPS_POS_Y", - "SIM_GPS_POS_Z", - "SIM_GPS_VERR_X", - "SIM_GPS_VERR_Y", - "SIM_GPS_VERR_Z", "SIM_GYR1_RND", - "SIM_GYR1_SCALE_X", - "SIM_GYR1_SCALE_Y", - "SIM_GYR1_SCALE_Z", "SIM_GYR2_RND", - "SIM_GYR2_SCALE_X", - "SIM_GYR2_SCALE_Y", - "SIM_GYR2_SCALE_Z", "SIM_GYR3_RND", - "SIM_GYR3_SCALE_X", - "SIM_GYR3_SCALE_Y", - "SIM_GYR3_SCALE_Z", "SIM_GYR4_RND", - "SIM_GYR4_SCALE_X", - "SIM_GYR4_SCALE_Y", - "SIM_GYR4_SCALE_Z", "SIM_GYR5_RND", - "SIM_GYR5_SCALE_X", - "SIM_GYR5_SCALE_Y", - "SIM_GYR5_SCALE_Z", "SIM_GYR_FAIL_MSK", "SIM_GYR_FILE_RW", "SIM_IE24_ENABLE", "SIM_IE24_ERROR", "SIM_IE24_STATE", - "SIM_IMU_COUNT", - "SIM_IMU_POS_X", - "SIM_IMU_POS_Y", - "SIM_IMU_POS_Z", "SIM_IMUT1_ACC1_X", "SIM_IMUT1_ACC1_Y", "SIM_IMUT1_ACC1_Z", @@ -2418,9 +2318,6 @@ def get_sim_parameter_documentation_get_whitelist(self): "SIM_IMUT_FIXED", "SIM_IMUT_START", "SIM_IMUT_TCONST", - "SIM_INIT_ALT_OFS", - "SIM_INIT_LAT_OFS", - "SIM_INIT_LON_OFS", "SIM_INS_THR_MIN", "SIM_LED_LAYOUT", "SIM_LOOP_DELAY", @@ -2625,7 +2522,7 @@ def test_parameter_documentation_get_all_parameters(self): def find_format_defines(self, lines): ret = {} for line in lines: - if type(line) == bytes: + if isinstance(line, bytes): line = line.decode("utf-8") m = re.match(r'#define (\w+_(?:LABELS|FMT|UNITS|MULTS))\s+(".*")', line) if m is None: @@ -2682,7 +2579,7 @@ def all_log_format_ids(self): for line in open(f).readlines(): if debug: print("line: %s" % line) - if type(line) == bytes: + if isinstance(line, bytes): line = line.decode("utf-8") line = re.sub("//.*", "", line) # trim comments if re.match(r"\s*$", line): @@ -2761,7 +2658,7 @@ def all_log_format_ids(self): linestate_within = 90 linestate = linestate_none for line in open(filepath, 'rb').readlines(): - if type(line) == bytes: + if isinstance(line, bytes): line = line.decode("utf-8") line = re.sub("//.*", "", line) # trim comments if re.match(r"\s*$", line): @@ -2783,6 +2680,8 @@ def all_log_format_ids(self): continue if "#if AC_PRECLAND_ENABLED" in line: continue + if "#if OFFBOARD_GUIDED == ENABLED" in line: + continue if "#end" in line: continue if "LOG_COMMON_STRUCTURES" in line: @@ -2859,7 +2758,7 @@ def all_log_format_ids(self): continue count = 0 for line in open(filepath, 'rb').readlines(): - if type(line) == bytes: + if isinstance(line, bytes): line = line.decode("utf-8") if state == state_outside: if (re.match(r"\s*AP::logger\(\)[.]Write(?:Streaming)?\(", line) or @@ -3229,7 +3128,7 @@ def message_hook(self, mav, msg): """Called as each mavlink msg is received.""" # print("msg: %s" % str(msg)) if msg.get_type() == 'STATUSTEXT': - self.progress("AP: %s" % msg.text) + self.progress("AP: %s" % msg.text, send_statustext=False) self.write_msg_to_tlog(msg) @@ -3449,6 +3348,17 @@ def HIGH_LATENCY2(self): raise NotAchievedException("Air Temperature not received from HIGH_LATENCY2") self.HIGH_LATENCY2_links() + def context_set_message_rate_hz(self, id, rate_hz, run_cmd=None): + if run_cmd is None: + run_cmd = self.run_cmd + + overridden_message_rates = self.context_get().overridden_message_rates + + if id not in overridden_message_rates: + overridden_message_rates[id] = self.measure_message_rate(id) + + self.set_message_rate_hz(id, rate_hz, run_cmd=run_cmd) + def HIGH_LATENCY2_links(self): self.start_subtest("SerialProtocol_MAVLinkHL links") @@ -3815,6 +3725,13 @@ def save_wp(self, ch=7): self.set_rc(ch, 1000) self.delay_sim_time(1) + def correct_wp_seq_numbers(self, wps): + # renumber the items: + count = 0 + for item in wps: + item.seq = count + count += 1 + def create_simple_relhome_mission(self, items_in, target_system=1, target_component=1): '''takes a list of (type, n, e, alt) items. Creates a mission in absolute frame using alt as relative-to-home and n and e as @@ -3825,34 +3742,24 @@ def create_simple_relhome_mission(self, items_in, target_system=1, target_compon items.extend(items_in) seq = 0 ret = [] - for (t, n, e, alt) in items: + for item in items: + if not isinstance(item, tuple): + # hope this is a mission item... + item.seq = seq + seq += 1 + ret.append(item) + continue + (t, n, e, alt) = item lat = 0 lng = 0 if n != 0 or e != 0: loc = self.home_relative_loc_ne(n, e) lat = loc.lat lng = loc.lng - p1 = 0 frame = mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT_INT if not self.ardupilot_stores_frame_for_cmd(t): frame = mavutil.mavlink.MAV_FRAME_GLOBAL - ret.append(self.mav.mav.mission_item_int_encode( - target_system, - target_component, - seq, # seq - frame, - t, - 0, # current - 0, # autocontinue - p1, # p1 - 0, # p2 - 0, # p3 - 0, # p4 - int(lat*1e7), # latitude - int(lng*1e7), # longitude - alt, # altitude - mavutil.mavlink.MAV_MISSION_TYPE_MISSION), - ) + ret.append(self.create_MISSION_ITEM_INT(t, seq=seq, frame=frame, x=int(lat*1e7), y=int(lng*1e7), z=alt)) seq += 1 return ret @@ -3870,8 +3777,11 @@ def get_mission_count(self): def run_auxfunc(self, function, level, + run_cmd=None, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): - self.run_cmd( + if run_cmd is None: + run_cmd = self.run_cmd + run_cmd( mavutil.mavlink.MAV_CMD_DO_AUX_FUNCTION, p1=function, p2=level, @@ -3987,14 +3897,25 @@ def assert_received_message_field_values(self, message, fieldvalues, verbose=Tru self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon) return m - def wait_message_field_values(self, message, fieldvalues, timeout=10, epsilon=None, instance=None): + # FIXME: try to use wait_and_maintain here? + def wait_message_field_values(self, message, fieldvalues, timeout=10, epsilon=None, instance=None, minimum_duration=None): + tstart = self.get_sim_time_cached() + pass_start = None while True: - if self.get_sim_time_cached() - tstart > timeout: + now = self.get_sim_time_cached() + if now - tstart > timeout: raise NotAchievedException("Field never reached values") m = self.assert_receive_message(message, instance=instance) if self.message_has_field_values(m, fieldvalues, epsilon=epsilon): + if minimum_duration is not None: + if pass_start is None: + pass_start = now + continue + if now - pass_start < minimum_duration: + continue return m + pass_start = None def onboard_logging_not_log_disarmed(self): self.start_subtest("Test LOG_DISARMED-is-false behaviour") @@ -4506,21 +4427,25 @@ def assert_rally_content_same(self, f1, f2): raise ValueError("count %u not handled" % count) self.progress("Rally content same") - def load_rally(self, filename): + def load_rally_using_mavproxy(self, filename): """Load rally points from a file to flight controller.""" self.progress("Loading rally points (%s)" % filename) path = os.path.join(testdir, self.current_test_name_directory, filename) mavproxy = self.start_mavproxy() mavproxy.send('rally load %s\n' % path) mavproxy.expect("Loaded") + self.delay_sim_time(10) # allow transfer to complete self.stop_mavproxy(mavproxy) def load_sample_mission(self): self.load_mission(self.sample_mission_filename()) + def generic_mission_filepath_for_filename(self, filename): + return os.path.join(testdir, "Generic_Missions", filename) + def load_generic_mission(self, filename, strict=True): return self.load_mission_from_filepath( - os.path.join(testdir, "Generic_Missions", filename), + self.generic_mission_filepath_for_filename(filename), strict=strict) def load_mission(self, filename, strict=True): @@ -4776,7 +4701,6 @@ def check_mission_item_upload_download(self, items, itype, mission_type, strict= self.upload_using_mission_protocol(mission_type, items) self.progress("check %s upload/download: download items" % itype) downloaded_items = self.download_using_mission_protocol(mission_type) - self.progress("Downloaded items: (%s)" % str(downloaded_items)) if len(items) != len(downloaded_items): raise NotAchievedException("Did not download same number of items as uploaded want=%u got=%u" % (len(items), len(downloaded_items))) @@ -4784,6 +4708,8 @@ def check_mission_item_upload_download(self, items, itype, mission_type, strict= self.check_fence_items_same(items, downloaded_items, strict=strict) elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_MISSION: self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict) + elif mission_type == mavutil.mavlink.MAV_MISSION_TYPE_RALLY: + self.check_mission_waypoint_items_same(items, downloaded_items, strict=strict) else: raise NotAchievedException("Unhandled") @@ -4800,6 +4726,13 @@ def check_mission_upload_download(self, items, strict=True): mavutil.mavlink.MAV_MISSION_TYPE_MISSION, strict=strict) + def check_rally_upload_download(self, items): + self.check_mission_item_upload_download( + items, + "rally", + mavutil.mavlink.MAV_MISSION_TYPE_RALLY + ) + def check_dflog_message_rates(self, log_filepath, message_rates): reader = self.dfreader_for_path(log_filepath) @@ -4870,7 +4803,7 @@ def rc_defaults(self): def set_rc_from_map(self, _map, timeout=20): map_copy = _map.copy() for v in map_copy.values(): - if type(v) != int: + if not isinstance(v, int): raise NotAchievedException("RC values must be integers") self.rc_queue.put(map_copy) @@ -5052,6 +4985,12 @@ def send_mavlink_arm_command(self): p1=1, # ARM ) + def send_mavlink_disarm_command(self): + self.send_cmd( + mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, + p1=0, # DISARM + ) + def send_mavlink_run_prearms_command(self): self.send_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS) @@ -5525,7 +5464,7 @@ def get_parameter(self, *args, **kwargs): def send_get_parameter_direct(self, name): encname = name - if sys.version_info.major >= 3 and type(encname) != bytes: + if sys.version_info.major >= 3 and not isinstance(encname, bytes): encname = bytes(encname, 'ascii') self.mav.mav.param_request_read_send(self.sysid_thismav(), 1, @@ -5649,6 +5588,8 @@ def context_pop(self, process_interaction_allowed=True): 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 module in dead.installed_modules: print("Removing module (%s)" % module) self.remove_installed_modules(module) @@ -5702,6 +5643,42 @@ def __exit__(self, type, value, traceback): def sysid_thismav(self): return 1 + def create_MISSION_ITEM_INT( + self, + t, + p1=0, + p2=0, + p3=0, + p4=0, + x=0, + y=0, + z=0, + frame=mavutil.mavlink.MAV_FRAME_GLOBAL, + autocontinue=1, + current=0, + target_system=1, + target_component=1, + seq=0, + mission_type=mavutil.mavlink.MAV_MISSION_TYPE_MISSION, + ): + return self.mav.mav.mission_item_int_encode( + target_system, + target_component, + seq, # seq + frame, + t, + 0, # current + 0, # autocontinue + p1, # p1 + 0, # p2 + 0, # p3 + 0, # p4 + x, # latitude + y, # longitude + z, # altitude + mission_type + ) + def run_cmd_int(self, command, p1=0, @@ -5719,8 +5696,13 @@ def run_cmd_int(self, p5=None, p6=None, p7=None, + quiet=False, + mav=None, ): + if mav is None: + mav = self.mav + if p5 is not None: x = p5 if p6 is not None: @@ -5736,20 +5718,38 @@ def run_cmd_int(self, self.get_sim_time() # required for timeout in run_cmd_get_ack to work """Send a MAVLink command int.""" - self.mav.mav.command_int_send(target_sysid, - target_compid, - frame, - command, - 0, # current - 0, # autocontinue - p1, - p2, - p3, - p4, - x, - y, - z) - self.run_cmd_get_ack(command, want_result, timeout) + if not quiet: + try: + 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)) + mav.mav.command_int_send(target_sysid, + target_compid, + frame, + command, + 0, # current + 0, # autocontinue + p1, + p2, + p3, + p4, + x, + y, + z) + self.run_cmd_get_ack(command, want_result, timeout, mav=mav) def send_cmd(self, command, @@ -5772,16 +5772,17 @@ def send_cmd(self, target_sysid = self.sysid_thismav() if target_compid is None: target_compid = 1 - try: - command_name = mavutil.mavlink.enums["MAV_CMD"][command].name - except KeyError: - command_name = "UNKNOWN=%u" % command if not quiet: - self.progress("Sending COMMAND_LONG to (%u,%u) (%s) (p1=%f p2=%f p3=%f p4=%f p5=%f p6=%f p7=%f)" % + try: + command_name = mavutil.mavlink.enums["MAV_CMD"][command].name + except KeyError: + command_name = "UNKNOWN" + self.progress("Sending COMMAND_LONG to (%u,%u) (%s=%u) (p1=%f p2=%f p3=%f p4=%f p5=%f p6=%f p7=%f)" % ( target_sysid, target_compid, command_name, + command, p1, p2, p3, @@ -5900,7 +5901,7 @@ def verify_parameter_values(self, parameter_stuff, max_delta=0.0): for param in parameter_stuff: fetched_value = self.get_parameter(param) wanted_value = parameter_stuff[param] - if type(wanted_value) == tuple: + if isinstance(wanted_value, tuple): max_delta = wanted_value[1] wanted_value = wanted_value[0] if abs(fetched_value - wanted_value) > max_delta: @@ -6373,10 +6374,13 @@ def validator(value2, target2=None): **kwargs ) - def wait_altitude(self, altitude_min, altitude_max, relative=False, timeout=30, **kwargs): + def wait_altitude(self, altitude_min, altitude_max, relative=False, timeout=None, **kwargs): """Wait for a given altitude range.""" assert altitude_min <= altitude_max, "Minimum altitude should be less than maximum altitude." + if timeout is None: + timeout = 30 + def validator(value2, target2=None): if altitude_min <= value2 <= altitude_max: return True @@ -6434,6 +6438,10 @@ def validator(value2, target2=None): **kwargs ) + def groundspeed(self): + m = self.assert_receive_message('VFR_HUD') + return m.groundspeed + def wait_groundspeed(self, speed_min, speed_max, timeout=30, **kwargs): self.wait_vfr_hud_speed("groundspeed", speed_min, speed_max, timeout=timeout, **kwargs) @@ -6503,7 +6511,7 @@ def validator(value2, target2): ) def wait_and_maintain(self, value_name, target, current_value_getter, validator=None, accuracy=2.0, timeout=30, **kwargs): - if type(target) is Vector3: + if isinstance(target, Vector3): return self.wait_and_maintain_vector( value_name, target, @@ -6534,6 +6542,7 @@ def wait_and_maintain_vector(self, achieving_duration_start = None sum_of_achieved_values = Vector3() last_value = Vector3() + last_fail_print = 0 count_of_achieved_values = 0 called_function = kwargs.get("called_function", None) minimum_duration = kwargs.get("minimum_duration", 0) @@ -6543,7 +6552,15 @@ def wait_and_maintain_vector(self, self.progress("Waiting for %s=(%s)" % (value_name, str(target))) last_print_time = 0 - while self.get_sim_time_cached() < tstart + timeout: # if we failed to received message with the getter the sim time isn't updated # noqa + while True: # if we failed to received message with the getter the sim time isn't updated # noqa + now = self.get_sim_time_cached() + if now - tstart > timeout: + raise AutoTestTimeoutException( + "Failed to attain %s want %s, reached %s" % + (value_name, + str(target), + str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value))) # noqa + last_value = current_value_getter() if called_function is not None: called_function(last_value, target) @@ -6580,11 +6597,10 @@ def wait_and_maintain_vector(self, achieving_duration_start = None sum_of_achieved_values.zero() count_of_achieved_values = 0 - raise AutoTestTimeoutException( - "Failed to attain %s want %s, reached %s" % - (value_name, - str(target), - str(sum_of_achieved_values / count_of_achieved_values) if count_of_achieved_values != 0 else str(last_value))) + if now - last_fail_print > 1: + self.progress("Waiting for (%s), got %s" % + (target, last_value)) + last_fail_print = now def validate_kwargs(self, kwargs, valid={}): for key in kwargs: @@ -6627,7 +6643,10 @@ def wait_and_maintain_range(self, while self.get_sim_time_cached() < tstart + timeout: # if we failed to received message with the getter the sim time isn't updated # noqa last_value = current_value_getter() if called_function is not None: - called_function(last_value, target) + if print_diagnostics_as_target_not_range: + called_function(last_value, target) + else: + called_function(last_value, minimum, maximum) if validator is not None: if print_diagnostics_as_target_not_range: is_value_valid = validator(last_value, target) @@ -6656,7 +6675,7 @@ def wait_and_maintain_range(self, achieved_duration_bit) ) else: - if type(last_value) is float: + if isinstance(last_value, float): self.progress( "%s=%0.2f (%s between %s and %s)%s" % (value_name, @@ -6761,11 +6780,12 @@ def get_speed_vector(self, timeout=1): return Vector3(msg.vx, msg.vy, msg.vz) """Wait for a given speed vector.""" - def wait_speed_vector(self, speed_vector, accuracy=0.2, timeout=30, **kwargs): + def wait_speed_vector(self, speed_vector, accuracy=0.3, timeout=30, **kwargs): def validator(value2, target2): - return (math.fabs(value2.x - target2.x) <= accuracy and - math.fabs(value2.y - target2.y) <= accuracy and - math.fabs(value2.z - target2.z) <= accuracy) + for (want, got) in (target2.x, value2.x), (target2.y, value2.y), (target2.z, value2.z): + if want != float("nan") and (math.fabs(got - want) > accuracy): + return False + return True self.wait_and_maintain( value_name="SpeedVector", @@ -7207,7 +7227,7 @@ def assert_mode_is(self, 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_cached() + tstart = self.get_sim_time() while True: now = self.get_sim_time_cached() if now - tstart > timeout: @@ -7227,7 +7247,8 @@ def wait_gps_sys_status_not_present_or_enabled_and_healthy(self, timeout=30): if (not (m.onboard_control_sensors_health & mavutil.mavlink.MAV_SYS_STATUS_SENSOR_GPS)): self.progress("GPS not healthy") continue - self.progress("GPS healthy") + self.progress("GPS healthy after %f/%f seconds" % + ((now - tstart), timeout)) return def assert_sensor_state(self, sensor, present=True, enabled=True, healthy=True, verbose=False): @@ -7723,7 +7744,14 @@ def send_statustext(self, text): text = bytes(text, "ascii") elif 'unicode' in str(type(text)): text = text.encode('ascii') - self.mav.mav.statustext_send(mavutil.mavlink.MAV_SEVERITY_WARNING, text) + seq = 0 + while len(text): + self.mav.mav.statustext_send(mavutil.mavlink.MAV_SEVERITY_WARNING, text[:50], id=self.statustext_id, chunk_seq=seq) + text = text[50:] + seq += 1 + self.statustext_id += 1 + if self.statustext_id > 255: + self.statustext_id = 1 def get_stacktrace(self): return ''.join(traceback.format_stack()) @@ -7833,6 +7861,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= name = test.name desc = test.description test_function = test.function + test_kwargs = test.kwargs if attempt != 1: self.progress("RETRYING %s" % name) test_output_filename = self.buildlogs_path("%s-%s-retry-%u.txt" % @@ -7869,7 +7898,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= orig_speedup = self.get_parameter("SIM_SPEEDUP") self.set_parameter("SIM_SPEEDUP", test.speedup) - test_function() + test_function(**test_kwargs) except Exception as e: self.print_exception_caught(e) ex = e @@ -8076,10 +8105,11 @@ def start_SITL(self, binary=None, sitl_home=None, **sitl_args): count = 0 for sup_binary in self.sup_binaries: self.progress("Starting Supplementary Program ", sup_binary) - start_sitl_args["customisations"] = [sup_binary[1]] + start_sitl_args["customisations"] = [sup_binary['customisation']] start_sitl_args["supplementary"] = True - start_sitl_args["stdout_prefix"] = "%s-%u" % (os.path.basename(sup_binary[0]), count) - sup_prog_link = util.start_SITL(sup_binary[0], **start_sitl_args) + start_sitl_args["stdout_prefix"] = "%s-%u" % (os.path.basename(sup_binary['binary']), count) + start_sitl_args["defaults_filepath"] = sup_binary['param_file'] + sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args) self.sup_prog.append(sup_prog_link) self.expect_list_add(sup_prog_link) count += 1 @@ -8122,25 +8152,18 @@ def start_sup_program(self, instance=None, args=None): "callgrind": self.callgrind, "wipe": True, } - if instance is None: - for sup_binary in self.sup_binaries: - start_sitl_args["customisations"] = [sup_binary[1]] - if args is not None: - start_sitl_args["customisations"] = [sup_binary[1], args] - start_sitl_args["supplementary"] = True - sup_prog_link = util.start_SITL(sup_binary[0], **start_sitl_args) - time.sleep(3) - self.sup_prog.append(sup_prog_link) # add to list - self.expect_list_add(sup_prog_link) # add to expect list - else: - # start only the instance passed - start_sitl_args["customisations"] = [self.sup_binaries[instance][1]] + for i in range(len(self.sup_binaries)): + if instance is not None and instance != i: + continue + sup_binary = self.sup_binaries[i] + start_sitl_args["customisations"] = [sup_binary['customisation']] if args is not None: - start_sitl_args["customisations"] = [self.sup_binaries[instance][1], args] + start_sitl_args["customisations"] = [sup_binary['customisation'], args] start_sitl_args["supplementary"] = True - sup_prog_link = util.start_SITL(self.sup_binaries[instance][0], **start_sitl_args) - time.sleep(3) - self.sup_prog[instance] = sup_prog_link # add to list + start_sitl_args["defaults_filepath"] = sup_binary['param_file'] + sup_prog_link = util.start_SITL(sup_binary['binary'], **start_sitl_args) + time.sleep(1) + self.sup_prog[i] = sup_prog_link # add to list self.expect_list_add(sup_prog_link) # add to expect list def sitl_is_running(self): @@ -8445,11 +8468,11 @@ def SetHome(self): start_loc = self.sitl_start_location() self.progress("SITL start loc: %s" % str(start_loc)) delta = abs(orig_home.latitude * 1.0e-7 - start_loc.lat) - if delta > 0.000001: + if delta > 0.000006: raise ValueError("homes differ in lat got=%f vs want=%f delta=%f" % (orig_home.latitude * 1.0e-7, start_loc.lat, delta)) delta = abs(orig_home.longitude * 1.0e-7 - start_loc.lng) - if delta > 0.000001: + if delta > 0.000006: raise ValueError("homes differ in lon got=%f vs want=%f delta=%f" % (orig_home.longitude * 1.0e-7, start_loc.lng, delta)) if self.is_rover(): @@ -9714,7 +9737,7 @@ def ArmFeatures(self): self.progress("ALL PASS") # TODO : Test arming magic; - def get_message_rate(self, victim_message, timeout=10, mav=None): + def measure_message_rate(self, victim_message, timeout=10, mav=None): if mav is None: mav = self.mav tstart = self.get_sim_time() @@ -9738,25 +9761,40 @@ def get_message_rate(self, victim_message, timeout=10, mav=None): def rate_to_interval_us(self, rate): return 1/float(rate)*1000000.0 - def set_message_rate_hz(self, id, rate_hz, mav=None): + def interval_us_to_rate(self, interval): + if interval == 0: + raise ValueError("Zero interval is infinite rate") + return 1000000.0/float(interval) + + def set_message_rate_hz(self, id, rate_hz, mav=None, run_cmd=None): '''set a message rate in Hz; 0 for original, -1 to disable''' - if type(id) == str: + if run_cmd is None: + run_cmd = self.run_cmd + if isinstance(id, str): id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % id) if rate_hz == 0 or rate_hz == -1: set_interval = rate_hz else: set_interval = self.rate_to_interval_us(rate_hz) - self.run_cmd( + run_cmd( mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, p1=id, p2=set_interval, mav=mav, ) + def get_message_rate_hz(self, id, mav=None, run_cmd=None): + '''return rate message is being sent, in Hz''' + if run_cmd is None: + run_cmd = self.run_cmd + + interval = self.get_message_interval(id, mav=mav, run_cmd=run_cmd) + return self.interval_us_to_rate(interval) + def send_get_message_interval(self, victim_message, mav=None): if mav is None: mav = self.mav - if type(victim_message) == str: + if isinstance(victim_message, str): victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message) mav.mav.command_long_send( 1, @@ -9771,6 +9809,32 @@ def send_get_message_interval(self, victim_message, mav=None): 0, 0) + def get_message_interval(self, victim_message, mav=None, run_cmd=None): + '''returns message interval in microseconds''' + if run_cmd is None: + run_cmd = self.run_cmd + + self.send_get_message_interval(victim_message, mav=mav) + m = self.assert_receive_message('MESSAGE_INTERVAL', timeout=1, mav=mav) + + if isinstance(victim_message, str): + victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message) + if m.message_id != victim_message: + raise NotAchievedException(f"Unexpected ID in MESSAGE_INTERVAL (want={victim_message}, got={m.message_id}") + + return m.interval_us + + def set_message_interval(self, victim_message, interval_us, mav=None): + '''sets message interval in microseconds''' + if isinstance(victim_message, str): + victim_message = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % victim_message) + self.run_cmd( + mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, + p1=victim_message, + p2=interval_us, + mav=mav, + ) + def test_rate(self, desc, in_rate, @@ -9787,7 +9851,7 @@ def test_rate(self, self.set_message_rate_hz(victim_message, in_rate, mav=mav) - new_measured_rate = self.get_message_rate(victim_message, timeout=message_rate_sample_period, mav=mav) + new_measured_rate = self.measure_message_rate(victim_message, timeout=message_rate_sample_period, mav=mav) self.progress( "Measured rate: %f (want %f)" % (round(new_measured_rate, ndigits=ndigits), @@ -9831,6 +9895,22 @@ def SET_MESSAGE_INTERVAL(self): self.start_subtest('Many-message tests') self.test_set_message_interval_many() + def MESSAGE_INTERVAL_COMMAND_INT(self): + '''Test MAV_CMD_SET_MESSAGE_INTERVAL works as COMMAND_INT''' + original_rate = round(self.measure_message_rate("VFR_HUD", 20)) + self.context_set_message_rate_hz('VFR_HUD', original_rate*2, run_cmd=self.run_cmd_int) + 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") + + self.start_subtest("Use REQUEST_MESSAGE via COMMAND_INT") + # 148 is AUTOPILOT_VERSION: + self.context_collect('AUTOPILOT_VERSION') + self.run_cmd_int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE, 148) + self.delay_sim_time(2) + count = len(self.context_collection('AUTOPILOT_VERSION')) + if count != 1: + raise NotAchievedException(f"Did not get single AUTOPILOT_VERSION message (count={count}") + def test_set_message_interval_many(self): messages = [ 'CAMERA_FEEDBACK', @@ -9859,7 +9939,7 @@ def assert_message_rate_hz(self, message, want_rate, sample_period=20, ndigits=0 if mav is None: mav = self.mav self.drain_mav(mav) - rate = round(self.get_message_rate(message, sample_period, mav=mav), ndigits=ndigits) + rate = round(self.measure_message_rate(message, sample_period, mav=mav), ndigits=ndigits) self.progress("%s: Want=%f got=%f" % (message, round(want_rate, ndigits=ndigits), round(rate, ndigits=ndigits))) if rate != want_rate: raise NotAchievedException("Did not get expected rate (want=%f got=%f)" % (want_rate, rate)) @@ -9867,7 +9947,7 @@ def assert_message_rate_hz(self, message, want_rate, sample_period=20, ndigits=0 def test_set_message_interval_basic(self): ex = None try: - rate = round(self.get_message_rate("VFR_HUD", 20)) + rate = round(self.measure_message_rate("VFR_HUD", 20)) self.progress("Initial rate: %u" % rate) self.test_rate("Test set to %u" % (rate/2,), rate/2, rate/2, victim_message="VFR_HUD") @@ -9877,7 +9957,7 @@ def test_set_message_interval_basic(self): self.test_rate("Resetting original rate", 0, rate) self.progress("try getting a message which is not ordinarily streamed out") - rate = round(self.get_message_rate("CAMERA_FEEDBACK", 20)) + rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 20)) if rate != 0: raise PreconditionFailedException("Already getting CAMERA_FEEDBACK") self.progress("try various message rates") @@ -9894,7 +9974,7 @@ def test_set_message_interval_basic(self): want_rate = self.get_parameter("SCHED_LOOP_RATE") * 0.8 self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK, want_rate) - rate = round(self.get_message_rate("CAMERA_FEEDBACK", 20)) + rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 20)) self.set_parameter("SIM_SPEEDUP", old_speedup) self.progress("Want=%f got=%f" % (want_rate, rate)) if abs(rate - want_rate) > 2: @@ -9925,7 +10005,7 @@ def test_set_message_interval_basic(self): def send_poll_message(self, message_id, target_sysid=None, target_compid=None, quiet=False, mav=None): if mav is None: mav = self.mav - if type(message_id) == str: + if isinstance(message_id, str): message_id = eval("mavutil.mavlink.MAVLINK_MSG_ID_%s" % message_id) self.send_cmd( mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE, @@ -9939,7 +10019,7 @@ def send_poll_message(self, message_id, target_sysid=None, target_compid=None, q def poll_message(self, message_id, timeout=10, quiet=False, mav=None): if mav is None: mav = self.mav - if type(message_id) == str: + 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) @@ -9989,7 +10069,7 @@ def REQUEST_MESSAGE(self, timeout=60): '''Test MAV_CMD_REQUEST_MESSAGE''' self.set_parameter("CAM1_TYPE", 1) # Camera with servo trigger self.reboot_sitl() # needed for CAM1_TYPE to take effect - rate = round(self.get_message_rate("CAMERA_FEEDBACK", 10)) + rate = round(self.measure_message_rate("CAMERA_FEEDBACK", 10)) if rate != 0: raise PreconditionFailedException("Receiving camera feedback") self.poll_message("CAMERA_FEEDBACK") @@ -10000,10 +10080,11 @@ def clear_mission(self, mission_type, target_system=1, target_component=1): ''' if mission_type == mavutil.mavlink.MAV_MISSION_TYPE_ALL: # recurse - if not self.is_tracker() and not self.is_plane(): + if not self.is_tracker() and not self.is_blimp(): self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE) - self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION) - if not self.is_sub() and not self.is_tracker(): + if not self.is_blimp(): + self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION) + if not self.is_sub() and not self.is_tracker() and not self.is_blimp(): self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_RALLY) self.last_wp_load = time.time() return @@ -10953,6 +11034,9 @@ def send_yaw_rate_vel(rate, vector, mav_frame): self.do_RTL(distance_min=0, distance_max=wp_accuracy) self.disarm_vehicle() + def is_blimp(self): + return False + def is_copter(self): return False @@ -10990,7 +11074,7 @@ def upload_fences_from_locations(self, seq = 0 items = [] for locs in list_of_list_of_locs: - if type(locs) == dict: + 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 @@ -11038,6 +11122,22 @@ def upload_fences_from_locations(self, self.check_fence_upload_download(items) + def rally_MISSION_ITEM_INT_from_loc(self, loc): + return self.create_MISSION_ITEM_INT( + mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT, + x=int(loc.lat*1e7), + y=int(loc.lng*1e7), + z=loc.alt, + frame=mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, + mission_type=mavutil.mavlink.MAV_MISSION_TYPE_RALLY + ) + + def upload_rally_points_from_locations(self, rally_point_locs): + '''takes a sequence of locations, sets vehicle rally points to those locations''' + items = [self.rally_MISSION_ITEM_INT_from_loc(x) for x in rally_point_locs] + self.correct_wp_seq_numbers(items) + self.check_rally_upload_download(items) + def wait_for_initial_mode(self): '''wait until we get a heartbeat with an expected initial mode (the one specified in the vehicle constructor)''' @@ -11619,6 +11719,17 @@ def ahrstrim_preflight_cal(self): self.progress("Correct value %.4f for %s error %.2f%%" % (v, pname, error_pct)) + def user_takeoff(self, alt_min=30, timeout=30, max_err=5): + '''takeoff using mavlink takeoff command''' + self.run_cmd( + mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, + p7=alt_min, # param7 + ) + self.wait_altitude(alt_min - 1, + (alt_min + max_err), + relative=True, + timeout=timeout) + def ahrstrim_attitude_correctness(self): self.wait_ready_to_arm() HOME = self.sitl_start_location() @@ -12668,8 +12779,8 @@ def FRSkyD(self): # grab a battery-remaining percentage self.run_cmd( mavutil.mavlink.MAV_CMD_BATTERY_RESET, - p1=255, # battery mask - p2=96, # percentage + p1=65535, # battery mask + p2=96, # percentage ) m = self.assert_receive_message('BATTERY_STATUS', timeout=1) want_battery_remaining_pct = m.battery_remaining @@ -12964,6 +13075,12 @@ def CompassPrearms(self): }) self.assert_prearm_failure("Compasses inconsistent") self.context_pop() + self.wait_ready_to_arm() + # the following line papers over a probably problem with the + # EKF recovering from bad compass offsets. Without it, the + # EKF will maintain a 10-degree offset from the true compass + # heading seemingly indefinitely. + self.reboot_sitl() def AHRS_ORIENTATION(self): '''test AHRS_ORIENTATION parameter works''' @@ -12993,23 +13110,26 @@ def GPSTypes(self): # if gps_type is None we auto-detect sim_gps = [ # (0, "NONE"), - (1, "UBLOX", None, "u-blox"), - (5, "NMEA", 5, "NMEA"), - (6, "SBP", None, "SBP"), - # (7, "SBP2", 9, "SBP2"), # broken, "waiting for config data" - (8, "NOVA", 15, "NOVA"), # no attempt to auto-detect this in AP_GPS + (1, "UBLOX", None, "u-blox", 5, 'detected'), + (5, "NMEA", 5, "NMEA", 5, 'detected'), + (6, "SBP", None, "SBP", 5, 'detected'), + # (7, "SBP2", 9, "SBP2", 5), # broken, "waiting for config data" + (8, "NOVA", 15, "NOVA", 5, 'detected'), # no attempt to auto-detect this in AP_GPS + (11, "GSOF", 11, "GSOF", 5, 'detected'), + (19, "MSP", 19, "MSP", 32, 'specified'), # no attempt to auto-detect this in AP_GPS # (9, "FILE"), ] self.context_collect("STATUSTEXT") - for (sim_gps_type, name, gps_type, detect_name) in sim_gps: + 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("SERIAL3_PROTOCOL", serial_protocol) if gps_type is None: gps_type = 1 # auto-detect self.set_parameter("GPS_TYPE", gps_type) self.context_clear_collection('STATUSTEXT') self.reboot_sitl() - self.wait_statustext("detected as %s" % detect_name, check_context=True) + self.wait_statustext("%s as %s" % (detect_prefix, detect_name), check_context=True) n = self.poll_home_position(timeout=120) distance = self.get_distance_int(orig, n) if distance > 1: @@ -13163,7 +13283,7 @@ def write_content_to_filepath(self, content, filepath): '''write biunary content to filepath''' with open(filepath, "wb") as f: if sys.version_info.major >= 3: - if type(content) != bytes: + if not isinstance(content, bytes): raise NotAchievedException("Want bytes to write_content_to_filepath") f.write(content) f.close() @@ -13227,6 +13347,77 @@ def EmbeddedParamParser(self): self.customise_SITL_commandline([], binary=binary_with_defaults) self.assert_parameter_values(param_values) + def _MotorTest(self, + command, + timeout=60, + mot1_servo_chan=1, + mot4_servo_chan=4, + wait_finish_text=True, + quadplane=False): + '''Run Motor Tests (with specific mavlink message)''' + self.start_subtest("Testing PWM output") + pwm_in = 1300 + # default frame is "+" - start motor of 2 is "B", which is + # motor 1... see + # https://ardupilot.org/copter/docs/connect-escs-and-motors.html + command( + mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST, + p1=2, # start motor + p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM, + p3=pwm_in, # pwm-to-output + p4=2, # timeout in seconds + p5=2, # number of motors to output + p6=0, # compass learning + timeout=timeout, + ) + # long timeouts here because there's a pause before we start motors + self.wait_servo_channel_value(mot1_servo_chan, pwm_in, timeout=10) + self.wait_servo_channel_value(mot4_servo_chan, pwm_in, timeout=10) + if wait_finish_text: + self.wait_statustext("finished motor test") + self.wait_disarmed() + # wait_disarmed is not sufficient here; it's actually the + # *motors* being armed which causes the problem, not the + # vehicle's arm state! Could we use SYS_STATUS here instead? + self.delay_sim_time(10) + self.end_subtest("Testing PWM output") + + self.start_subtest("Testing percentage output") + percentage = 90.1 + # since MOT_SPIN_MIN and MOT_SPIN_MAX are not set, the RC3 + # min/max are used. + expected_pwm = 1000 + (self.get_parameter("RC3_MAX") - self.get_parameter("RC3_MIN")) * percentage/100.0 + # quadplane doesn't use the expect value - it wants 1900 + # rather than the calculated 1901... + if quadplane: + expected_pwm = 1900 + self.progress("expected pwm=%f" % expected_pwm) + command( + mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST, + p1=2, # start motor + p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PERCENT, + p3=percentage, # pwm-to-output + p4=2, # timeout in seconds + p5=2, # number of motors to output + p6=0, # compass learning + timeout=timeout, + ) + self.wait_servo_channel_value(mot1_servo_chan, expected_pwm, timeout=10) + self.wait_servo_channel_value(mot4_servo_chan, expected_pwm, timeout=10) + if wait_finish_text: + self.wait_statustext("finished motor test") + self.wait_disarmed() + # wait_disarmed is not sufficient here; it's actually the + # *motors* being armed which causes the problem, not the + # vehicle's arm state! Could we use SYS_STATUS here instead? + self.delay_sim_time(10) + self.end_subtest("Testing percentage output") + + def MotorTest(self, timeout=60, **kwargs): + '''Run Motor Tests''' # common to Copter and QuadPlane + self._MotorTest(self.run_cmd, **kwargs) + self._MotorTest(self.run_cmd_int, **kwargs) + def tests(self): return [ self.PIDTuning, @@ -13262,7 +13453,7 @@ def autotest(self, tests=None, allow_skips=True): tests = self.tests() all_tests = [] for test in tests: - if type(test) != Test: + if not isinstance(test, Test): test = Test(test) all_tests.append(test) diff --git a/Tools/autotest/default_params/blimp.parm b/Tools/autotest/default_params/blimp.parm index 192455b115c7b9..a790eec33454f5 100644 --- a/Tools/autotest/default_params/blimp.parm +++ b/Tools/autotest/default_params/blimp.parm @@ -38,6 +38,18 @@ RC7_TRIM 1500 RC8_MAX 2000 RC8_MIN 1000 RC8_TRIM 1500 +SERVO1_MAX 2200 +SERVO1_MIN 500 +SERVO1_TRIM 1350 +SERVO2_MAX 2200 +SERVO2_MIN 500 +SERVO2_TRIM 1350 +SERVO3_MAX 2200 +SERVO3_MIN 500 +SERVO3_TRIM 1350 +SERVO4_MAX 2200 +SERVO4_MIN 500 +SERVO4_TRIM 1350 # setting servo functions for the four fins SERVO1_FUNCTION 33 @@ -76,16 +88,18 @@ INS_ACC3SCAL_Z 1.000 ARMING_RUDDER 0 GCS_PID_MASK 255 +SIM_SERVO_SPEED 0.06 +LOG_BITMASK 65535 # default PID params for position and velocity-controlled modes -MAX_POS_XY 0.3 +MAX_POS_XY 0.15 MAX_POS_YAW 0.3 MAX_POS_Z 0.15 -MAX_VEL_XY 0.4 -MAX_VEL_YAW 0.5 +MAX_VEL_XY 0.2 +MAX_VEL_YAW 0.4 MAX_VEL_Z 0.2 -VELXY_D 0.0 +VELXY_D 1.0 VELXY_FF 0.0 VELXY_FLTD 3.0 VELXY_FLTE 3.0 @@ -98,7 +112,7 @@ VELYAW_FLTD 3.0 VELYAW_FLTE 3.0 VELYAW_I 0.8 VELYAW_IMAX 5.0 -VELYAW_P 15.0 +VELYAW_P 10.0 VELZ_D 0.0 VELZ_FF 0.0 VELZ_FLTD 3.0 diff --git a/Tools/autotest/default_params/copter-heli-dual.parm b/Tools/autotest/default_params/copter-heli-dual.parm index d12d6725f63c4a..5b5e58adda58a6 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.0012 -ATC_RAT_PIT_P 0.001 -ATC_RAT_PIT_FF 0.17 +ATC_RAT_PIT_D 0.0005 +ATC_RAT_PIT_P 0.02 +ATC_RAT_PIT_FF 0.0 ATC_RAT_YAW_D 0.0015 ATC_RAT_YAW_P 0.14685 ATC_HOVR_ROL_TRM 0 diff --git a/Tools/autotest/default_params/copter-heli.parm b/Tools/autotest/default_params/copter-heli.parm index 08a836dd01f97f..994bf370801ecf 100644 --- a/Tools/autotest/default_params/copter-heli.parm +++ b/Tools/autotest/default_params/copter-heli.parm @@ -70,7 +70,7 @@ ATC_ACCEL_Y_MAX 60000 ATC_HOVR_ROL_TRM 320 H_COL_MAX 1740 H_COL_MIN 1460 -H_COL_ANG_MAX 10 +H_COL_ANG_MAX 12 H_COL_ANG_MIN -2 H_RSC_MODE 2 H_RSC_SETPOINT 66 diff --git a/Tools/autotest/default_params/copter-tri.parm b/Tools/autotest/default_params/copter-tri.parm index 0f861b77064703..16927c554186f5 100644 --- a/Tools/autotest/default_params/copter-tri.parm +++ b/Tools/autotest/default_params/copter-tri.parm @@ -1,6 +1,6 @@ SERVO7_MIN 1000 SERVO7_MAX 2000 -SERVO7_TRIM 1360 +SERVO7_TRIM 1500 FRAME_CLASS 7 ATC_RAT_YAW_FLTE 5.0 MOT_YAW_SV_ANGLE 60 diff --git a/Tools/autotest/default_params/copter.parm b/Tools/autotest/default_params/copter.parm index 7f41498a4ece87..17e5c25b26d972 100644 --- a/Tools/autotest/default_params/copter.parm +++ b/Tools/autotest/default_params/copter.parm @@ -2,8 +2,8 @@ FRAME_TYPE 0 FS_THR_ENABLE 1 ARSPD_PIN 1 ARSPD_BUS 2 -ATC_RAT_YAW_P 0.09 -ATC_RAT_YAW_I 0.009 +ATC_RAT_YAW_P 0.3 +ATC_RAT_YAW_I 0.02 BATT_MONITOR 4 COMPASS_OFS_X 5 COMPASS_OFS_Y 13 diff --git a/Tools/autotest/default_params/periph.parm b/Tools/autotest/default_params/periph.parm new file mode 100644 index 00000000000000..506d302c6676cc --- /dev/null +++ b/Tools/autotest/default_params/periph.parm @@ -0,0 +1,24 @@ +# parameters for SITL peripheral + +GPS_TYPE 1 +COMPASS_ENABLE 1 +BARO_ENABLE 1 +ARSPD_TYPE 100 +RNGFND1_TYPE 100 +RNGFND1_MAX_CM 12000 +BATT_MONITOR 16 +BATT_I2C_BUS 2 + +# by default disable motors/servos, overridden in vehicle specific parameters +OUT1_FUNCTION -1 +OUT2_FUNCTION -1 +OUT3_FUNCTION -1 +OUT4_FUNCTION -1 +OUT5_FUNCTION -1 +OUT6_FUNCTION -1 +OUT7_FUNCTION -1 +OUT8_FUNCTION -1 + +# enable some simulated ADSB vehicles +SIM_ADSB_COUNT 4 +ADSB_PORT 2 diff --git a/Tools/autotest/default_params/plane-jsbsim.parm b/Tools/autotest/default_params/plane-jsbsim.parm index e53e15acd64f26..a77ec1084ef7d1 100644 --- a/Tools/autotest/default_params/plane-jsbsim.parm +++ b/Tools/autotest/default_params/plane-jsbsim.parm @@ -7,6 +7,7 @@ TRIM_THROTTLE 50 LIM_PITCH_MIN -2000 LIM_PITCH_MAX 2500 LIM_ROLL_CD 6500 +LAND_DISARMDELAY 3 LAND_PITCH_CD 100 LAND_FLARE_SEC 3 ARSPD_USE 1 diff --git a/Tools/autotest/default_params/quad-can.parm b/Tools/autotest/default_params/quad-can.parm new file mode 100644 index 00000000000000..0fe872319e3659 --- /dev/null +++ b/Tools/autotest/default_params/quad-can.parm @@ -0,0 +1,8 @@ +CAN_P1_DRIVER 1 +CAN_D1_UC_ESC_BM 0x0F +SIM_CAN_SRV_MSK 0xFf +SIM_VIB_MOT_MAX 270 +GPS_TYPE 9 +RNGFND1_TYPE 24 +RNGFND1_MAX_CM 11000 +BATT_MONITOR 8 diff --git a/Tools/autotest/default_params/quad-periph.parm b/Tools/autotest/default_params/quad-periph.parm new file mode 100644 index 00000000000000..2e29723e09d2eb --- /dev/null +++ b/Tools/autotest/default_params/quad-periph.parm @@ -0,0 +1,17 @@ +# extra parameters for SITL peripheral quadplane + +SIM_CAN_SRV_MSK 0x0f + +# ESCs +OUT1_FUNCTION 33 +OUT1_MIN 1000 +OUT1_MAX 2000 +OUT2_FUNCTION 34 +OUT2_MIN 1000 +OUT2_MAX 2000 +OUT3_FUNCTION 35 +OUT3_MIN 1000 +OUT3_MAX 2000 +OUT4_FUNCTION 36 +OUT4_MIN 1000 +OUT4_MAX 2000 diff --git a/Tools/autotest/default_params/quadplane-can.parm b/Tools/autotest/default_params/quadplane-can.parm new file mode 100644 index 00000000000000..3971389f992640 --- /dev/null +++ b/Tools/autotest/default_params/quadplane-can.parm @@ -0,0 +1,13 @@ +CAN_P1_DRIVER 1 +CAN_D1_UC_ESC_BM 0xF0 +CAN_D1_UC_ESC_OF 4 +CAN_D1_UC_SRV_BM 0x0F +CAN_D1_UC_OPTION 16 +SIM_CAN_SRV_MSK 0xfff +SIM_VIB_MOT_MAX 270 +GPS_TYPE 9 +ARSPD_TYPE 8 +RNGFND1_TYPE 24 +RNGFND1_MAX_CM 11000 +RNGFND_LANDING 1 +BATT_MONITOR 8 diff --git a/Tools/autotest/default_params/quadplane-ice.parm b/Tools/autotest/default_params/quadplane-ice.parm index 9b645e2e46336a..1ed7ff8b84072d 100644 --- a/Tools/autotest/default_params/quadplane-ice.parm +++ b/Tools/autotest/default_params/quadplane-ice.parm @@ -1 +1,2 @@ Q_OPTIONS 64 +ICE_RPM_THRESH 50 # idles at 70 (1% thrust) diff --git a/Tools/autotest/default_params/quadplane-periph.parm b/Tools/autotest/default_params/quadplane-periph.parm new file mode 100644 index 00000000000000..dc7a19687b6122 --- /dev/null +++ b/Tools/autotest/default_params/quadplane-periph.parm @@ -0,0 +1,23 @@ +# extra parameters for SITL peripheral quadplane + +SIM_CAN_SRV_MSK 0xff + +# control surfaces +OUT1_FUNCTION 51 +OUT2_FUNCTION 52 +OUT3_FUNCTION 53 +OUT4_FUNCTION 54 + +# ESCs +OUT5_FUNCTION 33 +OUT5_MIN 1000 +OUT5_MAX 2000 +OUT6_FUNCTION 34 +OUT6_MIN 1000 +OUT6_MAX 2000 +OUT7_FUNCTION 35 +OUT7_MIN 1000 +OUT7_MAX 2000 +OUT8_FUNCTION 36 +OUT8_MIN 1000 +OUT8_MAX 2000 diff --git a/Tools/autotest/helicopter.py b/Tools/autotest/helicopter.py index ca7acdc1cc7ae8..0dddcea057b831 100644 --- a/Tools/autotest/helicopter.py +++ b/Tools/autotest/helicopter.py @@ -167,7 +167,7 @@ def takeoff(self, self.user_takeoff(alt_min=alt_min) else: self.set_rc(3, takeoff_throttle) - self.wait_for_alt(alt_min=alt_min, timeout=timeout) + self.wait_altitude(alt_min-1, alt_min+5, relative=True, timeout=timeout) self.hover() self.progress("TAKEOFF COMPLETE") @@ -194,7 +194,7 @@ def FlyEachFrame(self): # to carry the path to the JSON. actual_model = model.split(":")[0] defaults = self.model_defaults_filepath(actual_model) - if type(defaults) != list: + if not isinstance(defaults, list): defaults = [defaults] self.customise_SITL_commandline( ["--defaults", ','.join(defaults), ], @@ -303,7 +303,7 @@ def StabilizeTakeOff(self): if abs(m.relative_alt) > 100: raise NotAchievedException("Took off prematurely") self.progress("Pushing throttle past half-way") - self.set_rc(3, 1600) + self.set_rc(3, 1650) self.progress("Monitoring takeoff") self.wait_altitude(6.9, 8, relative=True) @@ -401,20 +401,27 @@ def ManAutoRotation(self, timeout=600): self.context_collect('STATUSTEXT') self.change_mode('STABILIZE') self.progress("Triggering manual autorotation by disabling interlock") - self.set_rc(3, 1300) + self.set_rc(3, 1000) self.set_rc(8, 1000) - self.wait_servo_channel_value(8, 1200, timeout=3) + self.wait_servo_channel_value(8, 1199, timeout=3) self.progress("channel 8 set to autorotation window") + # wait to establish autorotation + self.delay_sim_time(2) + self.set_rc(8, 2000) self.wait_servo_channel_value(8, 1659, timeout=AROT_RAMP_TIME * 1.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, 1700) + self.set_rc(3, 1500) self.delay_sim_time(5) # initiate autorotation again - self.set_rc(3, 1200) + self.set_rc(3, 1000) self.set_rc(8, 1000) self.wait_statustext(r"SIM Hit ground at ([0-9.]+) m/s", @@ -549,11 +556,7 @@ def scurve_nasty_mission(self, target_system=1, target_component=1): copy.copy(wp5_by_three), self.mission_item_rtl(target_system=target_system, target_component=target_component), ]) - # renumber the items: - count = 0 - for item in ret: - item.seq = count - count += 1 + self.correct_wp_seq_numbers(ret) return ret def scurve_nasty_up_mission(self, target_system=1, target_component=1): @@ -626,11 +629,7 @@ def scurve_nasty_up_mission(self, target_system=1, target_component=1): wp7, self.mission_item_rtl(target_system=target_system, target_component=target_component), ]) - # renumber the items: - count = 0 - for item in ret: - item.seq = count - count += 1 + self.correct_wp_seq_numbers(ret) return ret def fly_mission_points(self, points): diff --git a/Tools/autotest/logger_metadata/enum_parse.py b/Tools/autotest/logger_metadata/enum_parse.py index 24ff2106653a02..50c026a21651f3 100755 --- a/Tools/autotest/logger_metadata/enum_parse.py +++ b/Tools/autotest/logger_metadata/enum_parse.py @@ -72,6 +72,11 @@ def match_enum_line(self, line): # Match: " FRED = 17, // optional comment" m = re.match("\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+) *\\) *,?(?: *// *(.*) *)?$", + line) if m is not None: return (None, None, None) diff --git a/Tools/autotest/logger_metadata/parse.py b/Tools/autotest/logger_metadata/parse.py index d66d557cf3b131..ea58198ea2bcc8 100755 --- a/Tools/autotest/logger_metadata/parse.py +++ b/Tools/autotest/logger_metadata/parse.py @@ -186,7 +186,7 @@ def emit_output(self): # expand things like PIDR,PIDQ,PIDA into multiple doccos new_doccos = [] for docco in self.doccos: - if type(docco.name) == list: + if isinstance(docco.name, list): for name in docco.name: tmpdocco = copy.copy(docco) tmpdocco.name = name diff --git a/Tools/autotest/param_metadata/param.py b/Tools/autotest/param_metadata/param.py index deb7861c422eea..3cc5266a47ecc4 100644 --- a/Tools/autotest/param_metadata/param.py +++ b/Tools/autotest/param_metadata/param.py @@ -4,6 +4,9 @@ def __init__(self, name, real_path): self.name = name self.real_path = real_path + def change_name(self, name): + self.name = name + class Vehicle(object): def __init__(self, name, path, reference=None): @@ -47,6 +50,7 @@ def has_param(self, pname): 'Volatile', 'ReadOnly', 'Calibration', + 'Vector3Parameter', ] # Follow SI units conventions from: @@ -125,6 +129,7 @@ def has_param(self, pname): 'kg/m/m' : 'kilograms per square meter', # metre is the SI unit name, meter is the american spelling of it 'kg/m/m/m': 'kilograms per cubic meter', 'litres' : 'litres', + 'Ohm' : 'Ohm', } required_param_fields = [ diff --git a/Tools/autotest/param_metadata/param_parse.py b/Tools/autotest/param_metadata/param_parse.py index ed39e3330261ba..7f5f9c21202dee 100755 --- a/Tools/autotest/param_metadata/param_parse.py +++ b/Tools/autotest/param_metadata/param_parse.py @@ -352,11 +352,25 @@ def process_library(vehicle, library, pathprefix=None): # applicable for this vehicle. continue - p.path = path # Add path. Later deleted - only used for duplicates - if library.check_duplicates and library.has_param(p.name): - error("Duplicate parameter %s in %s" % (p.name, library.name)) - continue - library.params.append(p) + if getattr(p, 'Vector3Parameter', None) is not None: + params_to_add = [] + for axis in 'X', 'Y', 'Z': + new_p = copy.copy(p) + new_p.change_name(p.name + "_" + axis) + for a in ["Description"]: + if hasattr(new_p, a): + current = getattr(new_p, a) + setattr(new_p, a, current + " (%s-axis)" % axis) + params_to_add.append(new_p) + else: + params_to_add = [p] + + for p in params_to_add: + p.path = path # Add path. Later deleted - only used for duplicates + if library.check_duplicates and library.has_param(p.name): + error("Duplicate parameter %s in %s" % (p.name, library.name)) + continue + library.params.append(p) group_matches = prog_groups.findall(p_text) debug("Found %u groups" % len(group_matches)) @@ -434,6 +448,9 @@ def clean_param(param): new_valueList.append(":".join([start, end])) param.Values = ",".join(new_valueList) + if hasattr(param, "Vector3Parameter"): + delattr(param, "Vector3Parameter") + def do_copy_values(vehicle_params, libraries, param): if not hasattr(param, "CopyValuesFrom"): @@ -441,6 +458,10 @@ def do_copy_values(vehicle_params, libraries, param): # so go and find the values... wanted_name = param.CopyValuesFrom + if hasattr(param, 'Vector3Parameter'): + suffix = param.name[-2:] + wanted_name += suffix + del param.CopyValuesFrom for x in vehicle_params: name = x.name @@ -470,6 +491,11 @@ def do_copy_fields(vehicle_params, libraries, param): # so go and find the values... wanted_name = param.CopyFieldsFrom del param.CopyFieldsFrom + + if hasattr(param, 'Vector3Parameter'): + suffix = param.name[-2:] + wanted_name += suffix + for x in vehicle_params: name = x.name (v, name) = name.split(":") diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index ec6b101aaa19a9..6b5729bf9894f2 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -506,7 +506,7 @@ def start_SITL(binary, '-d', '-m', '-S', 'ardupilot-gdb', - 'gdb', '-x', '/tmp/x.gdb', binary, '--args']) + 'gdb', '--cd', os.getcwd(), '-x', '/tmp/x.gdb', binary, '--args']) elif lldb: f = open("/tmp/x.lldb", "w") for breakingpoint in breakpoints: @@ -536,13 +536,6 @@ def start_SITL(binary, cmd.extend(['--speedup', str(speedup)]) if sim_rate_hz is not None: cmd.extend(['--rate', str(sim_rate_hz)]) - if defaults_filepath is not None: - if type(defaults_filepath) == list: - defaults = [reltopdir(path) for path in defaults_filepath] - if len(defaults): - cmd.extend(['--defaults', ",".join(defaults)]) - else: - cmd.extend(['--defaults', reltopdir(defaults_filepath)]) if unhide_parameters: cmd.extend(['--unhide-groups']) # somewhere for MAVProxy to connect to: @@ -550,6 +543,14 @@ def start_SITL(binary, if not enable_fgview_output: cmd.append("--disable-fgview") + if defaults_filepath is not None: + if isinstance(defaults_filepath, list): + defaults = [reltopdir(path) for path in defaults_filepath] + if len(defaults): + cmd.extend(['--defaults', ",".join(defaults)]) + else: + cmd.extend(['--defaults', reltopdir(defaults_filepath)]) + cmd.extend(customisations) pexpect_logfile_prefix = stdout_prefix diff --git a/Tools/autotest/pysim/vehicleinfo.py b/Tools/autotest/pysim/vehicleinfo.py index 7fe584587cfe6c..9709dcd917e0d2 100644 --- a/Tools/autotest/pysim/vehicleinfo.py +++ b/Tools/autotest/pysim/vehicleinfo.py @@ -188,6 +188,11 @@ def __init__(self): "default_params_filename": ["default_params/copter.parm", "models/Callisto.param"], }, + "quad-can": { + "waf_target": "bin/arducopter", + "default_params_filename": ["default_params/copter.parm", "default_params/quad-can.parm"], + "periph_params_filename": ["default_params/periph.parm", "default_params/quad-periph.parm"], + }, }, }, "Helicopter": { @@ -260,6 +265,11 @@ def __init__(self): "waf_target": "bin/arduplane", "default_params_filename": ["default_params/quadplane.parm", "default_params/plane-ice.parm", "default_params/quadplane-ice.parm"], }, + "quadplane-can": { + "waf_target": "bin/arduplane", + "default_params_filename": ["default_params/quadplane.parm", "default_params/quadplane-can.parm"], + "periph_params_filename": ["default_params/periph.parm", "default_params/quadplane-periph.parm"], + }, "firefly": { "waf_target": "bin/arduplane", "default_params_filename": "default_params/firefly.parm", @@ -419,6 +429,7 @@ def __init__(self): "gps": { "configure_target": "sitl_periph_gps", "waf_target": "bin/AP_Periph", + "default_params_filename": "default_params/periph.parm", }, } }, diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 9168130492cc17..9074baaceacade 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -11,8 +11,10 @@ import math from pymavlink import mavutil +from pymavlink.rotmat import Vector3 from common import AutoTest +from common import Test from common import AutoTestTimeoutException, NotAchievedException, PreconditionFailedException import operator @@ -169,6 +171,10 @@ def AirMode(self): self.wait_ready_to_arm() self.start_subtest("Verify that arming with switch does not spin motors in other modes") + # disable compass magnetic field arming check that is triggered by the simulated lean of vehicle + # this is required because adjusting the AHRS_TRIM values only affects the IMU and not external compasses + arming_magthresh = self.get_parameter("ARMING_MAGTHRESH") + self.set_parameter("ARMING_MAGTHRESH", 0) # introduce a large attitude error to verify that stabilization is not active ahrs_trim_x = self.get_parameter("AHRS_TRIM_X") self.set_parameter("AHRS_TRIM_X", math.radians(-60)) @@ -207,8 +213,9 @@ def AirMode(self): self.progress("Waiting for Motor1 to stop") self.wait_servo_channel_value(5, min_pwm, comparator=operator.le) self.wait_ready_to_arm() - # remove attitude error + # remove attitude error and reinstance compass arming check self.set_parameter("AHRS_TRIM_X", ahrs_trim_x) + self.set_parameter("ARMING_MAGTHRESH", arming_magthresh) self.start_subtest("verify that AIRMODE auxswitch turns airmode on/off while armed") """set RC7_OPTION to AIRMODE""" @@ -352,53 +359,99 @@ def EXTENDED_SYS_STATE(self): '''Check extended sys state works''' self.EXTENDED_SYS_STATE_SLT() - def fly_qautotune(self): - self.change_mode("QHOVER") - self.wait_ready_to_arm() - self.arm_vehicle() - self.set_rc(3, 1800) - self.wait_altitude(30, - 40, - relative=True, - timeout=30) + def QAUTOTUNE(self): + '''test Plane QAutoTune mode''' + + # this is a list of all parameters modified by QAUTOTUNE. Set + # them so that when the context is popped we get the original + # values back: + parameter_values = self.get_parameters([ + "Q_A_RAT_RLL_P", + "Q_A_RAT_RLL_I", + "Q_A_RAT_RLL_D", + "Q_A_ANG_RLL_P", + "Q_A_ACCEL_R_MAX", + "Q_A_RAT_PIT_P", + "Q_A_RAT_PIT_I", + "Q_A_RAT_PIT_D", + "Q_A_ANG_PIT_P", + "Q_A_ACCEL_P_MAX", + "Q_A_RAT_YAW_P", + "Q_A_RAT_YAW_I", + "Q_A_RAT_YAW_FLTE", + "Q_A_ANG_YAW_P", + "Q_A_ACCEL_Y_MAX", + ]) + self.set_parameters(parameter_values) + + self.takeoff(15, mode='GUIDED') self.set_rc(3, 1500) + self.change_mode("QLOITER") self.change_mode("QAUTOTUNE") tstart = self.get_sim_time() - sim_time_expected = 5000 - deadline = tstart + sim_time_expected - while self.get_sim_time_cached() < deadline: + self.context_collect('STATUSTEXT') + while True: now = self.get_sim_time_cached() - m = self.mav.recv_match(type='STATUSTEXT', - blocking=True, - timeout=1) - if m is None: + if now - tstart > 5000: + raise NotAchievedException("Did not get success message") + try: + self.wait_text("AutoTune: Success", timeout=1, check_context=True) + except AutoTestTimeoutException: continue - self.progress("STATUSTEXT (%u<%u): %s" % (now, deadline, m.text)) - if "AutoTune: Success" in m.text: - break + # got success message + break self.progress("AUTOTUNE OK (%u seconds)" % (now - tstart)) + self.context_clear_collection('STATUSTEXT') + + self.progress("Landing to save gains") self.set_rc(3, 1200) - self.wait_altitude(-5, 1, relative=True, timeout=30) - while self.get_sim_time_cached() < deadline: - self.mavproxy.send('disarm\n') + self.wait_speed_vector( + Vector3(float('nan'), float('nan'), 1.4), + timeout=5, + ) + self.wait_speed_vector( + Vector3(0.0, 0.0, 0.0), + timeout=20, + ) + distance = self.distance_to_home() + if distance > 20: + raise NotAchievedException("wandered from home (distance=%f)" % + (distance,)) + self.set_rc(3, 1000) + tstart = self.get_sim_time() + while True: + now = self.get_sim_time_cached() + if now - tstart > 500: + raise NotAchievedException("Did not get success message") + self.send_mavlink_disarm_command() try: - self.wait_text("AutoTune: Saved gains for Roll Pitch Yaw", timeout=0.5) + self.wait_text( + "AutoTune: Saved gains for Roll Pitch Yaw.*", + timeout=0.5, + check_context=True, + regex=True, + ) except AutoTestTimeoutException: continue break + self.wait_disarmed() + self.reboot_sitl() # far from home - def takeoff(self, height, mode): + def takeoff(self, height, mode, timeout=30): """climb to specified height and set throttle to 1500""" self.set_current_waypoint(0, check_afterwards=False) self.change_mode(mode) self.wait_ready_to_arm() self.arm_vehicle() + if mode == 'GUIDED': + self.user_takeoff(alt_min=height, timeout=timeout) + return self.set_rc(3, 1800) self.wait_altitude(height, height+5, relative=True, - timeout=30) + timeout=timeout) self.set_rc(3, 1500) def do_RTL(self): @@ -408,14 +461,24 @@ def do_RTL(self): self.zero_throttle() def fly_home_land_and_disarm(self, timeout=30): - self.set_parameter("LAND_TYPE", 0) - filename = "flaps.txt" + self.context_push() + self.change_mode('LOITER') + self.set_parameter('RTL_AUTOLAND', 2) + filename = "QuadPlaneDalbyRTL.txt" self.progress("Using %s to fly home" % filename) - self.load_mission(filename) - self.change_mode("AUTO") - self.set_current_waypoint(7) + self.load_generic_mission(filename) + self.send_cmd_do_set_mode("RTL") + self.wait_mode('AUTO') + self.wait_current_waypoint(4) + self.wait_statustext('Land descend started') + self.wait_statustext('Land final started', timeout=60) self.wait_disarmed(timeout=timeout) + self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_MISSION) + # the following command is accepted, but doesn't actually + # work! Should be able to remove check_afterwards! self.set_current_waypoint(0, check_afterwards=False) + self.change_mode('MANUAL') + self.context_pop() def wait_level_flight(self, accuracy=5, timeout=30): """Wait for level flight.""" @@ -682,6 +745,40 @@ def PilotYaw(self): self.set_rc(4, 1500) self.do_RTL() + def FwdThrInVTOL(self): + '''test use of fwd motor throttle into wind''' + self.set_parameters({"SIM_WIND_SPD": 25, # need very strong wind for this test + "SIM_WIND_DIR": 360, + "Q_WVANE_ENABLE": 1, + "Q_WVANE_GAIN": 1, + "STICK_MIXING": 0, + "Q_FWD_THR_USE": 2, + "SIM_ENGINE_FAIL": 2}) # we want to fail the forward thrust motor only + + self.takeoff(10, mode="QLOITER") + self.set_rc(2, 1000) + self.delay_sim_time(10) + # Check that it is using some forward throttle + fwd_thr_pwm = self.get_servo_channel_value(3) + if fwd_thr_pwm < 1150 : + raise NotAchievedException("fwd motor pwm command low, want >= 1150 got %f" % (fwd_thr_pwm)) + # check that pitch is on limit + m = self.mav.recv_match(type='ATTITUDE', blocking=True) + pitch = math.degrees(m.pitch) + if abs(pitch + 3.0) > 0.5 : + raise NotAchievedException("pitch should be -3.0 +- 0.5 deg, got %f" % (pitch)) + self.set_rc(2, 1500) + self.delay_sim_time(5) + loc1 = self.mav.location() + self.set_parameter("SIM_ENGINE_MUL", 0) # simulate a complete loss of forward motor thrust + self.delay_sim_time(20) + self.change_mode('QLAND') + self.wait_disarmed(timeout=60) + loc2 = self.mav.location() + position_drift = self.get_distance(loc1, loc2) + if position_drift > 5.0 : + raise NotAchievedException("position drift high, want < 5.0 m got %f m" % (position_drift)) + def Weathervane(self): '''test nose-into-wind functionality''' # We test nose into wind code paths and yaw direction in copter autotest, @@ -894,6 +991,19 @@ def LoiterAltQLand_Terrain(self, self.reset_SITL_commandline() self.context_pop() + def GUIDEDToAUTO(self): + '''Test using GUIDED mode for takeoff before shifting to auto''' + self.load_mission("mission.txt") + self.takeoff(30, mode='GUIDED') + + # extra checks would go here + self.assert_not_receiving_message('CAMERA_FEEDBACK') + + self.change_mode('AUTO') + self.wait_current_waypoint(3) + self.change_mode('QRTL') + self.wait_disarmed(timeout=240) + def Tailsitter(self): '''tailsitter test''' self.set_parameter('Q_FRAME_CLASS', 10) @@ -916,19 +1026,24 @@ def Tailsitter(self): raise NotAchievedException("Changed throttle output on mode change to QHOVER") self.disarm_vehicle() - def ICEngine(self): - '''Test ICE Engine support''' - rc_engine_start_chan = 11 + def setup_ICEngine_vehicle(self, start_chan): + '''restarts SITL with an IC Engine setup''' self.set_parameters({ - 'ICE_START_CHAN': rc_engine_start_chan, + 'ICE_START_CHAN': start_chan, }) - model = "quadplane-ice" + model = "quadplane-ice" self.customise_SITL_commandline( [], model=model, defaults_filepath=self.model_defaults_filepath(model), - wipe=False) + wipe=False, + ) + + def ICEngine(self): + '''Test ICE Engine support''' + rc_engine_start_chan = 11 + self.setup_ICEngine_vehicle(start_chan=rc_engine_start_chan) self.wait_ready_to_arm() self.wait_rpm(1, 0, 0, minimum_duration=1) @@ -946,7 +1061,7 @@ def ICEngine(self): self.wait_rpm(1, 6500, 7500, minimum_duration=30, timeout=40) self.progress("Setting min-throttle") self.set_rc(3, 1000) - self.wait_rpm(1, 300, 400, minimum_duration=1) + self.wait_rpm(1, 65, 75, minimum_duration=1) self.progress("Setting engine-start RC switch to LOW") self.set_rc(rc_engine_start_chan, 1000) self.wait_rpm(1, 0, 0, minimum_duration=1) @@ -967,18 +1082,8 @@ def ICEngine(self): def ICEngineMission(self): '''Test ICE Engine Mission support''' rc_engine_start_chan = 11 - self.set_parameters({ - 'ICE_START_CHAN': rc_engine_start_chan, - }) - model = "quadplane-ice" + self.setup_ICEngine_vehicle(start_chan=rc_engine_start_chan) - self.customise_SITL_commandline( - [], - model=model, - defaults_filepath=self.model_defaults_filepath(model), - wipe=False) - - self.reboot_sitl() self.load_mission("mission.txt") self.wait_ready_to_arm() self.set_rc(rc_engine_start_chan, 2000) @@ -986,6 +1091,81 @@ def ICEngineMission(self): self.change_mode('AUTO') self.wait_disarmed(timeout=300) + def MAV_CMD_DO_ENGINE_CONTROL(self): + '''test MAV_CMD_DO_ENGINE_CONTROL mavlink command''' + + expected_idle_rpm_min = 65 + expected_idle_rpm_max = 75 + expected_starter_rpm_min = 345 + expected_starter_rpm_max = 355 + + rc_engine_start_chan = 11 + self.setup_ICEngine_vehicle(start_chan=rc_engine_start_chan) + + self.wait_ready_to_arm() + + for method in self.run_cmd, self.run_cmd_int: + self.change_mode('MANUAL') + self.set_rc(rc_engine_start_chan, 1500) # allow motor to run + self.wait_rpm(1, 0, 0, minimum_duration=1) + self.arm_vehicle() + self.wait_rpm(1, 0, 0, minimum_duration=1) + self.start_subtest("Start motor") + method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1) + self.wait_rpm(1, expected_starter_rpm_min, expected_starter_rpm_max) + self.wait_rpm(1, expected_idle_rpm_min, expected_idle_rpm_max, minimum_duration=10) + + # starting the motor while it is running is failure + # (probably wrong, but that's how this works): + self.start_subtest("try start motor again") + self.context_collect('STATUSTEXT') + method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1, want_result=mavutil.mavlink.MAV_RESULT_FAILED) + self.wait_statustext("already running", check_context=True) + self.context_stop_collecting('STATUSTEXT') + # shouldn't affect run state: + self.wait_rpm(1, expected_idle_rpm_min, expected_idle_rpm_max, minimum_duration=1) + + self.start_subtest("Stop motor") + method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0) + self.wait_rpm(1, 0, 0, minimum_duration=1) + + self.start_subtest("Stop motor (again)") + method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0) + self.wait_rpm(1, 0, 0, minimum_duration=1) + + self.start_subtest("Check start chan control disable") + old_start_channel_value = self.get_rc_channel_value(rc_engine_start_chan) + self.set_rc(rc_engine_start_chan, 1000) + self.context_collect('STATUSTEXT') + method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1, want_result=mavutil.mavlink.MAV_RESULT_FAILED) + self.wait_statustext("start control disabled", check_context=True) + self.context_stop_collecting('STATUSTEXT') + self.set_rc(rc_engine_start_chan, old_start_channel_value) + self.wait_rpm(1, 0, 0, minimum_duration=1) + + self.start_subtest("test start-at-height") + self.wait_rpm(1, 0, 0, minimum_duration=1) + self.context_collect('STATUSTEXT') + method( + mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, + p1=1, # start + p3=15.5, # ... at 15.5 metres + ) + self.wait_statustext("height set to 15.5m", check_context=True) + self.wait_rpm(1, 0, 0, minimum_duration=2) + + self.takeoff(20, mode='GUIDED') + self.wait_rpm(1, expected_starter_rpm_min, expected_starter_rpm_max, minimum_duration=1) + self.wait_statustext("Engine running", check_context=True) + self.context_stop_collecting('STATUSTEXT') + + # stop the motor again: + method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=0) + self.wait_rpm(1, 0, 0, minimum_duration=1) + + self.change_mode('QLAND') + self.wait_disarmed() + def Ship(self): '''Ensure we can take off from simulated ship''' self.context_push() @@ -1208,15 +1388,71 @@ def RCDisableAirspeedUse(self): self.context_pop() self.reboot_sitl() + def mission_MAV_CMD_DO_VTOL_TRANSITION(self): + '''mission item forces transition''' + wps = self.create_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 200, 0, 30), + self.create_MISSION_ITEM_INT( + mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION, + p1=mavutil.mavlink.MAV_VTOL_STATE_MC + ), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 300, 200, 30), + self.create_MISSION_ITEM_INT( + mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION, + p1=mavutil.mavlink.MAV_VTOL_STATE_FW + ), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 100, 200, 30), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + self.check_mission_upload_download(wps) + + self.change_mode('AUTO') + self.wait_ready_to_arm() + + self.arm_vehicle() + self.wait_current_waypoint(4) + self.wait_servo_channel_value(5, 1200, comparator=operator.gt) + self.wait_current_waypoint(6) + self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90) + + self.fly_home_land_and_disarm() + + def mavlink_MAV_CMD_DO_VTOL_TRANSITION(self): + '''mavlink command forces transition during mission''' + 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.change_mode('AUTO') + self.wait_ready_to_arm() + + self.arm_vehicle() + self.wait_current_waypoint(2) + self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90) + + for command in self.run_cmd, self.run_cmd_int: + command(mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION, p1=mavutil.mavlink.MAV_VTOL_STATE_MC) + self.wait_servo_channel_value(5, 1200, comparator=operator.gt, timeout=300) + command(mavutil.mavlink.MAV_CMD_DO_VTOL_TRANSITION, p1=mavutil.mavlink.MAV_VTOL_STATE_FW) + self.wait_servo_channel_value(5, 1000, comparator=operator.eq, timeout=90) + + self.fly_home_land_and_disarm() + def tests(self): '''return list of all tests''' ret = super(AutoTestQuadPlane, self).tests() ret.extend([ + self.FwdThrInVTOL, self.AirMode, self.TestMotorMask, self.PilotYaw, self.ParameterChecks, + self.QAUTOTUNE, self.LogDownload, self.EXTENDED_SYS_STATE, self.Mission, @@ -1226,13 +1462,23 @@ def tests(self): self.Tailsitter, self.ICEngine, self.ICEngineMission, + self.MAV_CMD_DO_ENGINE_CONTROL, self.MidAirDisarmDisallowed, + self.GUIDEDToAUTO, self.BootInAUTO, self.Ship, self.MAV_CMD_NAV_LOITER_TO_ALT, self.LoiterAltQLand, self.VTOLLandSpiral, self.VTOLQuicktune, + Test(self.MotorTest, kwargs={ # tests motors 4 and 2 + "mot1_servo_chan": 8, # quad-x second motor cw from f-r + "mot4_servo_chan": 6, # quad-x third motor cw from f-r + "wait_finish_text": False, + "quadplane": True, + }), self.RCDisableAirspeedUse, + self.mission_MAV_CMD_DO_VTOL_TRANSITION, + self.mavlink_MAV_CMD_DO_VTOL_TRANSITION, ]) return ret diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 647f46b348ee9d..12c36f5dce1608 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -342,38 +342,21 @@ def Sprayer(self): def DriveMaxRCIN(self, timeout=30): """Drive rover at max RC inputs""" - self.context_push() - ex = None - - try: - self.progress("Testing max RC inputs") - self.change_mode("MANUAL") - - self.wait_ready_to_arm() - self.arm_vehicle() - - self.set_rc(3, 2000) - self.set_rc(1, 1000) + self.progress("Testing max RC inputs") + self.change_mode("MANUAL") - tstart = self.get_sim_time() - while self.get_sim_time_cached() - tstart < timeout: - m = self.mav.recv_match(type='VFR_HUD', blocking=True, timeout=1) - if m is not None: - self.progress("Current speed: %f" % m.groundspeed) + self.wait_ready_to_arm() + self.arm_vehicle() - # reduce throttle - self.set_rc(3, 1500) - self.set_rc(1, 1500) + self.set_rc(3, 2000) + self.set_rc(1, 1000) - except Exception as e: - self.print_exception_caught(e) - ex = e + tstart = self.get_sim_time() + while self.get_sim_time_cached() - tstart < timeout: + m = self.assert_receive_message('VFR_HUD') + self.progress("Current speed: %f" % m.groundspeed) self.disarm_vehicle() - self.context_pop() - - if ex: - raise ex ################################################# # AUTOTEST ALL @@ -599,14 +582,107 @@ def AC_Avoidance(self): def ServoRelayEvents(self): '''Test ServoRelayEvents''' - self.do_set_relay(0, 0) - off = self.get_parameter("SIM_PIN_MASK") - self.do_set_relay(0, 1) - on = self.get_parameter("SIM_PIN_MASK") - if on == off: - raise NotAchievedException( - "Pin mask unchanged after relay cmd") - self.progress("Pin mask changed after relay command") + for method in self.run_cmd, self.run_cmd_int: + self.context_push() + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0) + off = self.get_parameter("SIM_PIN_MASK") + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1) + on = self.get_parameter("SIM_PIN_MASK") + if on == off: + raise NotAchievedException( + "Pin mask unchanged after relay cmd") + self.progress("Pin mask changed after relay command") + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0) + + self.set_message_rate_hz("RELAY_STATUS", 10) + + # default configuration for relays in sim have one relay: + self.assert_received_message_field_values('RELAY_STATUS', { + "present": 3, + "on": 0, + }) + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1) + self.assert_received_message_field_values('RELAY_STATUS', { + "present": 3, + "on": 1, + }) + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=1, p2=1) + self.assert_received_message_field_values('RELAY_STATUS', { + "present": 3, + "on": 3, + }) + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0) + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=1, p2=0) + self.assert_received_message_field_values('RELAY_STATUS', { + "present": 3, + "on": 0, + }) + + # add another servo: + self.set_parameter("RELAY_PIN6", 14) + self.assert_received_message_field_values('RELAY_STATUS', { + "present": 35, + "on": 0, + }) + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=5, p2=1) + self.assert_received_message_field_values('RELAY_STATUS', { + "present": 35, + "on": 32, + }) + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1) + self.assert_received_message_field_values('RELAY_STATUS', { + "present": 35, + "on": 33, + }) + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=5, p2=0) + self.assert_received_message_field_values('RELAY_STATUS', { + "present": 35, + "on": 1, + }) + + self.start_subtest("test MAV_CMD_DO_REPEAT_RELAY") + self.context_push() + self.set_parameter("SIM_SPEEDUP", 1) + method( + mavutil.mavlink.MAV_CMD_DO_REPEAT_RELAY, + p1=0, # servo 1 + p2=5, # 5 times + p3=0.5, # 1 second between being on + ) + for value in 0, 1, 0, 1, 0, 1, 0, 1: + self.wait_message_field_values('RELAY_STATUS', { + "on": value, + }) + self.context_pop() + self.delay_sim_time(3) + self.assert_received_message_field_values('RELAY_STATUS', { + "on": 1, # back to initial state + }) + self.context_pop() + + self.start_subtest("test MAV_CMD_DO_SET_SERVO") + for value in 1678, 2300, 0: + method(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=13, p2=value) + self.wait_servo_channel_value(13, value) + + self.start_subtest("test MAV_CMD_DO_REPEAT_SERVO") + + self.context_push() + self.set_parameter("SIM_SPEEDUP", 1) + trim = self.get_parameter("SERVO13_TRIM") + value = 2000 + method( + mavutil.mavlink.MAV_CMD_DO_REPEAT_SERVO, + p1=12, # servo12 + p2=value, # pwm + p3=5, # count + p4=0.5, # cycle time (1 second between high and high) + ) + for value in trim, value, trim, value, trim, value, trim, value: + self.wait_servo_channel_value(12, value) + self.context_pop() + + self.set_message_rate_hz("RELAY_STATUS", 0) def MAVProxy_SetModeUsingSwitch(self): """Set modes via mavproxy switch""" @@ -1277,7 +1353,8 @@ def SYSID_ENFORCE(self): def Rally(self): '''Test Rally Points''' - self.load_rally("rover-test-rally.txt") + self.load_rally_using_mavproxy("rover-test-rally.txt") + self.assert_parameter_value('RALLY_TOTAL', 2) self.wait_ready_to_arm() self.arm_vehicle() @@ -6282,6 +6359,161 @@ def printmessage(mav, m): # both the vehicle and this tests's special heartbeat raise NotAchievedException("Got heartbeat on private channel from non-vehicle") + def MAV_CMD_DO_SET_REVERSE(self): + '''test MAV_CMD_DO_SET_REVERSE command''' + self.change_mode('GUIDED') + self.wait_ready_to_arm() + self.arm_vehicle() + + here = self.mav.location() + target_loc = self.offset_location_ne(here, 2000, 0) + self.send_guided_mission_item(target_loc) + + self.wait_groundspeed(3, 100, minimum_duration=5) + + for method in self.run_cmd, self.run_cmd_int: + self.progress("Forwards!") + method(mavutil.mavlink.MAV_CMD_DO_SET_REVERSE, p1=0) + self.wait_heading(0) + + self.progress("Backwards!") + method(mavutil.mavlink.MAV_CMD_DO_SET_REVERSE, p1=1) + self.wait_heading(180) + + self.progress("Forwards!") + method(mavutil.mavlink.MAV_CMD_DO_SET_REVERSE, p1=0) + self.wait_heading(0) + + self.disarm_vehicle() + + def MAV_CMD_NAV_RETURN_TO_LAUNCH(self): + '''test MAV_CMD_NAV_RETURN_TO_LAUNCH mavlink command''' + self.change_mode('GUIDED') + self.wait_ready_to_arm() + self.arm_vehicle() + + here = self.mav.location() + target_loc = self.offset_location_ne(here, 2000, 0) + self.send_guided_mission_item(target_loc) + self.wait_distance_to_home(20, 100) + + self.run_cmd(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH) + self.wait_mode('RTL') + + self.change_mode('GUIDED') + + self.run_cmd_int(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH) + self.wait_mode('RTL') + + self.wait_distance_to_home(0, 5, timeout=30) + self.disarm_vehicle() + + def MAV_CMD_DO_CHANGE_SPEED(self): + '''test MAV_CMD_NAV_RETURN_TO_LAUNCH mavlink command''' + self.change_mode('GUIDED') + self.wait_ready_to_arm() + self.arm_vehicle() + + original_loc = self.mav.location() + here = original_loc + target_loc = self.offset_location_ne(here, 2000, 0) + self.send_guided_mission_item(target_loc) + self.wait_distance_to_home(20, 100) + + speeds = 3, 7, 12, 4 + + for speed in speeds: + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, p2=speed) + self.wait_groundspeed(speed-0.5, speed+0.5, minimum_duration=5) + + self.send_guided_mission_item(original_loc) + + for speed in speeds: + self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, p2=speed) + self.wait_groundspeed(speed-0.5, speed+0.5, minimum_duration=5) + + self.change_mode('RTL') + + self.wait_distance_to_home(0, 5, timeout=30) + self.disarm_vehicle() + + def MAV_CMD_MISSION_START(self): + '''simple test for starting missing using this command''' + # home and 1 waypoint a long way away: + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 0), + ]) + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + for method in self.run_cmd, self.run_cmd_int: + self.change_mode('MANUAL') + self.wait_groundspeed(0, 1) + method(mavutil.mavlink.MAV_CMD_MISSION_START) + self.wait_mode('AUTO') + self.wait_groundspeed(3, 100) + self.disarm_vehicle() + + def MAV_CMD_NAV_SET_YAW_SPEED(self): + '''tests for MAV_CMD_NAV_SET_YAW_SPEED guided-mode command''' + self.change_mode('GUIDED') + self.wait_ready_to_arm() + self.arm_vehicle() + + for method in self.run_cmd, self.run_cmd_int: + self.change_mode('MANUAL') + self.wait_groundspeed(0, 1) + self.change_mode('GUIDED') + self.start_subtest("Absolute angles") + for (heading, speed) in (10, 5), (190, 10), (0, 2), (135, 6): + def cf(*args, **kwargs): + method( + mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED, + p1=heading, + p2=speed, + p3=0, # zero is absolute-angles + ) + self.wait_groundspeed(speed-0.5, speed+0.5, called_function=cf, minimum_duration=2) + self.wait_heading(heading-0.5, heading+0.5, called_function=cf, minimum_duration=2) + + self.start_subtest("relative angles") + original_angle = 90 + method( + mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED, + p1=original_angle, + p2=5, + p3=0, # zero is absolute-angles + ) + self.wait_groundspeed(4, 6) + self.wait_heading(original_angle-0.5, original_angle+0.5) + + expected_angle = original_angle + for (angle_delta, speed) in (5, 6), (-30, 2), (180, 7): + method( + mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED, + p1=angle_delta, + p2=speed, + p3=1, # one is relative-angles + ) + + def cf(*args, **kwargs): + method( + mavutil.mavlink.MAV_CMD_NAV_SET_YAW_SPEED, + p1=0, + p2=speed, + p3=1, # one is absolute-angles + ) + expected_angle += angle_delta + if expected_angle < 0: + expected_angle += 360 + if expected_angle > 360: + expected_angle -= 360 + self.wait_groundspeed(speed-0.5, speed+0.5, called_function=cf, minimum_duration=2) + self.wait_heading(expected_angle, called_function=cf, minimum_duration=2) + self.do_RTL() + self.disarm_vehicle() + def tests(self): '''return list of all tests''' ret = super(AutoTestRover, self).tests() @@ -6310,11 +6542,15 @@ def tests(self): self.Gripper, self.GripperMission, self.SET_MESSAGE_INTERVAL, + self.MESSAGE_INTERVAL_COMMAND_INT, self.REQUEST_MESSAGE, self.SYSID_ENFORCE, self.SET_ATTITUDE_TARGET, self.SET_POSITION_TARGET_LOCAL_NED, self.MAV_CMD_DO_SET_MISSION_CURRENT, + self.MAV_CMD_DO_CHANGE_SPEED, + self.MAV_CMD_MISSION_START, + self.MAV_CMD_NAV_SET_YAW_SPEED, self.Button, self.Rally, self.Offboard, @@ -6348,6 +6584,7 @@ def tests(self): self.DepthFinder, self.ChangeModeByNumber, self.EStopAtBoot, + self.MAV_CMD_NAV_RETURN_TO_LAUNCH, self.StickMixingAuto, self.AutoDock, self.PrivateChannel, @@ -6356,6 +6593,7 @@ def tests(self): self.DriveMaxRCIN, self.NoArmWithoutMissionItems, self.CompassPrearms, + self.MAV_CMD_DO_SET_REVERSE, ]) return ret diff --git a/Tools/autotest/run_in_terminal_window.sh b/Tools/autotest/run_in_terminal_window.sh index 86bd86a2d16200..7a83f1c565dacd 100755 --- a/Tools/autotest/run_in_terminal_window.sh +++ b/Tools/autotest/run_in_terminal_window.sh @@ -43,7 +43,7 @@ elif [ -n "$DISPLAY" -a -n "$(which gnome-terminal)" ]; then gnome-terminal -e "$*" elif [ -n "$STY" ]; then # We are running inside of screen, try to start it there - screen -X screen -t "$name" $* + screen -X screen -t "$name" bash -c "cd $PWD; $*" else filename="/tmp/$name.log" echo "RiTW: Window access not found, logging to $filename" diff --git a/Tools/autotest/run_mission.py b/Tools/autotest/run_mission.py new file mode 100755 index 00000000000000..99a0bc519868f5 --- /dev/null +++ b/Tools/autotest/run_mission.py @@ -0,0 +1,107 @@ +#!/usr/bin/python3 + +''' +Run a mission in SITL + +AP_FLAKE8_CLEAN +''' + +import common +import os +import sys +import argparse + +from pysim import util + + +class RunMission(common.AutoTest): + def __init__(self, vehicle_binary, model, mission_filepath, speedup=None, sim_rate_hz=None): + super(RunMission, self).__init__(vehicle_binary) + self.mission_filepath = mission_filepath + self.model = model + self.speedup = speedup + self.sim_rate_hz = sim_rate_hz + + if self.speedup is None: + self.speedup = 100 + + def vehicleinfo_key(self): + '''magically guess vehicleinfo_key from filepath''' + path = self.binary.lower() + if "plane" in path: + return "ArduPlane" + if "copter" in path: + return "ArduCopter" + raise ValueError("Can't determine vehicleinfo_key from binary path") + + def run(self): + self.start_SITL( + binary=self.binary, + model=self.model, + sitl_home=self.sitl_home_string_from_mission_filepath(self.mission_filepath), + speedup=self.speedup, + sim_rate_hz=self.sim_rate_hz, + defaults_filepath=self.model_defaults_filepath(self.model), + ) + self.get_mavlink_connection_going() + + # hack; Plane defaults are annoying... we should do better + # here somehow. + if self.vehicleinfo_key() == "ArduPlane": + self.set_parameter("RTL_AUTOLAND", 1) + + self.load_mission_from_filepath(self.mission_filepath, strict=False) + self.change_mode('AUTO') + self.set_streamrate(1) + self.wait_ready_to_arm() + self.arm_vehicle() + self.wait_disarmed(timeout=600) + self.stop_SITL() + + +if __name__ == "__main__": + ''' main program ''' + os.environ['PYTHONUNBUFFERED'] = '1' + + if sys.platform != "darwin": + os.putenv('TMPDIR', util.reltopdir('tmp')) + + parser = argparse.ArgumentParser("run_mission.py") + parser.add_argument( + 'vehicle_binary', + type=str, + help='vehicle binary to use' + ) + parser.add_argument( + 'model', + type=str, + help='vehicle model to use' + ) + parser.add_argument( + 'mission_filepath', + type=str, + help='mission file path' + ) + parser.add_argument( + '--speedup', + type=int, + help='simulation speedup', + default=None, + ) + parser.add_argument( + '--sim-rate-hz', + type=int, + help='simulation physics rate', + default=None, + ) + + args = parser.parse_args() + + x = RunMission( + args.vehicle_binary, + args.model, + args.mission_filepath, + speedup=args.speedup, + sim_rate_hz=args.sim_rate_hz + ) + x.run() diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 21efe9b6081872..3e0fb79eb4c566 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -660,13 +660,24 @@ def start_antenna_tracker(opts): os.chdir(oldpwd) -def start_CAN_GPS(opts): - """Compile and run the sitl_periph_gps""" +def start_CAN_Periph(opts, frame_info): + """Compile and run the sitl_periph""" global can_uarta progress("Preparing sitl_periph_gps") options = vinfo.options["sitl_periph_gps"]['frames']['gps'] - do_build(opts, options) + defaults_path = frame_info.get('periph_params_filename', None) + if defaults_path is None: + defaults_path = options.get('default_params_filename', None) + + if not isinstance(defaults_path, list): + defaults_path = [defaults_path] + + # add in path and make a comma separated list + defaults_path = ','.join([util.relcurdir(os.path.join(autotest_dir, p)) for p in defaults_path]) + + if not cmd_opts.no_rebuild: + do_build(opts, options) exe = os.path.join(root_dir, 'build/sitl_periph_gps', 'bin/AP_Periph') cmd = ["nice"] cmd_name = "sitl_periph_gps" @@ -689,6 +700,9 @@ def start_CAN_GPS(opts): cmd.extend(["-x", gdb_commands_file.name]) cmd.append("--args") cmd.append(exe) + if defaults_path is not None: + cmd.append("--defaults") + cmd.append(defaults_path) run_in_terminal_window(cmd_name, cmd) @@ -1131,10 +1145,10 @@ def generate_frame_help(): group_sim.add_option("", "--enable-onvif", action="store_true", help="enable onvif camera control sim using AntennaTracker") -group_sim.add_option("", "--can-gps", +group_sim.add_option("", "--can-peripherals", action='store_true', default=False, - help="start a DroneCAN GPS instance (use Tools/scripts/CAN/can_sitl_nodev.sh first)") + help="start a DroneCAN peripheral instance") group_sim.add_option("-A", "--sitl-instance-args", type='string', default=None, @@ -1472,8 +1486,8 @@ def generate_frame_help(): if cmd_opts.tracker: start_antenna_tracker(cmd_opts) -if cmd_opts.can_gps: - start_CAN_GPS(cmd_opts) +if cmd_opts.can_peripherals or frame_infos.get('periph_params_filename', None) is not None: + start_CAN_Periph(cmd_opts, frame_infos) if cmd_opts.custom_location: location = [(float)(x) for x in cmd_opts.custom_location.split(",")] @@ -1603,7 +1617,7 @@ def generate_frame_help(): entities[i][k] = v config['entities'] = list(entities.values()) env = Environment(loader=FileSystemLoader(os.path.join(autotest_dir, 'template'))) - mission = env.get_template('scrimmage.xml').render(**config) + mission = env.get_template('scrimmage.xml.j2').render(**config) tmp = mkstemp() atexit.register(os.remove, tmp[1]) diff --git a/Tools/autotest/template/scrimmage.xml b/Tools/autotest/template/scrimmage.xml.j2 similarity index 100% rename from Tools/autotest/template/scrimmage.xml rename to Tools/autotest/template/scrimmage.xml.j2 diff --git a/Tools/bootloaders/ACNS-CM4Pilot_bl.bin b/Tools/bootloaders/ACNS-CM4Pilot_bl.bin new file mode 100755 index 00000000000000..971f486cead951 Binary files /dev/null and b/Tools/bootloaders/ACNS-CM4Pilot_bl.bin differ diff --git a/Tools/bootloaders/ACNS-F405AIO_bl.bin b/Tools/bootloaders/ACNS-F405AIO_bl.bin new file mode 100755 index 00000000000000..5961638f2bb3f8 Binary files /dev/null and b/Tools/bootloaders/ACNS-F405AIO_bl.bin differ diff --git a/Tools/bootloaders/AR-F407SmartBat_bl.bin b/Tools/bootloaders/AR-F407SmartBat_bl.bin new file mode 100755 index 00000000000000..41d9182f704508 Binary files /dev/null and b/Tools/bootloaders/AR-F407SmartBat_bl.bin differ diff --git a/Tools/bootloaders/AR-F407SmartBat_bl.elf b/Tools/bootloaders/AR-F407SmartBat_bl.elf new file mode 100755 index 00000000000000..49212ab4543676 Binary files /dev/null and b/Tools/bootloaders/AR-F407SmartBat_bl.elf differ diff --git a/Tools/bootloaders/AR-F407SmartBat_bl.hex b/Tools/bootloaders/AR-F407SmartBat_bl.hex new file mode 100644 index 00000000000000..5f4de701c613b2 --- /dev/null +++ b/Tools/bootloaders/AR-F407SmartBat_bl.hex @@ -0,0 +1,1361 @@ +:020000040800F2 +:1000000000070020F5040008F92B0008952B0008D4 +:10001000D52B0008952B0008B52B0008F704000825 +:10002000F7040008F7040008F7040008413F00083F +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008414E0008694E000844 +:10006000914E0008B94E0008E14E0008F704000860 +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F7040008112B000823 +:100090003D2B0008692B0008F7040008094F0008F1 +:1000A000F7040008F7040008F7040008F704000844 +:1000B00005500008F7040008F7040008F7040008DA +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008F7040008F7040008F704000814 +:1000E0007D4F0008F7040008F7040008F704000833 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008F7040008A3 +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E000E51400080000000000000000000000000E +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600004F05EFA04F048FB4FF055301F491B4A77 +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE704F03CFAC8 +:1005B00004F028FB144C154DAC4203DA54F8041B2C +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E704F024BA0007002008 +:1005E000002300200000000808ED00E000010020CA +:1005F000000700206854000800230020802300200A +:1006000080230020684D0020E0010008E40100087C +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002003F02EFEF4 +:10064000FEE703F091FD00DFFEE70000F8B500F0E3 +:1006500051FF04F079F9064604F0CEF90746A8B92F +:100660002B4B9E422DD001339E422DD026F0FF020F +:10067000284B9A4203D0054641F2883408E0F0B294 +:1006800000F034FE3D4642F2107401E005460024BD +:1006900000F032FE08B10024254601F0D7FAB0B9C7 +:1006A00014B14FF47A74012517B11B4B9E4214D13B +:1006B000002004F055F9ADB900F098FE00F01CFFE1 +:1006C00022E005460024E3E700240125E0E70320BB +:1006D00000F02CF800242546E6E704F085F9002414 +:1006E0002546E5E700F040F8E6E700F0D1FE4FF4DC +:1006F0007A7003F0DBFD002CF7D002F085FA401B86 +:10070000A042F2D900F030F802F07EFA0546F2E796 +:10071000010007B0000008B0263A09B0302383F387 +:100720001188854680F308880847704708B50C4B48 +:100730001870032806D8DFE800F00A06020E02202F +:1007400000F046FF08BD022000F038FFFAE7054B35 +:1007500000225A60F6E7034B00225A60F2E700BF1E +:10076000802300208423002008B501F06FFA03469F +:1007700068B9072B0FD89A0002F1006202F58032A7 +:100780001268B2F1FF3F05D00133DBB2F1E703207D +:10079000FFF7CCFF08BD174B5A68013B9A42F9D9C5 +:1007A000154B9B6803F1006303F580339A42F1D245 +:1007B00004F0ECF804F0FEF8002000F0B9FE02208E +:1007C000FFF7B4FF0D4B1A6C00221A64196E1A66FB +:1007D000196E596C5A64596E5A665B6E72B6054B47 +:1007E0004FF0E022C2F8083D59681868FFF796FFFD +:1007F000D0E700BF000001080023002000380240BD +:10080000094A136899B21B0C49F2690000FB0133D5 +:100810001360064B186882B2000C44F2506101FB71 +:100820000200186080B270471823002014230020B3 +:1008300010B50446FFF7E4FFB0FBF4F304FB13002C +:1008400080B210BD10B40346002202604260826094 +:10085000C260044C07CC186059609A605DF8044B84 +:10086000704700BF107AFF1F70B50E4614461D4634 +:1008700002F070FE60B9022D33D1012C01D00020AE +:1008800030E019A3D3E90023C6E90023012029E0C1 +:10089000282C1FD00CD8012C15D0052C06D114A360 +:1008A000D3E90023C6E9002301201BE0002019E062 +:1008B000302C06D110A3D3E90023C6E90023012080 +:1008C00010E000200EE00EA3D3E90023C6E90023C8 +:1008D000012007E00CA3D3E90023C6E9002301208F +:1008E00000E0002070BD00BF401DA12026812A0B22 +:1008F000F017304A39059E5678F6339F93CACD8D4E +:100900009E6AC421818A46EE26417272DF25D7B7DE +:1009100070B58AB006460D4602F076F904464FF4EB +:10092000C870FFF785FF044404F51674174B1C606C +:10093000EB7E23B9164B00221A700AB070BD05A9D0 +:10094000284600F087FF0028F7D101A8FFF77AFFBB +:100950009DF81640224601A90DF1170004F0E4FBB2 +:1009600048B90F2C0BD80A4B1C70084A1368A3F522 +:1009700016731360E1E7064B00221A70DDE79DF85D +:100980001410304602F0DEFDD7E700BFA033002090 +:100990009D3300202DE9F043ADF5517D80460E4694 +:1009A0000DF5E2790027719740F27512394672A869 +:1009B00000F02CFE0EAC4FF4C4723946204600F015 +:1009C00025FE02F021F92F4BA3FB003080092E4BAE +:1009D000186093E8070084E8070002232374677413 +:1009E0000DF15A00FFF72EFF042384F820306E2308 +:1009F00084F821300DF1180C244D0FCDACE80F0018 +:100A000095E80F00ACE80700ACF800301D2384F82F +:100A100032310DF1180CBCE80F00CDF86B01CDF8A8 +:100A20006F11CDF87321CDF87731BCE80700CDF810 +:100A30007B01CDF87F11CDF883219CF800308DF833 +:100A4000873101224946204600F034FE80B20590ED +:100A5000CDF810900397B37E029306F1190301932A +:100A60000123009305A3D3E90023F17E404602F061 +:100A700027FE0DF5517DBDE8F08300BF9E6AC421BD +:100A8000818A46EED34D62108C2300201452000858 +:100A9000F0B5FDB006460D462B4B1C7A6CBB07A982 +:100AA000284600F01BFF002845D19DF81D70C82F77 +:100AB00041D84FF4A6620021234800F0A7FD032C83 +:100AC0000AD82202204B4FF48A7101FB0433C3F889 +:100AD000E4200134E4B2F2E71B4C3A460DF11E016A +:100AE00004F1090000F07EFDE219002353729DF825 +:100AF0001C3023720BB9EA7E2272812200213AA8AF +:100B000000F084FD5BAC012221463AA800F022FFF0 +:100B100080B20590049400230393AB7E029305F109 +:100B2000190301932823009305A3D3E90023E97E49 +:100B3000304602F0C5FD7DB0F0BD00BFAFF30080D0 +:100B400026417272DF25D7B7A8440020134BB3F8B3 +:100B50002C35834200D9704710B50446002100F0BF +:100B600011FD01340D4BA3F82C450C4BB3F82C05AB +:100B700000F0ECFC88B1094BB3F82C0500F0F8FC50 +:100B800058B9064C0021B4F82C0500F0FBFCB4F871 +:100B90002C350133A4F82C35E7E710BDA84400201C +:100BA0002DE9F041F0B00646274C94F8D8304FF4C8 +:100BB0008A7505FB004585F8DC30002785F8E8706C +:100BC000D82239463AA800F021FD04F10908404630 +:100BD00000F012FDC2B28DF8F020D5F8E4303A935F +:100BE0003B9741460DF1F10000F0FCFC06AD0122FF +:100BF00029463AA800F0D8FE80B20590049501235A +:100C000003930823029304F1D80301933023009344 +:100C10000BA3D3E90023217A0C4802F051FDB8421E +:100C200003DC002070B0BDE8F08101F0EDFF4FF46F +:100C30008A7202FB0646C6F8E0000120F2E700BF18 +:100C400078F6339F93CACD8DA8440020A4330020AA +:100C500038B501F0D9FF0546002408E00532B3EBB2 +:100C6000420F02D3FFF79CFFF8B10134E4B2032C2A +:100C70001BD80E4B93F8D900204400F003004FF42A +:100C80008A7202FB003393F8E830002BEDD1074B5A +:100C900002FB0033D3F8E030002BE3D0EB1A034A19 +:100CA0001268F92ADAD8FA22D8E738BDA844002019 +:100CB000F0B58FB000230A938DF834308DF83530BD +:100CC0000B930C9300242746002C46D101238DF86A +:100CD0000C3000238DF80D3041F2D00204FB02F2FB +:100CE000204955185258966800200021CDE900018E +:100CF0000DF10D0203A92846B0479DF80C604EB3D4 +:100D0000194A536983F48053536100230693079370 +:100D10000893099341F2D00304FB03F3114AD3581B +:100D20005F690DF10E0304AA0AA92846B84707AB6C +:100D30000BAA92E8030083E803009DF834308DF895 +:100D400024300A9B0693DDE9042306A9074802F034 +:100D5000BFFE37460134E4B2B6E7002FB2D10FB080 +:100D6000F0BD00BFD833002000080240A4330020AB +:100D700010B58CB0264802F0EDFB08B10CB010BDE8 +:100D800001F042FF234B1B689842F7D301F03CFF70 +:100D900004464FF4C870FFF74BFD044404F5167485 +:100DA0001C4B1C6000238DF828301B4B1B7813B99B +:100DB00001238DF8283006A8FFF744FD164B19785B +:100DC000C1F11004E4B2062C00D90624224606AB79 +:100DD00019440DF1290000F005FC013404940AAB1C +:100DE0000393182302930D4B01930123009306A351 +:100DF000D3E90023064802F003FC074B00221A70D7 +:100E0000BCE700BFAFF30080401DA12026812A0B64 +:100E1000A4330020A03300209D3300209C33002009 +:100E200010B588B001F0F0FE114BA3FB00239B0925 +:100E30001048036006AC0122214600F0E3FC80B2BA +:100E400004900394182302930B4B019340F2551323 +:100E5000009305A3D3E90023084802F0D1FB08B0B2 +:100E600010BD00BFAFF30080F1C6A7C1D068080F66 +:100E7000D34D62108C230020DC490020A4330020D5 +:100E800010B502460B46094C204602F051FC2046A4 +:100E900002F060FB38B1064B1B7A2BB10322054BE5 +:100EA0005A71FFF7BDFF10BD0222F8E7A4330020FE +:100EB000A84400208C230020012800D0704738B5BA +:100EC0004FF6FF73994200D038BD0025084C002D25 +:100ED00007DB204601F0C2F904F586541034013DC9 +:100EE000F5E7044A0449002004F0CEF8ECE700BF1F +:100EF000D8330020184A0020FD0E000838B50F4CEA +:100F00000F4B9C4219D0A4F58653A3F110040D4A4F +:100F100043F8102C41F25C03E21812793AB9E55813 +:100F20002DB1284600F0A0FE284604F0B3F804F5E1 +:100F30008250083000F098FEE2E738BDA844002057 +:100F4000D833002074520008F0B587B0254802F06D +:100F5000E3FB002839D00446002302938DF81430B7 +:100F60008DF8153003930493027B8DF8142003AAA7 +:100F70004068A16803C2226842F0004202921D4606 +:100F80001C46D5B941F2D00305FB03F3164A9E185F +:100F90009B581F6901F03CFE144A82184FF0000371 +:100FA000009341F1000302A93046B8470028C8BFAA +:100FB00044F001040135EDB2E3E744B90C4B1B7872 +:100FC000072B0BD801330A4A137007B0F0BD054850 +:100FD00002F0A6FB064B00221A70B7E7014802F0A8 +:100FE0009FFBF2E7A4330020D833002040420F00DB +:100FF000DD490020CA7E9B4B1B7A9A4240F031812A +:101000002DE9F04700AF08460024032C0CD8954B7F +:101010004FF48A7202FB043393F8DC20437E9A4239 +:1010200007D00134E4B2F0E7002323B9BD46BDE8A0 +:10103000F0870123F9E74FF48A7104FB01F1E031F5 +:10104000884B19440A3100F0DBFC0028EED1854BB7 +:101050004FF48A7202FB0434012384F8E83001F073 +:10106000D3FDD4F8E030C31A192B05D940F6B832B5 +:10107000934202D9134600E019237A4AD2ED007A4E +:10108000F8EE677A9FED787A27EE877A07EE903A46 +:10109000F8EE677ADFED756A67EEA67A77EE277A63 +:1010A000FCEEE77AC2ED007A3CE013464FF48A7218 +:1010B00002FB0535002385F8E830C5F8E030C54669 +:1010C000684B5B689B0A0133694A1381AEE70020D5 +:1010D00042F8040B013B002BF9DA2246304600F0BF +:1010E00081FA604B5B68002B4BD05E4B93F8D200CB +:1010F00000F02CFA8246002847D05A4BD3F8D4305F +:10110000002B4ED0574BD3F8D430234453454ED800 +:101110005FFA89F23146534B586800F081FA002893 +:101120004CD1C5464F4B93F8D9504FF48A7202FB0D +:10113000053393F8E830002BC2D0E846494A4FF413 +:101140008A7303FB0523D3F8E41053689942ACD1AA +:1011500044494FF48A7305FB03F3CA18B2F8EC4014 +:10116000E21C4FEA9209E03319440E314A4609F174 +:10117000FF3392000732D208A8EBC20295466E46B2 +:10118000A9E7012000F0D4F9AFE70024354B1C7229 +:1011900000F002FA204600F0CBF9354B0B221A8101 +:1011A0008DE7304B93F8D200FFF7D0FCAAE72D4B28 +:1011B00093F8D2000130FFF7C9FCA9E7294B5A6820 +:1011C00022445A60D3F8D4602644C3F8D46093F81C +:1011D000D20000F0BBF986420BD3224B93F8D22009 +:1011E000013283F8D220D3F8D420A2EB0A02C3F84C +:1011F000D420FF2C23D91B4C4FF48A7303FB0545E5 +:10120000002385F8E830C5F8E030D5F8E43003F580 +:101210008063C5F8E43094F8D900FFF7C1FCFFF70C +:1012200093FE94F8D93001335A4203F0030302F0DD +:10123000030258BF534284F8D930C54672E70024F0 +:10124000084B1C7200F0A8F9204600F071F900F07C +:10125000FDFC074A108108B1C546E7E6FFF784FAAE +:10126000FAE77047A84400206666663FCDCCCC3DC7 +:101270008C23002038B505460C4602F06BF950B1BE +:10128000E38A282B1CD014D8012B0FD121462846E5 +:10129000FFF780FB0CE0237E022B09D1E38A012BB0 +:1012A00006D121462846FFF733FB01E0052B0CD081 +:1012B00038BD302BFCD121462846FFF79BFEF7E7CF +:1012C00021462846FFF7E4FBF2E7BFF34F8F0549BD +:1012D000CA6802F4E062044B1343CB60BFF34F8F44 +:1012E00000BFFDE700ED00E00400FA05014B1870B7 +:1012F000704700BF9823002030B585B04FF00053F1 +:101300001A68324B9A420FD003F080FB044678B340 +:101310002F4A136C43F0007313642E4B9A6D2E4BBF +:101320009A4228D0002423E04FF00054607DFFF75C +:10133000DDFF227D294B1A72002309E01902274A9A +:101340004FF48A7000FB0322C2F8E4100133DBB2D1 +:10135000032BF3D94FF00054C92204F116012048A1 +:1013600000F040F9E0220021204600F04FF901246E +:10137000204605B030BD174B1B6E23B37F2B01D920 +:101380000024F5E7174A01AB10685168926807C35B +:10139000032101A800F08AFB0E4B5B6D984201D03F +:1013A0000024E5E70B4B1B6D994201D00024DFE7D9 +:1013B000084D0023AB6595F86000FFF797FFEA6DD5 +:1013C000094B1A60D4E70024D2E700BF9AAD44C5A8 +:1013D00000380240006600405041A0B0A844002000 +:1013E000B1440020586600401023002030B583B07F +:1013F00000F02CFC1D4B188102225A71002474B994 +:1014000041F2D00304FB03F319481A58556801222E +:10141000184909681844A8470134E4B2EFE70023EB +:101420000193154B0093154B4FF480521449154806 +:1014300002F06CF8144B197899B901F0E5FB0446F9 +:101440004FF4C870FFF7F4F9044404F516740F4B19 +:101450001C6003F0D1FA10B1044B0F221A8103B0C3 +:1014600030BD084802F06EF8E7E700BF8C2300208B +:10147000D8330020102300206908000875120008E6 +:101480009C230020A433002098230020A0330020B8 +:1014900008B50CE0114B186001F0BAFBFFF7F0FC47 +:1014A00013E0C82002F002FF0D4B1B7AA3B1FFF737 +:1014B0004BFDFFF7FDFBFFF75BFC01F0A5FB074BC6 +:1014C0001B68C31AB3F57A7FE4D2054B1B7A002B55 +:1014D000E7D0FFF7BDFBE4E708BD00BFD849002017 +:1014E000A844002008B54FF6FF710120FFF7E4FC87 +:1014F00008BD00BF704700BF10B503F0F9F80A4BF4 +:101500001880002406E003F0C9F80444074A136871 +:1015100001331360B4F5803F05D2034B1B88034AA7 +:1015200010688342EFD810BD0C4A0020E04900202B +:1015300008B503F037F908BD08B5920000F1006066 +:1015400000F5803003F02AF908BD00BF08B5064B4E +:101550001B88064A12689B1A834201D8002008BDE6 +:10156000104403F09BF8FAE70C4A0020E049002001 +:1015700008B5034B1B68184403F0BCF808BD00BF56 +:10158000E049002008B5034B1B68184403F0CAF873 +:1015900008BD00BFE049002008B5074B93F8243090 +:1015A0000BB9012008BD0449002381F8243008222A +:1015B000086AFFF7C1FFF5E7E4490020022800D0E0 +:1015C0007047024B4FF080529A61F9E700080240E1 +:1015D000022800D07047024B4FF480529A61F9E71D +:1015E00000080240002304E011F803C000F803C023 +:1015F00001339342F8D370470346002000E00130E6 +:1016000013F9012B002AFAD1704700BF034602E00C +:1016100003F8011B624602F1FF3C002AF8D1704733 +:101620002DE9F843814688461546214B93F824302E +:1016300033B31F4A126A02EB8303834220D0FFF7C1 +:10164000ABFF0346E0B930E0194E96F82400C0F134 +:101650000804AC4228BF2C46E4B2A7003A464146F3 +:1016600006EB8000FFF7BEFFB944B8442D1BEDB276 +:1016700096F824301C44E4B286F82440082C0DD09F +:1016800095B10B4B93F82430002BDDD10848C0F8FE +:1016900020902022FF21FFF7B9FFD5E7FFF77CFF5D +:1016A00003460028ECD100E001231846BDE8F8838A +:1016B000E44900202DE9F84380460E46914640F269 +:1016C000791200213046FFF7A1FF43462022002176 +:1016D000304602F079F908F1040302222021304655 +:1016E00002F072F908F1050303222221304602F0CC +:1016F0006BF908F1060303222521304602F064F954 +:1017000008F1080310222821304602F05DF908F1A3 +:10171000100308223821304602F056F908F111036F +:1017200008224021304602F04FF908F11203082246 +:101730004821304602F048F908F1140320225021D4 +:10174000304602F041F908F118034022702130467A +:1017500002F03AF908F120073B460822B021304652 +:1017600002F032F908F121030822B821304602F0D4 +:101770002BF9C025002408E03B1902330822294632 +:10178000304602F021F9083501340F2CF4D907F165 +:10179000120308222946304602F016F905F1080422 +:1017A0000025BB7C9D420BD205F110033B44033363 +:1017B00008222146304602F007F908340135F0E7E7 +:1017C000B9F1000F10D0002598F832319D4214D2A3 +:1017D00005F598734344033308222146304602F04E +:1017E000F3F808340135EFE708F59973072221462D +:1017F000304602F0E9F80734E5E7E01DC008BDE82F +:10180000F88300BF38B505460C4600212160C4F8B6 +:10181000031003462022204602F0D6F82B1D022298 +:101820002021204602F0D0F86B1D03222221204601 +:1018300002F0CAF8AB1D03222521204602F0C4F8AD +:1018400005F1080310222821204602F0BDF80720E8 +:1018500038BD00BFF0B583B007460E46047F009147 +:1018600000230722194601F0ADFF731C00930023EB +:1018700001220721384601F0A5FF3CB1BB8ADB00FD +:10188000083BDB08B3700825002414E0B31C009368 +:10189000002305220821384601F094FF0D25F3E7C7 +:1018A000331903330093002308222946384601F0F8 +:1018B00089FF08350134B3789C42F1D30735ED0830 +:1018C0003B7F2BB1B88A401B18BF012003B0F0BD8D +:1018D000B88AA8422CBF00200120F7E7F0B583B0FA +:1018E00007460C46057F009100230822194601F0A7 +:1018F00069FF661C3DB1BB8ADB00083BDB086370F7 +:101900000825002413E000960023082211463846DB +:1019100001F058FF1025F4E7331901330093002339 +:1019200008222946384601F04DFF08350134337846 +:101930009C42F1D30735ED083B7F2BB1B88A401BA1 +:1019400018BF012003B0F0BDB88AA8422CBF002008 +:101950000120F7E7F8B506460F461446812200211C +:101960003846FFF753FE334608220021384602F07E +:101970002BF814B10825002410E0731C072208215D +:10198000384602F021F80F25F5E733190233082213 +:101990002946384602F018F80835013473789C421D +:1019A000F3D3E81DC008F8BDF8B506460F46144647 +:1019B000CE2200213846FFF729FE33462822002197 +:1019C000384602F001F8083614B12825002410E04A +:1019D000334608222821384601F0F6FF3025F5E786 +:1019E0003319013308222946384601F0EDFF083546 +:1019F000013433789C42F3D3E81DC008F8BD00BF22 +:101A0000F0B583B007460E46047F009101231022F3 +:101A1000002101F0D7FE3CB1BB8ADB00103BDB08A4 +:101A200073801025002414E0B31C009300230922C6 +:101A30001021384601F0C6FE1925F3E733190433A7 +:101A40000093002308222946384601F0BBFE0835E2 +:101A5000013473889C42F1D30735ED083B7F2BB1ED +:101A6000B88A401B18BF012003B0F0BDB88AA84255 +:101A70002CBF00200120F7E700B58E460AE040F3B6 +:101A8000000C09490CEA010181EA50000133DBB284 +:101A9000072BF4D91346013A23B11EF8013B5840F5 +:101AA0000023F5E75DF804FB2083B8ED30B583B083 +:101AB00004460B464FF0FF30014620E00018494134 +:101AC0000133DBB2072B0BD80029F7DA10EB000C3F +:101AD00041EB010210488CEA000010495140EFE749 +:101AE0000EF1010E5FFA8EFEBEF1030F06D801ABB8 +:101AF00013F80E3081EA03610023E3E72B465D1EF5 +:101B0000ADB22BB154F8043B01934FF0000EEBE75C +:101B1000C043C94303B030BD9336EAA9EBE1F042BC +:101B2000F0B583B01F4B6A4693E8030082E80300D8 +:101B300008231D491D4803F007FB30B30446036921 +:101B4000B3F5702F23D8418B40F26E42914220D1E1 +:101B500000F11807164A024402F110018B421BD310 +:101B60009B1AA3F1100511490020FFF785FF0646D7 +:101B70002A4639460020FFF77FFFA368B3420DD104 +:101B8000E36883420CD1002004E00A2002E00B202D +:101B900000E00C2003B0F0BD1020FBE70D20F9E7BA +:101BA0000D20F7E734520008DCFF0E0000000108AA +:101BB0000800FFF7F0B583B0204B6A4693E80300B6 +:101BC00082E8030008231E491E4803F0BDFA38B31B +:101BD00004460369B3F5702F24D8B0F8661040F2BC +:101BE0006E42914220D100F16407174A024402F18B +:101BF0005C018B421BD39B1AA3F15C0511490020A9 +:101C0000FFF73AFF06462A4639460020FFF734FF21 +:101C1000A368B3420DD1E36883420CD1002004E0F5 +:101C20000A2002E00B2000E00C2003B0F0BD1020E1 +:101C3000FBE70D20F9E70D20F7E700BF4052000851 +:101C400090FF0E00000001080800FFF710B5FFF735 +:101C500067FF044608B9204610BDFFF7ABFF002818 +:101C6000F9D10446F7E700BF10B50446037C0BB179 +:101C7000204610BD006803F04FFAF9E7BFF35B8F11 +:101C8000C368BFF35B8FBFF35B8F8268BFF35B8F6B +:101C90009A4208D94268BFF35B8F8068BFF35B8FBD +:101CA000101A18447047BFF35B8F8068BFF35B8FD7 +:101CB000181A7047BFF35B8F0023C360BFF35B8FBD +:101CC000BFF35B8F8360BFF35B8F70470346406851 +:101CD00000B97047BFF35B8F9A68BFF35B8FBFF3A8 +:101CE0005B8FD968BFF35B8F914209D35868BFF30C +:101CF0005B8FDB68BFF35B8FD21A013A1044E8E7D1 +:101D00000020F4E738B505460C46FFF7B7FFA042C0 +:101D100001D2002038BDBFF35B8FA968BFF35B8F92 +:101D20000C446968B4FBF1F301FB1344BFF35B8F10 +:101D3000AC60BFF35B8F0120ECE700BF70B50446D9 +:101D40000E461546FFF7C2FFA84200D3284608B941 +:101D5000002070BD2368BFF35B8FE268BFF35B8F29 +:101D6000134433606268BFF35B8FE368BFF35B8F3C +:101D7000D11A884207D971602168B1609B1A184452 +:101D8000F0600220E5E770600120E2E738B5054623 +:101D90000C46FFF79BFFA04201D2002038BDBFF3E5 +:101DA0005B8FE968BFF35B8F0C446968B4FBF1F3A8 +:101DB00001FB1344BFF35B8FEC60BFF35B8F01202B +:101DC000ECE700BF2DE9F04385B0814688466946BF +:101DD000FFF7B4FF0746002425460EE004AB03EBF3 +:101DE000C40656F80C2C08EB050156F8100CFFF74A +:101DF000F9FB56F80C3C1D440134A742EEDC2946A1 +:101E00004846FFF7C3FF284605B0BDE8F08300BF92 +:101E1000BFF35B8FC368BFF35B8FBFF35B8F8268D9 +:101E2000BFF35B8F9A4210D94368BFF35B8F826820 +:101E3000BFF35B8F9B1A0B6073B10368BFF35B8FBB +:101E40008068BFF35B8F18447047BFF35B8F826875 +:101E5000BFF35B8F9B1AEEE700207047F0B583B0AD +:101E600007460E461546FFF709FF04460190A842B3 +:101E700000D32C4614B9002003B0F0BD01A93846A8 +:101E8000FFF7C6FF019B6BB1A34200D901943060FC +:101E900001987060A0420DD23B68B360241AF460D0 +:101EA0000220E9E73B68336074600023B360F360AD +:101EB0000120E1E70120DFE72DE9F04184B0884609 +:101EC0006946FFF7CBFF0746002425460EE004AB2A +:101ED00003EBC40656F80C2C56F8101C08EB050052 +:101EE000FFF780FB56F80C3C1D440134A742EEDCA2 +:101EF000284604B0BDE8F08138B50546FFF7DCFFA1 +:101F0000044601462846FFF7FDFE204638BD00BFC7 +:101F100010B5026854681A46A04710BD01207047EA +:101F20000020704700207047704700BF00207047B6 +:101F30000E20704700F5805090F8C800C0F34000B4 +:101F4000704700BF00F5805090F9C900704700BF8E +:101F5000F0B583B0BDF820500C6814F0005F40F07D +:101F60008C800C7B082C00F28B80302484F3118849 +:101F700062B64469A66816F0806F0FD1A66816F0A5 +:101F8000006F6DD1A66816F0805F02D04FF0020E90 +:101F900006E0002080F3118862B65FE04FF0000E8B +:101FA000F4460E68002E5EDB76050EF1180E4FEA41 +:101FB0000E1E44F80E600E6816F0804F06D00CF12D +:101FC00018063601A75947F00207A7510F7B0CF1FD +:101FD00018064FEA061E04EB061677608E6804EBBF +:101FE0000C17C7F88C614E68C7F8886154F80E600A +:101FF00046F0010644F80E6041F2680E0EEB4C14F8 +:10200000044400EB4C16764432607360D1F800E073 +:102010004F688E68C4F808E0E76026618E89A68262 +:102020000CF1840C00EB4C1C9CF8044065F300049C +:102030008CF80440C5F34006E4B266F341048CF822 +:102040000440E4B26FF3C3048CF80440002484F32A +:10205000118862B6009500F00FFE012003B0F0BDBC +:102060004FF0010E9CE7F60046F004060EF1180E44 +:102070004FEA0E1E44F80E609DE74FF0FF30EDE78B +:102080004FF0FF30EAE700BF08B5302383F3118833 +:1020900062B600F58050C06DFFF70CFE002383F39D +:1020A000118862B608BD00BF70B504460D4641F206 +:1020B0005C068059FFF70AFE1F2801D8002070BD7A +:1020C00020222946A059FFF77DFE202814BF0020BA +:1020D0000120F4E72DE9F04188B006460D46174689 +:1020E0009846302383F3118862B600220023CDE99D +:1020F00000230024ADF8084003948DF818408DF8B3 +:1021000019400494059441F25C040059FFF7B6FDB0 +:102110001F2807D8002078B980F3118862B608B06C +:10212000BDE8F081202269463059FFF7E5FE2028FE +:1021300014BF00200120EEE703AB07CB28606960E5 +:10214000AA601B88AB81DDE90023C7E90023BDF845 +:102150000830A8F80030002383F3118862B64346A4 +:102160003A462946304600F05FFDD8E710B5374BB8 +:1021700003600023436083600246354C42F8184BED +:10218000836113735373C36103629FED2E7B80EDF4 +:102190000A7B0386436380F8403080F841308363D4 +:1021A000C36300F1480423464FF07F0C0DE09FED20 +:1021B000257B83ED007B00221A81DA601A765A763D +:1021C0001A615A6120330CF1FF3CBCF1000FEEDACA +:1021D00000F58252083200F580539C644FF480541D +:1021E000DC6400241C655C654FF0010C83F858C06A +:1021F000DA6583F860C000F5835308334FF0020EB0 +:10220000BEF1000F11DB9C469FED0E7BACEC027B18 +:1022100000229A608CF80C208CF80D20DA601A618C +:102220009A6120330EF1FF3EEAE700F5805383F810 +:10223000C91011B9074B436110BD074800F0DEFC1F +:10224000AFF300800000000000000000BC52000856 +:1022500074520008006400404C52000810B5044657 +:10226000034B19784A1C1A70FFF780FF204610BDF7 +:10227000144A0020002977D070B582B00C46424B3A +:10228000994211D90A234149B1FBF4FC013BDBB26D +:102290009E46581CBCFBF0F100FB11C131B1022B72 +:1022A00064D9013BDBB2F3E71123ECE7BCFBF0F0B0 +:1022B000411EB1F5806F5CD2C3EBC30E1EF103016A +:1022C0004DD4C1F3C70C8DF800C0A3EB0C05EDB2E3 +:1022D0008DF801500CF101064FF47A710CFB0111DD +:1022E000354491FBF5F189B2ADF80210B1F5617F8B +:1022F00018D9BEF1010E34D4CEF3C70E8DF804E028 +:10230000A3EB0E03DBB28DF805300EF101054FF49F +:102310007A710EFB01112B4491FBF3F3ADF80630FB +:10232000019B00939DF800104B1C9DF80160334405 +:1023300000FB03F3154DB5FBF3F3A3421BD10139A9 +:10234000C9B20F2919D8D6B1082E1AD80138108071 +:1023500000239370D170013E1671012007E0073110 +:10236000AFE70EF1070EC7E700207047002002B06C +:1023700070BD0020FBE70020F9E70020F7E7002010 +:10238000F5E70020F3E700BF3F420F0080DE800248 +:1023900070B506460D460024B4F57A7F0BD27369FA +:1023A0005B6803F00103AB4207D04FF47A7001F091 +:1023B0007DFF0134F0E7002000E0012070BD00BF88 +:1023C000032964D870B588B004460D46164600F55A +:1023D000805393F8C830C3F3800113F0040F00D189 +:1023E000114604F5805393F8C82061F3820283F804 +:1023F000C82041F2680303EB451304EB030C05F11D +:10240000840304EB43131B7913F0010F08D03EB192 +:1024100005F1840304EB43131B7913F0080F10D06C +:102420006EB105F1840304EB43131B7913F0080F1D +:1024300005D1843504EB451443F00803237108B03B +:1024400070BD00220023CDE900230023ADF8083041 +:1024500003938DF818308DF819300493059303AB6E +:10246000DCF80800DCF80C10DCF8102007C3BCF81E +:1024700014201A80DDE90C23CDE900230123ADF8F7 +:1024800008302368DB6B694620469847C8E77047E9 +:102490004269936913F0700F23D00023936100E029 +:1024A0000133022B1DDC03F1840200EB421212798E +:1024B00012F0040FF4D003F1840200EB42121279FF +:1024C00012F0020FECD04269064951F823109160D6 +:1024D00003F1840200EB4212117941F00401117101 +:1024E000DEE770476052000870B582B004461646B9 +:1024F0001D4643699A6812F0010F0ED163699A680C +:1025000012F4807F14D163699A6812F4803F1CD161 +:102510002046FFF7BDFF02B070BD9A6801219960A7 +:1025200000960195C2F340020021FFF749FFE5E75D +:102530009A684FF48071996000960195C2F3402229 +:1025400001212046FFF73CFFDDE79A684FF4803118 +:10255000996000960195C2F3404202212046FFF7A0 +:102560002FFFD5E738B504460846002971D16169C7 +:1025700001F10C0CDCF8001011F0030F68D0DCF84E +:102580000010616900F11B052D014D5915F0040F74 +:1025900063D100F11B052D014D596D0DA56100F1B1 +:1025A0001B052D014D5915F0020F03D0A56945F00B +:1025B0008045A56100F11B0501EB05156D6805F06F +:1025C0000F0E84F824E001EB0011D1F8B801207758 +:1025D000D1F8B801000A6077D1F8B801000CA077F3 +:1025E000D1F8B801000EE077D1F8BC0184F82000E2 +:1025F000D1F8BC01000A84F82100D1F8BC01000C1C +:1026000084F82200D1F8BC11090E84F82310382177 +:10261000CCF80010A569E069216A6563A063E163F5 +:10262000A18CA4F84010A262E362002323862368F1 +:10263000DB6B04F128012046984704F5805292F89C +:10264000C83043F0040382F8C8302046FFF720FF6B +:1026500038BD616901F1100C8CE700F11B052D01FB +:102660004D59ED08A56145F00045A56197E700BF0C +:10267000302181F3118862B60021022937DC30B5A0 +:1026800002E0013102292DDC01F1840C00EB4C1C2D +:102690009CF804C01CF0040FF3D101F1840C00EB92 +:1026A0004C1C9CF804C01CF0100FEAD000EB411E3B +:1026B00041F2680C0EEB0C045EF80C506468954215 +:1026C0009C41DED244690C4D55F82150A56001F1C2 +:1026D000840C00EB4C1C9CF804E04EF0040E8CF8CB +:1026E00004E0CEE7002383F3118862B630BD0023F7 +:1026F00083F3118862B670476052000808B5302332 +:1027000083F3118862B6FFF7C3FE002383F31188B9 +:1027100062B608BD43699B6803F0E053B3F1E05F24 +:102720002DD070B505460E465BB3302383F3118878 +:1027300062B6002400E00134022C1ADC04F18403A8 +:1027400005EB43131B7913F0080FF4D104F1840354 +:1027500005EB43131B7913F0040FECD141F2700128 +:1027600001EB44112944304600F0C4FA0028E2D1BC +:1027700000E00120002383F3118862B670BD0120C0 +:1027800070470020FAE700BF08B5302383F31188B3 +:1027900062B600F58050C06DFFF770FA002383F336 +:1027A000118862B61F288CBF0020012008BD00BF21 +:1027B000F8B507460E4614461D4600231370FFF772 +:1027C000E3FF80F00103337025B129463846FFF757 +:1027D000A1FF2070F8BD00BFF8B504460D461646AF +:1027E0001F4600F015FA02460B46297809B93078E1 +:1027F00060B12046FFF73CFF2046FFF77FFF3B46D6 +:10280000324629462046FFF7D3FF0120F8BD00BF1E +:10281000302383F3118862B61C4B1A6C42F00072AD +:102820001A641A6A42F000721A621A6A22F000727E +:102830001A62002383F3118862B600F5805393F87F +:10284000C83013F0010F20D110B5044601B910BDF6 +:10285000302383F3118862B60321132001F0D0FBEB +:102860000321142001F0CCFB0321152001F0C8FB4B +:1028700004F5805494F8C83043F0010384F8C8305C +:10288000002383F3118862B6E1E770470038024005 +:1028900000F5805393F8C930012B00F233812DE904 +:1028A000F0418AB004460E461746984A52F8232053 +:1028B000002A38D0E6602774944B1B68002B36D072 +:1028C00004F5805393F8C930012B06D18F4B18685B +:1028D00003681B6B9847002838D001212046FFF77A +:1028E00097FF302383F3118862B66269136823F07F +:1028F000020313606269136843F0010313606269A5 +:102900000023536183F3118862B601212046FFF74B +:102910003FFD034648BB62694FF400411160184611 +:102920000AB0BDE8F081794A42F82300C2E741F2DB +:10293000D00002F0B1FB054610B10021FFF716FCF4 +:10294000724B1D60002DBBD10023E8E76F4D0021C5 +:102950002868FFF75DFF286803685B683A463146E0 +:10296000984703460028B8D1D9E704F58053D86DBD +:10297000FFF7A0F94FF000082BE020220021684665 +:10298000FEF744FE002302938DF814308DF81530C5 +:1029900003930493069341F2680505EB481504EB95 +:1029A000050EEC46BCE80F006051CEF80410CEF8DE +:1029B0000820CEF80C30BCE80700CEF81000CEF8A6 +:1029C0001410CEF818209CF800308EF81C3008F156 +:1029D0000108B8F1020FD0D904F5805393F8C8204C +:1029E0006FF3820283F8C8200023ADF820308DF801 +:1029F00022308DF823308DF8243008AA3146204645 +:102A0000FFF738FC034600286FD0636961221A6023 +:102A10009DF822301B0603F040739DF8232012041A +:102A200002F4702213439DF82420120502F4E00200 +:102A30001343BDF82020C2F309021343022F59D0DB +:102A4000002162690B43D361636913225A61626991 +:102A5000136823F00103136000212046FFF798FC60 +:102A60000346002849D004F5805292F8C9209ABB49 +:102A70006169D1F8002242F00102C1F800226169C7 +:102A8000D1F8002222F47C5222F00E02C1F800227A +:102A90006169D1F8002242F46062C1F800226169E4 +:102AA0000022C1F814226169C1F80422616941F66B +:102AB000FF70C1F80C026169C1F840226169C1F878 +:102AC000442262690121C2F81C126169D1F8002216 +:102AD00022F00102C1F8002204F5805494F8C820C5 +:102AE00042F0020284F8C82019E762694FF40041FD +:102AF000116014E74FF00041A3E762694FF4004111 +:102B000011600CE700231846704700BF104A0020F0 +:102B100008B500F07DF802460B4652EA030102D0E8 +:102B2000013A43F1FF330449086808B1FFF7DCFCC0 +:102B300001F03AFA08BD00BF104A002008B500F0C5 +:102B400067F802460B4652EA030102D0013A43F10C +:102B5000FF330449086810B10021FFF703FD01F0BD +:102B600023FA08BD104A002008B500F051F80246CB +:102B70000B4652EA030102D0013A43F1FF33044904 +:102B8000086810B10121FFF7EDFC01F00DFA08BD56 +:102B9000104A002000B59BB0EFF309816822684617 +:102BA000FEF720FDEFF30583014B9B6BFEE700BFB3 +:102BB00000ED00E000B59BB0EFF3098168226846A4 +:102BC000FEF710FDEFF30583014B9B6BFEE700BFA3 +:102BD00000ED00E000B59BB0EFF309816822684684 +:102BE000FEF700FDEFF30583014B5B6BFEE700BFD3 +:102BF00000ED00E0FEE700BFFEE700BF0FB408B540 +:102C0000029801F0E3FAFEE708B501F035FE08BDD1 +:102C100008B501F00BFE08BD00207047002070478A +:102C200000207047704700BF30B583B084460D4622 +:102C3000043003C802AA02E9030069B10C461B88EC +:102C400013F0040F08D1DCF800309B6B6046984706 +:102C50002A46C1B20098A047012003B030BD00BF92 +:102C600082B0EC468CE80600031D9CE8030083E874 +:102C70000500012002B0704770B58AB004460E46C8 +:102C8000031D93E803000AAB03E9030069B10D4695 +:102C9000BDF8383013F0040F0AD123689B6B20462F +:102CA00098473246C1B20898A84701200AB070BDC3 +:102CB00000220023CDE900230023ADF80830039360 +:102CC0008DF818308DF819300493059303AB3068F4 +:102CD0007168B26807C3B2891A80FFF799FFCDE91E +:102CE00000010423ADF808302368DB6B69462046F9 +:102CF0009847DAE7036823F0604C0A6822F06041E5 +:102D0000D00FB0EBD37F0FD0002B08DB002A09DBFC +:102D10008C4513D08C452CBF0020012070474FEA12 +:102D20009C4CF3E7890CF3E7C3F38073C2F3807024 +:102D30008C4504D08C452CBF002001207047834275 +:102D4000FCD1F7E7084670470846704708467047C9 +:102D500008467047401A83B2002800DB704703F131 +:102D6000200000B2FAE700BF03780133DBB2037042 +:102D70001F2B01D900230370704700BF082818D902 +:102D800009280BD00A280BD00B280BD00C280BD00D +:102D90000D280BD00E280BD0402070470C20704718 +:102DA000102070471420704718207047202070476B +:102DB00030207047082818D90C280BD910280BD9B7 +:102DC00014280BD918280BD920280BD930280BD957 +:102DD0000F207047092070470A2070470B2070476A +:102DE0000C2070470D2070470E207047034621F0DD +:102DF000604C20F06042C00FB0EBD17F0FD00029B3 +:102E000008DB002B09DB944513D094452CBF002030 +:102E1000012070474FEA9C4CF3E7920CF3E7C1F3B3 +:102E20008071C3F38070944504D094452CBF00207A +:102E3000012070478142FCD1F7E700BF2DE9F04146 +:102E400007460D46D0F82480B8F1000F0CD0464656 +:102E50004446A4B169686068FFF7C8FF30B92368C9 +:102E600026465BB11C46F4E7796208E0A04502D033 +:102E700035602C6003E02C607D6200E02560BDE8D9 +:102E8000F08100BFC37DC3F38402013262F3860385 +:102E9000C375C38A6FF30903C382C37D6FF3C7137E +:102EA000C375704738B504460D46006A04E00168F2 +:102EB00004F10C00FFF74AFF10B10369AB42F6D1F1 +:102EC00038BD00BF2DE9F043079CCE0803EBD405C5 +:102ED00001F0070304F007041A442AE003F007088E +:102EE00004F00707C646B84538BFBE46CEF1080E07 +:102EF000D11A8E4528BF8E464FF47F4C2CFA0EFC1B +:102F00005FFA8CFC4CFA07FCD90800EB060919F8AB +:102F1000011001FA08F1F940C9B24FEAD40815F8D6 +:102F2000087079400CEA01014F4005F808707344BD +:102F300074449342D2D1BDE8F08300BF2DE9F04F35 +:102F400087B004900E4605920393838AB1EBC30FBA +:102F500080F084801146DA0031448A4204D2D2B231 +:102F6000F3B2D21AD3B20593049BDB683BB3272E8E +:102F700036D8C6F12803059A9A422ED35FFA86FB0B +:102F8000CBF1280B5FFA8BFB00230093039B5A467F +:102F9000314604988068FFF795FF5E44059BA3EBDC +:102FA0000B04E4B2049B9F8A07F10057053FFF0022 +:102FB000D3F80C9028214B46B9461F4627E0049BC6 +:102FC0001B69002BD3D100230093039B059A314644 +:102FD00004988068FFF776FF33E0DDF814B0D3E79C +:102FE000059C4FF0000BDDE72546CDF800B0039BB4 +:102FF0002A46711A381DFFF765FF2E44AB445FFA6D +:103000008BFB641BE4B2A9EB0A093F684146A7B1F8 +:103010009CB1CA46B9F1E00F28BF4FF0E00A0AEBB5 +:1030200001084645EFD2A8EB06039C42DCD35FFAC9 +:1030300088F5F3B2ED1AEDB2D7E7049B186900B139 +:1030400024B9BDF9140007B0BDE8F08FCDF800B089 +:10305000039B2246711AFFF735FFF2E70020F2E7E3 +:10306000002070470139002307E0C25C10F801C05E +:1030700000F803C04254013301398B42F5D3704745 +:1030800080EA0120002303E0400080B20133DBB27C +:10309000072B09D810F4004FF6D0400080B280F41E +:1030A000815080F00100F1E7704700BF70B516460F +:1030B0001D46002411E0C4F12003A4F1200C26FADF +:1030C00004F105FA03F3194325FA0CFC41EA0C015B +:1030D000C9B2FFF7D5FF0834A4B23F2CEBD970BDBD +:1030E00038B50C4604E014F8011BFFF7C9FF2A4667 +:1030F000551E002AF7D138BD38B5058C072D0BD9E0 +:103100000446D0E902234FF6FF70FFF7CFFF2A46AF +:10311000E169FFF7E5FF38BD4FF6FF70FBE700BF41 +:1031200010B4016100F1040C002305E001EB43142D +:10313000CCF80040A44601339A42F7D80023CCF8DB +:10314000003002814381838103605DF8044B704746 +:103150000346406848B102685A605A89013292B207 +:103160005A8199898A4200D99A81704708B5FFF738 +:10317000EFFF08B10023036008BD00BF2DE9F84F41 +:103180008246894616461F46CB8AC3F30903052BA0 +:1031900034D018460024042B0BD8BAB2A24208D966 +:1031A000315D09EB0302D17601339BB20134A4B245 +:1031B000F1E7BBB2A34218D9B9F816B0CBF3090BAB +:1031C000ABF1050293083E49A1FB0313C3EBC30314 +:1031D000A2EB83031FFA83F8D9F8041081B150469B +:1031E000FFF7B0FD054601231CE00344B9F81620A3 +:1031F00063F30902A9F81620012055E00024DBE75B +:103200005046FFF7B3FF054601465046FFF79CFDC9 +:10321000C9F80400002D49D04FF000082CE001331C +:103220009BB215462A68002AF9D107EB0B02053A32 +:1032300092082349A1FB021292B2013292B2934248 +:103240001AD2B8F1000F17D15046FFF78FFF286050 +:1032500078B3054610E0325D05EB0C031A710CF1F2 +:10326000010C1FFA8CFC0134A4B2BCF11B0F01D875 +:10327000A142F0D8A14204D8B9B2A1420AD9C446A9 +:10328000F3E75046FFF772FF2860A8B105464FF0FC +:103290000008F1E7B9F81630C3F30902114461F3ED +:1032A0000903A9F816300120BDE8F88F6FF002007D +:1032B000FAE76FF00200F7E76FF00200F4E700BFF3 +:1032C0002549922443680B6041604389013B438157 +:1032D000704700BFF8B506460D460EE006F10C0437 +:1032E0002046FFF72FFD014607682046FFF7EAFF5B +:1032F00039462046FFF728FD686069680029EDD14E +:10330000EB8A6FF30903EB8200200021F8BD00BFB8 +:1033100008B5FFF71DFF034628B100220260426096 +:103320008260C2600261184608BD00BF2DE9F04FFF +:1033300083B001921D465B69002B00F08A808146B4 +:103340008B462B8C1BB1EA69002A00F08580072B85 +:1033500006D94FF0800A4FF000084446474664E023 +:1033600009F10C00FFF7D4FF0446002877D02A8C1F +:10337000E9690830FEF736F9288C013080B2FFF792 +:1033800019FDFFF7FBFC431E9BB22B840133237412 +:103390006B691B7803F01F032A8C43F0C00322449F +:1033A00013724BF00043636021464846FFF746FD29 +:1033B0000127384603B0BDE8F08F002007E0EA6936 +:1033C000125D33441A72013080B20134A4B2034654 +:1033D000062802D82A8CA242F1D82B8CA34235D0E1 +:1033E000013080B2FFF7E6FCFFF7C8FC013880B27D +:1033F0004FEA4813DBB243EA0A0A6B691B7803F011 +:103400001F034AEA030A331883F808A04BF000436D +:1034100073600130307431464846FFF70FFD0137C5 +:103420003FB288F001084FF0000A2B8CA342C0D0B5 +:1034300009F10C00FFF76CFF064698B1002CBCD1D7 +:10344000019B03721B0A43720220C0E74FF0400A3F +:10345000C6E76FF00107ACE76FF00107A9E76FF06F +:103460000207A6E76FF00207A3E700BF30B589B0F7 +:1034700004460D46202200216846FEF7C7F8049551 +:103480002046FFF765FE8646A0B1EC46BCE80F007B +:10349000CEF80000CEF80410CEF80820CEF80C309C +:1034A000BCE80F00CEF81000CEF81410CEF81820AB +:1034B000CEF81C30704609B030BD00BF70B5044670 +:1034C00000F10C063046FFF7D1FF054628B1216A0E +:1034D0003046FFF73DFC28602562284670BD00BFDE +:1034E00038B504460D46036A1BB1FFF7DBFC38B163 +:1034F00038BD0C30FFF7BAFF0028F9D02062F7E79B +:1035000029462046FFF7DAFFF2E700BFF8B5044688 +:103510000E4615461F4630220021FEF777F8A760B9 +:10352000069B6360079BA3626A09B5F5001F01D380 +:103530004FF6FF7292B2314604F10C00FFF7F0FD36 +:10354000F8BD00BF037823B919B111F0800F00D185 +:1035500001707047007870472DE9F84305460C4626 +:10356000D1F81C90B9F1000F23D094F81880B8F16D +:103570001F0F3BD82846FFF7EDFF0646F8B9228C0F +:10358000072A36D8278A37F0030335D149464FF644 +:10359000FF70FFF7A5FD47F6FE7303405B0243EAA9 +:1035A00008633F0207F440773B431E434FF6FF7228 +:1035B0000EE00B8C002BD8D06FF001050FE0238AB2 +:1035C0001B0243EA08631E432046FFF795FD0246AF +:1035D000234631462846FFF7A9FE051E02DC284691 +:1035E000BDE8F8836069FFF7BFFBF8E76FF00105FE +:1035F000F5E76FF00305F2E76FF00105EFE700BFB5 +:1036000070B58AB0044616461D4628220021684639 +:10361000FDF7FCFF02960395BDF83830ADF8103089 +:103620000F9B05939DF840308DF81830119B079340 +:10363000BDF84830ADF8203069462046FFF78CFFD2 +:103640000AB070BD2DE9F04106460F461546D36914 +:103650002BB395F81880B8F11F0F2AD83046FFF722 +:1036600079FF48B32C8A240444EA08642B7844EA9E +:10367000C33444EA0724044344F080042846FFF797 +:103680003BFD02462B4621463046FFF74FFE041E07 +:1036900002DD2B78012B08D02046BDE8F081138C89 +:1036A000002BD6D06FF00104F6E76869FFF75CFBEA +:1036B000F2E76FF00104EFE76FF00304ECE700BFFF +:1036C000F0B58BB004460D4617461E462822002151 +:1036D0006846FDF79BFF9DF84C30012B14BF00237B +:1036E00001238DF80030029703969DF84030ADF825 +:1036F0001030119B05939DF848308DF81830149BBD +:103700000793BDF85430ADF820306A46294620466C +:10371000FFF798FF0BB0F0BD406A00B1043070476E +:1037200008B5416A0B6843620C30FFF7CBFD08BD5A +:103730002DE9F041054616469846076A3C4619E0D1 +:1037400021462846FFF7C6FD05F10C072B6A1968CC +:103750003846FFF7FBFA286221463846FFF7B2FDEC +:103760002C6A274606E0216805F10C00FFF7EEFA07 +:10377000274604460CB3A168E368711A68EB03039B +:103780000F4A8A424FF0000272EB0303EBD22B6A1E +:10379000A342D5D021462846FFF79CFD23683B6015 +:1037A00005F10C0321461C461846FFF78BFD3968CE +:1037B0002046FFF7CBFA0446DCE7BDE8F08100BF06 +:1037C00080841E002DE9F04182B0089E002800F0A0 +:1037D000E28014461D460746002E00F0DF80531E8F +:1037E000DBB23F2B00F2DD80012A02D1002D40F038 +:1037F000DB800023009301936B4622463846FFF797 +:103800009DFB071E3BDD14F0070F0AD002AB03EB54 +:10381000D40111F8083C624202F00702134101F89A +:10382000083C012C0BD0082C2DD9102C2ED9202C83 +:103830002FD9402C00F2BB804FF0080800E0A046D2 +:10384000FFF70EFC40BB9DB1B4EBC80F10D0082CA5 +:1038500027D89DF80020631E22FA03F313F0010F0E +:1038600006D00123A3405B42DBB213438DF8003046 +:10387000002D72D0082C5ED89DF900303370384688 +:1038800002B0BDE8F0814FF00108D9E74FF002081F +:10389000D6E74FF00408D3E741466846FFF7E2FB5E +:1038A000D1E7102C0FD8BDF80020631E22FA03F3D5 +:1038B00013F0010FDCD00123A3405B429BB2134302 +:1038C000ADF80030D4E7202C0CD8009A631E22FA01 +:1038D00003F313F0010FCBD00123A3405B421A4343 +:1038E0000092C5E73F2C65D8DDF800C0019A631E41 +:1038F000C4F12100A4F121012CFA03F302FA00F033 +:10390000034322FA01F10B4313F0010FB0D001235E +:10391000A4F12001C4F1200003FA01F123FA00F020 +:103920000143A3405B4261EB41014CEA03030A43BC +:10393000009301929CE7102C03D8BDF9003033802E +:103940009DE7202C02D8009B336098E7402C34D8A8 +:10395000DDE90023C6E9002391E7012C05D0082CFE +:1039600007D89DF80030337089E79DF80030337038 +:1039700085E7102C03D8BDF8003033807FE7202C7A +:1039800002D8009B33607AE7402C19D8DDE9002388 +:10399000C6E9002373E76FF0010770E76FF00107D6 +:1039A0006DE76FF001076AE76FF0010767E76FF0F7 +:1039B000080764E76FF0080761E76FF008075EE744 +:1039C0006FF008075BE700BFF0B585B005460E460F +:1039D000402A03D8144612B9012400E040240022F2 +:1039E00002920392012C06D0082C22D81B788DF865 +:1039F0000830012703E01B788DF808302746FFF7D1 +:103A00002FFB68BB14F0070F0AD004AB03EBD40103 +:103A100011F8083C624202F00702934001F8083CAA +:103A200000962B462246002102A8FFF74BFA05B06C +:103A3000F0BD102C04D81B88ADF808300227DEE753 +:103A4000202C03D81B6802930427D8E7402C05D804 +:103A5000D3E90023CDE902230827D0E70027CEE7EA +:103A6000394602A8FFF7FEFACCE700BF70B506465C +:103A70000C4605E00D6806F10C00FFF723FCE5603D +:103A8000E1680029F6D10023E360A3602361A382EB +:103A900070BD00BF10F0800F04D010F4004F03D0B1 +:103AA00001207047022070470020704710B504467F +:103AB000FFF7F0FF022802D0C4F3074010BDC4F3A3 +:103AC0000F2014F07F0FF9D100F00300F6E700BFDC +:103AD0002DE9F04F99B006460D4603920493D1F8B4 +:103AE00000904846FFF7D6FF0746022800F088807E +:103AF000C9F30628B9F1000F80F2028219F0C04F15 +:103B000040F001822C7B002C00F00082022F05D0B7 +:103B10003046FFF71FFD404540F0FB81C9F30463C9 +:103B2000099309F07F0A4846FFF7C0FF0A9040EA70 +:103B3000074949EA8A4949EA4869013C2C4494F812 +:103B4000048000220023CDE916235FEAD8130293F4 +:103B500059D07468CDF800A03B46024616A93046FD +:103B6000A047002800F0D88149463046FFF7B8FC4E +:103B70000446002800F0D381A368E168039A059306 +:103B8000D01A0790049B069163EB0103089395F804 +:103B90000DC0CDF82CC094F81AC0CDF830C094F800 +:103BA0001790C9F3840908F01F0B59464846FFF7E0 +:103BB000D1F80D9049465846FFF7CCF86368059A4E +:103BC000069952EA010C34D09D4A07998A424FF077 +:103BD0000002089972EB010C7CD30B9A0C998A4273 +:103BE0001BD0984B079A93424FF00003089A9341D9 +:103BF00072D2029B002B71D00F2871DD002319E0D7 +:103C00004FF0000876E749463046FFF74BF9044687 +:103C10000028B1D16FF00C0085E1029A002AE0D0B3 +:103C20000D9A012A01DD012304E0002BD9D00123E4 +:103C300000E00123002B55D16A7BA37E9A4240F01D +:103C40007181029B13B118F0400F66D1C8F3401385 +:103C5000E27DB3EBD21F40F06981C2F384039B4540 +:103C600040F06781029B002B00F0908018F0400F1D +:103C700040F08C802B7B032B40F25E81039BA36082 +:103C8000049BE360AF1D2B7B033BDBB23A4621462E +:103C900006F10C00FFF772FA00286DDB2B796A79C8 +:103CA00043EA02232383DDE916234FF6FF70FFF773 +:103CB000FDF9A0822A7B033AD2B23946FFF710FA07 +:103CC000A082E37DDA43C2F3C01262F3C713E37547 +:103CD000002028E10123ADE70023ABE70023A9E79B +:103CE0000123A7E7E37D68F38603E375DBB26FF397 +:103CF000C713E37521463046FFF7ECFA6B7BA376DA +:103D0000029B002B98D1E37DC3F38402013262F35E +:103D10008603E3756FF00C0005E1039BA360049A32 +:103D2000E260202200210EA8FDF770FC039B0E9399 +:103D3000049A0F922B1D10932B7B013BDBB2ADF845 +:103D40004C300A9BADF84E308DF850708DF851B064 +:103D5000099B8DF852308DF853A096F82C3083F0E3 +:103D600001038DF85430B3680EA9304698472046B9 +:103D7000FFF788F80020D6E021463046FFF7AAFA80 +:103D80002046FFF77FF86FF00200CCE0029B13B9EA +:103D900018F0400F1ED095F80C9009F1FF395FFA2A +:103DA00089F9B4F81680C8F30908B8F1040F30D8BF +:103DB00043464FF00008042B54D8C84552D205EBB7 +:103DC00008021179E218D176013308F101085FFA8F +:103DD00088F8F0E72F1D2B7B013BDBB23A462146EA +:103DE00006F10C00FFF7CAF9002808DB2A7B013A2C +:103DF000D2B23946A08AFFF773F9A08261E7214663 +:103E00003046FFF767FA2046FFF73CF86FF00200F4 +:103E100089E0616806F10C00FEF794FF024608B1E4 +:103E2000052304E04FF000081CE01C330A4611682B +:103E30000029FAD1A8EB03034FF000080EE000BF01 +:103E400080841E0040420F0005EB08010879D1185C +:103E50000871013308F101085FFA88F81B2B01D8BB +:103E6000C845F1D3039B0E93049B0F9304F11B03EE +:103E70001093616806F10C00FEF764FF1190C845CD +:103E800035D2A84408F104031293E38AC3F309036B +:103E90009944ADF84C900A9BADF84E308DF85070B7 +:103EA0008DF851B0099B8DF852308DF853A096F8DB +:103EB0002C3083F001038DF85430002363602A7B9B +:103EC000013A291DA08AFFF70BF9A082238B9842A3 +:103ED0000FD00EA93046FFF7C9FD2046FEF7D2FFEE +:103EE000A28A238B9A4209D06FF010001BE00023B6 +:103EF000CAE7B3680EA930469847EAE7002012E007 +:103F00006FF009000FE06FF009000CE06FF009009E +:103F100009E06FF00A0006E06FF00B0003E06FF0BD +:103F2000020000E0002019B0BDE8F08F6FF00D0036 +:103F3000F9E76FF00E00F6E76FF00F00F3E700BF50 +:103F4000EFF30983683305494A6B22F001024A63A3 +:103F500083F30988002383F31188704700EF00E0A2 +:103F6000302080F3118862B60C4BD96821F4E061EF +:103F70000904090C0A4A0A43DA60D3F8FC2042F02B +:103F80008072C3F8FC2007490A6842F001020A6007 +:103F90002022DA7783F82200704700BF00ED00E0AE +:103FA0000003FA05001000E0302383F31188104B62 +:103FB0005B6813F4006F03D1002383F3118870470B +:103FC00010B5F1EE103AEFF30984683C4FF08073BE +:103FD000E361084BDB6B236684F3098800F0B8F8D3 +:103FE00010B1054BA36110BD044BA361FBE700BFFB +:103FF00000ED00E000EF00E0430600084606000880 +:104000000901C9B2074A131883F8001300F01F0111 +:10401000400901238B4000F1600142F8213042F851 +:104020002030704700E100E00023037503691B683E +:10403000996882689142FAD203605A6842601060BF +:104040005860704708B50846302383F311880B7D0C +:10405000032B0ED0042B10D043B14FF0FF338361FC +:10406000FFF7E2FF002383F3118808BD83F3118873 +:10407000FBE78B6900221A60EFE74A680B68136060 +:104080004A685A60E9E700BF0023037503691B68AB +:10409000996882689142FAD803605A684260106059 +:1040A0005860704710B5084BD8681C6822681A60C1 +:1040B000536001222275DC60FFF7E6FF01462046CF +:1040C000FCF7AAFA10BD00BF204A002008B5FFF790 +:1040D000ABFF08BD08B5064BD968087518680268BB +:1040E0001A60536001220275D860FCF795FA08BD8A +:1040F000204A002030B587B004460C4BDD68B1F192 +:10410000FF3F0FD02B460A4A684600F04BF9204685 +:10411000FFF7E0FF009B13B1684600F051F9A86972 +:1041200007B030BDFFF7D6FFF9E700BF204A0020F7 +:104130004540000808B5054BD9681B689A688B682C +:104140009A4201D9FFF7AEFF08BD00BF204A002008 +:10415000044BDA681B6898689368984294BF002003 +:1041600001207047204A002010B5084BD8681C6811 +:1041700022681A60536001222275DC60FFF784FF19 +:1041800001462046FCF748FA10BD00BF204A002037 +:1041900008B50B4B01221A70002353B109490A4894 +:1041A00000F078FC064B02221A70002383F311887A +:1041B00008BD034A02EB8302002151600133ECE7A2 +:1041C000884C002000530008204A002008B572B631 +:1041D000044B186500F000FB00F0D6FB024B0322F5 +:1041E0001A70FEE7204A0020884C002008B500F035 +:1041F00021F908BDEFF3118058B9EFF30583C3F33C +:1042000008031BB1302383F311887047302383F3F5 +:104210001188704778B908B5EFF30583C3F3080335 +:104220001BB1002383F3118808BDFFF783FF002330 +:1042300083F31188F8E770478B6002230B75002326 +:104240004B7508610846704708B58168A1F1840381 +:1042500041F8143C026941F8442C426941F8402C71 +:10426000044A41F8242CC368026820390248FFF749 +:10427000E3FF08BD31060008204A002008B5FFF71B +:10428000E3FFFFF723FF08BD08B5034BDB68986128 +:104290000F20FFF71FFF08BD204A002008B530237C +:1042A00083F31188FFF7F0FF08BD00BF08B5014692 +:1042B000302383F311880820FFF71CFF002383F3CA +:1042C000118808BDF8B515461C46C2608B60486071 +:1042D00003680B6059600160092C00D80A24C0688B +:1042E000204400F0C3FB0A2700F0BCFB0646431B3A +:1042F0009C4202D90A2F07D8F8BD7C1C281900F06F +:10430000C3FB27463546EFE7012000F003FCF3E747 +:1043100070B504460D46092900D80A250A266019F9 +:1043200000F0B2FB00F09EFB041BA54202D90A2E4E +:1043300004D870BD013635460446F0E7012000F090 +:10434000E9FBF6E7F8B505460E46174600F08AFB8E +:104350002B689D4209D0EC68041B3C1900D33C46F5 +:104360009B68A34208D82B680CE03B4602463146C6 +:104370002846FFF7A7FF14E03946FFF7C9FFF2E729 +:10438000A41A1B689A689442FAD8B46033605A68D9 +:10439000726016605E609A68121B9A604FF0FF337D +:1043A000AB60F8BD08B50361C260002343610A46F3 +:1043B00001460248FFF7C6FF08BD00BF304A002093 +:1043C00008B51B4B1B69984210D042680368136004 +:1043D00042685A600268816893680B4493600023C6 +:1043E0000360134B4FF0FF329A6108BD1968104A01 +:1043F000134643F8101F4B600021016012699A4276 +:1044000012D0816893680B44936000F02BFB084A3C +:10441000D369A0EB030C126991686145E5D91B1AB9 +:104420001944FFF775FFE0E700F028FBDDE700BF68 +:10443000204A0020F8B50BE0002383F31188E368DD +:10444000216920469847302383F311886369CBB9EB +:104450002C4D2C6900F006FBEB69C21AA568954249 +:1044600042D81D44274BDD61616822680A6061689B +:1044700051600022226053F8102F9A42DCD100F0E4 +:10448000FDFAD9E700F0EEFA0746461B6269B24230 +:104490000CD32B1A13441B4A52F8101F91420AD016 +:1044A0009E1900D23346174A12690CE0022000F030 +:1044B00031FB0023EFE73A4621461348FFF702FF9E +:1044C0001FE05B1A126891688B42FAD8A3602260E1 +:1044D000516861600C6054609168CB1A9360094B1D +:1044E0004FF0FF329A61B3E7064A52F8101F91422B +:1044F00007D0044AD0611B1AA1681944A160FFF7D4 +:1045000007FFF8BD204A0020304A002000207047F5 +:10451000FEE700BF704700BF4FF0FF30704700BF9D +:10452000BFF34F8F024BDB6813F4803FFAD1704723 +:10453000003C0240014BF322DA607047003C02402D +:1045400008B50B4B1B7803B108BDFFF7E9FF094B1A +:104550001B69002B05DB074A136823F48063136093 +:10456000F2E7044B044A5A6002F188325A60F2E7DB +:10457000904C0020003C02402301674508B50C4BDD +:104580001B7803B108BDFFF7CBFF0A4B1A6942F055 +:1045900000421A611A6842F480521A601A6822F4C2 +:1045A00080521A601A6842F480621A60EAE700BF1B +:1045B000904C0020003C024012F0010F65D1F8B58C +:1045C00004460E4615461318B3F1016F5FD8314B00 +:1045D0001B6813F0010F01D1002059E0FFF7B0FF75 +:1045E000FFF7A8FFFFF79CFF032D29D914F0030F55 +:1045F00026D1294A136923F440731361136943F4E4 +:10460000007343F00103136137682760BFF34F8FD6 +:10461000FFF786FF23689F4203D1043D043604342C +:10462000E2E71D4A136923F00103136104E01A4A0B +:10463000136923F001031361FFF7A0FF002027E0B7 +:10464000012D19D9144A136923F4407313611369B6 +:1046500043F4807343F00103136133882380BFF375 +:104660004F8FFFF75DFF23889BB232889A42DED1DD +:10467000023D02360234E3E7074A136923F00103DF +:104680001361FFF77BFF012002E00020704700204C +:10469000F8BD00BF00380240003C0240014B53F817 +:1046A000200070470C5300080B281AD870B5064636 +:1046B0000D4B1B788BB900244FF0006508E00B4BC5 +:1046C00043F824502046FFF7E9FF05440134E4B2E3 +:1046D0000B2CF4D9044B01221A70044B53F826001A +:1046E00070BD0020704700BFC44C0020944C0020D7 +:1046F0000C2070470B2801D90020704738B50546BB +:10470000FFF7D2FF04462846FFF7C8FF30B1236801 +:10471000B3F1FF3F04D104380434F7E7012038BD7A +:104720000020FCE70B2801D90020704738B504466B +:10473000FFF7F6FEFFF704FFFFF7FCFE154BA3FBA8 +:104740000423DB081A4603EB4303A4EB8303DB00DB +:10475000DBB2D201D2B2134343F4007343F002033D +:104760000D4A1361136943F480331361FFF7D8FED8 +:104770002046FFF799FF05462046FFF78FFF0146C9 +:10478000284600F0FDF8FFF7F9FE2046FFF7B2FFDC +:1047900038BD00BFABAAAAAA003C024008B5FFF78B +:1047A0000BFF08BD08B5034610B10A4A127822B1C2 +:1047B00013B9084B1B7833B908BDFFF7C1FE054B91 +:1047C00001221A70F8E7034B00221A70FFF7D6FE99 +:1047D000F2E700BF904C002010B500240BE0074822 +:1047E00004EB44039A00134603445968805800F0D0 +:1047F000C9F80134E4B2012CF1D910BD3C530008D2 +:1048000008B50846114600F069FC08BD08B501204E +:1048100000F064FC08BD00BF08B5084600F07CFC51 +:1048200008BD00BF08B500F01DF908BD70B582B025 +:10483000FFF7E0FC0E4E0546FFF7F4FF32689042AA +:1048400003460ED30B49D1E900411C1941F1000187 +:10485000284601913360FFF7DDFC0199204602B044 +:1048600070BD044A5168146801315160EDE700BF22 +:10487000C84C0020D04C002070B582B0FFF7BAFCC5 +:10488000104E0546FFF7CEFF32689042034613D321 +:104890000D49D1E900411C1941F10001284601915F +:1048A0003360FFF7B7FC01994FF47A72002320467A +:1048B000FBF79EFC02B070BD034A516814680131D9 +:1048C0005160E8E7C84C0020D04C002009E000F11E +:1048D000010C064A52F8202041F8042B1A465FFAD0 +:1048E0008CF0531EDBB2002AF1D1704750280040F3 +:1048F00010B4124B1B6F13F4004F08D10F4B1C6FF9 +:1049000044F400741C671C6F44F400441C670C4C96 +:10491000236843F48073236009E000F1010C51F82F +:10492000044B084A42F820401A465FFA8CF0531EA6 +:10493000DBB2002AF1D15DF8044B70470038024029 +:10494000007000405028004000B583B0012201A94A +:104950000020FFF7BBFF019803B05DF804FB00BF28 +:1049600010B582B00446FFF7EFFFA04201D102B0BC +:1049700010BD0194012201A90020FFF7B9FFF6E75D +:10498000704700BF704700BF704700BF074B45F23C +:1049900055521A6002225A6040F6FF729A604CF635 +:1049A000CC421A60024B01221A707047003000405E +:1049B000DC4C0020034B1B781BB1034B4AF6AA22A8 +:1049C0001A607047DC4C002000300040044B1B682C +:1049D00023B9044BD3F87428014B1A60704700BF09 +:1049E000D84C002000300240024B4FF08072C3F8D8 +:1049F000742870470030024008B5FFF7E7FF024B0C +:104A00001868C0F3407008BDD84C002008B5FFF707 +:104A1000DDFF024B1868C0F3007008BDD84C0020C1 +:104A2000704700BFFEE700BF084B094903E051F89B +:104A3000042B43F8042B074A9342F8D302E00022E8 +:104A400043F8042B044A9342F9D37047684D002081 +:104A5000E8540008684D0020684D002008B500F0BB +:104A6000DBF808BD4FF08043586A70474FF0804331 +:104A7000586300221A610222DA6070474FF08043C7 +:104A80000022DA60704700BF4FF0804358637047E0 +:104A9000FEE700BF70B586B004460E46194B58605D +:104AA000002585620163FFF75BFA24606460A560FE +:104AB000E56204F11003236163614FF0FF33A361EA +:104AC000E561FFF7CFFF02462B46C4E908232565C1 +:104AD00080230D4A04F134012046FFF7ADFBE0606E +:104AE00001230375094A009272680192B26802922A +:104AF0000393074B049305956846FFF7BFFB06B089 +:104B000070BD00BF884C0020545300085C5300085F +:104B1000914A0008024AD36A0343D362704700BF38 +:104B2000204A00204B6843608B688360CB68C36079 +:104B30000B6943614B6903628B6943620B680360D5 +:104B4000704700BF10B5214B1A6940F2FF110A43AC +:104B50001A611A6922F4FF7222F001021A611A69BD +:104B60001A6B0A431A631A6D0A431A651B6D184CB7 +:104B700021461848FFF7D6FF04F11C011648FFF73D +:104B8000D1FF04F138011548FFF7CCFF04F15401BF +:104B90001348FFF7C7FF04F170011248FFF7C2FF87 +:104BA00004F18C011048FFF7BDFF04F1A8010F4884 +:104BB000FFF7B8FF04F1C4010D48FFF7B3FF04F19C +:104BC000E0010C48FFF7AEFF10BD00BF0038024007 +:104BD0006453000800000240000402400008024044 +:104BE000000C024000100240001402400018024075 +:104BF000001C02400020024008B5FFF7A3FF00F0B0 +:104C000095F808BD08B500F025FAFFF7C1FAFFF7DF +:104C1000DDFE08BD704700BF0F4B1A6C42F0010269 +:104C20001A641A6E42F001021A661B6E0B4A9368F0 +:104C300043F0010393604FF0804353229A624FF098 +:104C4000FF32DA6200229A615A63DA605A60012206 +:104C50005A611A60704700BF00380240002004E02B +:104C600008B54FF080421369D168C9B20B40D943EF +:104C7000116113F0020F00D108BD302383F31188B6 +:104C8000FFF7B4FA002383F31188F5E70B4A1368A2 +:104C900043F4807313600A4B1B6F03F44073B3F546 +:104CA000007F05D0064B4FF480321A6700221A6746 +:104CB000024A536823F40073536070470070004049 +:104CC0000038024008B5184B1A696FEAC2526FEA01 +:104CD000D2521A611A69C2F308021A611A695A6932 +:104CE0004FF0FF3058615A69002159615A691A6AB8 +:104CF00062F080521A621A6A02F080521A621A6ACC +:104D00005A6A58625A6A59625A6A1A6C42F0805258 +:104D10001A641A6E42F080521A661B6EFFF7B6FFD5 +:104D200000F076F908BD00BF003802403B4B4FF061 +:104D300080521A643A4A4FF4404111601A6842F0B6 +:104D400001021A60354B1B6813F0020FFAD0334A88 +:104D5000936823F003039360304B9B6813F00C0FB0 +:104D6000FAD12E4B1A6802F0F9021A6000229A60FA +:104D70001A6842F480321A60284B1B6813F4003F13 +:104D8000FAD0264A536F43F001035367234B5B6FFE +:104D900013F0020FFAD0214B224A5A601A6842F0EF +:104DA00080721A601E4B5B6813F4804FFAD01B4B65 +:104DB0001B6813F0007FFAD0184B1B4A9A601B4BFC +:104DC0001A681B4B9A421FD01A4B40F205721A60A8 +:104DD000184B1B6803F00F03052BF9D10F4A93689A +:104DE00043F0020393600D4B9B6803F00C03082B08 +:104DF000F9D10A4B5A6C42F480425A645A6E42F41A +:104E000080425A665B6E70470B4B1A680B4B9A4296 +:104E1000DAD1084B40F205121A60D9E70038024097 +:104E2000007000400854400700948838002004E0D7 +:104E300011640020003C024000ED00E041C20F413F +:104E400008B5074A536903F0010353612BB1054BC1 +:104E50001B6813B1034A50689847FFF7A5F808BDCF +:104E6000003C0140E04C002008B5074A536903F0BC +:104E7000020353612BB1054B9B6813B1034AD06801 +:104E80009847FFF791F808BD003C0140E04C002036 +:104E900008B5074A536903F0040353612BB1054B6E +:104EA0001B6913B1034A50699847FFF77DF808BDA5 +:104EB000003C0140E04C002008B5074A536903F06C +:104EC000080353612BB1054B9B6913B1034AD069A9 +:104ED0009847FFF769F808BD003C0140E04C00200E +:104EE00008B5074A536903F0100353612BB1054B12 +:104EF0001B6A13B1034A506A9847FFF755F808BD7B +:104F0000003C0140E04C002010B51A4B5C6904F4F1 +:104F100078725A6114F0200F05D0174B9B6A13B1B9 +:104F2000154AD06A984714F0400F05D0124B1B6BFE +:104F300013B1114A506B984714F0800F05D00E4BF7 +:104F40009B6B13B10C4AD06B984714F4807F05D04B +:104F5000094B1B6C13B1084A506C984714F4007F3E +:104F600005D0054B9B6C13B1034AD06C9847FFF7F3 +:104F70001BF810BD003C0140E04C002010B51F4B59 +:104F80005C6904F47C425A6114F4806F05D01C4BB8 +:104F90001B6D13B11A4A506D984714F4006F05D079 +:104FA000174B9B6D13B1164AD06D984714F4805F70 +:104FB00005D0134B1B6E13B1114A506E984714F471 +:104FC000005F05D00E4B9B6E13B10D4AD06E984713 +:104FD00014F4804F05D00A4B1B6F13B1084A506F71 +:104FE000984714F4004F05D0054B9B6F13B1044A4A +:104FF000D06F9847FEF7D8FF10BD00BF003C0140BE +:10500000E04C002008B5FFF72BFEFEF7CDFF08BDF2 +:1050100008B506210846FEF7F3FF06210720FEF734 +:10502000EFFF06210820FEF7EBFF06210920FEF71F +:10503000E7FF06210A20FEF7E3FF06211720FEF70F +:10504000DFFF06212820FEF7DBFF07211C20FEF7EB +:10505000D7FF08BD08B5FFF735FE00F005F8FFF7EC +:10506000D9FDFFF7FBFC08BD002307E0054A00213E +:1050700042F8331002EBC302516001330F2BF5D914 +:10508000704700BFE04C00200B460146184600F078 +:105090002DB8000000F040B8012838BF012010B53D +:1050A0000446204600F030F830B900F007F808B99F +:1050B00000F00CF88047F4E710BD0000024B1868C0 +:1050C000BFF35B8F704700BF604D002008B506201E +:1050D00000F084F80120FFF71BFA0000024B0A469B +:1050E00001461868FFF78CBB1C23002010B5054C47 +:1050F00013462CB10A4601460220AFF3008010BDD2 +:105100002046FCE700000000024B01461868FFF74C +:105110007DBB00BF1C230020024B01461868FFF72F +:105120007BBB00BF1C23002010B501390244904214 +:1051300001D1002005E0037811F8014FA34201D00E +:10514000181B10BD0130F2E72DE9F041A3B1C91AD7 +:1051500017780144044603F1FF3C8C42204601D9F4 +:10516000002009E00578BD4204F10104F5D10CEB03 +:105170000405D618A54201D1BDE8F08115F8018DCE +:1051800016F801EDF045F5D0E7E700001F2938B526 +:1051900004460D4604D9162303604FF0FF3038BD96 +:1051A000426C12B152F821304BB9204600F030F871 +:1051B0002A4601462046BDE8384000F017B8012BCA +:1051C0000AD0591C03D1162303600120E7E700240D +:1051D00042F82540284698470020E0E7024B014668 +:1051E0001868FFF7D3BF00BF1C23002038B5074D58 +:1051F00000230446084611462B60FFF78DF9431C37 +:1052000002D12B6803B1236038BD00BF644D00207C +:10521000FFF77CB96F72672E6172647570696C6F8D +:10522000742E41522D46343037536D617274426191 +:105230007400000040A2E4F16468910600000000E0 +:1052400041A3E5F265699207000000004261642015 +:1052500043414E496661636520696E6465782E003E +:1052600080000000008000000000800000000000BE +:1052700000000000111F000891280008D92700082D +:105280001D1F0008511F0008D5200008211F00081D +:10529000311F0008251F00082D1F0008291F0008C6 +:1052A00089200008351F0008612C0008451F0008F0 +:1052B000A92000080000000000000000111F0008E5 +:1052C000F52B0008192C00081D1F0008792C000878 +:1052D000292C0008211F00081D2C0008251F00088C +:1052E000212C0008291F0008252C0008F52B000898 +:1052F000612C0008F52B0008F52B00086330000036 +:10530000FC520008784A0020884C00200040000031 +:1053100000400000004000000040000000000100CC +:105320000000020000000200000002000000020075 +:105330000000020000000200000002000000002047 +:105340000000020001000000000002200000020036 +:10535000020000006D61696E0000000069646C6508 +:10536000000000000000802A00000000AAAAAAAAEB +:1053700000000024FFFF0000000000000090090072 +:105380000000000000000000AAAAAAAA0000000075 +:10539000FFFF00000000000000000000000000050A +:1053A00000000000AAAAAAA600000000FFEF00006B +:1053B00000000000000000000000000000000000ED +:1053C000AAAAAAAA00000000FFFF00000000000037 +:1053D000000000000000000000000000AAAAAAAA25 +:1053E00000000000FFFF00000000000000000000BF +:1053F0000000000000000000AAAAAAAA0000000005 +:10540000FFFF00000000000000000000000000009E +:1054100000000000AAAAAAAA00000000FFFF0000E6 +:10542000000000000000000000000000000000007C +:105430000A0000000000000003000000000000005F +:10544000000000000000000000000000000000005C +:10545000000000000000000000000000000000004C +:10546000C0ADFF7F010000006E04000000000000DE +:1054700000000F000000000040420F00FE2A010063 +:10548000D2040000202300200000000000000000E3 +:10549000000000000000000000000000000000000C +:1054A00000000000000000000000000000000000FC +:1054B00000000000000000000000000000000000EC +:1054C00000000000000000000000000000000000DC +:1054D00000000000000000000000000000000000CC +:0854E0000000000000000000C4 +:00000001FF diff --git a/Tools/bootloaders/ARK_CANNODE_bl.bin b/Tools/bootloaders/ARK_CANNODE_bl.bin new file mode 100644 index 00000000000000..3d2eb3c643b5fc Binary files /dev/null and b/Tools/bootloaders/ARK_CANNODE_bl.bin differ diff --git a/Tools/bootloaders/ARK_CANNODE_bl.hex b/Tools/bootloaders/ARK_CANNODE_bl.hex new file mode 100644 index 00000000000000..352197b9428a9e --- /dev/null +++ b/Tools/bootloaders/ARK_CANNODE_bl.hex @@ -0,0 +1,1380 @@ +:020000040800F2 +:1000000000070020F5040008FD2A0008B52A0008B2 +:10001000DD2A0008B52A0008D52A0008F7040008E0 +:10002000F7040008F7040008F7040008F13A000894 +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008254F00084D4F00087A +:10006000754F00089D4F0008C54F0008F7040008B1 +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F7040008692A0008CC +:10009000952A0008A52A0008F7040008ED4F00087B +:1000A000F7040008F7040008F7040008F704000844 +:1000B000F7040008F7040008F7040008F704000834 +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008C1500008D5500008F7040008D4 +:1000E00051500008F7040008F7040008F70400085E +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008E9500008F7040008A5 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008F7040008A3 +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E000D916000800000000000000000000000018 +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600004F0E2FA04F07AFB4FF055301F491B4AC1 +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE704F0C0FA44 +:1005B00004F0A2FB144C154DAC4203DA54F8041BB2 +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E704F0A8BA0007002084 +:1005E000002300200000000808ED00E000010020CA +:1005F0000007002090550008002300208C230020D5 +:1006000090230020284F0020E0010008E4010008AA +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002003F0D4FE4E +:10064000FEE703F037FE00DFFEE70000F8B501F03B +:1006500055F804F003FA074604F052FA0546B8BB11 +:10066000204B9F4234D001339F4234D01E4B27F0A1 +:10067000FF029A4232D1F8B200F044FE2E4642F216 +:10068000107400F045FE08B10024264601F02AFB54 +:1006900020B1032000F07CF80024264635B1134B2E +:1006A0009F4203D004F024FA00242646002004F0E0 +:1006B000DFF90EB100F082F801F0A4F900F086FE37 +:1006C00001F088F8204600F0CDF800F077F8F9E75F +:1006D0002E460024D5E704460126D2E7064641F21D +:1006E0008834CEE7010007B0000008B0263A09B010 +:1006F00008B501F03BF8A0F120035842584108BD6D +:1007000007B541F21203022101A8ADF8043001F04F +:100710004BF803B05DF804FB38B5302383F3118840 +:10072000174803680BB103F01DFF164A1448002355 +:100730004FF47A7103F00CFF002383F31188124CFD +:10074000236813B12368013B2360636813B16368B6 +:10075000013B63600D4D2B7833B963687BB9022090 +:1007600001F0E6F8322363602B78032B07D163682E +:100770002BB9022001F0DCF84FF47A73636038BDC6 +:100780009023002019070008B0240020A82300208F +:10079000084B187003280CD8DFE800F008050208A1 +:1007A000022001F0C3B8022001F0BEB8024B0022C3 +:1007B0005A607047A8230020B024002010B501F033 +:1007C00091FA30B1204B03221A70204B00225A605C +:1007D00010BD1F4B1F4A1C4619680131F8D0043365 +:1007E0009342F9D162681C4B9A42F1D91B4B9B682A +:1007F00003F1006303F580339A42E9D204F04CF927 +:1008000004F05EF9002000F0FFFF0220FFF7C0FFB8 +:10081000134B1A6C00221A64196E1A66196E596C01 +:100820005A64596E5A665B6E72B64FF0E0233021FF +:10083000C3F8084DD4E9003281F311889D4683F353 +:1008400008881047C4E700BFA8230020B024002078 +:100850000000010820000108FFFF0008002300201D +:10086000003802402DE9F04F93B0AC4B00902022AD +:10087000FF210AA89D6801F06FF8A94A1378A3B96F +:10088000A848012103601170302383F311880368A5 +:100890000BB103F067FEA44AA24800234FF47A711B +:1008A00003F056FE002383F31188009B13B19F4B86 +:1008B000009A1A609E4A009C1378032B1EBF0023E7 +:1008C00013709A4A4FF0000A18BF5360D346564639 +:1008D000D146012001F02AF824B1944B1B68002B6B +:1008E00000F01582002000F041FF0390039B002BD5 +:1008F00001DA00F0B3FD039B002BEDDB012001F0DA +:1009000013F8039B213B162BE3D801A252F823F0E6 +:100910006D09000895090008290A0008D308000895 +:10092000D3080008D3080008B30A0008830C0008A5 +:100930009D0B0008FF0B0008270C00084D0C000859 +:10094000D30800085F0C0008D3080008D10C000889 +:100950000D0A0008D3080008150D000879090008E1 +:100960000D0A0008D3080008FF0B00080220FFF75B +:10097000BFFE002840F0F581009B0221BAF1000F74 +:1009800008BF1C4605A841F21233ADF8143000F040 +:100990000BFF9EE74FF47A7000F0E8FE071EEBDBDA +:1009A0000220FFF7A5FE0028E6D0013F052F00F248 +:1009B000DA81DFE807F0030A0D10133605230593EB +:1009C000042105A800F0F0FE17E054480421F9E7DF +:1009D00058480421F6E758480421F3E74FF01C0873 +:1009E000404600F013FF08F104080590042105A813 +:1009F00000F0DAFEB8F12C0FF2D1012000FA07F76F +:100A000047EA0B0B5FFA8BFB4FF0000900F0F0FF99 +:100A100026B10BF00B030B2B08BF0024FFF770FE71 +:100A200057E746480421CDE7002EA5D00BF00B0375 +:100A30000B2BA1D10220FFF75BFE074600289BD0BD +:100A4000012000F0E1FE0220FFF7A2FE00265FFA7F +:100A500086F8404600F0E8FE044690B1002140468A +:100A600000F0F2FE01360028F1D1BA46044641F208 +:100A70001213022105A8ADF814303E4600F094FE92 +:100A800027E70120FFF784FE2546244B9B68AB42F5 +:100A900007D9284600F0BAFE013040F067810435DE +:100AA000F3E7234B00251D70204BBA465D603E46A0 +:100AB000ACE7002E3FF460AF0BF00B030B2B7FF481 +:100AC0005BAF0220FFF764FE322000F04FFEB0F172 +:100AD0000008FFF651AF18F003077FF44DAF0F4A3F +:100AE000926808EB050393423FF646AFB8F5807F66 +:100AF0003FF742AF124B0193B84523DD4FF47A70B4 +:100B000000F034FE0390039A002AFFF635AF019BF4 +:100B1000039A03F8012B0137EDE700BF0023002003 +:100B2000AC2400209023002019070008B0240020E6 +:100B3000A823002004230020082300200C230020E9 +:100B4000AC230020C820FFF7D3FD074600283FF460 +:100B500013AF1F2D11D8C5F1200242450AAB25F075 +:100B6000030028BF424683490192184400F0E2FE88 +:100B7000019A8048FF2100F0EFFE4FEAA8037D496B +:100B80000193C8F38702284600F0EEFE06460028CF +:100B90003FF46DAF019B05EB830537E70220FFF7BC +:100BA000A7FD00283FF4E8AE00F06EFE00283FF4F9 +:100BB000E3AE0027B846704B9B68BB4218D91F2F85 +:100BC00011D80A9B01330ED027F0030312AA134455 +:100BD00053F8203C05934046042205A901F03AF859 +:100BE00004378046E7E7384600F010FE0590F2E74C +:100BF000CDF81480042105A800F0D6FD06E70023F7 +:100C0000642104A8049300F0C5FD00287FF4B4AE6D +:100C10000220FFF76DFD00283FF4AEAE049800F00F +:100C20001BFE0590E6E70023642104A8049300F06E +:100C3000B1FD00287FF4A0AE0220FFF759FD002887 +:100C40003FF49AAE049800F017FEEAE70220FFF79F +:100C50004FFD00283FF490AE00F026FEE1E70220B1 +:100C6000FFF746FD00283FF487AE05A9142000F0E9 +:100C700021FE04210746049004A800F095FD3946A2 +:100C8000B9E7322000F072FD071EFFF675AEBB0714 +:100C90007FF472AE384A926807EB090393423FF63D +:100CA0006BAE0220FFF724FD00283FF465AE27F06D +:100CB00003074F44B9453FF4A9AE484600F0A6FDEE +:100CC0000421059005A800F06FFD09F10409F1E782 +:100CD0004FF47A70FFF70CFD00283FF44DAE00F0A2 +:100CE000D3FD002844D00A9B01330BD008220AA967 +:100CF000002000F039FE00283AD02022FF210AA867 +:100D000000F02AFEFFF7FCFC1C4803F073FB13B055 +:100D1000BDE8F08F002E3FF42FAE0BF00B030B2B32 +:100D20007FF42AAE0023642105A8059300F032FD6C +:100D3000074600287FF420AE0220FFF7D9FC80464A +:100D400000283FF419AEFFF7DBFC41F2883003F0D6 +:100D500051FB059800F06AFE464600F049FE3C460D +:100D6000B7E5064652E64FF0000905E6BA467EE6CC +:100D700037467CE6AC23002000230020A08601003B +:100D8000094A136849F2690099B21B0C00FB013350 +:100D90001360064B186844F2506182B2000C01FBEC +:100DA0000200186080B2704718230020142300202E +:100DB00010B500211022044600F0CEFD034B03CBFA +:100DC000206061601868A06010BD00BF107AFF1F2E +:100DD0002DE9F041ADF54E7D0DF134086CAC40F2DB +:100DE000751207460D460EA80021C8F8001000F045 +:100DF000B3FD4FF4C4720021204600F0ADFD01F0B8 +:100E000085FE254B4FF47A72B0FBF2F0186093E840 +:100E10000700012384E807000DF5E9702382FFF73E +:100E2000C7FF4FF4A6431D49238406A804F072FAB5 +:100E3000192384F832310DF2E32206AB0DF1300CA8 +:100E40001E4603CE664510605160334602F108022B +:100E5000F6D13378137041460122204600F000FE9F +:100E600000230393AB7E029305F11903019380B233 +:100E70000123CDE904800093E97E05A3D3E9002393 +:100E8000384602F00BFA0DF54E7DBDE8F08100BF4B +:100E90009E6AC421818A46EEB824002024530008AB +:100EA0002DE9F043224DBBB001F030FEAB6840F2BB +:100EB000ED22C31A934232D906AFA8602B462822EE +:100EC0000021384602F09AFB05F10E0000F03CFDCF +:100ED000002604465FFA80F905F10E08F3B2F1002E +:100EE000994501F1280107D908EB06030822384685 +:100EF00002F084FB0136F1E708230122CDE902323A +:100F000005340C4B0193A4B230230093CDE9047453 +:100F100005A3D3E90023297B074802F0BFF93BB0C2 +:100F2000BDE8F083AFF3008078F6339F93CACD8D90 +:100F3000D0450020DD450020D0340020F0B58B8A5C +:100F4000013B9BB2C92BC9B006460C4647D8274D7A +:100F50002F7B27BB05F10C03009308223B46394643 +:100F6000204602F00FFA7B1CFAB2D9001F46A38A72 +:100F7000013B9A4205DA0E322A44009200230822ED +:100F8000EEE700230022C5E900230023AB6085F8CB +:100F9000D730C5F8D8302B7B0BB9E37E2B73812279 +:100FA000002106AD27A800F0D7FC0122294627A87A +:100FB00000F024FE00230393A37E029304F119039F +:100FC00080B201932823CDE90450E17E009330469E +:100FD00004A3D3E9002302F061F9FFF761FF49B0F0 +:100FE000F0BD00BF26417272DF25D7B7D045002083 +:100FF00070B50D4614461E4602F0ACF850B9022EEC +:1010000010D1012C0ED112A3D3E90023C5E900238E +:10101000012007E0282C10D005D8012C09D0052C80 +:101020000FD0002070BD302CFBD10BA3D3E90023DF +:10103000ECE70BA3D3E90023E8E70BA3D3E90023F4 +:10104000E4E70BA3D3E90023E0E700BFAFF30080A0 +:10105000401DA12026812A0B78F6339F93CACD8D9F +:101060009E6AC421818A46EE26417272DF25D7B777 +:10107000F017304A39059E562DE9F04F8DB002AF7A +:1010800080460D4602F066F8044600285CD12B7EAF +:10109000022B1BD1EB8A012B18D101F037FD06463C +:1010A000FFF76EFE03464FF4C870DFF81C92B3FBE7 +:1010B000F0F206F5167602FB103316FA83F3C9F840 +:1010C0000030EB7E33B97B4B00221A702C37BD46C3 +:1010D000BDE8F08FAB8AE6B2013BB34204F10104F4 +:1010E0000CD907F108031E44E100009600230822F2 +:1010F00001F0F801284602F045F9EBE707F1180086 +:10110000FFF756FE324607F1180107F1080004F018 +:101110008BF80028D7D10F2E08D8664B1E70D9F84F +:101120000030A3F51673C9F80030CFE7FB1DF87146 +:101130000146009307220346284602F023F9F97975 +:10114000404601F0FFFFC1E7EB8A282B26D010D8DC +:10115000012B1ED0052BB9D1BFF34F8F5649574BEA +:10116000CA6802F4E0621343CB60BFF34F8F00BF45 +:10117000FDE7302BAAD16B7E514C0133627BDBB291 +:101180009342E94603D1EA7E237B9A420BD0CD46B7 +:101190009CE729464046FFF71BFE97E72946404655 +:1011A000FFF7CCFE92E74FF0000807F11803A7F80D +:1011B00018801022009341460123284602F0E2F8ED +:1011C000AE8A023EB6B2F31C9B109B000733DB08CD +:1011D000A9EBC3039D460DF1080A1FFA88F34FEAF5 +:1011E000C8019E4201F110010AD90AEB08030093DD +:1011F00008220023284602F0C5F808F10108ECE7B0 +:1012000094F8D70000F010FBD4F8D810054619B9AF +:1012100094F8D70000F018FBD4F8D83033449D423E +:1012200005D294F8D7000021013000F00DFB4FEA01 +:10123000960B4FF000081FFA88F18B45D4E9003275 +:1012400009D90AEB880103EB8800012200F08CFB2E +:1012500008F10108EFE7F31842F10002C4E9003297 +:10126000D4F8D83094F8D70006EB0308C4F8D88037 +:1012700000F0DAFA804509D394F8D730D4F8D800D2 +:101280000133401B84F8D730C4F8D800FF2E0D4D31 +:1012900009D80023237300F0F7FA00F023FD28811A +:1012A00008B9FFF78BFA23689B0A01332B810023CF +:1012B000A3606CE7C934002000ED00E00400FA05EB +:1012C000D0450020B8240020CC34002010B50A4BB3 +:1012D0000A4A1A6003F5805393F860203AB9DC6D2E +:1012E0002CB1204600F076FD204603F053FFBDE808 +:1012F0001040034800F06EBD00350020DC530008AC +:1013000048450020014B1870704700BFC4240020DE +:1013100030B54FF00054244B22689A4285B007D074 +:1013200003F0F8FB0446A8B90024204605B030BD00 +:101330001E4B627D1A701E48237D03731D49C9220E +:101340000E3000F0F7FA2046E022002100F004FB06 +:101350000124EAE7184A194D136C43F00073136433 +:10136000AA6D174B9A42DFD12B6E013B7E2BDBD847 +:10137000144A07CA01AB83E807001846032100F0AE +:101380007FFC6B6D83424FF00003CDD12A6D8A4202 +:1013900001BFAB65054B2A6E1A7003BF0A4BEA6D9D +:1013A0001A601C46C1E700BF9AAD44C5C4240020A2 +:1013B000D0450020160000200038024000660040A2 +:1013C0005041A0B0586600401023002037B51A4D98 +:1013D00000F088FC02236B71184B288119681848AB +:1013E000012201F031FA00230193164B16490093B4 +:1013F0001648174B4FF4805201F07CFE154B1978BC +:1014000011B1124801F09EFE01F080FB0446FFF787 +:10141000B7FC4FF4C873B0FBF3F202FB130304F5FF +:10142000167010FA83F00C4B186003F069FB08B1DA +:101430000F232B8103B030BDB824002010230020DF +:1014400000350020F10F0008C8240020D03400200F +:1014500079100008C4240020CC3400202DE9F04F7E +:101460002DED028B93A7D7E900670FF25029D9E938 +:1014700000898A4C95B0DFF84CA2DFF84CB22046C8 +:1014800001F038FF034650B30025CDE91155109502 +:10149000ADF84C50027B8DF84C209968406811AA39 +:1014A00003C21B6843F00043109301F031FB10EBC3 +:1014B0000A0241F10003009510A9584600F0F2FD20 +:1014C000A842774A05DD204601F018FF744A1570DE +:1014D000D5E71378072B00F2B980013313700DADF7 +:1014E0009FED6C8B0023DFF8E0B10C93ADF83C303E +:1014F0000D936B6000230DF125028DED008B4FF0F5 +:10150000010A09A958468DF825308DF824A001F06C +:101510004BF99DF824200023002A40F09B802046B0 +:1015200001F018FE0546002847D1DFF8A0B101F010 +:10153000EDFADBF8003098423FD301F0E7FA07906C +:10154000FFF71EFC079A4FF4C87302F51672B0FB42 +:10155000F3F101FB130312FA83F3CBF80030DFF849 +:1015600070B19BF800100791002914BF2B46534619 +:1015700010A88DF83030FFF71BFC0799C1F110025D +:10158000D2B2062A10AB28BF062219440DF1310051 +:10159000079200F0CFF9079A0CAB0393182302933C +:1015A0000132404BD2B2CDE900A304923B46324611 +:1015B000204601F015FE8BF8005001F0A7FA3A4AD8 +:1015C0003A4D1368C31AB3F57A7F32D3106001F035 +:1015D0009FFA02460B46204601F09AFE204601F093 +:1015E000B9FD30B32B7BDFF8ECA0002B14BF032335 +:1015F00002238AF8053001F089FA0DF1400B4FF40F +:101600007A730122B0FBF3F05946CAF80000504645 +:1016100000F0CCFA18230293254B019380B240F2DC +:101620005513CDE903B0009342464B46204601F0E6 +:10163000D7FD2B7B2BB1FFF733FC2B7B002B7FF4EB +:101640001AAF15B0BDEC028BBDE8F08F204601F05B +:1016500055FE44E71946102210A800F07DF90DF15F +:1016600026030AAA0CA9584600F01AFE95E80300C2 +:1016700011AB83E803009DF83C308DF84C300C9B97 +:10168000109310A9DDE90A23204602F015F831E78E +:10169000AFF300800000000000000000D034002004 +:1016A000B5460020C8340020B0460020D0450020B8 +:1016B000B4460020401DA12026812A0BF1C6A7C1F7 +:1016C000D068080F40420F0000350020CC340020C5 +:1016D000C9340020B824002008B5054800F07AFE7F +:1016E000BDE80840034A0449002003F04DBD00BF97 +:1016F0000035002004470020CD120008704700008C +:101700002DE9F84F4FF47A73DFF85880DFF85890DE +:1017100006460D4602FB03F7002498F900305A1CD8 +:101720005FFA84FA01D0A34212D159F82400036869 +:101730002A46D3F820B031463B46D847854207D1E8 +:10174000074B012083F800A0BDE8F88F0124E4E7EF +:10175000002CFBD04FF4FA7002F04CFE0020F3E7AF +:10176000F84600201C2300202023002007B500237A +:10177000024601210DF107008DF80730FFF7C0FF89 +:1017800020B19DF8070003B05DF804FB4FF0FF3077 +:10179000F9E700000A4608B50421FFF7B1FF80F021 +:1017A0000100C0B2404208BD30B4074B0A46197868 +:1017B000064B53F821402368DD69054B0146AC46D2 +:1017C000204630BC604700BFF846002020230020A0 +:1017D000A086010070B502F0D1FF094E094D30809E +:1017E000002428683388834208D902F0C1FF2B689F +:1017F00004440133B4F5803F2B60F2D370BD00BFC9 +:10180000FA460020B846002003F07AB800F10060E4 +:1018100000F580300068704700F10060920000F52C +:10182000803002F0F9BF0000054B1A68054B1B8899 +:101830009B1A834202D9104402F09ABF00207047DD +:10184000B8460020FA460020024B1B68184402F0FC +:10185000AFBF00BFB846002010F003030AD1B0F5B7 +:10186000047F05D200F10050A0F51040D0F80038F8 +:10187000184670470023FBE700F10050A0F5104028 +:10188000D0F8100A70470000064991F8243033B1AF +:101890000023086A81F824300822FFF7BDBF012029 +:1018A000704700BFBC460020014B1868704700BF5E +:1018B000002004E070B5194B1D68194B0138C5F3C1 +:1018C0000B0408442D0C04221E88A6420BD15C6830 +:1018D0000A46013C824213460FD214F9016F4EB101 +:1018E00002F8016BF6E7013A03F10803ECD18142FB +:1018F0000B4602D22C2203F8012B0A4A0524168833 +:10190000AE4204D1984284BF967803F8016B013C43 +:1019100002F10402F3D1581A70BD00BF002004E0A8 +:10192000805300086C5300087047000070470000A7 +:101930007047000010B50023934203D0CC5CC45420 +:101940000133F9E710BD000003460246D01A12F930 +:10195000011B0029FAD1704702440346934202D08A +:1019600003F8011BFAE770472DE9F8431F4D1446B1 +:1019700095F824200746884652BBDFF870909CB348 +:1019800095F824302BB92022FF2148462F62FFF71B +:10199000E3FF95F82400C0F10802A24228BF2246C6 +:1019A000D6B24146920005EB8000FFF7C3FF95F8E1 +:1019B0002430A41B1E44F6B2082E17449044E4B20F +:1019C00085F82460DBD1FFF75FFF0028D7D108E05E +:1019D0002B6A03EB82038342CFD0FFF755FF002829 +:1019E000CBD10020BDE8F8830120FBE7BC460020F6 +:1019F000024B1A78024B1A70704700BFF84600205D +:101A00001C23002010B5074C074920684FF4E13330 +:101A10000B6002F0B5FB60680349BDE8104002F0BE +:101A2000AFBB00BF20230020E4460020094B10B5C7 +:101A30001422044600211846FFF78EFF064A074B82 +:101A4000127804600146BDE8104053F8220002F00D +:101A500097BB00BFE4460020F8460020202300206A +:101A60002DE9F0470D46044600219046284640F2F5 +:101A70007912FFF771FF234620220021284601F04A +:101A8000BDFD231D02222021284601F0B7FD631D64 +:101A900003222221284601F0B1FDA31D03222521A6 +:101AA000284601F0ABFD04F1080310222821284646 +:101AB00001F0A4FD04F1100308223821284601F0AA +:101AC0009DFD04F1110308224021284601F096FDF6 +:101AD00004F1120308224821284601F08FFD04F189 +:101AE000140320225021284601F088FD04F1180338 +:101AF00040227021284601F081FD04F120030822D4 +:101B0000B021284601F07AFD04F121030822B82112 +:101B1000284601F073FD04F12207C0263B463146FA +:101B200008222846083601F069FDB6F5A07F07F1C6 +:101B30000107F3D104F1320308223146284601F0AF +:101B40005DFD002704F1330A94F832304FEAC709EB +:101B50009F4209F5A47615D3B8F1000F08D131469C +:101B600004F599730722284601F048FD09F24F1643 +:101B7000274694F832213B1B93420CD3F01DC0083A +:101B8000BDE8F0870AEB070308223146284601F03A +:101B900035FD0137D8E707F23313314608222846CE +:101BA00001F02CFD08360137E3E7000013B50446C9 +:101BB0000846002101602346C0F80310202201904E +:101BC00001F01CFD0198231D0222202101F016FDC9 +:101BD0000198631D0322222101F010FD0198A31D2D +:101BE0000322252101F00AFD019804F108031022C7 +:101BF000282101F003FD072002B010BDF8B50E4604 +:101C000005461446002181223046FFF7A5FE2B46EB +:101C100008220021304601F0F1FC7CB96B1C072240 +:101C20000821304601F0EAFC0F2401236A785F1C8A +:101C3000013B934204D3E01DC008F8BD0824F4E73B +:101C4000EB1921460822304601F0D8FC08343B4607 +:101C5000ECE7000030B5094D0A4491420DD011F86F +:101C6000013B5840082340F30004013B2C4013F093 +:101C7000FF0384EA5000F6D1EFE730BD2083B8EDD2 +:101C8000F7B54FF0FF33DFF854C0DFF854E000EB56 +:101C900081011A4688421CD050F8044B019401AFD0 +:101CA000042417F8015B82EA05620825DB18164652 +:101CB00005F1FF355241002EBCBF83EA0C0382EAD6 +:101CC0000E0215F0FF05F1D1013C14F0FF04E8D13C +:101CD000E0E7D843D14303B0F0BD00BF9336EAA993 +:101CE000EBE1F042F7B5354A106851686B4603C323 +:101CF0006A4633493348082303F0A6FA044688BBF2 +:101D00000A25314A106851686B4603C36A462F4959 +:101D10002C48082303F098FA0446002845D00369AC +:101D2000B3F5702F41D8B0F86620532A3DD1284A28 +:101D3000024402F15C018B4237D35C3B2149002015 +:101D40009E1AFFF787FF3246074604F16401002020 +:101D5000FFF780FFA3689F4227D1E368984208BF3E +:101D6000002522E00369B3F5702F25D8428B532A52 +:101D700020D1174A024402F110018B4218D3103BC4 +:101D8000104900209D1AFFF765FF2A46064604F118 +:101D900018010020FFF75EFFA3689E4202D1E368AE +:101DA000984201D00D25ACE70025284603B0F0BDD0 +:101DB0001025A6E70C25A4E70B25A2E7A0530008F1 +:101DC000DCFF0E0000000108A953000890FF0E0080 +:101DD0000800FFF710B5037C044613B9006803F050 +:101DE0001BFA204610BD00000023BFF35B8FC360C9 +:101DF000BFF35B8FBFF35B8F8360BFF35B8F704775 +:101E0000BFF35B8F0068BFF35B8F704770B505460B +:101E10000C30FFF7F5FF05F1080604463046FFF7E2 +:101E2000EFFFA04206D930466D68FFF7E9FF254471 +:101E3000281A70BD3046FFF7E3FF201AF9E70000CB +:101E400070B50546406898B105F10800FFF7D8FF66 +:101E500005F10C0604463046FFF7D2FF84423046B7 +:101E600094BF6D680025FFF7CBFF013C2C44201A7E +:101E700070BD000038B50C460546FFF7C7FFA0420D +:101E800010D305F10800FFF7BBFF04446868B4FBFA +:101E9000F0F100FB1144BFF35B8F0120AC60BFF396 +:101EA0005B8F38BD0020FCE72DE9F0411446074662 +:101EB0000D46FFF7C5FF844228BF0446D4B1B8469B +:101EC00058F80C6B4046FFF79BFF304428604046B3 +:101ED0007E68FFF795FF331A9C4203D86C6001209F +:101EE000BDE8F0816B60A41B3B68AB602044E860F8 +:101EF0000220F5E72046F3E738B50C460546FFF724 +:101F00009FFFA04210D305F10C00FFF779FF0444B6 +:101F10006868B4FBF0F100FB1144BFF35B8F012054 +:101F2000EC60BFF35B8F38BD0020FCE72DE9FF417B +:101F3000884669460746FFF7B7FF6C4606B204EBD2 +:101F4000C6060025B44209D06268206808EB050186 +:101F5000FFF7F0FC636808341D44F3E72946384670 +:101F6000FFF7CAFF284604B0BDE8F081F8B5054682 +:101F70000C300F46FFF744FF05F1080604463046D3 +:101F8000FFF73EFFA042304688BF6C68FFF738FF7E +:101F9000201A386020B130462C68FFF731FF20440A +:101FA000F8BD000073B5144606460D46FFF72EFF38 +:101FB000844228BF04460190DCB101A93046FFF7F6 +:101FC000D5FF019B33B93268C5E90233C5E9002466 +:101FD00001200CE09C4238BF0194286001986860A1 +:101FE0008442F5D93368AB60241AEC60022002B059 +:101FF00070BD2046FBE700002DE9FF410F46694612 +:10200000FFF7D0FF6C4600B204EBC0050026AC42DF +:1020100009D0D4F8048054F8081BB8194246FFF7D9 +:1020200089FC4644F3E7304604B0BDE8F081000087 +:1020300038B50546FFF7E0FF044601462846FFF79E +:1020400019FF204638BD0000302383F3118862B6A3 +:1020500070470000002383F3118862B670470000C8 +:1020600010B4026854681A4623465DF8044B1847BA +:102070000120704700207047002070477047000023 +:10208000002070470E20704700F5805090F8C8007F +:10209000C0F340007047000000F5805090F9C9007F +:1020A00070470000F7B50C68BDF8207014F00054BC +:1020B0001E466FD10B7B082B6CD8FFF7C5FF456917 +:1020C000AB685B010CD4AB681B0108D4AC6814F09E +:1020D00080545DD1FFF7BEFF204603B0F0BD012460 +:1020E0000B6804F1180C002BB8BFDB004FEA0C1C86 +:1020F000B4BF43F004035B0545F80C300B680FFADE +:1021000084FC13F0804F18BF05EB0C1E05EB0C1C74 +:102110001EBFDEF8803143F00203CEF880310B7B26 +:10212000CCF8843105EB04158B68C5F88C314B680D +:10213000C5F88831DCF8803143F00103CCF88031F8 +:1021400000EB441541F268031D4403EB44130344C0 +:10215000C5E9002608330D4601F10C0C55F804EBD7 +:1021600043F804EB6545F9D184342D881D8000EBDC +:10217000441407F00303257925F00B052B43237145 +:10218000FFF768FF0097334600F0E2FC0120A4E768 +:102190000224A5E74FF0FF309FE7000013B500F5DC +:1021A00080540191E06DFFF74BFE1F280AD9019979 +:1021B000E06D2022FFF7BAFEA0F1200358425841FB +:1021C00002B010BD0020FBE708B500F58050FFF716 +:1021D0003BFFC06DFFF708FEBDE80840FFF73ABFC0 +:1021E00000220260828142608260704710B5002246 +:1021F0000023C0E900230023044603810C30FFF7CD +:10220000EFFF204610BD0000F0B5054600F58050F8 +:102210000C4690F8C83013F0040FC3F3800108BFD8 +:10222000114661F3820304F1840680F8C83005EB9F +:10223000461389B01B79D8072ED57AB319072DD448 +:102240006846FFF7D3FF05EB441303F5835303F10F +:10225000180703AA103318685968144603C40833D2 +:10226000BB422246F7D1186820609B88A380DDE935 +:102270000E23CDE900230123ADF808302B68694611 +:10228000DB6B2846984705EB46152B791A075CBF90 +:1022900043F008032B7101E0002AF4D109B0F0BD2E +:1022A0002DE9F047074688B007F5805468469A46FE +:1022B0008846FFF7C9FE9146FFF798FFE06DFFF7EC +:1022C000A5FD1F2829D9E06D20226946FFF7B0FE41 +:1022D000202822D103AD444605AB2E4603CE9E42B4 +:1022E00020606160354604F10804F6D13068206052 +:1022F000B388A380DDE90023C9E90023BDF80830D5 +:10230000AAF80030FFF7A6FE4A4653464146384633 +:1023100008B0BDE8F04700F009BCFFF79BFE0020C5 +:1023200008B0BDE8F08700002DE9F84F0023C0E9B0 +:102330000133254B044640F8183B0F46FFF750FF8A +:1023400004F12800FFF752FF04F1480804F5825514 +:102350004646083530462036FFF748FFAE42F9D1F1 +:1023600004F580554FF480534FF00009C5E9133947 +:10237000C5F848800123EE6504F5875804F58456B6 +:10238000C5F8549085F8583085F86030083608F163 +:1023900008084FF0000A4FF0000B46E908ABA6F121 +:1023A0001800FFF71DFF203646F8289C4645F4D15B +:1023B00085F8C97017B1054800F0A2FB044B6361B2 +:1023C0002046BDE8F88F00BFDC530008B453000876 +:1023D0000064004010B5044B197804464A1C1A707A +:1023E000FFF7A2FF204610BD004700202DE9F0476F +:1023F000002950D0294B2A4FB7FBF1F599428CBFE9 +:102400000A231123581EB5FBF3FC03FB1C53C4B273 +:102410002BB102280346F5D80020BDE8F0870CF167 +:10242000FF36B6F5806FF7D2C4EBC40E0EF103038E +:102430004FEAE309C3F3C703A4EB030809F1010A58 +:102440004FF47A755FFA88F009FB05555AFA88F857 +:10245000B5FBF8F5B5F5617FC1BF0EF1FF33C3F3EE +:10246000C703E01AC0B25C1C50FA84F40CFB04F4FD +:10247000B7FBF4F4A142CFD1013BDBB20F2BCBD899 +:102480000138C0B20728C7D800211071168091709A +:10249000D3700120C1E70846BFE700BF3F420F00ED +:1024A00040787D0170B505460E464FF47A746B692D +:1024B0005B6803F00103B34207D04FF47A7001F078 +:1024C00099FF013CF3D1204670BD0120FCE70000DC +:1024D00030B54269936913F0700F16D000230B4C8E +:1024E000936103F1840200EB421211794D0709D583 +:1024F000890707D5416954F823508D60117941F05F +:10250000040111710133032BEBD130BDC853000816 +:1025100073B51D46436916469A68D207044609D525 +:102520009A6801219960C2F34002CDE9006500215B +:10253000FFF76AFE63699A68D1050BD59A684FF474 +:1025400080719960C2F34022CDE9006501212046E7 +:10255000FFF75AFE63699A68D2030BD59A684FF465 +:1025600080319960C2F34042CDE9006502212046E6 +:10257000FFF74AFE204602B0BDE87040FFF7A8BF53 +:10258000F8B50446466900296CD106F10C07386895 +:1025900080076AD006EB01153868D5F8B00110F055 +:1025A000040FD5F8B0011ABFC00840F00040400D3C +:1025B000A061D5F8B0C11CF0020F1CBF40F08040F4 +:1025C000A061D5F8B40106EB011100F00F0084F80A +:1025D0002400D1F8B8012077D1F8B801000A60775B +:1025E000D1F8B801000CA077D1F8B801000EE0775F +:1025F000D1F8BC0184F82000D1F8BC01000A84F8AD +:102600002100D1F8BC01000C84F82200D1F8BC11E3 +:10261000090E84F823103821396004F1340004F1E4 +:10262000180104F1240551F8046B40F8046BA94229 +:10263000F9D109880180C4E90A23214600232386B1 +:1026400051F8283B2046DB6B984704F58052204622 +:1026500092F8C83043F0040382F8C830BDE8F8406F +:10266000FFF736BF06F1100791E7F8BD10B5044635 +:1026700000F04EFA02460B4652EA030102D0013A3C +:1026800063F100030449086820B12146BDE8104009 +:10269000FFF776BF10BD00BFFC460020F8B500F57F +:1026A00083511E46FFF7D0FCDFF844C008310024F8 +:1026B00004F1840500EB45152B795F070ED4DB068A +:1026C0000CD5D1E900739742B34107D243695CF856 +:1026D00024709F602B7943F004032B710134032C89 +:1026E00001F12001E4D1BDE8F840FFF7B3BC00BF21 +:1026F000C853000808B5FFF7A7FCFFF7E9FEBDE8DF +:102700000840FFF7A7BC0000F8B543690546986884 +:1027100000F0E050B0F1E05F0F461FD0E8B1FFF7E6 +:1027200093FC05F583541034002606F1840305EB71 +:1027300043131B791A0706D50136032E04F1200432 +:10274000F3D1012007E05B07F6D42146384600F0BC +:1027500039FA0028F0D1FFF77DFCF8BD0120FCE735 +:1027600000F5805008B5FFF76FFCC06DFFF74EFB1A +:10277000FFF770FC43090CBF0120002008BD0000DA +:10278000F8B51D46002313700F4606461446FFF7A2 +:10279000E7FF80F00100387025B129463046FFF789 +:1027A000B3FF2070F8BD00002DE9B8410C46154676 +:1027B0001F46804600F0ACF90B462178024609B965 +:1027C000287850B14046FFF769FFFFF793FF3B467B +:1027D0002A462146FFF7D4FF0120BDE8B88100005A +:1027E00010B5FFF731FC174B1A6C42F000721A64F7 +:1027F0001A6A42F000721A621A6A00F5805422F0D6 +:1028000000721A62FFF726FC94F8C830DB0718D470 +:10281000B9B103211320FFF717FC01F0E5FA0321FA +:10282000142001F0E1FA0321152001F0DDFA94F8FB +:10283000C83043F0010384F8C830BDE81040FFF70A +:1028400009BC10BD003802402DE9F04700F5805565 +:1028500088B095F8C930012B0446884616467FD8C3 +:10286000804F57F823200AB947F82300D7F800A073 +:10287000C4F80C802674BAF1000F63D095F8C93003 +:10288000012B6FD001212046FFF7AAFFFFF7DCFBE9 +:102890006269136823F0020313606269136843F0EE +:1028A00001031360636900275F6101212046FFF780 +:1028B000D1FBFFF7F7FD002800F09580E86DFFF7EA +:1028C00093FA04F58359BA4609F108092022002138 +:1028D0006846FFF741F802A8FFF782FCCDF818A080 +:1028E0006A4609EB07030DF1180E9446BCE8030095 +:1028F000F44518605960624603F10803F5D1DCF82D +:102900000000186020379CF804201A71602FDDD178 +:1029100095F8C8306FF38203002785F8C8306A46FF +:1029200041462046ADF80070ADF802708DF8047095 +:10293000FFF75CFD636948BB4FF400421A6008B0C2 +:10294000BDE8F08741F2D00002F026FC814610B1CC +:102950005146FFF7E9FCC7F80090B9F1000F8DD19F +:102960000020ECE7386803681B6B98470146002895 +:1029700088D13868FFF734FF3868036832465B68EF +:102980004146984700287FF47DAFE9E761221A604D +:102990009DF802309DF803201B06120402F47022F9 +:1029A00003F040731343BDF80020C2F30902134340 +:1029B0009DF804201205022E02F4E0020CBF4FF035 +:1029C00000410021134362690B43D3616369132201 +:1029D0005A616269136823F0010313603946204687 +:1029E000FFF760FD08B96369A6E795F8C93093BBA6 +:1029F0006169D1F8002242F00102C1F80022616948 +:102A0000D1F8002222F47C5222F00E02C1F80022FA +:102A10006169D1F8002242F46062C1F80022626963 +:102A2000C2F814326269C2F80432626941F6FF7179 +:102A3000C2F80C126269C2F840326269C2F84432CC +:102A400063690122C3F81C226269D2F8003223F0C4 +:102A50000103C2F8003295F8C83043F0020385F84C +:102A6000C8306CE7FC46002008B500F051F850EA89 +:102A70000103024602D0421E61F10001044B1868B6 +:102A800010B10B46FFF744FDBDE8084001F064B803 +:102A9000FC46002008B50020FFF7E8FDBDE808402F +:102AA00001F05AB808B50120FFF7E0FDBDE8084085 +:102AB00001F052B800B59BB0EFF309816822684677 +:102AC000FEF738FFEFF30583014B9B6BFEE700BF7A +:102AD00000ED00E008B5FFF7EDFF000000B59BB08A +:102AE000EFF3098168226846FEF724FFEFF30583C0 +:102AF000014B5B6BFEE700BF00ED00E0FEE700006E +:102B00000FB408B5029801F00BFCFEE701F044BFDA +:102B100001F01CBF13B56C4684E80600031D94E861 +:102B2000030083E80500012002B010BD73B585687D +:102B3000019155B11B885B0707D4D0E900369B6B28 +:102B40009847019AC1B23046A847012002B070BD33 +:102B5000F0B5866889B005460C465EB1BDF83830E0 +:102B60005B070AD4D0E900379B6B98472246C1B275 +:102B70003846B047012009B0F0BD00220023CDE95E +:102B800000230023ADF808300A4603AB01F1080624 +:102B9000106851681C4603C40832B2422346F7D17C +:102BA000106820609288A280FFF7B2FF0423ADF87E +:102BB00008302B68CDE90001DB6B69462846984751 +:102BC000D8E7000030B503680968DD0FB5EBD17FA9 +:102BD00023F0604421F060424FEAD1700BD0002B0B +:102BE000B8BFA40C0029B8BF920C944202D034BFE5 +:102BF0000120002030BD944205D1C1F38070C3F3A1 +:102C000080738342F6D194422CBF00200120F1E76B +:102C10002DE9F041456A15B94162BDE8F0814B6884 +:102C200023F06047C3F38A464FEAD37EC3F380782C +:102C300016EA230638BF3E46AC462B465A68BEEB22 +:102C4000D27F22F060440AD0002A18DAA40CB442E1 +:102C500017D19D420FD10D60DEE71346EEE7A74284 +:102C600007D102F08044C2F3807242450BD054B1C8 +:102C7000EFE708D2EDE7CCF800100B60CDE7B442E7 +:102C800001D0B442E5D81A689C46002AE5D1196003 +:102C9000C3E700002DE9F047089D01F007044FEA63 +:102CA000D508224405F0070500EBD1004FF47F4919 +:102CB000944201D1BDE8F08704F0070705F0070A48 +:102CC00057453E4638BF5646C6F10806111B8E4290 +:102CD00028BF0E46E10808EBD50E415C13F80EC084 +:102CE000B94029FA06F721FA0AF1FFB28CEA01018C +:102CF00047FA0AF739408CEA010C03F80EC0344455 +:102D00003544D5E780EA0120082341F2210201B2CF +:102D10004000002980B203F1FF33B8BF504013F0E8 +:102D2000FF03F4D17047000038B50C468D18A5425A +:102D300000D138BD14F8011BFFF7E4FFF7E70000EE +:102D400042684AB1136843604389818901339BB269 +:102D50009942438138BF83811046704770B588B06F +:102D6000202204460D4668460021FEF7F5FD204668 +:102D70000495FFF7E5FF024658B16B46054608AEDD +:102D80001C4603CCB44228606960234605F108055F +:102D9000F6D1104608B070BD082817D909280CD004 +:102DA0000A280CD00B280CD00C280CD00D280CD0E5 +:102DB0000E2814BF4020302070470C207047102090 +:102DC000704714207047182070472020704700007B +:102DD000082817D90C280CD910280CD914280CD97C +:102DE00018280CD920280CD930288CBF0F200E2091 +:102DF0007047092070470A2070470B2070470C204D +:102E000070470D20704700002DE9F843078C072F0D +:102E100004461ED9D0E9029800254FF6FF73C5F18C +:102E20002006A5F1200029FA05F108FA06F628FA8D +:102E300000F031430143C9B21846FFF763FF08357C +:102E4000402D0346EBD1E1693A46BDE8F843FFF770 +:102E50006BBF4FF6FF70BDE8F883000010B54B68FC +:102E600023B9CA8A63F30902CA8210BD04691A68C9 +:102E70001C600361C38A013BC3824A60EFE7000024 +:102E80002DE9F84F1D46CB8A0F46C3F309010529EA +:102E9000814692460B4630D00020AAB207F11A04B0 +:102EA0009EB2042E1FFA80F80FD8904503F101035B +:102EB00006D3FB8A0A4462F30903FB8201201AE06D +:102EC0001AF80060E6540130EAE79045F1D2A1F12A +:102ED000050B1C237C68BBFBF3F203FB12BB1FFA40 +:102EE0008BF6002C45D14846FFF72AFF044638B937 +:102EF00078606FF00200BDE8F88F4FF00008E6E759 +:102F0000002606607860ADB24FF0000B454510D941 +:102F10000AEB0803221D13F8011B9155B1B208F109 +:102F200001081B291FFA88F82BD0454506F1010638 +:102F3000F1D8FB8AC3F30902154465F30903BCE722 +:102F4000013292B21C462368002BF9D16B1F0B444F +:102F50001C21B3FBF1F301339BB29A42D3D2BBF1F4 +:102F6000000FD0D14846FFF7EBFE20B9C4F800B0FF +:102F7000BFE70122E7E7C0F800B05E4620600446E4 +:102F8000C1E74545D5D94846FFF7DAFE08B92060C4 +:102F9000AFE7C0F800B0002620600446B6E70000A6 +:102FA0002DE9F04F2DED028B1C4683B05B69019239 +:102FB00007468846002B00F09A80238C2BB1E269EB +:102FC000002A00F09480072B35D807F10C00FFF79A +:102FD000B7FE054638B96FF00205284603B0BDECD0 +:102FE000028BBDE8F08F14220021FEF7B5FC228C85 +:102FF000E16905F10800FEF79DFC208C013080B2EC +:10300000FFF7E6FEFFF7C8FE013880B220840130EA +:1030100028746369228C1B782A4403F01F0363F031 +:103020003F0348F000411372384669602946FFF7B4 +:10303000EFFD0125D1E700F10C034FF0000908EE88 +:10304000103A4FF0800A4E464D4618EE100AFFF730 +:1030500077FE83460028BED014220021FEF77CFCB8 +:10306000002E3AD1019BABF8083002220BF1080E7A +:103070001FFA82FC0CF10100BCF1060F218C80B21A +:1030800001D88E422BD3FFF7A3FEFFF785FE6269BE +:103090001278013802F01F028E4208BF4FF0400A3A +:1030A00042EA49121BFA80F14AEA020A013048F06A +:1030B000004281F808A08BF81000CBF80420594694 +:1030C0003846FFF7A5FD238C0135B3422DB289F0B8 +:1030D00001094FF0000AB8D17FE70022C6E7E16995 +:1030E000895D0EF802100136B6B20132C0E76FF00A +:1030F000010572E7F8B515460E4630220021044658 +:103100001F46FEF729FC069B6360B5F5001F079B71 +:10311000A76034BF6A094FF6FF72A36297B2E661F7 +:1031200004F1100000239A4206D800230360A7820E +:10313000E3822383E360F8BD066001333046203626 +:10314000F1E7000003781BB94BB2002BC8BF017038 +:103150007047000000787047F8B50C46C96907460B +:1031600011B9238C002B37D1257E1F2D34D8387808 +:1031700028BB228C072A2CD8268A36F003032BD1B1 +:103180004FF6FF70FFF7D0FD20F001003102400440 +:1031900041EA0561400C41EA40254FF6FF722346A3 +:1031A00029463846FFF7FCFE002807DD62691378E0 +:1031B0000133DBB21F2B88BF00231370F8BD218AB7 +:1031C0002D0645EA012505432046FFF71DFE024670 +:1031D000E5E76FF00300F1E76FF00100EEE70000B4 +:1031E00070B58AB0044616460021282268461D465E +:1031F000FEF7B2FBBDF83830ADF810300F9B0593E9 +:103200009DF840308DF81830119B07936946BDF842 +:103210004830ADF820302046CDE90265FFF79CFF2D +:103220000AB070BD2DE9F041D36905460C4616463B +:103230000BB9138C5BBB377E1F2F28D895F8008005 +:10324000B8F1000F26D03046FFF7DEFD33782102BB +:1032500041EAC33141EA0801338A41EA076141EAA0 +:1032600003410246334641F080012846FFF798FEAD +:1032700000280ADD3378012B07D1726913780133F6 +:10328000DBB21F2B88BF00231370BDE8F0816FF005 +:103290000100FAE76FF00300F7E70000F0B58BB02C +:1032A00004460D4617460021282268461E46FEF7B2 +:1032B00053FB9DF84C305A1E534253418DF8003059 +:1032C0009DF84030ADF81030119B05939DF84830C3 +:1032D0008DF81830149B07936A46BDF85430ADF84A +:1032E000203029462046CDE90276FFF79BFF0BB040 +:1032F000F0BD0000406A00B104307047436A1A68AC +:10330000426202691A600361C38A013BC38270474B +:103310002DE9F041D0F82080194E14461D46414653 +:10332000002709B9BDE8F081D1E90223A21A65EBB3 +:103330000303964277EB03031ED2036A8B420DD13F +:10334000FFF78CFD036A1B68036203690B60C38A85 +:103350000161016A013BC3828846E2E7FFF77EFD17 +:103360000B68C8F8003003690B60C38A0161013B38 +:10337000C382D8F80010D4E788460968D1E700BFB7 +:1033800080841E002DE9F04F8BB00D46DDF8509083 +:1033900014469B468046002800F01981B9F1000FC1 +:1033A00000F01581531E3F2B00F21181012A03D139 +:1033B000BBF1000F40F00B810023CDE90833B8F8D2 +:1033C0001430B5EBC30F4FEAC30703D300200BB093 +:1033D000BDE8F08F2B199F42D8F80C303ABF7F1B05 +:1033E000FFB227461BB9D8F81030002B7AD0272D12 +:1033F0004ED8C5F12806B7424FF000032CBFF6B2F5 +:103400003E4600932946D8F8080008AB3246FFF73D +:1034100041FCA7EB060A35445FFA8AFAB8F8143083 +:1034200003F10053053BDB000493D8F80C30039301 +:103430002821039B13B1BAF1000F2CD1D8F810004A +:1034400040B1BAF1000F05D0009608AB5246691A98 +:10345000FFF720FC38B2002FB8D066070AD00AABBD +:1034600003EBD401624211F8083C02F00702134159 +:1034700001F8083C082C3CD9102C40F2B580202CD7 +:1034800040F2B780BBF1000F00F09C80082334E0CD +:10349000BA460026C2E7049BE02B28BFE023069330 +:1034A0000B44AB42059314D95A1B039800969245DE +:1034B00034BF5246D2B2691A08AB04300792FFF704 +:1034C000E9FB079A1644AAEB020A1544F6B25FFA22 +:1034D0008AFA049B069A05999B1A0493039B1B681E +:1034E0000393A6E70093D8F8080008AB3A462946AC +:1034F000AEE7BBF1000F13D00123B4EBC30F6CD0C8 +:10350000082C12D89DF82030621E23FA02F2D5074B +:1035100006D54FF0FF3202FA04F423438DF8203031 +:103520009DF8203089F8003051E7102C12D8BDF8F2 +:103530002030621E23FA02F2D10706D54FF0FF3287 +:1035400002FA04F42343ADF82030BDF82030A9F886 +:1035500000303CE7202C0FD80899631E21FA03F3B2 +:10356000DA0705D54FF0FF3202FA04F40C43089451 +:10357000089BC9F800302AE7402C2BD0DDE908650C +:10358000611EC4F12102A4F1210326FA01F105FA1A +:1035900002F225FA03F311431943CB0712D5012296 +:1035A000A4F12003C4F1200102FA03F322FA01F18D +:1035B000A240524243EA010363EB430332432B43ED +:1035C000CDE90823DDE90823C9E90023FFE66FF010 +:1035D0000100FCE66FF00800F9E6082CA0D9102CD9 +:1035E000B3D9202CEED8C3E7BBF1000FADD0022336 +:1035F00083E7BBF1000FBBD004237EE730B5012A7F +:10360000144638BF0124402C85B028BF4024002533 +:10361000012ACDE9025518D81B788DF808306307C8 +:103620000AD004AB03EBD405624215F8083C02F063 +:103630000702934005F8083C00910346224600210A +:1036400002A8FFF727FB05B030BD082AE4D9102AED +:1036500003D81B88ADF80830E1E7202A8DBFD3E9F5 +:1036600000231B680293CDE90223D8E710B5CB688D +:103670001BB98B600B618B8210BD04691A681C60DA +:103680000361C38A013BC382CA60F0E703064CBFF3 +:10369000C0F3C0300220704708B50246FFF7F6FFBE +:1036A000022806D15306C2F30F2001D100F0030017 +:1036B00008BDC2F30740FBE72DE9F04F93B0CDE919 +:1036C00003230A6804461046FFF7E0FF022814BFF0 +:1036D000C2F306260026002A0D46824680F2F281B9 +:1036E00012F0C04940F0EE81097B002900F0EA8128 +:1036F000022803D02378B34240F0E781C2F3046389 +:103700000693104602F07F030593FFF7C5FF059B64 +:1037100029444FEA834848EA0A4848EA4668CE788E +:1037200000230022CDE90823F309834648EA000874 +:10373000029367D0059B009302466768534608A929 +:103740002046B847002800F0C381276A4FB9414698 +:1037500004F10C00FFF702FB074690B96FF002007E +:1037600054E03B6998450DD03F68002FF9D14146A0 +:1037700004F10C00FFF7F2FA07460028EED0236AA6 +:103780003B60276297F817C006F01F08CCF3840C43 +:10379000ACEB08001FFA80FE0028B8BF0EF1200035 +:1037A000A8EB0C031FFA83FED7E90221B8BF00B2D1 +:1037B000002B0793BEBF0EF120031BB2079352EA02 +:1037C000010338D0039BDFF824E39A1A049B4FF0DF +:1037D000000C63EB010196457CEB01032BD36B7B63 +:1037E00097F81AE0734519D1029B002B78D0012875 +:1037F00021DC7868F8B9DFF8F0C2944570EB01037A +:1038000016D337E0276A27B96FF00C0013B0BDE874 +:10381000F08F3B699845B5D03F68F4E7B2489042D5 +:103820007CEB010301D30020F0E7029B002BFAD0D0 +:10383000079B0F2B17DCFA7DB30002F0030203F0A5 +:103840007C031343FB7539462046FFF707FB6B7B70 +:10385000BB76029B3BB9FB7DC3F38402013262F36A +:103860008603FB75D0E76A7BBB7E9A42DBD1029B65 +:10387000002B35D0B309022B32D0039BBB60049BD5 +:10388000FB60142200210DA8FEF766F8039B0A9343 +:10389000049B0B932B1D0C932B7BADF83EB0013B8F +:1038A000DBB2ADF83C30069B8DF84230059B8DF8BD +:1038B000433094F82C308DF840A083F001038DF84C +:1038C00044308DF84180A3680AA920469847FB7DC3 +:1038D000C3F38403013303F01F039B02FB82A2E7BF +:1038E000FB7DC6F34012B2EBD31F40F0F480C3F36C +:1038F0008403434540F0F280029A2B7BB609002AEC +:103900004DD0F2075DD4032B40F2EB80039BBB60EC +:10391000049BFB602B7BAE1D033BDBB2324639467A +:1039200004F10C00FFF7ACFA00280CDA3946204607 +:10393000FFF794FAFB7DC3F38403013303F01F0305 +:103940009B02FB820AE7DDE90884AB883B834FF6E4 +:10395000FF73C9F12000A9F1200228FA09F104FA45 +:1039600000F0014324FA02F211431846C9B2FFF7EE +:10397000C9F909F10809B9F1400F0346E9D1B88244 +:103980002A7B033AD2B23146FFF7CEF9FB7DB882EB +:10399000DA43C2F3C01262F3C713FB7543E786B97B +:1039A0002E1D013BDBB23246394604F10C00FFF715 +:1039B00067FA0028BADB2A7BB88A013AD2B23146CC +:1039C000E2E7F98AC1F30901013B0429DAB25BD8C5 +:1039D000281D002307F11B069A4208D910F801CBD5 +:1039E00006F801C0013101330529DBB2F4D1039996 +:1039F0000A9104990B91934207F11B010C9138BF76 +:103A0000043379680D9134BF55FA83F300230E9384 +:103A1000FB8AADF83EB0C3F309031A44069B8DF848 +:103A20004230059B8DF8433094F82C30ADF83C20A3 +:103A300083F001038DF8443000238DF840A08DF809 +:103A400041807B602A7BB88A013A291DFFF76CF917 +:103A50003B8BB882834203D1A3680AA920469847CA +:103A600020460AA9FFF702FEFB7DBA8AC3F384034E +:103A7000013303F01F039B02FB823B8B9A420CBF76 +:103A800000206FF01000C1E67B68002BAFD005204E +:103A900001E01C3033461E68002EFAD1091A081DB9 +:103AA0002E1D184401EB090CBCF11B0F5FFA89F3C2 +:103AB0009DD89A429BD916F8013B00F8013B09F1C9 +:103AC0000109EFE76FF00900A0E66FF00A009DE63C +:103AD0006FF00B009AE66FF00D0097E66FF00E00A6 +:103AE00094E66FF00F0091E640420F0080841E00C4 +:103AF000EFF3098305494A6B22F001024A636833F8 +:103B000083F30988002383F31188704700EF00E0F6 +:103B1000302080F3118862B60C4B0D4AD96821F42D +:103B2000E0610904090C0A43DA60D3F8FC20094972 +:103B300042F08072C3F8FC200A6842F001020A6079 +:103B40002022DA7783F82200704700BF00ED00E002 +:103B50000003FA05001000E010B5302383F311884C +:103B60000E4B5B6813F4006314D0F1EE103AEFF3E0 +:103B70000984683C4FF08073E361094BDB6B23667B +:103B800084F3098800F08AFB10B1064BA36110BDD5 +:103B9000054BFBE783F31188F9E700BF00ED00E078 +:103BA00000EF00E04306000846060008026843688C +:103BB0001143016003B1184770470000024AD368FF +:103BC00043F0C003D360704700100140024AD3683D +:103BD00043F0C003D36070470044004010B50A4C66 +:103BE0000A4A2046002100F0A9FA094B094AC4E913 +:103BF0009723094C094A0021204600F09FFA084902 +:103C0000084BC4E9971310BD08470020BD3B0008CE +:103C100080F0FA020010014074490020CD3B0008FA +:103C20000044004040787D012A4A037C002918BFE7 +:103C30000A46012B30B5C0F868220CD1264B9842B9 +:103C400039D1264B596C41F010015964596E41F03D +:103C5000100159665B6EB2F904501468D0F86032F6 +:103C6000D0F85C12002D03EB5403B3FBF4F3BEBF9A +:103C700023F0070503F0070343EA450394888B60AC +:103C8000D38843F040030B61138943F001034B6178 +:103C900044F4045343F02C03CB6004F4A0540023F9 +:103CA0000B60B4F5806F0B684B680CBF7F23FF235C +:103CB00080F8643230BD0A4B9842CCD1074B196C66 +:103CC00041F400311964196E41F4003119661B6E1C +:103CD000C1E700BF1C54000808470020003802401C +:103CE000744900202DE9F041D0F85C62F768336830 +:103CF000DA0504469DB20DD5302383F311884FF4C5 +:103D000080610430FFF752FF6FF48073336000234B +:103D100083F31188302383F3118804F1040815F02C +:103D20002F033AD183F31188380615D5290613D508 +:103D3000302383F3118804F1380000F07BF9002868 +:103D40004EDA0821201DFFF731FF4FF67F733B400D +:103D5000F360002383F311887A0616D56B0614D519 +:103D6000302383F31188D4E913239A420AD1236CB8 +:103D700043B127F040073F041021201D3F0CFFF7FF +:103D800015FFF760002383F31188D4F86822D36805 +:103D900043B3BDE8F041106918472B0714D015F064 +:103DA000080F0CBF00214FF48071E80748BF41F0B5 +:103DB0002001AA0748BF41F040016B0748BF41F00E +:103DC00080014046FFF7F2FEAD06736805D594F812 +:103DD00064122046194000F0E1F93568ADB29EE763 +:103DE0007060B6E7BDE8F08100F1604303F5614320 +:103DF0000901C9B283F80013012200F01F039A40A1 +:103E000043099B0003F1604303F56143C3F880213C +:103E10001A607047F8B5154682680669AA420B46D3 +:103E2000816938BF8568761AB54204460BD21846B8 +:103E30002A46FDF77FFDA3692B44A361A3685B1BA2 +:103E4000A3602846F8BD0CD918463246FDF772FD2E +:103E5000AF1BE1683A463044FDF76CFDE3683B4434 +:103E6000EBE718462A46FDF765FDE368E5E7000045 +:103E700083689342F7B51546044638BF8568D0E994 +:103E80000460361AB5420BD22A46FDF753FD63692A +:103E90002B446361A36828465B1BA36003B0F0BD9D +:103EA0000DD932460191FDF745FD0199E068AF1B40 +:103EB0003A463144FDF73EFDE3683B44E9E72A46D4 +:103EC000FDF738FDE368E4E710B50A440024C36158 +:103ED000029B8460C0E90000C0E90511C160026175 +:103EE000036210BD08B5D0E90532934201D1826862 +:103EF00082B98268013282605A1C42611970D0E92D +:103F000004329A4224BFC3684361002100F08EFA54 +:103F1000002008BD4FF0FF30FBE7000070B53023F4 +:103F200004460E4683F31188A568A5B1A368A2696B +:103F3000013BA360531CA36115782269934224BFFF +:103F4000E368A361E3690BB120469847002383F33C +:103F50001188284607E03146204600F057FA00282D +:103F6000E2DA85F3118870BD2DE9F74F04460E465D +:103F700017469846D0F81C904FF0300A8AF3118803 +:103F80004FF0000B154665B12A4631462046FFF733 +:103F900041FF034660B94146204600F037FA002849 +:103FA000F1D0002383F31188781B03B0BDE8F08FB4 +:103FB000B9F1000F03D001902046C847019B8BF355 +:103FC0001188ED1A1E448AF31188DCE7C0E9051157 +:103FD000C160C3611144009B8260C0E900000161BF +:103FE00003627047F8B504460D461646302383F346 +:103FF0001188A768A7B1A368013BA36063695A1C35 +:1040000062611D70D4E904329A4224BFE36863619F +:10401000E3690BB120469847002080F3118807E040 +:104020003146204600F0F2F90028E2DA87F31188E1 +:10403000F8BD0000D0E905239A4210B501D182688D +:104040007AB98268013282605A1C82611C780369E5 +:104050009A4224BFC3688361002100F0E7F920463B +:1040600010BD4FF0FF30FBE72DE9F74F04460E4639 +:1040700017469846D0F81C904FF0300A8AF3118802 +:104080004FF0000B154665B12A4631462046FFF732 +:10409000EFFE034660B94146204600F0B7F900281C +:1040A000F1D0002383F31188781B03B0BDE8F08FB3 +:1040B000B9F1000F03D001902046C847019B8BF354 +:1040C0001188ED1A1E448AF31188DCE70268436800 +:1040D0001143016003B11847704700001430FFF727 +:1040E00043BF00004FF0FF331430FFF73DBF000027 +:1040F0003830FFF7B9BF00004FF0FF333830FFF71B +:10410000B3BF00001430FFF709BF00004FF0FF31CC +:104110001430FFF703BF00003830FFF763BF000023 +:104120004FF0FF323830FFF75DBF0000012914BFA8 +:104130006FF0130000207047FFF750BD37B51546EC +:104140000E4A026000224260C0E9022201220446B7 +:1041500002740B46009000F15C014FF48072143041 +:10416000FFF7B2FE00942B464FF4807204F5AE7157 +:1041700004F13800FFF72AFF03B030BD30540008C7 +:1041800010B53023044683F31188FFF74DFD022359 +:104190002374002080F3118810BD000038B5C36976 +:1041A00004460D461BB904210844FFF78FFF29463A +:1041B00004F11400FFF796FE002806DA201D4FF4E4 +:1041C0000061BDE83840FFF781BF38BD00230375AB +:1041D000826803691B6899689142FBD25A68036040 +:1041E000426010605860704700230375826803695D +:1041F0001B6899689142FBD85A680360426010605E +:104200005860704708B50846302383F311880B7D4A +:10421000032B05D0042B0DD02BB983F3118808BDD7 +:104220008B6900221A604FF0FF338361FFF7CEFFE6 +:104230000023F2E7D1E9003213605A60F3E700008F +:10424000FFF7C4BF054BD9680875186802681A6083 +:10425000536001220275D860FCF7DEB9E04B002004 +:1042600030B50C4BDD684B1C87B004460FD02B4695 +:10427000094A684600F06CF92046FFF7E3FF009B0F +:1042800013B1684600F06EF9A86907B030BDFFF7BA +:10429000D9FFF9E7E04B002005420008044B1A68FB +:1042A000DB6890689B68984294BF002001207047AB +:1042B000E04B0020084B10B51C68D86822681A60D3 +:1042C000536001222275DC60FFF78EFF0146204615 +:1042D000BDE81040FCF7A0B9E04B0020044B1A6881 +:1042E000DB6892689B689A4201D9FFF7E3BF704789 +:1042F000E04B002038B5074C07490848012300254A +:104300002370656000F052FC0223237085F311884E +:1043100038BD00BF484E00205C540008E04B002030 +:1043200008B572B6044B186500F0FEFA00F0B2FB57 +:10433000024B03221A70FEE7E04B0020484E00209B +:1043400000F046B9EFF3118020B9EFF30583302276 +:1043500082F311887047000010B530B9EFF305847F +:10436000C4F3080414B180F3118810BDFFF7B6FF41 +:1043700084F31188F9E700008B60022308618B82C7 +:10438000084670478368A3F1840243F8142C02693D +:1043900043F8442C426943F8402C094A43F8242C42 +:1043A000C26843F8182C022203F80C2C002203F8F0 +:1043B0000B2C044A43F8102CA3F12000704700BFD7 +:1043C00031060008E04B002008B5FFF7DBFFBDE831 +:1043D0000840FFF735BF0000024BDB6898610F20F3 +:1043E000FFF730BFE04B0020302383F31188FFF745 +:1043F000F3BF000008B50146302383F3118808207D +:10440000FFF72EFF002383F3118808BD064BDB68FE +:1044100039B1426818605A60136043600420FFF7A6 +:104420001FBF4FF0FF307047E04B002003689842F9 +:1044300006D01A680260506099611846FFF700BF05 +:104440007047000010B503689C68A2420CD85C68F5 +:104450008A600B604C602160596099688A1A9A6082 +:104460004FF0FF33836010BD1B68121BECE70000A8 +:104470000A2938BF0A2170B504460D460A2660197C +:1044800000F08CFB00F074FB041BA54203D8751CE4 +:104490002E460446F3E70A2E04D9BDE870400120F9 +:1044A00000F0C4BB70BD0000F8B5144B0D46D961D7 +:1044B00003F1100141600A2A1969826038BF0A229B +:1044C000016048601861A818144600F057FB0A27DD +:1044D00000F04EFB431BA342064606D37C1C281962 +:1044E00000F05CFB27463546F2E70A2F04D9BDE809 +:1044F000F840012000F09ABBF8BD00BFE04B00205F +:10450000F8B506460D4600F033FB0F4A134653F844 +:10451000107F9F4206D12A4601463046BDE8F8404A +:10452000FFF7C2BFD169BB68441A2C1928BF2C46BB +:10453000A34202D92946FFF79BFF22463146034892 +:10454000BDE8F840FFF77EBFE04B0020F04B0020B5 +:1045500010B4C0E9032300235DF8044B4361FFF767 +:10456000CFBF000010B5194C236998420DD0D0E997 +:104570000032816813605A609A680A449A60002386 +:1045800003604FF0FF33A36110BD2346026843F878 +:10459000102F53600022026022699A4203D1BDE8C5 +:1045A000104000F0F5BA936881680B44936000F006 +:1045B000DFFA2269E1699268441AA242E4D91144FF +:1045C000BDE81040091AFFF753BF00BFE04B0020C1 +:1045D0002DE9F047DFF8BC8008F110072C4ED8F821 +:1045E000105000F0C5FAD8F81C40AA68031B9A4284 +:1045F0003ED81444D5E900324FF00009C8F81C40F9 +:1046000013605A60C5F80090D8F81030B34201D159 +:1046100000F0BEFA89F31188D5E90331284698479E +:10462000302383F311886B69002BD8D000F0A0FAF7 +:104630006A69A0EB04094A4582460DD2022000F0C7 +:10464000F5FA0022D8F81030B34208D15146284676 +:10465000BDE8F047FFF728BF121A2244F2E712EB39 +:10466000090938BF4A4629463846FFF7EBFEB5E749 +:10467000D8F81030B34208D01444211AC8F81C00EE +:10468000A960BDE8F047FFF7F3BEBDE8F08700BFC3 +:10469000F04B0020E04B002000207047FEE70000B8 +:1046A000704700004FF0FF3070470000BFF34F8F9E +:1046B000024AD368DB03FCD4704700BF003C0240D1 +:1046C00008B5094B1B7873B9FFF7F0FF074B1A6960 +:1046D000002ABFBF064A5A6002F188325A601A683F +:1046E00022F480621A6008BD504E0020003C024057 +:1046F0002301674508B50B4B1B7893B9FFF7D6FF2D +:10470000094B1A6942F000421A611A6842F4805259 +:104710001A601A6822F480521A601A6842F48062A1 +:104720001A6008BD504E0020003C02400B28F0B536 +:1047300016D80C4C0C4923787BB90C4D0E460C2333 +:104740004FF0006255F8047B46F8042B013B13F050 +:10475000FF033A44F6D10123237051F82000F0BD45 +:104760000020FCE7844E0020544E002068540008CE +:10477000014B53F820007047685400080C20704724 +:104780000B2810B5044601D9002010BDFFF7CEFF5D +:10479000064B53F824301844C21A0BB90120F4E731 +:1047A00012680132F0D1043BF6E700BF68540008FC +:1047B0000B2838B5044628D8FFF7C4FDFFF776FF6D +:1047C000FFF77EFF124AF323D360E300DBB243F42A +:1047D000007343F002031361136943F480331361E0 +:1047E00005462046FFF762FFFFF7A0FF094B53F88D +:1047F000241000F04BF92846FFF77CFFFFF7ACFDD3 +:104800002046BDE83840FFF7BBBF002038BD00BFE1 +:10481000003C02406854000812F001032DE9F04109 +:1048200005460E4614464BD18218B2F1016F61D88D +:10483000314B1B6813F001035CD0304FFFF782FD52 +:10484000FFF73EFFF323FB60FFF730FF314640F2F6 +:104850000128032C18D824F00104284E0C446D1AAA +:1048600040F20118A142336905EB01072AD123F078 +:1048700001033361FFF73EFFFFF76EFD0120BDE846 +:10488000F081043C0435E4E7AB07E4D13B6923F451 +:1048900040733B613B6943EA08033B6151F8046B99 +:1048A0002E60BFF34F8FFFF701FF2B689E42E8D0C9 +:1048B0003B6923F001033B61FFF71CFFFFF74CFD51 +:1048C0000020DCE723F440733361336943EA0803D3 +:1048D00033610B883B80BFF34F8FFFF7E7FE3F88C4 +:1048E00031F8023BBFB2BB42BCD0336923F00103B5 +:1048F0003361E1E71846C2E700380240003C02405D +:10490000084908B50B7828B11BB9FFF7D9FE012378 +:104910000B7008BD002BFCD0BDE808400870FFF705 +:10492000E9BE00BF504E00204FF480214FF00050F0 +:1049300000F0AEB80846114600F050BC012000F06F +:104940004DBC0000084600F067BC000070B582B0A6 +:10495000FFF7F8FC0E4E054600F00AF93268904267 +:1049600037BF0C4A0B49516814682EBFD1E900418A +:10497000013151600419034641F1000128460191BB +:104980003360FFF7E9FC0199204602B070BD00BF1B +:10499000884E0020904E002070B582B0FFF7D2FC08 +:1049A000104E054600F0E4F83268904237BF0E4AD8 +:1049B0000D49516814682EBFD1E9004101315160A1 +:1049C000041941F100010346284601913360FFF7C5 +:1049D000C3FC01994FF47A7200232046FBF708FCD0 +:1049E00002B070BD884E0020904E002010B50244E9 +:1049F000064BD2B2904200D110BD441C00B253F815 +:104A0000200041F8040BE0B2F4E700BF502800405A +:104A10000F4B30B51C6F240407D41C6F44F4007492 +:104A20001C671C6F44F400441C670A4C236843F461 +:104A3000807323600244084BD2B2904200D130BD53 +:104A4000441C00B251F8045B43F82050E0B2F4E794 +:104A500000380240007000405028004007B5012295 +:104A600001A90020FFF7C2FF019803B05DF804FB25 +:104A700013B50446FFF7F2FFA04205D0012201A9B9 +:104A800000200194FFF7C4FF02B010BD7047000082 +:104A90007047000070470000074B45F255521A60FE +:104AA00002225A6040F6FF729A604CF6CC421A60BD +:104AB000024B01221A707047003000409C4E0020CB +:104AC000034B1B781BB1034B4AF6AA221A607047AE +:104AD0009C4E002000300040034B1A681AB9034A6C +:104AE000D2F874281A607047984E002000300240B7 +:104AF000024B4FF08072C3F87428704700300240B8 +:104B000008B5FFF7E9FF024B1868C0F3407008BD15 +:104B1000984E002008B5FFF7DFFF024B1868C0F37E +:104B2000007008BD984E002070470000FEE70000AE +:104B30000A4B0B480B4A90420BD30B4BDA1C121A50 +:104B4000C11E22F003028B4238BF00220021FCF775 +:104B500003BF53F8041B40F8041BECE71C56000885 +:104B6000284F0020284F0020284F002000F0D0B808 +:104B7000014B586A704700BF000C0040034B0022F5 +:104B800058631A610222DA60704700BF000C0040CF +:104B9000014B0022DA607047000C0040014B586363 +:104BA000704700BF000C0040FEE7000070B51B4BD3 +:104BB00001630025044686B0586085620E46FEF704 +:104BC000A7FF04F11003C4E904334FF0FF33C4E935 +:104BD0000635C4E90044A560E562FFF7C9FF2B462E +:104BE0000246C4E9082304F134010D4A25658023F7 +:104BF0002046FFF7C1FB0123E0600A4A03750092DB +:104C000072680192B268CDE90223074B6846CDE98C +:104C10000435FFF7D9FB06B070BD00BF484E002039 +:104C2000985400089D540008A94B0008024AD36A12 +:104C30001843D062704700BFE04B00204B684360D0 +:104C40008B688360CB68C3600B6943614B69036207 +:104C50008B6943620B6803607047000008B5234B03 +:104C600023481A6942F0FF021A611A6922F0FF0212 +:104C70001A611A691A6B42F0FF021A631A6D42F048 +:104C8000FF021A651B4A1B6D1146FFF7D7FF02F1A1 +:104C90001C0100F58060FFF7D1FF02F1380100F53B +:104CA0008060FFF7CBFF02F1540100F58060FFF751 +:104CB000C5FF02F1700100F58060FFF7BFFF02F150 +:104CC0008C0100F58060FFF7B9FF02F1A80100F543 +:104CD0008060FFF7B3FF02F1C40100F58060FFF7C9 +:104CE000ADFFBDE8084000F08FB800BF00380240BB +:104CF00000000240A454000808B500F029FAFFF7AC +:104D0000F9FABDE80840FFF7E7BE00007047000071 +:104D10000E4B1A6C42F008021A641A6E42F0080236 +:104D20001A660B4A1B6E936843F008039360094BA5 +:104D300031229A624FF0FF32DA6200229A615A639E +:104D4000DA605A6001225A611A60704700380240E6 +:104D5000002004E0000C0040094A08B51169D3683E +:104D60000B40D9B2C9439B07116107D5302383F3A8 +:104D70001188FFF7E5FA002383F3118808BD00BF0F +:104D8000000C00401E4B1A6962F0FF021A611A699A +:104D9000D2B21A614FF0FF301A695A695861002186 +:104DA0005A6959615A691A6A62F080521A621A6A1B +:104DB00002F080521A621A6A5A6A58625A6A596232 +:104DC0005A6A1A6C42F080521A641A6E42F080528B +:104DD0001A661A6E0B4A106840F480701060186FE3 +:104DE00000F44070B0F5007F1EBF4FF480301867AC +:104DF0001967536823F40073536000F07DB900BF56 +:104E000000380240007000403B4B3C4A1A643C4A68 +:104E10004FF4404111601A6842F001021A601A68AA +:104E20009007FCD59A6822F003029A60324B9A6888 +:104E300012F00C02FBD1196801F0F90119609A60B7 +:104E40001A6842F480321A601A689103FCD55A6FCE +:104E500042F001025A67284B5A6F9207FCD5294A43 +:104E60005A601A6842F080721A60254A53685804E2 +:104E7000FCD5214B1A689101FCD5234AC3F8842044 +:104E80001A6842F080621A601A681201FCD51F4A43 +:104E90009A600322C3F88C204FF00062C3F894207C +:104EA0001B4B1A681B4B9A421B4B21D11B4A1168A2 +:104EB0001B4A91421CD140F203121A60164A136831 +:104EC00003F00F03032BFAD10B4B9A6842F0020256 +:104ED0009A609A6802F00C02082AFAD15A6C42F4DD +:104EE00080425A645A6E42F480425A665B6E704742 +:104EF00040F20372E1E700BF0038024000040010F6 +:104F000000700040041940020830002400948838E2 +:104F1000002004E011640020003C024000ED00E0AD +:104F200041C20F41074A08B5536903F001035361B9 +:104F300023B1054A13680BB150689847BDE8084093 +:104F4000FEF70ABE003C0140A04E0020074A08B50B +:104F5000536903F00203536123B1054A93680BB10F +:104F6000D0689847BDE80840FEF7F6BD003C014018 +:104F7000A04E0020074A08B5536903F004035361AB +:104F800023B1054A13690BB150699847BDE8084041 +:104F9000FEF7E2BD003C0140A04E0020074A08B5E4 +:104FA000536903F00803536123B1054A93690BB1B8 +:104FB000D0699847BDE80840FEF7CEBD003C0140EF +:104FC000A04E0020074A08B5536903F0100353614F +:104FD00023B1054A136A0BB1506A9847BDE80840EF +:104FE000FEF7BABD003C0140A04E0020164B10B5A4 +:104FF0005C6904F478725A61A30604D5134A936A73 +:105000000BB1D06A9847600604D5104A136B0BB1F8 +:10501000506B9847210604D50C4A936B0BB1D06BAB +:105020009847E20504D5094A136C0BB1506C9847B8 +:10503000A30504D5054A936C0BB1D06C9847BDE825 +:105040001040FEF789BD00BF003C0140A04E00208B +:10505000194B10B55C6904F47C425A61620504D5B1 +:10506000164A136D0BB1506D9847230504D5134AAA +:10507000936D0BB1D06D9847E00404D50F4A136EC1 +:105080000BB1506E9847A10404D50C4A936E0BB136 +:10509000D06E9847620404D5084A136F0BB1506F65 +:1050A0009847230404D5054A936F0BB1D06F9847F6 +:1050B000BDE81040FEF750BD003C0140A04E00206E +:1050C00008B50348FEF70EFEBDE80840FEF744BDF4 +:1050D0000847002008B50348FEF704FEBDE8084075 +:1050E000FEF73ABD7449002008B5FFF735FEBDE86C +:1050F0000840FEF731BD0000062108B50846FEF75E +:1051000073FE06210720FEF76FFE06210820FEF73A +:105110006BFE06210920FEF767FE06210A20FEF736 +:1051200063FE06211720FEF75FFE06212820FEF70A +:105130005BFE07213220FEF757FE0C212520FEF7EB +:1051400053FEBDE808400C212620FEF74DBE0000AE +:1051500008B5FFF717FE00F009F8FEF7EDFFFFF7BF +:10516000D5FDBDE80840FFF701BD00000023054A5A +:1051700019460133102BC2E9001102F10802F8D1DF +:10518000704700BFA04E00200B460146184600F0B5 +:105190002DB8000000F040B8012838BF012010B53C +:1051A0000446204600F030F830B900F007F808B99E +:1051B00000F00CF88047F4E710BD0000024B1868BF +:1051C000BFF35B8F704700BF204F002008B506205B +:1051D00000F084F80120FFF761FA0000024B0A4654 +:1051E00001461868FFF7A6BB2823002010B5054C20 +:1051F00013462CB10A4601460220AFF3008010BDD1 +:105200002046FCE700000000024B01461868FFF74B +:1052100095BB00BF28230020024B01461868FFF70A +:1052200091BB00BF2823002010B5013902449042F1 +:1052300001D1002005E0037811F8014FA34201D00D +:10524000181B10BD0130F2E72DE9F041A3B1C91AD6 +:1052500017780144044603F1FF3C8C42204601D9F3 +:10526000002009E00578BD4204F10104F5D10CEB02 +:105270000405D618A54201D1BDE8F08115F8018DCD +:1052800016F801EDF045F5D0E7E700001F2938B525 +:1052900004460D4604D9162303604FF0FF3038BD95 +:1052A000426C12B152F821304BB9204600F030F870 +:1052B0002A4601462046BDE8384000F017B8012BC9 +:1052C0000AD0591C03D1162303600120E7E700240C +:1052D00042F82540284698470020E0E7024B014667 +:1052E0001868FFF7D3BF00BF2823002038B5074D4B +:1052F00000230446084611462B60FFF7D3F9431CF0 +:1053000002D12B6803B1236038BD00BF244F0020B9 +:10531000FFF7C2B9034611F8012B03F8012B002A4D +:10532000F9D170476F72672E6172647570696C6F26 +:10533000742E41524B5F43414E4E4F444500000096 +:1053400053544D3332463F3F3F0053544D33324662 +:105350003430780053544D3332463432780053544D +:105360004D333246343436585800000001203300A3 +:105370000010410001105A000310590007103100BD +:105380000000000040530008130400004A530008C6 +:105390001904000054530008210400005E53000863 +:1053A00040A2E4F1646891060041A3E5F2656992C8 +:1053B000070000004261642043414E496661636515 +:1053C00020696E6465782E00800000000080000077 +:1053D00000008000000000000000000061200008C4 +:1053E00049280008A927000871200008A520000806 +:1053F000A1220008752000088520000879200008F7 +:10540000812000087D200008C921000889200008AB +:10541000152B0008992000089D2100080096000027 +:10542000000000000000000000000000000000007C +:1054300000000000F9400008E54000082141000894 +:105440000D4100081941000805410008F14000081D +:10545000DD4000082D41000863300000585400086A +:10546000384C0020484E0020004000000040000062 +:1054700000400000004000000000010000000200A9 +:105480000000020000000200000002000000020014 +:1054900000000200000002006D61696E0069646C2A +:1054A00065000000A00195AA00070000AAAAAAAA08 +:1054B00050010064FFF900000077000000900970BF +:1054C0008000000100000000AAAAAAAA4000000172 +:1054D000FFFF00000070000000000000000000500E +:1054E00000000000AAAAAA5A00000000FF3F000026 +:1054F00000000000000000000000000000000000AC +:10550000AAAAAAAA00000000FFFF000000000000F5 +:10551000000000000000000000000000AAAAAAAAE3 +:1055200000000000FFFF000000000000000000007D +:105530000000000000000000AAAAAAAA00000000C3 +:10554000FFFF00000000000000000000000000005D +:1055500000000000AAAAAAAA00000000FFFF0000A5 +:10556000000000000000000000000000000000003B +:105570000A0000000000000003000000000000001E +:10558000000000009CACFF7F010000000000000054 +:10559000530000000000000000000F0000000000A9 +:1055A00040420F00FE2A0100D2040000FF0000006C +:1055B00008470020744900202C2300200000000030 +:1055C00000000000000000000000000000000000DB +:1055D00000000000000000000000000000000000CB +:1055E00000000000000000000000000000000000BB +:1055F00000000000000000000000000000000000AB +:10560000000000000000000000000000000000009A +:0C5610000000000000000000000000008E +:00000001FF diff --git a/Tools/bootloaders/ARK_GPS_bl.bin b/Tools/bootloaders/ARK_GPS_bl.bin index e5e610d13b3b32..35f306f9c63f2a 100755 Binary files a/Tools/bootloaders/ARK_GPS_bl.bin and b/Tools/bootloaders/ARK_GPS_bl.bin differ diff --git a/Tools/bootloaders/ARK_GPS_bl.hex b/Tools/bootloaders/ARK_GPS_bl.hex index 0ce07ba00bfa64..e705911e53c6aa 100644 --- a/Tools/bootloaders/ARK_GPS_bl.hex +++ b/Tools/bootloaders/ARK_GPS_bl.hex @@ -1,1036 +1,1283 @@ :020000040800F2 -:1000000000070020E5040008B915000839150008AC -:10001000911500083915000865150008E704000867 -:10002000E7040008E7040008E7040008993700081F -:10003000E7040008E7040008E7040008E7040008F4 -:10004000E7040008E7040008E7040008E7040008E4 -:10005000E7040008E7040008C53B0008F13B00087E -:100060001D3C0008493C0008753C0008E7040008F6 -:10007000E7040008E7040008E7040008E7040008B4 -:10008000E7040008E7040008E704000871250008F9 -:10009000DD2500083126000885260008A13C00085F -:1000A000E7040008E7040008E7040008E704000884 -:1000B000153A0008E7040008E7040008E704000810 -:1000C000E7040008E7040008E7040008E704000864 -:1000D000E7040008E70400081D290008E7040008F9 -:1000E000093D0008E7040008E7040008E7040008E9 -:1000F000E7040008E7040008E7040008E704000834 -:10010000E7040008E7040008E7040008E704000823 -:10011000E7040008E7040008E7040008E704000813 -:10012000E7040008E7040008E7040008E704000803 -:10013000E7040008E7040008E7040008E7040008F3 -:10014000E7040008E7040008E7040008E7040008E3 -:10015000E7040008E7040008E7040008E7040008D3 -:10016000E7040008E7040008E7040008E7040008C3 -:10017000E7040008E7040008E7040008E7040008B3 -:10018000E7040008E7040008E7040008E7040008A3 -:10019000E7040008E7040008E7040008E704000893 -:1001A000E7040008E7040008E7040008E704000883 -:1001B000E7040008E7040008E7040008E704000873 -:1001C000E7040008E7040008E7040008E704000863 -:1001D000E7040008E7040008E7040008E704000853 -:1001E00053B94AB9002908BF00281CBF4FF0FF319E -:1001F0004FF0FF3000F074B9ADF1080C6DE904CE9A -:1002000000F006F8DDF804E0DDE9022304B07047F1 -:100210002DE9F047089D04468E46002B4DD18A42B9 -:10022000944669D9B2FA82F252B101FA02F3C2F1EC -:10023000200120FA01F10CFA02FC41EA030E94407D -:100240004FEA1C48210CBEFBF8F61FFA8CF708FB9E -:1002500016E341EA034306FB07F199420AD91CEB76 -:10026000030306F1FF3080F01F81994240F21C81A8 -:10027000023E63445B1AA4B2B3FBF8F008FB1033F0 -:1002800044EA034400FB07F7A7420AD91CEB040425 -:1002900000F1FF3380F00A81A74240F207816444F5 -:1002A000023840EA0640E41B00261DB1D44000237A -:1002B000C5E900433146BDE8F0878B4209D9002DDE -:1002C00000F0EF800026C5E9000130463146BDE868 -:1002D000F087B3FA83F6002E4AD18B4202D38242D2 -:1002E00000F2F980841A61EB030301209E46002D81 -:1002F000E0D0C5E9004EDDE702B9FFDEB2FA82F2D6 -:10030000002A40F09280A1EB0C014FEA1C471FFA33 -:100310008CFE0126200CB1FBF7F307FB131140EA1A -:1003200001410EFB03F0884208D91CEB010103F1E7 -:10033000FF3802D2884200F2CB804346091AA4B2A9 -:10034000B1FBF7F007FB101144EA01440EFB00FE7D -:10035000A64508D91CEB040400F1FF3102D2A645E2 -:1003600000F2BB800846A4EB0E0440EA03409CE781 -:10037000C6F12007B34022FA07FC4CEA030C20FA2E -:1003800007F401FA06F31C43F9404FEA1C4900FA4E -:1003900006F3B1FBF9F8200C1FFA8CFE09FB1811CB -:1003A00040EA014108FB0EF0884202FA06F20BD93E -:1003B0001CEB010108F1FF3A80F08880884240F28E -:1003C0008580A8F102086144091AA4B2B1FBF9F0D2 -:1003D00009FB101144EA014100FB0EFE8E4508D9CD -:1003E0001CEB010100F1FF346CD28E456AD9023852 -:1003F000614440EA0840A0FB0294A1EB0E01A14237 -:10040000C846A64656D353D05DB1B3EB080261EBA4 -:100410000E0101FA07F722FA06F3F1401F43C5E97E -:10042000007100263146BDE8F087C2F12003D840B4 -:100430000CFA02FC21FA03F3914001434FEA1C47F6 -:100440001FFA8CFEB3FBF7F007FB10360B0C43EAE8 -:10045000064300FB0EF69E4204FA02F408D91CEB98 -:10046000030300F1FF382FD29E422DD90238634496 -:100470009B1B89B2B3FBF7F607FB163341EA034136 -:1004800006FB0EF38B4208D91CEB010106F1FF3885 -:1004900016D28B4214D9023E6144C91A46EA00467C -:1004A00038E72E46284605E70646E3E61846F8E60E -:1004B0004B45A9D2B9EB020864EB0C0E0138A3E757 -:1004C0004646EAE7204694E74046D1E7D0467BE738 -:1004D000023B614432E7304609E76444023842E7B0 -:1004E000704700BF02E000F000F8FEE772B63A483D -:1004F00080F30888394880F3098839484EF6085156 -:10050000CEF20001086040F20000CCF200004EF68E -:100510003471CEF200010860BFF34F8FBFF36F8FCD -:1005200040F20000C0F2F0004EF68851CEF2000119 -:100530000860BFF34F8FBFF36F8F4FF00000E1EE05 -:10054000100A4EF63C71CEF200010860062080F3DE -:100550001488BFF36F8F03F09FF903F07BF903F06A -:10056000C5F94FF055301F491B4A91423CBF41F835 -:10057000040BFAE71C49194A91423CBF41F8040BAD -:10058000FAE71A491A4A1B4B9A423EBF51F8040B2C -:1005900042F8040BF8E700201749184A91423CBF83 -:1005A00041F8040BFAE703F059F903F0EDF9144CA4 -:1005B000144DAC4203DA54F8041B8847F9E700F005 -:1005C00041F8114C114DAC4203DA54F8041B884732 -:1005D000F9E703F041B900000007002000230020E4 -:1005E00000000008000100200007002078400008FB -:1005F00000230020242300202823002098390020F5 -:10060000E0010008E0010008E0010008E001000846 -:100610002DE9F04F2DED108AC1F80CD0C3689D462E -:10062000BDEC108ABDE8F08F002383F311882846C3 -:10063000A047002002F086FDFEE702F00BFD00DF80 -:10064000FEE700002DE9F04103F044F8074603F00F -:100650008FF8054600283DD12B4B9F423AD00133FD -:100660009F423AD0294B27F0FF029A4239D1F8B283 -:1006700000F052FAA84642F2107400F055FC08B19E -:100680000024A04600F04EFA064670B37CBB4646F6 -:1006900035B11F4B9F4203D003F062F80024264679 -:1006A000002003F021F81B4B1B691B0422D40EB160 -:1006B00000F032F800F096FC00F07CFE00F07EFFC7 -:1006C0000546CCB100F07AFF401BA04214D900F0DF -:1006D00023F8F3E7A8460024CFE704464FF00108CB -:1006E000CBE780464FF47A74C7E70446D0E74FF46F -:1006F0007A74CDE70024DDE700F026FD4FF47A7030 -:1007000002F026FDDDE700BF010007B0000008B0E1 -:10071000263A09B0000402401E4B1F4A10B51C4681 -:100720001968013134D004339342F9D162681B4B0C -:100730009A422DD91A4B9B6803F1006303F580336D -:100740009A4225D202F0E0FF02F0F2FF002000F012 -:100750004BFE144B0220187000F082FE124B1A6CF4 -:1007600000221A64196E1A66196E596C5A64596E11 -:100770005A665B6E72B64FF0E0232021C3F8084D35 -:10078000D4E9003281F311889D4683F3088810472D -:1007900010BD00BF0000010820000108FFFF000895 -:1007A000002300202823002000380240094A136853 -:1007B00049F2690099B21B0C00FB01331360064B30 -:1007C000186844F2506182B2000C01FB020018600C -:1007D00080B27047202300201C23002010B5002188 -:1007E0001022044600F058FE034B03CB20606160EA -:1007F0001868A06010BD00BF107AFF1F2DE9F043FC -:10080000224DBBB000F0DAFEAB6840F2ED22C31A15 -:10081000934232D906AFA8602B46282200213846E1 -:1008200001F0DAFB05F10E0000F02EFE0026044672 -:100830005FFA80F905F10E08F3B2F100994501F174 -:10084000280107D908EB06030822384601F0C4FB4B -:100850000136F1E708230122CDE9023205340C4BC1 -:100860000193A4B230230093CDE9047405A3D3E926 -:100870000023297B074801F0C7F93BB0BDE8F083AE -:10088000AFF3008078F6339F93CACD8D703300208C -:100890007D3300204433002070B50D4614461E46BB -:1008A00001F048F950B9022E10D1012C0ED112A33B -:1008B000D3E90023C5E90023012007E0282C10D04C -:1008C00005D8012C09D0052C0FD0002070BD302C8C -:1008D000FBD10BA3D3E90023ECE70BA3D3E900235F -:1008E000E8E70BA3D3E90023E4E70BA3D3E9002354 -:1008F000E0E700BFAFF30080401DA12026812A0B56 -:1009000078F6339F93CACD8D9E6AC421818A46EEC4 -:1009100026417272DF25D7B7F017304A39059E5647 -:1009200013B504462346084620220021019001F019 -:1009300053FB22790198032A234628BF032203F898 -:10094000042F2021022201F047FB62790198072A37 -:10095000234628BF072203F8052F2221032201F096 -:100960003BFBA2790198072A234628BF072203F8F8 -:10097000062F2521032201F02FFB019804F1080323 -:100980001022282101F028FB382002B010BD000001 -:100990002DE9F04FFFB01FAD0CAE40F2751280464E -:1009A0000F4620A80021296000F076FD4822002192 -:1009B000304600F071FD00F001FE554B4FF47A72A5 -:1009C000B0FBF2F0186093E80700012386E8070007 -:1009D0000DF152003382FFF701FF4FF4A24333843D -:1009E00006AB18464B4903F039FA15223064294604 -:1009F000304686F83C20FFF793FF10AB04460146D3 -:100A00000822284601F0E8FA0822A1180DF1410356 -:100A1000284601F0E1FA0DF14203082204F1100129 -:100A2000284601F0D9FA11AB202204F1180128461A -:100A300001F0D2FA12AB402204F13801284601F04D -:100A4000CBFA14AB082204F17801284601F0C4FA6D -:100A50000DF15103082204F18001284601F0BCFA8F -:100A600004F1880A0DF1520904F5847B4B46514686 -:100A7000082228460AF1080A01F0AEFAD34509F126 -:100A80000109F3D119AB08225946284601F0A4FA0E -:100A900004F588744FF0000996F834304B450AD9B4 -:100AA000B36B21464B440822284601F095FA0834DE -:100AB00009F10109F0E74FF0000996F83C304B4589 -:100AC00004EBC90108D9336C08224B44284601F0D5 -:100AD00083FA09F10109F0E700230393BB7E029337 -:100AE000073107F119030193C1F3CF010123CDE9C8 -:100AF00004510093F97E04A3D3E90023404601F09A -:100B000083F87FB0BDE8F08F9E6AC421818A46EEEB -:100B10002C2300206C3E0008014B1870704700BF6A -:100B200038230020F0B5324B1C7B85B034B1314BFB -:100B30000E221A810024204605B0F0BD2E4A10680E -:100B4000516802AB03C308232C492D480DEB030267 -:100B500003F062F9054630B9264B2A480A221A8169 -:100B600000F0E6FCE6E70169B1F5E02F06D9214B7C -:100B700025480B221A8100F0DBFCDCE7438B512B6C -:100B800008D01C4A21480C2111815122194600F03D -:100B9000CFFCD0E71E4A024402F11003994204D26E -:100BA000144B1C4810221A81E5E710398E1A204692 -:100BB000134900F007FD3246074605F118012046AB -:100BC00000F000FDAB689F4202D1EB6898420AD06A -:100BD000084B0D221A810090D5E902123B460E48BF -:100BE00000F0A6FCA6E70D4800F0A2FC0124A2E755 -:100BF000703300202C230020153F0008DCFF060086 -:100C000000000108843E0008903E0008A23E000853 -:100C10000800FFF7C03E0008DD3E0008063F000860 -:100C20002DE9F04FADB006AF80460C4600F082FFD4 -:100C3000054600285AD1237E022B1BD1E38A012BC3 -:100C400018D100F0BBFC0646FFF7B0FD03464FF499 -:100C5000C870DFF8D092B3FBF0F206F5167602FB0F -:100C6000103316FA83F3C9F80030E37E33B9A84B8A -:100C700000221A709C37BD46BDE8F08FA38AEEB201 -:100C8000013BB34205F101050BD93B1D1E44E900B0 -:100C900000960023082201F0F801204601F060F8D8 -:100CA000ECE707F11400FFF799FD324607F1140154 -:100CB000381D03F0A1F80028D9D10F2E08D8944B85 -:100CC0001E70D9F80030A3F51673C9F80030D1E7CB -:100CD000FB1CF8700146009307220346204601F0F2 -:100CE0003FF8F978404600F01DFFC3E7E38A282B60 -:100CF00026D010D8012B1ED0052BBBD1BFF34F8FB0 -:100D00008449854BCA6802F4E0621343CB60BFF3A9 -:100D10004F8F00BFFDE7302BACD1637E7F4D013399 -:100D20006A7BDBB29342E94603D1E27E2B7B9A4297 -:100D300065D0CD469EE721464046FFF729FE99E75C -:100D4000A38A013B9BB2C92B94D8744D2E7B26BB42 -:100D500005F10C030093082233463146204600F08B -:100D6000FFFF731CF2B2D9001E46A38A013B9A42D0 -:100D700005DA0E322A44009200230822EEE700230F -:100D80000022C5E900230023AB6085F8D730C5F801 -:100D9000D8302B7B0BB9E37E2B73002507F11409A8 -:100DA0003B1D082229464846C7E90155FD6001F070 -:100DB00013F93B7A05F1010AAB424FEACA0608D99A -:100DC000FB6808222B443146484601F005F9554698 -:100DD000EFE7C6F3CF06E17ECDE904960023039347 -:100DE000A37E0293193428230093019446A3D3E9E8 -:100DF0000023404600F008FFFFF700FD3AE74FF000 -:100E0000000807F11403A7F814801022009341464C -:100E10000123204600F0A4FFA68A023EB6B2F31CCE -:100E20009B109B000733DB08A9EBC3039D460DF124 -:100E3000180A1FFA88F34FEAC801B34201F1100102 -:100E40000AD20AEB0803009308220023204600F090 -:100E500087FF08F10108ECE795F8D70000F0CEFA1B -:100E6000D5F8D83004461BB995F8D70000F0D6FA6B -:100E7000D5F8D83033449C4204D295F8D7000130DD -:100E800000F0CCFA4FEA960B4FF000081FFA88F1F9 -:100E90008B45D5E9003209D90AEB880103EB8800BC -:100EA000012200F001FB08F10108EFE7F31842F11D -:100EB0000002C5E90032D5F8D83095F8D70006EB26 -:100EC0000308C5F8D88000F099FA804509D395F851 -:100ED000D730D5F8D8000133001B85F8D730C5F8D6 -:100EE000D800FF2E08D800232B7300F0A9FAFFF7D3 -:100EF00019FE08B1FFF710FC2B68094A9B0A013361 -:100F000013810023AB6014E726417272DF25D7B747 -:100F10003D33002000ED00E00400FA0570330020AE -:100F20002C2300204033002030B54FF00054244BD8 -:100F300022689A4285B007D002F024FC0446A8B982 -:100F40000024204605B030BD1E4B627D1A701E483D -:100F5000237D03731D49C9220E3000F08BFA204611 -:100F6000E022002100F098FA0124EAE7184A194D1E -:100F7000136C43F000731364AA6D174B9A42DFD1D0 -:100F80002B6E013B7E2BDBD8144A07CA01AB83E8EA -:100F900007001846032100F02BFB6B6D83424FF0D6 -:100FA0000003CDD12A6D8A4201BFAB65054B2A6E85 -:100FB0001A7003BF0A4BEA6D1A601C46C1E700BFF6 -:100FC0009AAD44C53823002070330020160000205D -:100FD00000380240006600405041A0B05866004012 -:100FE000182300202DE9FF474B4C02236371002397 -:100FF00002934A4BD3F800C0BCF57A7F12D3484B1A -:10100000484FB7FBFCF69C458CBF0A231123581EA2 -:10101000B6FBF3F503FB1562C1B2002A3ED00228ED -:101020000346F4D89DF80B303F4940485A1E9DF8BE -:101030000A30013B1B0443EA0253BDF80820013A81 -:1010400013434B6001F026FD00230193384B3949CF -:1010500000933948394B4FF4805200F03DFD384B36 -:10106000197811B1344800F05DFD00F0A7FA05468B -:10107000FFF79CFB4FF4C873B0FBF3F202FB1303C2 -:1010800005F5167010FA83F02E4B186002F070FB15 -:1010900008B10F23238104B0BDE8F0876B1EB3F5C0 -:1010A000806FBFD2C1EBC10E0EF103034FEAE3091B -:1010B000C3F3C703A1EB030809F1010A4FF47A70E7 -:1010C0005FFA88F609FB00005AFA88F8B0FBF8F0DE -:1010D000B0F5617F08D90EF1FF33C3F3C703C91A16 -:1010E000CEB2591E0F2914D8721E072A8CBF0022B7 -:1010F0000122991901FB0551B7FBF1F7BC4591D1CC -:10110000002A8FD0ADF808508DF80A308DF80B60AA -:1011100088E71346EDE700BF2C23002018230020AA -:101120003F420F0040787D011023002088340020CA -:10113000990800083C23002044330020210C0008BB -:1011400038230020403300202DE9F04F91A7D7E944 -:1011500000670FF24829D9E90089874D93B0DFF87D -:1011600044B2864C284600F0B3FD0DF1300A0790DA -:1011700070B310220021504600F08EF9079B197BB6 -:101180004FF0000261F303028DF83020586899682F -:101190000EAA03C21B680D9A63F31C029DF830303F -:1011A0000D9243F020038DF830300023524619464B -:1011B000584601F07FFC079028B9284600F08CFDC6 -:1011C000079B2370CEE72378072B3CD8013323708D -:1011D00018220021504600F05FF9DFF8C8B1684CD2 -:1011E000002319465246584601F08CFC014670BB5C -:1011F000102208A800F050F9636983F480636361EA -:1012000000F0DEF90B4612A9024611E903000DF1C8 -:10121000240C8CE803009DF83410C1F30300890608 -:101220004CBF0E99BDF838C08DF82C0046BFC1F3F5 -:101230001C0C4CF00041CCF30A010891284608A987 -:1012400000F012FFCCE7284600F046FDC0E7284634 -:1012500000F070FC0446002848D1DFF84CB100F0E3 -:10126000ADF9DBF80030984240D300F0A7F90790C1 -:10127000FFF79CFA079A8DF8204003464FF4C87098 -:1012800002F51672B3FBF0F101FB103312FA83F38F -:10129000CBF80030DFF814B19BF8001011B901232E -:1012A0008DF8203050460791FFF798FA0799C1F161 -:1012B0001004E4B2062C28BF0624224651440DF146 -:1012C000210000F0D7F808AB0393182302930134F0 -:1012D0002C4B0193E4B20123009304943B46324625 -:1012E000284600F029FC00238BF8003000F066F956 -:1012F000254A264C1368C31AB3F57A7F31D31060A0 -:1013000000F05EF902460B46284600F0EFFC284646 -:1013100000F010FC28B3237BDFF894B0002B14BF3F -:10132000032302238BF8053000F048F94FF47A7359 -:101330005146B0FBF3F0CBF800005846FFF7F0FA47 -:10134000182307300293124B0193C0F3CF0040F2F1 -:101350005513CDE903A0009342464B46284600F0C2 -:10136000EBFB237B2BB1FFF749FA237B002B7FF4A8 -:10137000F6AE13B0BDE8F08F4433002055340020A2 -:10138000000002403C330020503400207033002025 -:1013900054340020401DA12026812A0BF1C6A7C18C -:1013A000D068080F88340020403300203D330020EF -:1013B0002C23002070B502F02DF8094E094D308025 -:1013C000002428683388834208D902F01DF82B686E -:1013D00004440133B4F5803F2B60F2D370BD00BFED -:1013E000843400205834002002F0D8B800F10060A6 -:1013F000920000F5803002F05BB80000054B1A68DF -:10140000054B1B889B1A834202D9104401F0FCBF94 -:1014100000207047583400208434002038B5074D30 -:1014200004462868204401F0F7FF28B928682044C2 -:10143000BDE8384002F008B838BD00BF583400207D -:10144000064991F8243033B10023086A81F824302A -:101450000822FFF7CBBF0120704700BF5C3400209B -:10146000022802BF024B4FF480629A61704700BFAE -:101470000000024010B50023934203D0CC5CC4545A -:101480000133F9E710BD000003460246D01A12F9F5 -:10149000011B0029FAD1704702440346934202D04F -:1014A00003F8011BFAE770472DE9F8431F4D144676 -:1014B00095F824200746884652BBDFF870909CB30D -:1014C00095F824302BB92022FF2148462F62FFF7E0 -:1014D000E3FF95F82400C0F10802A24228BF22468B -:1014E000D6B24146920005EB8000FFF7C3FF95F8A6 -:1014F0002430A41B1E44F6B2082E17449044E4B2D4 -:1015000085F82460DBD1FFF79BFF0028D7D108E0E6 -:101510002B6A03EB82038342CFD0FFF791FF0028B1 -:10152000CBD10020BDE8F8830120FBE75C3400202C -:101530000FB4002004B0704700B59BB0EFF30981F1 -:1015400068226846FFF796FFEFF30583044B9A6B1A -:10155000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE749 -:1015600000ED00E000B59BB0EFF30981682268460A -:10157000FFF780FFEFF30583044B9A6B9A6A9A6A30 -:101580009A6A9A6A9A6A9B6AFEE700BF00ED00E0D9 -:1015900000B59BB0EFF3098168226846FFF76AFF48 -:1015A000EFF30583034B5A6B9A6A9A6A9A6A9A6AAE -:1015B0009B6AFEE700ED00E0FEE7000002F028B8BD -:1015C00002F000B830B5094D0A4491420DD011F82F -:1015D000013B5840082340F30004013B2C4013F02A -:1015E000FF0384EA5000F6D1EFE730BD2083B8ED69 -:1015F000F7B54FF0FF33DFF854C0DFF854E000EBED -:1016000081011A4688421CD050F8044B019401AF66 -:10161000042417F8015B82EA05620825DB181646E8 -:1016200005F1FF355241002EBCBF83EA0C0382EA6C -:101630000E0215F0FF05F1D1013C14F0FF04E8D1D2 -:10164000E0E7D843D14303B0F0BD00BF9336EAA929 -:10165000EBE1F0422DE9F041C56915B9C161BDE882 -:10166000F0814B6823F06047C3F38A464FEAD37E8C -:10167000C3F3807816EA230638BF3E46AC462B46B5 -:101680005A68BEEBD27F22F060440AD0002A18DAF2 -:10169000A40CB44217D19D420FD10D60DEE7134672 -:1016A000EEE7A74207D102F08044C2F380724245C0 -:1016B0000BD054B1EFE708D2EDE7CCF800100B6087 -:1016C000CDE7B44201D0B442E5D81A689C46002A5E -:1016D000E5D11960C3E700002DE9F047089D01F04E -:1016E00007044FEAD508224405F0070500EBD100B6 -:1016F0004FF47F49944201D1BDE8F08704F0070719 -:1017000005F0070A57453E4638BF5646C6F108065B -:10171000111B8E4228BF0E46E10808EBD50E415C36 -:1017200013F80EC0B94029FA06F721FA0AF1FFB200 -:101730008CEA010147FA0AF739408CEA010C03F8F8 -:101740000EC034443544D5E780EA0120082341F235 -:10175000210201B24000002980B203F1FF33B8BF7B -:10176000504013F0FF03F4D17047000038B50C4629 -:101770008D18A54200D138BD14F8011BFFF7E4FF16 -:10178000F7E7000002684AB113680360C388018963 -:1017900001339BB29942C38038BF03811046704722 -:1017A00070B588B0202204460D4668460021FFF738 -:1017B00073FE20460495FFF7E5FF024658B16B46DD -:1017C000054608AE1C4603CCB44228606960234637 -:1017D00005F10805F6D1104608B070BD082817D9E4 -:1017E00009280CD00A280CD00B280CD00C280CD0BF -:1017F0000D280CD00E2814BF4020302070470C203C -:101800007047102070471420704718207047202020 -:1018100070470000082817D90C280CD910280CD9BB -:1018200014280CD918280CD920280CD930288CBFA2 -:101830000F200E207047092070470A2070470B20A8 -:1018400070470C2070470D207047000010B54B68A2 -:1018500023B9CA8A63F30902CA8210BDC4681A6830 -:101860001C60C360438A013B43824A60EFE700008B -:101870002DE9F84F1D46CB8A0F46C3F3090106290F -:10188000814692460B4630D00020AAB207F11904D7 -:101890009EB2052E1FFA80F80FD8904503F1010380 -:1018A00006D3FB8A0A4462F30903FB8201201AE093 -:1018B0001AF80060E6540130EAE79045F1D2A1F150 -:1018C000060B1C237C68BBFBF3F203FB12BB1FFA65 -:1018D0008BF6002C45D14846FFF754FF044638B933 -:1018E00078606FF00200BDE8F88F4FF00008E6E77F -:1018F000002606607860ADB24FF0000B454510D968 -:101900000AEB0803221D13F8011B9155B1B208F12F -:1019100001081B291FFA88F82BD0454506F101065E -:10192000F1D8FB8AC3F30902154465F30903BCE748 -:10193000013292B21C462368002BF9D1AB1F0B4435 -:101940001C21B3FBF1F301339BB29A42D3D2BBF11A -:10195000000FD0D14846FFF715FF20B9C4F800B0FA -:10196000BFE70122E7E7C0F800B05E46206004460A -:10197000C1E74545D5D94846FFF704FF08B92060BF -:10198000AFE7C0F800B0002620600446B6E70000CC -:101990002DE9F04F2DED028B83B0CDE90013BDF89A -:1019A0003C5007469146002A00F092802DB10E9BD4 -:1019B000002B00F08D80072D32D807F10C00FFF7C7 -:1019C000E1FE044638B96FF00204204603B0BDECD6 -:1019D000028BBDE8F08F14220021FFF75DFD0E9908 -:1019E0002A4604F10800FFF745FD681CC0B2FFF766 -:1019F00011FFFFF7F3FE207499F80030013814FA54 -:101A000080F003F01F0363F03F030372009B43F079 -:101A10000041616038462146FFF71CFE0124D4E7EF -:101A200000F10C034FF0000808EE103A4FF0800A66 -:101A30004646444618EE100AFFF7A4FE83460028E7 -:101A4000C1D014220021FFF727FDC6BB019BABF8D4 -:101A5000083002200E9B00F1080299195BFA82F20D -:101A60000130C0B2082801D0AE422AD3FFF7D2FE1F -:101A7000FFF7B4FE99F80020009B411E02F01F0200 -:101A800042EA4812AE4208BF4FF0400A5BFA81F1C9 -:101A90004AEA020A43F0004281F808A08BF81000DD -:101AA000CBF8042059463846FFF7D4FD0134AE4246 -:101AB00024B288F001084FF0000ABBD185E700206E -:101AC000C8E711F801CB02F801CB0136B6B2C7E77F -:101AD0006FF0010479E70000F8B515460E4628229C -:101AE000002104461F46FFF7D7FC069B6360B5F54F -:101AF000001F079BA76034BF6A094FF6FF7223627D -:101B000004F10C0097B200239A4205D80023036029 -:101B100027826382A382F8BD0660013330462036F7 -:101B2000F2E7000003781BB94BB2002BC8BF01706D -:101B300070470000007870472DE9F74FDDF83C90C2 -:101B4000BDF830500D9E9DF83840BDF8407080467D -:101B500092469B46B9F1000F01D1002F51D11F2CA5 -:101B60004FD898F80000B0B9072F47D835F00303D5 -:101B700047D13A4649464FF6FF70FFF7F7FD20F090 -:101B800001002D02400445EA0464400C44EA40246C -:101B90004FF6FF7321E040EA0520072F40EA046476 -:101BA000F6D900254FF6FF73C5F12000A5F12002FC -:101BB0002AFA05F10BFA00F001432BFA02F2114365 -:101BC0001846C9B2FFF7C0FD0835402D0346EBD1DA -:101BD0003A464946FFF7CAFD0346CDE9009732462B -:101BE00021464046FFF7D4FE33780133DBB21F2B8A -:101BF00088BF0023337003B0BDE8F08F6FF003009F -:101C0000F9E76FF00100F6E72DE9F04F85B0924655 -:101C1000DDF848800F9D9DF840209DF84490BDF868 -:101C20004C7006469B46B8F1000F01D1002F48D1F9 -:101C30001F2A46D83378002B46D00C0244EA0264AF -:101C40009DF8381044EAC93444EA01441C43072F84 -:101C500044F0800432D900234FF6FF72C3F1200C08 -:101C6000A3F120002AFA03F10BFA0CFC41EA0C0163 -:101C70002BFA00F00143C9B210460393FFF764FD4D -:101C8000039B0833402B0246E8D13A464146FFF712 -:101C90006DFD0346CDE900872A4621463046FFF711 -:101CA00077FEB9F1010F06D12B780133DBB21F2B80 -:101CB00088BF00232B7005B0BDE8F08F4FF6FF738F -:101CC000E8E76FF00100F6E76FF00300F3E70000CC -:101CD000C06900B104307047C3691A68C261C26844 -:101CE0001A60C360438A013B438270472DE9F0418B -:101CF000D0F81880194E14461D464146002709B9F0 -:101D0000BDE8F081D1E90223A21A65EB03039642F4 -:101D100077EB03031ED283698B420DD1FFF796FD4B -:101D200083691B688361C3680B60438AC1608169F2 -:101D3000013B43828846E2E7FFF788FD0B68C8F85D -:101D40000030C3680B60438AC160013B4382D8F80E -:101D50000010D4E788460968D1E700BF80841E00E0 -:101D60002DE9F04F8BB00D46DDF8509014469B46A0 -:101D70008046002800F01981B9F1000F00F01581AC -:101D8000531E3F2B00F21181012A03D1BBF1000F3A -:101D900040F00B810023CDE90833B8F81430B5EBDF -:101DA000C30F4FEAC30703D300200BB0BDE8F08F89 -:101DB0002B199F42D8F80C303ABF7F1BFFB2274641 -:101DC0001BB9D8F81030002B7AD02F2D4ED8C5F182 -:101DD0003006B7424FF000032CBFF6B23E460093E8 -:101DE0002946D8F8080008AB3246FFF775FCA7EB88 -:101DF000060A35445FFA8AFAB8F8143003F1005342 -:101E0000063BDB000493D8F80C3003933021039B8E -:101E100013B1BAF1000F2CD1D8F8100040B1BAF1CB -:101E2000000F05D0009608AB5246691AFFF754FC24 -:101E300038B2002FB8D066070AD00AAB03EBD40142 -:101E4000624211F8083C02F00702134101F8083C15 -:101E5000082C3CD9102C40F2B580202C40F2B780E1 -:101E6000BBF1000F00F09C80082334E0BA46002646 -:101E7000C2E7049BE02B28BFE02306930B44AB4250 -:101E8000059314D95A1B03980096924534BF5246C5 -:101E9000D2B2691A08AB04300792FFF71DFC079A0B -:101EA0001644AAEB020A1544F6B25FFA8AFA049BBA -:101EB000069A05999B1A0493039B1B680393A6E754 -:101EC0000093D8F8080008AB3A462946AEE7BBF1C4 -:101ED000000F13D00123B4EBC30F6CD0082C12D821 -:101EE0009DF82030621E23FA02F2D50706D54FF086 -:101EF000FF3202FA04F423438DF820309DF820309D -:101F000089F8003051E7102C12D8BDF82030621E3D -:101F100023FA02F2D10706D54FF0FF3202FA04F499 -:101F20002343ADF82030BDF82030A9F800303CE75D -:101F3000202C0FD80899631E21FA03F3DA0705D580 -:101F40004FF0FF3202FA04F40C430894089BC9F8DE -:101F500000302AE7402C2BD0DDE90865611EC4F172 -:101F60002102A4F1210326FA01F105FA02F225FA71 -:101F700003F311431943CB0712D50122A4F1200327 -:101F8000C4F1200102FA03F322FA01F1A240524205 -:101F900043EA010363EB430332432B43CDE90823B8 -:101FA000DDE90823C9E90023FFE66FF00100FCE644 -:101FB0006FF00800F9E6082CA0D9102CB3D9202C1A -:101FC000EED8C3E7BBF1000FADD0022383E7BBF12E -:101FD000000FBBD004237EE730B5012A144638BF7A -:101FE0000124402C85B028BF40240025012ACDE9DA -:101FF000025518D81B788DF8083063070AD004AB57 -:1020000003EBD405624215F8083C02F00702934046 -:1020100005F8083C009103462246002102A8FFF77C -:102020005BFB05B030BD082AE4D9102A03D81B8811 -:10203000ADF80830E1E7202A8DBFD3E900231B6803 -:102040000293CDE90223D8E710B5CB681BB98B60AA -:102050000B618B8210BDC4681A681C60C360438A20 -:10206000013B4382CA60F0E72DE9F04FD1F80080D0 -:1020700093B018F0800FCDE90323C8F3C01219BF45 -:10208000C8F3C03BC8F306264FF0020B1646B8F162 -:10209000000F04460D4680F2D18118F0C04305932D -:1020A00040F0CC810B7B002B00F0C881BBF1020F0C -:1020B00003D00178B14240F0C48108F07F0106915D -:1020C0006AB3C8F3074A2B44069A93F8039076063E -:1020D00046EA0B4646EA82465FEAD91346EA0A0612 -:1020E000079300F0908000220023CDE90A23069B8D -:1020F000009367685B4652460AA92046B847002805 -:102100007ED0A7699FB9314604F10C00FFF748FB68 -:102110000746E0B96FF0020013B0BDE8F08FC8F3D6 -:102120000F2A18F07F0F08BF0AF0030ACBE73B69BC -:102130009E420DD03F68002FF9D1314604F10C00CA -:10214000FFF72EFB07460028E4D0A3693B60A76198 -:10215000DDE90A2300264FF6FF70C6F1200E22FAB1 -:1021600006F103FA0EFEA6F1200C23FA0CFC41EA5C -:102170000E0141EA0C01C9B2083609920893FFF733 -:10218000E3FA402EDDE90832E7D1B882FB7D09F0A1 -:102190001F06C3F384039B1BD7E9022198B2002BCF -:1021A000BCBF00F120031BB252EA0100C8F304686F -:1021B0000FD00398821A049860EB0101A74890425F -:1021C0004FF000028A4104D3079A002A5BD0012B0A -:1021D00023DDFA7D4FEA890302F0030203F07C035A -:1021E0001343FB7539462046FFF730FB079BA3B925 -:1021F000FB7DC3F38402013262F38603FB7504E0C6 -:102200006FF00B0088E7A76917B96FF00C0083E740 -:102210003B699E42BAD03F68F6E719F0400F32D0D2 -:10222000039BBB60049BFB60142200210DA8FFF7F9 -:1022300033F9039B0A93049B0B932B1D0C932B7B6D -:10224000ADF83EA0013BDBB2ADF83C30069B8DF80B -:10225000433094F824308DF840B083F001038DF8BA -:1022600044308DF84160A3688DF842800AA9204669 -:102270009847FB7DC3F38403013303F01F039B02E4 -:10228000FB82002048E7FB7DC9F34012B2EBD31F6D -:1022900040F0DA80C3F38403B34240F0D88007995A -:1022A0002B7B4FEA9912002934D0D20741D4032B5B -:1022B00040F2D080039BBB60049BFB602B7BAE1D78 -:1022C000033BDBB23246394604F10C00FFF7D0FA8B -:1022D00000280DDA20463946FFF7B8FAFB7DC3F334 -:1022E0008403013303F01F039B02FB82032013E7E7 -:1022F000AB883B832A7B033AB88AD2B23146FFF7D8 -:1023000035FAFB7DB882DA43C2F3C01262F3C71319 -:10231000FB75B6E76AB92E1D013BDBB23246394682 -:1023200004F10C00FFF7A4FA0028D3DB2A7B013A62 -:10233000E2E7F98AC1F30901013B0529DAB259D86C -:10234000281D002307F11A0C9A4208D910F801EB56 -:102350000CF801E0013101330629DBB2F4D1039915 -:102360000A9104990B91934207F11A010C9138BF1D -:10237000043379680D9134BF55FA83F300230E932B -:10238000FB8AADF83EA0C3F309031A44069B8DF8FF -:10239000433094F82430ADF83C2083F001038DF8ED -:1023A000443000238DF840B08DF841608DF84280B4 -:1023B0007B602A7BB88A013A291DFFF7D7F93B8B4E -:1023C000B882834203D1A3680AA9204698472046D1 -:1023D0000AA9FFF739FEFB7DB88AC3F384030133F2 -:1023E00003F01F039B02FB823B8B984214BF11201A -:1023F000002091E67B68002BB1D0062001E01C3064 -:102400006346D3F800C0BCF1000FF8D1091A081DCB -:1024100005F1040C00EB030905989DF8143001EB5D -:10242000000EBEF11B0F9AD89A4298D91CF8013BB6 -:1024300009F8013B059B01330593EDE76FF00900B7 -:102440006AE66FF00A0067E66FF00D0064E66FF071 -:102450000E0061E66FF00F005EE600BF80841E0094 -:10246000404BF0B51C6C404E44F000741C641D6E73 -:1024700045F000751D661B6E3C4B9B6AD3F80052FD -:10248000354045F00105C3F80052D3F8004234400E -:1024900044EA002040F00100C3F80002002952D0B5 -:1024A0000020C3F81C020546C3F80402C3F80C025E -:1024B000C3F8140203EBC00401301C28C4F84052D6 -:1024C000C4F84452F6D100254FF0010C96781488D8 -:1024D000F70748BFD3F804720CFA04F044BF07436F -:1024E000C3F80472B70742BFD3F80C720743C3F8AE -:1024F0000C72760742BFD3F814620643C3F8146225 -:1025000003EBC4045668C4F840629668C4F8446299 -:10251000D3F81C4201352043A942C3F81C0202F142 -:102520000C02D3D1D3F8002222F00102C3F800221A -:102530000C4B1A6C22F000721A641A6E22F00072B0 -:102540001A661B6EF0BD0122C3F84012C3F8441294 -:10255000C3F80412C3F81412C3F80C22C3F81C22E7 -:10256000E0E700BF003802400000FFFF8834002091 -:10257000184A916A08B58B688B6013F0010104D08A -:1025800013F00C0F18BF4FF48031D80506D513F4A3 -:10259000406F14BF41F4003141F00201D80306D569 -:1025A00013F4402F14BF41F4802141F00401D3699A -:1025B0000BB108489847202383F31188064800216F -:1025C00000F0EEFD002383F31188BDE8084001F020 -:1025D00017B900BF883400209034002038B5124C61 -:1025E000A36ADD68AA0712D05A6922F002025A6172 -:1025F000A36913B1012120469847202383F3118852 -:102600000A48002100F0CCFD002383F31188EB067B -:1026100006D5A36A1021D960236A0BB102489847F6 -:10262000BDE8384001F0ECB8883400209834002030 -:1026300038B5124CA36A1D69AA0712D05A6922F054 -:1026400010025A61A36913B1022120469847202342 -:1026500083F311880A48002100F0A2FD002383F3D0 -:102660001188EB0606D5A36A10211961236A0BB104 -:1026700002489847BDE8384001F0C2B888340020CD -:102680009834002038B50F4CA36A5D685D602A0756 -:102690000AD5042222701A6822F002021A60636AC4 -:1026A00013B10021204698476B0706D5A36A9969A4 -:1026B000236A13B1034809049847BDE8384001F084 -:1026C0009FB800BF8834002010B50E4C204600F0A3 -:1026D000CFF90D4BA3620B21132000F0B1F90B21B0 -:1026E000142000F0ADF90B21152000F0A9F90B2101 -:1026F000162000F0A5F90022BDE8104011460E207A -:10270000FFF7AEBE8834002000640040114B9842B1 -:1027100010B5044609D1104B1A6C42F000721A64CD -:102720001A6E42F000721A661B6EA36A01221A60CA -:10273000A36A5A68D20707D5626851681268D961DE -:102740001A60064A5A6110BD0121082000F01EFCE3 -:10275000EEE700BF88340020003802405B870100AC -:1027600003291AD8DFE801F0020A0F14836A9B6874 -:1027700013F0E05F14BF012000207047836A98685F -:10278000C0F380607047836A9868C0F3C060704788 -:10279000836A9868C0F3007070470020704700009B -:1027A00010B5032925D8DFE801F00225292D836A19 -:1027B0009968C1F30161183103EB011310788406A5 -:1027C0004CBF54689488C0F300114FEA410148BFE0 -:1027D00041EAC40100F00F004CBF41F0040141EA9E -:1027E0004451586041F001019068D2689860DA6005 -:1027F000196010BD836A03F5C073DFE7836A03F5D0 -:10280000C873DBE7836A03F5D073D7E701290AD0E1 -:1028100002290FD081B9836ADA68920701D1186959 -:1028200003E001207047836AD86810F0030018BFE6 -:1028300001207047836AF2E70020704710B539B96C -:10284000836AD96889071BD11B699C0704D110BD15 -:10285000012915D00229FAD1816AD1F8C031D1F805 -:10286000C441D1F8C8011061D1F8CC0150612020D9 -:1028700008610869800717D1486940F0100012E02C -:10288000816AD1F8B031D1F8B441D1F8B801106102 -:10289000D1F8BC0150612020C860C868800703D10E -:1028A000486940F002004861C3F34000C3F380016F -:1028B000000140EA4111107920F03000014311710C -:1028C00089064BBF91681189DB085B0D4CBF63F330 -:1028D0001C0163F30A01137948BF916064F3030399 -:1028E00013714FEA14234FEA144458BF1181137037 -:1028F0005480ACE7024AD36843F0C003D36070470A -:1029000000440040044B5A6810439A6858600AB16A -:10291000181D1047704700BFB43400202DE9F04166 -:102920003C4ED6F85C52EF682B68DA059CB20CD5A9 -:10293000202383F311884FF40070FFF7E3FF6FF457 -:1029400080732B60002383F31188202383F3118885 -:10295000DFF8C08014F02F0339D183F311883806D3 -:1029600013D5210611D5202383F311882A4800F0BE -:1029700001FA00284CDA0820FFF7C4FF4FF67F73F6 -:102980003B40EB60002383F311887A0615D563067C -:1029900013D5202383F31188D6E913239A4209D152 -:1029A000336C3BB127F040073F0410203F0CFFF78A -:1029B000A9FFEF60002383F31188D6F86422D3685F -:1029C0000BB110699847BDE8F04100F019BF23072B -:1029D00012D014F0080F0CBF00208020E10748BF80 -:1029E00040F02000A20748BF40F04000630748BF06 -:1029F00040F48070FFF786FFA4066B6805D596F853 -:102A000060124046194000F057FA2C68A4B2A1E7C2 -:102A10006860B7E7B4340020EC34002010B5054CF2 -:102A2000054A0021204600F025FA044BC4F85C3228 -:102A300010BD00BFB4340020F52800080044004059 -:102A400000F1604303F561430901C9B283F8001343 -:102A5000012200F01F039A4043099B0003F16043E9 -:102A600003F56143C3F880211A607047FFF72CBE5D -:102A7000012300F10802C0E90222037000F11002F4 -:102A80000023C0E90422C0E90633C0E908334360EB -:102A90007047000010B52023044683F311880223F9 -:102AA00003704160FFF732FE04232370002383F399 -:102AB000118810BD2DE9F0411F4604460D4616460B -:102AC000202383F3118800F108082378052B0DD00B -:102AD00029462046FFF744FE40B1204632462946AB -:102AE000FFF75EFE002080F3118808E0394640467B -:102AF00000F03AFB0028E8D0002383F31188BDE8FA -:102B0000F08100002DE9F0411F4604460D461646AF -:102B1000202383F3118800F110082378052B0DD0B2 -:102B200029462046FFF772FE40B12046324629462C -:102B3000FFF784FE002080F3118808E03946404604 -:102B400000F012FB0028E8D0002383F31188BDE8D1 -:102B5000F0810000F8B5154682680669AA420B4666 -:102B6000816938BF8568761AB54204460BD218468B -:102B70002A46FEF77FFCA3692B44A361A3685B1B75 -:102B8000A3602846F8BD0CD918463246FEF772FC01 -:102B9000AF1BE1683A463044FEF76CFCE3683B4407 -:102BA000EBE718462A46FEF765FCE368E5E7000018 -:102BB00083689342F7B51546044638BF8568D0E967 -:102BC0000460361AB5420BD22A46FEF753FC6369FD -:102BD0002B446361A36828465B1BA36003B0F0BD70 -:102BE0000DD932460191FEF745FC0199E068AF1B13 -:102BF0003A463144FEF73EFCE3683B44E9E72A46A7 -:102C0000FEF738FCE368E4E710B50A440024C3612A -:102C1000029B8460C0E90000C0E90511C160026147 -:102C2000036210BD08B5D0E90532934201D1826834 -:102C300082B98268013282605A1C42611970D0E9FF -:102C400004329A4224BFC3684361002100F09CFA19 -:102C5000002008BD4FF0FF30FBE7000070B52023D7 -:102C600004460E4683F31188A568A5B1A368A2693E -:102C7000013BA360531CA36115782269934224BFD2 -:102C8000E368A361E3690BB120469847002383F30F -:102C90001188284607E03146204600F065FA0028F2 -:102CA000E2DA85F3118870BD2DE9F74F04460E4630 -:102CB00017469846D0F81C904FF0200A8AF31188E6 -:102CC0004FF0000B154665B12A4631462046FFF706 -:102CD00041FF034660B94146204600F045FA00280E -:102CE000F1D0002383F31188781B03B0BDE8F08F87 -:102CF000B9F1000F03D001902046C847019B8BF328 -:102D00001188ED1A1E448AF31188DCE7C0E9051129 -:102D1000C160C3611144009B8260C0E90000016191 -:102D200003627047F8B504460D461646202383F328 -:102D30001188A768A7B1A368013BA36063695A1C07 -:102D400062611D70D4E904329A4224BFE368636172 -:102D5000E3690BB120469847002080F3118807E013 -:102D60003146204600F000FA0028E2DA87F31188A5 -:102D7000F8BD0000D0E905239A4210B501D1826860 -:102D80007AB98268013282605A1C82611C780369B8 -:102D90009A4224BFC3688361002100F0F5F9204600 -:102DA00010BD4FF0FF30FBE72DE9F74F04460E460C -:102DB00017469846D0F81C904FF0200A8AF31188E5 -:102DC0004FF0000B154665B12A4631462046FFF705 -:102DD000EFFE034660B94146204600F0C5F90028E1 -:102DE000F1D0002383F31188781B03B0BDE8F08F86 -:102DF000B9F1000F03D001902046C847019B8BF327 -:102E00001188ED1A1E448AF31188DCE702684368D2 -:102E10001143016003B11847704700001430FFF7F9 -:102E200043BF00004FF0FF331430FFF73DBF0000F9 -:102E30003830FFF7B9BF00004FF0FF333830FFF7ED -:102E4000B3BF00001430FFF709BF00004FF0FF319F -:102E50001430FFF703BF00003830FFF763BF0000F6 -:102E60004FF0FF323830FFF75DBF000000207047A1 -:102E7000FFF7D4BD37B515460E4A02600022426006 -:102E8000C0E902220122044602740B46009000F1C0 -:102E90005C014FF480721430FFF7B6FE00942B46AD -:102EA0004FF4807204F5AE7104F13800FFF72EFF85 -:102EB00003B030BD203F000838B5C36904460D4655 -:102EC0001BB904210844FFF7A1FF294604F11400AF -:102ED000FFF7A8FE002806DA201D4FF48061BDE848 -:102EE0003840FFF793BF38BD024B0022C3E90033DF -:102EF0009A6070471C370020002303748268054BDA -:102F00001B6899689142FBD25A6803604260106066 -:102F1000586070471C37002008B5202383F31188C0 -:102F2000037C032B05D0042B0DD02BB983F3118820 -:102F300008BD436900221A604FF0FF334361FFF779 -:102F4000DBFF0023F2E7D0E9003213605A60F3E7B9 -:102F5000002303748268054B1B6899689142FBD873 -:102F60005A68036042601060586070471C37002048 -:102F7000054B19690874186802681A605360186173 -:102F800001230374FDF744BB1C37002030B54B1CF4 -:102F90000B4D87B0044610D02B690A4A01A800F0F7 -:102FA0001BF92046FFF7E4FF049B13B101A800F0D2 -:102FB0004FF92B69586907B030BDFFF7D9FFF8E723 -:102FC0001C370020192F000838B50C4D41612B69C2 -:102FD00081689A689142044603D8BDE83840FFF7FB -:102FE0008BBF1846FFF7B4FF01232C610146237401 -:102FF0002046BDE83840FDF70BBB00BF1C37002062 -:10300000044B1A681B6990689B68984294BF002023 -:10301000012070471C37002010B5084C2368206938 -:103020001A6822605460012223611A74FFF790FF2E -:1030300001462069BDE81040FDF7EABA1C370020C0 -:1030400008B5FFF7DDFF18B1BDE80840FFF7E4BFA2 -:1030500008BD0000FFF7E0BFFEE7000010B50C4C14 -:10306000FFF742FF00F0AAF80A498022204600F04C -:1030700031F8012344F8180C037400F09DFB002381 -:1030800083F3118862B60448BDE8104000F042B8EE -:1030900044370020483F0008583F000800F012B9AC -:1030A000EFF3118020B9EFF30583202282F311881A -:1030B0007047000010B530B9EFF30584C4F308047D -:1030C00014B180F3118810BDFFF7BAFF84F31188A3 -:1030D000F9E7000082600222028270478368A3F150 -:1030E0007C0243F80C2C026943F83C2C426943F8FB -:1030F000382C074A43F81C2CC26843F8102C0222D3 -:1031000003F8082C002203F8072CA3F118007047DD -:103110002906000810B5202383F31188FFF7DEFF8E -:1031200000210446FFF750FF002383F31188204657 -:1031300010BD0000024B1B6958610F20FFF718BF3C -:103140001C370020202383F31188FFF7F3BF000012 -:1031500008B50146202383F311880820FFF716FFE6 -:10316000002383F3118808BD49B1064B42681B69EF -:1031700018605A60136043600420FFF707BF4FF0E8 -:10318000FF3070471C3700200368984206D01A6849 -:103190000260506059611846FFF7AEBE70470000EC -:1031A00038B504460D462068844200D138BD036816 -:1031B00023605C604561FFF79FFEF4E7054B03F178 -:1031C0001402C3E905224FF0FF310022C3E90712C0 -:1031D000704700BF1C37002070B51C4EC0E90323A8 -:1031E00005460C4600F06EFB334653F8142F9A4206 -:1031F0000DD13062C5E901242A600A2C2CBF0019C8 -:103200000A30C6E90555BDE8704000F049BB316A97 -:10321000431AE31838BF1C469368A34202D9081921 -:1032200000F04CFB73699A6894420CD85A68AC6001 -:103230002B606A6015609A685D60121B9A604FF09F -:10324000FF33F36170BD1B68A41AECE71C37002044 -:1032500038B51B4C636998420DD0D0E90032136039 -:103260005A6000228168C2609A680A449A604FF0EE -:10327000FF33E36138BD2246036842F8143F002162 -:1032800093425A60C16003D1BDE8384000F010BBE2 -:103290009A688168256A0A449A6000F013FB6369A2 -:1032A0009A68411B8A42E5D9AB181D1A092D206A7C -:1032B00098BF01F10A02BDE83840104400F0FEBAA0 -:1032C0001C3700202DE9F041184C002704F11406AA -:1032D000656900F0F7FA236AAA68C11A8A4215D80C -:1032E00013442362D5E9003213605A606369D5F84C -:1032F0000C80EF60B34201D100F0DAFA87F3118855 -:103300002869C047202383F31188E1E76169B1424E -:1033100009D013441B1ABDE8F0410A2B2CBFC0187A -:103320000A3000F0CBBABDE8F08100BF1C370020A6 -:1033300000207047FEE70000704700004FF0FF30AC -:1033400070470000BFF34F8F024AD368DB03FCD401 -:10335000704700BF003C024008B5094B1B7873B9A9 -:10336000FFF7F0FF074B1A69002ABFBF064A5A60F1 -:1033700002F188325A601A6822F480621A6008BD2D -:10338000D8380020003C02402301674508B50B4BAC -:103390001B7893B9FFF7D6FF094B1A6942F0004238 -:1033A0001A611A6842F480521A601A6822F4805234 -:1033B0001A601A6842F480621A6008BDD83800208A -:1033C000003C02400728F0B516D80C4C0C49237875 -:1033D0007BB90C4D0E4608234FF0006255F8047B74 -:1033E00046F8042B013B13F0FF033A44F6D10123C6 -:1033F000237051F82000F0BD0020FCE7FC380020CD -:10340000DC380020703F0008014B53F82000704763 -:10341000703F000808207047072810B5044601D9FE -:10342000002010BDFFF7CEFF064B53F824301844A0 -:10343000C21A0BB90120F4E712680132F0D1043B43 -:10344000F6E700BF703F0008072838B5044628D8C3 -:10345000FFF726FEFFF776FFFFF77EFF124AF32302 -:10346000D360E300DBB243F4007343F00203136163 -:10347000136943F48033136105462046FFF762FF6A -:10348000FFF7A0FF094B53F8241000F03BF9284642 -:10349000FFF77CFFFFF70EFE2046BDE83840FFF740 -:1034A000BBBF002038BD00BF003C0240703F000899 -:1034B00012F001032DE9F04105460E4614464BD1AA -:1034C0008118334A914261D8324B1B6813F00103D3 -:1034D0005CD0314FFFF7E4FDFFF73EFFF323FB60C5 -:1034E000FFF730FF314640F20128032C18D824F0B2 -:1034F0000104294E0C446D1A40F20118A1423369AF -:1035000005EB01072AD123F001033361FFF73EFFEA -:10351000FFF7D0FD0120BDE8F081043C0435E4E76D -:10352000AB07E4D13B6923F440733B613B6943EA59 -:1035300008033B6151F8046B2E60BFF34F8FFFF718 -:1035400001FF2B689E42E8D03B6923F001033B61F9 -:10355000FFF71CFFFFF7AEFD0020DCE723F440730C -:103560003361336943EA080333610B883B80BFF35F -:103570004F8FFFF7E7FE3F8831F8023BBFB2BB42F7 -:10358000BCD0336923F001033361E1E71846C2E799 -:103590000000080800380240003C0240084908B515 -:1035A0000B7828B11BB9FFF7D7FE01230B7008BDBC -:1035B000002BFCD0BDE808400870FFF7E7BE00BF55 -:1035C000D838002070B582B0FFF76AFD0E4E054670 -:1035D00000F078F93268904237BF0C4A0B495168C5 -:1035E00014682EBFD1E9004101315160041903462E -:1035F00041F10001284601913360FFF75BFD01991D -:10360000204602B070BD00BF0039002008390020FC -:1036100070B582B0FFF744FD104E054600F052F938 -:103620003268904237BF0E4A0D49516814682EBF68 -:10363000D1E9004101315160041941F10001034613 -:10364000284601913360FFF735FD01994FF47A72F6 -:1036500000232046FCF7C4FD02B070BD00390020F5 -:103660000839002010B50244064BD2B2904200D176 -:1036700010BD441C00B253F8200041F8040BE0B226 -:10368000F4E700BF502800400F4B30B51C6F2404F6 -:1036900007D41C6F44F400741C671C6F44F400448E -:1036A0001C670A4C236843F4807323600244084B70 -:1036B000D2B2904200D130BD441C00B251F8045B3C -:1036C00043F82050E0B2F4E70038024000700040B8 -:1036D0005028004007B5012201A90020FFF7C2FFD2 -:1036E000019803B05DF804FB13B50446FFF7F2FF41 -:1036F000A04205D0012201A900200194FFF7C4FFD8 -:1037000002B010BD70470000074B45F255521A60D9 -:1037100002225A6040F6FF729A604CF6CC421A6060 -:10372000024B01221A70704700300040143900200B -:10373000034B1B781BB1034B4AF6AA221A60704751 -:103740001439002000300040034B1A681AB9034AAC -:10375000D2F874281A6070471039002000300240F7 -:10376000024B4FF08072C3F874287047003002405B -:1037700008B5FFF7E9FF024B1868C0F3407008BDB9 -:103780001039002008B5FFF7DFFF024B1868C0F3BF -:10379000007008BD10390020EFF3098305494A6B1A -:1037A00022F001024A63683383F30988002383F31C -:1037B0001188704700EF00E0202080F3118862B686 -:1037C0000C4B0D4AD96821F4E0610904090C0A4345 -:1037D000DA60D3F8FC20094942F08072C3F8FC207B -:1037E0000A6842F001020A601022DA7783F82200A8 -:1037F000704700BF00ED00E00003FA05001000E094 -:1038000010B5202383F311880E4B5B6813F400631B -:1038100014D0F1EE103AEFF30984683C4FF0807356 -:10382000E361094BDB6B236684F30988FFF7E8FB50 -:1038300010B1064BA36110BD054BFBE783F3118864 -:10384000F9E700BF00ED00E000EF00E03B060008F4 -:103850003E06000870470000FEE700000A4B0B48D8 -:103860000B4A90420BD30B4BDA1C121AC11E22F0EA -:1038700003028B4238BF00220021FDF70DBE53F832 -:10388000041B40F8041BECE79C400008983900201A -:1038900098390020983900207047000000F080B867 -:1038A0004FF08043002258631A610222DA607047A9 -:1038B0004FF080430022DA60704700004FF08043F1 -:1038C000586370474FF08043586A70474B684360B5 -:1038D0008B688360CB68C3600B6943614B6903628B -:1038E0008B6943620B6803607047000008B5234B87 -:1038F00023481A6942F0FF021A611A6922F0FF0296 -:103900001A611A691A6B42F0FF021A631A6D42F0CB -:10391000FF021A651B4A1B6D1146FFF7D7FF02F124 -:103920001C0100F58060FFF7D1FF02F1380100F5BE -:103930008060FFF7CBFF02F1540100F58060FFF7D4 -:10394000C5FF02F1700100F58060FFF7BFFF02F1D3 -:103950008C0100F58060FFF7B9FF02F1A80100F5C6 -:103960008060FFF7B3FF02F1C40100F58060FFF74C -:10397000ADFFBDE8084000F097B800BF0038024036 -:1039800000000240903F000808B500F017FAFFF76A -:1039900065FBBDE80840FFF7D7BE00007047000098 -:1039A000104B1A6C42F001021A641A6E42F00102C6 -:1039B0001A660D4A1B6E936843F0010393604FF043 -:1039C000804331229A624FF0FF32DA6200229A611C -:1039D0005A63DA605A6001225A6108211A601C2079 -:1039E000FFF72EB800380240002004E04FF080427C -:1039F00008B51169D3680B40D9B2C9439B0711615F -:103A000007D5202383F31188FFF748FB002383F3B6 -:103A1000118808BD08B5FFF7E9FFBDE80840FFF7CA -:103A2000EFBE00001E4B1A6962F0FF021A611A69AC -:103A3000D2B21A614FF0FF301A695A6958610021F9 -:103A40005A6959615A691A6A62F080521A621A6A8E -:103A500002F080521A621A6A5A6A58625A6A5962A5 -:103A60005A6A1A6C42F080521A641A6E42F08052FE -:103A70001A661A6E0B4A106840F480701060186F56 -:103A800000F44070B0F5007F1EBF4FF4803018671F -:103A90001967536823F40073536000F06FB900BFD7 -:103AA00000380240007000403B4B3C4A1A643C4ADC -:103AB0004FF4404111601A6842F001021A601A681E -:103AC0009007FCD59A6822F003029A60324B9A68FC -:103AD00012F00C02FBD1196801F0F90119609A602B -:103AE0001A6842F480321A601A689103FCD55A6F42 -:103AF00042F001025A67284B5A6F9207FCD5294AB7 -:103B00005A601A6842F080721A60254A5368580455 -:103B1000FCD5214B1A689101FCD5234AC3F88420B7 -:103B20001A6842F080621A601A681201FCD51F4AB6 -:103B30009A600322C3F88C204FF00062C3F89420EF -:103B40001B4B1A681B4B9A421B4B21D11B4A116815 -:103B50001B4A91421CD140F203121A60164A1368A4 -:103B600003F00F03032BFAD10B4B9A6842F00202C9 -:103B70009A609A6802F00C02082AFAD15A6C42F450 -:103B800080425A645A6E42F480425A665B6E7047B5 -:103B900040F20372E1E700BF003802400004001069 -:103BA0000070004004194002083000240094883856 -:103BB000002004E011640020003C024000ED00E021 -:103BC00041C20F41084A08B5516913680B4003F020 -:103BD0000103536123B1054A13680BB1506898473C -:103BE000BDE80840FFF70CBE003C0140183900203A -:103BF000084A08B5516913680B4003F0020353618A -:103C000023B1054A93680BB1D0689847BDE80840D6 -:103C1000FFF7F6BD003C014018390020084A08B5FE -:103C2000516913680B4003F00403536123B1054A43 -:103C300013690BB150699847BDE80840FFF7E0BD34 -:103C4000003C014018390020084A08B55169136842 -:103C50000B4003F00803536123B1054A93690BB18C -:103C6000D0699847BDE80840FFF7CABD003C014055 -:103C700018390020084A08B5516913680B4003F051 -:103C80001003536123B1054A136A0BB1506A984778 -:103C9000BDE80840FFF7B4BD003C014018390020E2 -:103CA000174B10B55A691C68144004F478725A61B5 -:103CB000A30604D5134A936A0BB1D06A98476006ED -:103CC00004D5104A136B0BB1506B9847210604D5ED -:103CD0000C4A936B0BB1D06B9847E20504D5094AA7 -:103CE000136C0BB1506C9847A30504D5054A936C2F -:103CF0000BB1D06C9847BDE81040FFF781BD00BF05 -:103D0000003C0140183900201A4B10B55A691C6854 -:103D1000144004F47C425A61620504D5164A136DBE -:103D20000BB1506D9847230504D5134A936D0BB121 -:103D3000D06D9847E00404D50F4A136E0BB1506E56 -:103D40009847A10404D50C4A936E0BB1D06E9847E6 -:103D5000620404D5084A136F0BB1506F98472304CF -:103D600004D5054A936F0BB1D06F9847BDE810405A -:103D7000FFF746BD003C014018390020062108B578 -:103D80000846FEF75DFE06210720FEF759FE0621D4 -:103D90000820FEF755FE06210920FEF751FE0621F8 -:103DA0000A20FEF74DFE06211720FEF749FEBDE86A -:103DB000084006212820FEF743BE000008B5FFF7A3 -:103DC00031FE00F00BF8FEF751FEFFF751F8FFF758 -:103DD000E5FDBDE80840FFF761BD00000023054A8E -:103DE00019460133102BC2E9001102F10802F8D183 -:103DF000704700BF1839002010B5013902449042C5 -:103E000001D1002005E0037811F8014FA34201D051 -:103E1000181B10BD0130F2E72DE9F041A3B1C91A1A -:103E200017780144044603F1FF3C8C42204601D937 -:103E3000002009E00578BD4204F10104F5D10CEB46 -:103E40000405D618A54201D1BDE8F08115F8018D11 -:103E500016F801EDF045F5D0E7E70000034611F84C -:103E6000012B03F8012B002AF9D170476F72672EDE -:103E70006172647570696C6F742E41524B5F47506C -:103E8000530000004E6F20617070207369670A0054 -:103E9000426164206677206C656E677468202575C2 -:103EA0000A0042616420626F6172645F6964202568 -:103EB000752073686F756C642062652025750A0033 -:103EC0004261642066772064657363726970746F01 -:103ED00072206C656E6774682025750A0042616403 -:103EE0002061707020435243203078253038783A72 -:103EF000307825303878203078253038783A307866 -:103F0000253038780A00476F6F64206669726D77D4 -:103F10006172650A0040A2E4F16468910600000045 -:103F200000000000392E0008252E0008612E000830 -:103F30004D2E0008592E0008452E0008312E00088D -:103F40001D2E00086D2E00086D61696E00000000D6 -:103F500069646C6500000000503F00086037002075 -:103F6000D83800200100000059300008000000008F -:103F70000040000000400000004000000040000041 -:103F8000000001000000020000000200000002002A -:103F9000A000902A00000000AAAAAAAA50000024AB -:103FA000FFFB000000770000009009000100000501 -:103FB00000000000AAAAAAA501000080FFEF0000EF -:103FC00000000000000000000000000000000000F1 -:103FD000AAAAAAAA00000000FFFF0000000000003B -:103FE000000000000000000000000000AAAAAAAA29 -:103FF00000000000FFFF00000000000000000000C3 -:104000000000000000000000AAAAAAAA0000000008 -:10401000FFFF0000000000000000000000000000A2 -:1040200000000000AAAAAAAA00000000FFFF0000EA -:104030000000000000000000000000000000000080 -:10404000AAAAAAAA00000000FFFF000000000000CA -:104050000000000000000000000000000A00000056 -:10406000000000000300000000000000000000004D -:10407000A0C1FF7F0100000051000000000000000F -:1040800000000700000000006400000000000000C5 -:0C40900040420F00FE2A0100D204000094 +:1000000000070020F5040008E52600089D260008EA +:10001000C52600089D260008BD260008F704000834 +:10002000F7040008F7040008F7040008D9360008B0 +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008E54400080D4500080F +:10006000354500085D45000885450008F70400088F +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F704000851260008E8 +:100090007D2600088D260008F7040008AD450008FD +:1000A000F7040008F7040008F7040008F704000844 +:1000B00095460008F7040008F7040008F704000854 +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008F704000881460008F704000848 +:1000E00011460008F7040008F7040008F7040008A8 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008F7040008A3 +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E000CD12000800000000000000000000000028 +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600003F0CAFD03F05CFE4FF055301F491B4AF3 +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE703F0A8FD5A +:1005B00003F084FE144C154DAC4203DA54F8041BCE +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E703F090BD000700209A +:1005E000002300200000000808ED00E000010020CA +:1005F00000070020904F00080023002080230020E7 +:1006000080230020C44F0020E0010008E40100081E +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002003F0CEF959 +:10064000FEE703F031F900DFFEE70000F8B500F047 +:100650004FFE03F0EBFC074603F03AFD0546002889 +:100660003FD12C4B9F423CD001339F423CD02A4B80 +:1006700027F0FF029A423AD1F8B200F045FC2E462C +:1006800042F2107400F046FC08B10024264601F046 +:100690001DF980B3032000F045F80024264635B14B +:1006A0001E4B9F4203D003F00BFD00242646002082 +:1006B00003F0C6FC1A4B1B691B0422D40EB100F0D8 +:1006C00047F800F093FC00F015FE02F013F8054621 +:1006D000CCB102F00FF8401BA04214D900F038F85A +:1006E000F3E72E460024CDE704460126CAE7064676 +:1006F0004FF47A74C6E7002CD1D04FF47A740126F7 +:10070000CDE70024DDE700F0B9FC4FF47A7003F088 +:100710006BF9DDE7010007B0000008B0263A09B028 +:1007200000040240084B187003280CD8DFE800F0E2 +:1007300008050208022000F03BBE022000F02EBE99 +:10074000024B00225A60704780230020842300203F +:1007500010B501F0BBF830B1204B03221A70204BCA +:1007600000225A6010BD1F4B1F4A1C4619680131F8 +:10077000F8D004339342F9D162681C4B9A42F1D904 +:100780001B4B9B6803F1006303F580339A42E9D267 +:1007900003F06AFC03F07CFC002000F0C5FD0220A1 +:1007A000FFF7C0FF134B1A6C00221A64196E1A6609 +:1007B000196E596C5A64596E5A665B6E72B64FF078 +:1007C000E0233021C3F8084DD4E9003281F31188C9 +:1007D0009D4683F308881047C4E700BF80230020AC +:1007E000842300200000010820000108FFFF00080A +:1007F0000023002000380240094A136849F26900CA +:1008000099B21B0C00FB01331360064B186844F2CD +:10081000506182B2000C01FB0200186080B2704788 +:10082000182300201423002010B5002110220446B4 +:1008300000F0DAFD034B03CB206061601868A06014 +:1008400010BD00BF107AFF1F2DE9F041ADF54E7DC0 +:100850000DF134086CAC40F2751207460D460EA837 +:100860000021C8F8001000F0BFFD4FF4C472002151 +:10087000204600F0B9FD01F03DFF274B4FF47A729E +:10088000B0FBF2F0186093E80700022384E8070049 +:100890000DF5E9702382FFF7C7FF4FF4A2431F490C +:1008A000238407A804F07CFA152384F832310DF272 +:1008B000E32207AB0DF12C0C1E4603CE66451060FB +:1008C0005160334602F10802F6D130681060337986 +:1008D000137141460122204600F0D2FD002303930C +:1008E000AB7E029305F11903019380B20123CDE998 +:1008F00004800093E97E06A3D3E90023384602F082 +:10090000C1FA0DF54E7DBDE8F08100BFAFF3008068 +:100910009E6AC421818A46EE8C230020B04D0008D7 +:100920002DE9F0412C4C237ADAB080460D465BBBB2 +:1009300027A9284600F0B4FE0746002842D19DF8BA +:100940009D60C82E3ED801464FF4A662204600F0B6 +:100950004BFD4FF48073C4F8F8314FF40073C4F8C2 +:100960000C334FF44073C4F8203432460DF19E012D +:1009700004F1090000F026FD26449DF89C307772B2 +:1009800023720BB9EB7E23728122002106AC27A8CB +:1009900000F02AFD0122214627A800F0BDFE002319 +:1009A0000393AB7E029305F1190380B201932823D0 +:1009B000CDE904400093E97E05A3D3E90023404636 +:1009C00002F060FA5AB0BDE8F08100BFAFF30080DA +:1009D00026417272DF25D7B7A8440020F0B5254E16 +:1009E0004FF48A7505FB0065F1B096F8D83085F8AC +:1009F000DC300024D822214685F8E8403AA800F0EF +:100A0000F3FC06F1090000F0E7FCD5F8E4308DF8BE +:100A1000F000C2B206AF06F109010DF1F100CDE917 +:100A20003A3400F0CFFC394601223AA800F0A0FE8B +:100A300080B2CDE9047008230127CDE9023706F121 +:100A4000D803019330230093317A0B4807A3D3E9ED +:100A5000002302F017FAA04206DD01F04BFEC5F8B4 +:100A6000E000384671B0F0BD2046FBE778F6339FD2 +:100A700093CACD8DA8440020A43300202DE9F04175 +:100A80001D4D1E4E1E4F86B0284602F027FA034623 +:100A900058B30024CDE90344ADF81440027B8DF82F +:100AA000142099684068029403AA03C21B68DFF807 +:100AB000548043F00043029301F01EFE821941F17D +:100AC0000003009402A9384601F0E0F8A04205DDD9 +:100AD000284602F007FA88F80040D5E798F8003079 +:100AE000072B05D8013388F8003006B0BDE8F08147 +:100AF000014802F0F7F9F8E7A433002040420F0064 +:100B0000D8330020DD49002070B50D4614461E463E +:100B100002F014F950B9022E10D1012C0ED112A3FB +:100B2000D3E90023C5E90023012007E0282C10D0D9 +:100B300005D8012C09D0052C0FD0002070BD302C19 +:100B4000FBD10BA3D3E90023ECE70BA3D3E90023EC +:100B5000E8E70BA3D3E90023E4E70BA3D3E90023E1 +:100B6000E0E700BFAFF30080401DA12026812A0BE3 +:100B700078F6339F93CACD8D9E6AC421818A46EE52 +:100B800026417272DF25D7B7F017304A39059E56D5 +:100B900038B505460E4C0021013500F0E7FBA4F8FE +:100BA0002C55B4F82C0500F0C9FB78B1B4F82C052D +:100BB00000F0D4FB014648B9B4F82C0500F0D6FB90 +:100BC000B4F82C350133A4F82C35EAE738BD00BF62 +:100BD000A844002010B50A4B0A4A1A6003F5805356 +:100BE00093F860203AB9DC6D2CB1204600F0E6FEA7 +:100BF000204604F015F8BDE81040034800F0DEBEC2 +:100C0000D8330020044E0008204400202DE9F04F86 +:100C10008FB000AF05460C4602F090F8002849D18D +:100C2000237E022B1BD1E38A012B18D101F062FD38 +:100C30000646FFF7E1FD03464FF4C870DFF8C482B3 +:100C4000B3FBF0F206F5167602FB103316FA83F3C7 +:100C5000C8F80030E37E33B9A34B00221A703C374A +:100C6000BD46BDE8F08F07F12401204600F0D6FC18 +:100C70000028F4D107F11400FFF7D6FD97F82640BD +:100C800007F11401224607F1270004F013F80028A9 +:100C9000E2D10F2C08D8944B1C70D8F80030A3F583 +:100CA0001673C8F80030DAE797F82410284602F0E7 +:100CB0003DF8D4E7E38A282B2BD010D8012B23D082 +:100CC000052BCCD1BFF34F8F8849894BCA6802F4FA +:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 +:100CE000BDD1844EE17E327A9142B8D1607E3146E8 +:100CF000002291F8DC50854200F0A5800132042AE0 +:100D000001F58A71F5D1AAE721462846FFF79CFD37 +:100D1000A5E721462846FFF703FEA0E7B2F8EC500E +:100D20007B6005F103094FEA99094FEA8902D11D59 +:100D3000C908A8EBC1039D46EB460021584600F0C8 +:100D400053FB04F1EE012A463144584600F03AFBC9 +:100D50007B6813B9012000F0E7FA96F8D20000F0A2 +:100D6000EDFA044630B9307200F008FB204600F07E +:100D7000DBFAB1E0D6F8D4203AB996F8D200B6F84A +:100D80002C25824201D8FFF703FFD6F8D4202A444D +:100D9000944208D296F8D200B6F82C25013082424F +:100DA00001D8FFF7F5FE70685FFA89F2594600F046 +:100DB00023FB08B9C54679E0726896F8D2002A4448 +:100DC0007260D6F8D42005EB0209C6F8D49000F082 +:100DD000B5FA814509D396F8D220D6F8D40001326D +:100DE000001B86F8D220C6F8D400FF2D0FD80024AF +:100DF000347200F0C3FA204600F096FA00F066FD67 +:100E00003D4B188108B9FFF7A3FCC54627E7BB682F +:100E100096F8D9000AFB0362FB68D2F8E41082F866 +:100E2000E83001F58061C2F8E030C2F8E410FFF765 +:100E3000D5FDFFF723FE96F8D920013202F0030218 +:100E400086F8D920B6E74FF48A7A0AFB02F505F155 +:100E5000EA013144204600F0B7FCF86000287FF436 +:100E6000FEAE3544012285F8E82001F043FCD5F8B8 +:100E7000E020D6ED007ADFED216A801A192838BF0C +:100E8000192040F6B832904228BF1046B8EE677A73 +:100E900007EE900AF8EEE77A67EEA67ADFED186AB9 +:100EA000E7EE267AFCEEE77AC6ED007A96F8D930BE +:100EB000BB60BA6873680AFB02F4321992F8E81052 +:100EC00059B1D2F8E4108B42E8463FF427AF002135 +:100ED00082F8E810C2F8E010C5467368064A9B0A1B +:100EE00001331381BBE600BF9D33002000ED00E01D +:100EF0000400FA05A84400208C230020CDCCCC3D72 +:100F00006666663FA0330020014B1870704700BF33 +:100F10009823002030B54FF000542B4B22689A42A2 +:100F200085B007D003F0DEF8044620BB002420463D +:100F300005B030BD254B627D25481A70237D0372B4 +:100F40004FF48073C0F8F8314FF40073C0F80C33DD +:100F500000254FF44073C0F820341E49C0F8E45017 +:100F6000C922093000F02EFA2046E022294600F07E +:100F70003BFA0124DBE7184A184D136C43F0007369 +:100F80001364AA6D164B9A42D0D12B6E013B7E2B77 +:100F9000CCD8144A07CA01AB83E8070018460321DE +:100FA00000F062FC6B6D83424FF00003BED12A6DEE +:100FB0008A4201BFAB65054B2A6E1A7003BF0A4B0C +:100FC000EA6D1A601C46B2E79AAD44C5982300202A +:100FD000A8440020160000200038024000660040AF +:100FE0005041A0B0586600401023002037B51A4D7C +:100FF00000F06CFC02236B71184B288119681848AB +:10100000012201F015FA00230193164B16490093B3 +:101010001648174B4FF4805201F060FE154B1978BB +:1010200011B1124801F082FE01F064FB0446FFF7A3 +:10103000E3FB4FF4C873B0FBF3F202FB130304F5B8 +:10104000167010FA83F00C4B186003F041F808B1E9 +:101050000F232B8103B030BD8C23002010230020F0 +:10106000D8330020090B00089C230020A433002063 +:101070000D0C000898230020A03300202DE9F04F2C +:101080002DED028B0FF23829D9E90089834C93B0FA +:101090000BAE9FED7E8BFFF7F1FC814FDFF828A2AE +:1010A00000230A93ADF834300B9373604FF0000BBC +:1010B0005B468DED008B01250DF11D0207A9384619 +:1010C0008DF81C508DF81DB001F062F99DF81C30B0 +:1010D000002B40F0A580204601F030FE0646002897 +:1010E00045D1704F01F006FB3B6898423FD301F0B9 +:1010F00001FB8246FFF780FB4FF4C873B0FBF3F2AD +:1011000002FB13030AF5167010FA83F03860664F7D +:1011100097F800B0CBF1100ABBF1000F14BF3346B3 +:101120002B465FFA8AFA0EA88DF82830FFF77CFB71 +:10113000BAF1060F28BF4FF0060A0EAB03EB0B0106 +:1011400052460DF1290000F03DF90AAB0393182334 +:1011500002930AF10102554BD2B2CDE90053049239 +:1011600020464CA3D3E9002301F02EFE3E7001F08F +:10117000C1FA4F4A4F4D1368C31AB3F57A7F2ED385 +:10118000106001F0B9FA02460B46204601F0B4FEA9 +:10119000204601F0D3FD10B32B7A474E002B14BF2D +:1011A00003230223737101F0A5FA0EAF4FF47A7393 +:1011B0000122B0FBF3F039463060304600F006FA09 +:1011C000182302933D4B019380B240F25513CDE9B1 +:1011D0000370009342464B46204601F0F5FD2B7A02 +:1011E00093B101F087FA002607464FF48A7A95F802 +:1011F000D900304400F003000AFB005393F8E820C4 +:1012000092B30136042EF2D1C82002F0EDFB2B7A06 +:10121000002B7FF43DAF13B0BDEC028BBDE8F08F27 +:10122000DAF8143083F48063CAF814305946102277 +:101230000EA800F0D9F80DF11E0308AA0AA9384635 +:1012400000F022FE96E803000FAB83E803009DF850 +:1012500034308DF844300A9B0E930EA9DDE9082343 +:10126000204602F01DF821E7D3F8E02042B12B68B8 +:10127000FA2B38BFFA23BA1A0533B2EB430FC0D3A7 +:10128000FFF7ACFB0028BCD1BEE700BF00000000A8 +:1012900000000000401DA12026812A0BA43300205D +:1012A000D8330020A03300209D3300209C33002041 +:1012B000D8490020A84400208C230020DC490020CD +:1012C000F1C6A7C1D068080F0000024008B5054864 +:1012D00000F074FEBDE80840034A0449002003F012 +:1012E00099BC00BFD8330020184A0020D50B000855 +:1012F0007047000070B502F03BFD094E094D30808B +:10130000002428683388834208D902F02BFD2B681B +:1013100004440133B4F5803F2B60F2D370BD00BFAD +:101320000C4A0020E049002002F0D2BD00F100602C +:10133000920000F5803002F061BD0000054B1A6894 +:10134000054B1B889B1A834202D9104402F00ABD48 +:1013500000207047E04900200C4A0020024B1B6827 +:10136000184402F007BD00BFE0490020024B1B6893 +:10137000184402F017BD00BFE0490020064991F86B +:10138000243033B10023086A81F824300822FFF7A3 +:10139000CDBF0120704700BFE4490020022802BFF2 +:1013A000024B4FF080629A61704700BF000002401C +:1013B000022802BF024B4FF480629A61704700BF5F +:1013C0000000024010B50023934203D0CC5CC4540B +:1013D0000133F9E710BD000003460246D01A12F9A6 +:1013E000011B0029FAD1704702440346934202D000 +:1013F00003F8011BFAE770472DE9F8431F4D144627 +:1014000095F824200746884652BBDFF870909CB3BD +:1014100095F824302BB92022FF2148462F62FFF790 +:10142000E3FF95F82400C0F10802A24228BF22463B +:10143000D6B24146920005EB8000FFF7C3FF95F856 +:101440002430A41B1E44F6B2082E17449044E4B284 +:1014500085F82460DBD1FFF791FF0028D7D108E0A1 +:101460002B6A03EB82038342CFD0FFF787FF00286C +:10147000CBD10020BDE8F8830120FBE7E449002040 +:101480002DE9F0470D46044600219046284640F2DB +:101490007912FFF7A9FF234620220021284601F0F8 +:1014A000A1FE231D02222021284601F09BFE631D80 +:1014B00003222221284601F095FEA31D03222521A7 +:1014C000284601F08FFE04F1080310222821284647 +:1014D00001F088FE04F1100308223821284601F0AB +:1014E00081FE04F1110308224021284601F07AFE12 +:1014F00004F1120308224821284601F073FE04F18A +:10150000140320225021284601F06CFE04F1180338 +:1015100040227021284601F065FE04F120030822D4 +:10152000B021284601F05EFE04F121030822B82113 +:10153000284601F057FE04F12207C0263B463146FB +:1015400008222846083601F04DFEB6F5A07F07F1C7 +:101550000107F3D104F1320308223146284601F095 +:1015600041FE002704F1330A94F832304FEAC709EC +:101570009F4209F5A47615D3B8F1000F08D1314682 +:1015800004F599730722284601F02CFE09F24F1644 +:10159000274694F832213B1B93420CD3F01DC00820 +:1015A000BDE8F0870AEB070308223146284601F020 +:1015B00019FE0137D8E707F23313314608222846CF +:1015C00001F010FE08360137E3E7000013B50446CA +:1015D0000846002101602346C0F803102022019034 +:1015E00001F000FE0198231D0222202101F0FAFDE6 +:1015F0000198631D0322222101F0F4FD0198A31D2F +:101600000322252101F0EEFD019804F108031022C8 +:10161000282101F0E7FD072002B010BDF7B5002337 +:10162000047F00910E4607221946054601F09EFCF4 +:10163000731C0093012200230721284601F096FC29 +:10164000C4B9B31C0093052223460821284601F0A3 +:101650008DFC0D243746B278BB1B934211D32B7FF0 +:10166000A88A0734E408BBB9844294BF0020012053 +:1016700003B0F0BDAB8ADB00083BDB08B370082485 +:10168000E8E7FB1C0093214600230822284601F0CE +:101690006DFC08340137DEE7201A18BF0120E7E7A8 +:1016A000F7B50023047F00910E460822194605462F +:1016B00001F05CFC731CC4B9082200931146234658 +:1016C000284601F053FC1024012372785F1C013B73 +:1016D000934211D32B7FA88A0734E408BBB9844214 +:1016E00094BF0020012003B0F0BDAB8ADB00083BB3 +:1016F000DB0873700824E7E7F31900932146002301 +:101700000822284601F032FC08343B46DDE7201A67 +:1017100018BF0120E7E70000F8B50E46054614465D +:10172000002181223046FFF75FFE2B460822002170 +:10173000304601F057FD7CB96B1C0722082130466A +:1017400001F050FD0F2401236A785F1C013B934296 +:1017500004D3E01DC008F8BD0824F4E7EB192146C6 +:101760000822304601F03EFD08343B46ECE700001D +:10177000F8B50E46054614460021CE223046FFF746 +:1017800033FE2B4628220021304601F02BFD7CB988 +:1017900005F1080308222821304601F023FD3024FA +:1017A0002F462A7A7B1B934204D3E01DC008F8BD64 +:1017B0002824F5E707F1090321460822304601F005 +:1017C00011FD08340137ECE7F7B5047F00910E46B0 +:1017D000012310220021054601F0C8FBC4B9B31C47 +:1017E0000093092223461021284601F0BFFB19244B +:1017F00037467288BB1B9A4211D82B7FA88A0734C0 +:10180000E408BBB9844294BF0020012003B0F0BDBE +:10181000AB8ADB00103BDB0873801024E8E73B1D3C +:101820000093214600230822284601F09FFB08343C +:101830000137DEE7201A18BF0120E7E730B5094D70 +:101840000A4491420DD011F8013B5840082340F35F +:101850000004013B2C4013F0FF0384EA5000F6D152 +:10186000EFE730BD2083B8EDF7B54FF0FF33DFF879 +:1018700054C0DFF854E000EB81011A4688421CD0C6 +:1018800050F8044B019401AF042417F8015B82EA7D +:1018900005620825DB18164605F1FF355241002E7A +:1018A000BCBF83EA0C0382EA0E0215F0FF05F1D1FA +:1018B000013C14F0FF04E8D1E0E7D843D14303B082 +:1018C000F0BD00BF9336EAA9EBE1F042F7B5354A27 +:1018D000106851686B4603C36A463349334808238E +:1018E00003F0F8F9044688BB0A25314A10685168AC +:1018F0006B4603C36A462F492C48082303F0EAF9D4 +:101900000446002845D00369B3F5E02F41D8B0F86C +:101910006620512A3DD1284A024402F15C018B42E3 +:1019200037D35C3B214900209E1AFFF787FF3246E0 +:10193000074604F164010020FFF780FFA3689F427F +:1019400027D1E368984208BF002522E00369B3F578 +:10195000E02F25D8428B512A20D1174A024402F1A8 +:1019600010018B4218D3103B104900209D1AFFF73D +:1019700065FF2A46064604F118010020FFF75EFFC6 +:10198000A3689E4202D1E368984201D00D25ACE7DE +:101990000025284603B0F0BD1025A6E70C25A4E7D6 +:1019A0000B25A2E7C84D0008DCFF06000000010877 +:1019B000D14D000890FF06000800FFF710B5037C2A +:1019C000044613B9006803F06DF9204610BD00000D +:1019D0000023BFF35B8FC360BFF35B8FBFF35B8FED +:1019E0008360BFF35B8F7047BFF35B8F0068BFF30B +:1019F0005B8F704770B505460C30FFF7F5FF05F1BA +:101A0000080604463046FFF7EFFFA04206D93046ED +:101A10006D68FFF7E9FF2544281A70BD3046FFF7CF +:101A2000E3FF201AF9E7000070B50546406898B159 +:101A300005F10800FFF7D8FF05F10C060446304613 +:101A4000FFF7D2FF8442304694BF6D680025FFF750 +:101A5000CBFF013C2C44201A70BD000038B50C4669 +:101A60000546FFF7C7FFA04210D305F10800FFF7B6 +:101A7000BBFF04446868B4FBF0F100FB1144BFF302 +:101A80005B8F0120AC60BFF35B8F38BD0020FCE7AB +:101A90002DE9F041144607460D46FFF7C5FF844285 +:101AA00028BF0446D4B1B84658F80C6B4046FFF73F +:101AB0009BFF3044286040467E68FFF795FF331A4D +:101AC0009C4203D86C600120BDE8F0816B60A41BD0 +:101AD0003B68AB602044E8600220F5E72046F3E76E +:101AE00038B50C460546FFF79FFFA04210D305F11D +:101AF0000C00FFF779FF04446868B4FBF0F100FBC9 +:101B00001144BFF35B8F0120EC60BFF35B8F38BDE6 +:101B10000020FCE72DE9FF41884669460746FFF7AC +:101B2000B7FF6C4606B204EBC6060025B44209D0E6 +:101B30006268206808EB0501FFF744FC636808341D +:101B40001D44F3E729463846FFF7CAFF284604B08C +:101B5000BDE8F081F8B505460C300F46FFF744FFAD +:101B600005F1080604463046FFF73EFFA042304626 +:101B700088BF6C68FFF738FF201A386020B1304604 +:101B80002C68FFF731FF2044F8BD000073B5144600 +:101B900006460D46FFF72EFF844228BF04460190FB +:101BA000DCB101A93046FFF7D5FF019B33B932689C +:101BB000C5E90233C5E9002401200CE09C4238BF8E +:101BC00001942860019868608442F5D93368AB605D +:101BD000241AEC60022002B070BD2046FBE7000032 +:101BE0002DE9FF410F466946FFF7D0FF6C4600B272 +:101BF00004EBC0050026AC4209D0D4F8048054F8A8 +:101C0000081BB8194246FFF7DDFB4644F3E73046B0 +:101C100004B0BDE8F081000038B50546FFF7E0FFED +:101C2000044601462846FFF719FF204638BD00004C +:101C3000302383F3118862B670470000002383F3DA +:101C4000118862B67047000010B4026854681A46E2 +:101C500023465DF8044B1847012070470020704769 +:101C60000020704770470000002070470E2070472A +:101C700000F5805090F8C800C0F3400070470000A5 +:101C800000F5805090F9C90070470000F7B50C6866 +:101C9000BDF8207014F000541E466FD10B7B082B4A +:101CA0006CD8FFF7C5FF4569AB685B010CD4AB6826 +:101CB0001B0108D4AC6814F080545DD1FFF7BEFF5F +:101CC000204603B0F0BD01240B6804F1180C002B72 +:101CD000B8BFDB004FEA0C1CB4BF43F004035B0544 +:101CE00045F80C300B680FFA84FC13F0804F18BFD6 +:101CF00005EB0C1E05EB0C1C1EBFDEF8803143F01B +:101D00000203CEF880310B7BCCF8843105EB04154F +:101D10008B68C5F88C314B68C5F88831DCF88031A8 +:101D200043F00103CCF8803100EB441541F2680325 +:101D30001D4403EB44130344C5E9002608330D4654 +:101D400001F10C0C55F804EB43F804EB6545F9D1AF +:101D500084342D881D8000EB441407F0030325799B +:101D600025F00B052B432371FFF768FF00973346DF +:101D700000F0E2FC0120A4E70224A5E74FF0FF30C9 +:101D80009FE7000013B500F580540191E06DFFF767 +:101D90004BFE1F280AD90199E06D2022FFF7BAFEF9 +:101DA000A0F120035842584102B010BD0020FBE7CB +:101DB00008B500F58050FFF73BFFC06DFFF708FE48 +:101DC000BDE80840FFF73ABF00220260828142600E +:101DD0008260704710B500220023C0E90023002371 +:101DE000044603810C30FFF7EFFF204610BD0000D2 +:101DF000F0B5054600F580500C4690F8C83013F059 +:101E0000040FC3F3800108BF114661F3820304F19C +:101E1000840680F8C83005EB461389B01B79D807D3 +:101E20002ED57AB319072DD46846FFF7D3FF05EBFB +:101E3000441303F5835303F1180703AA10331868FA +:101E40005968144603C40833BB422246F7D11868C8 +:101E500020609B88A380DDE90E23CDE900230123C8 +:101E6000ADF808302B686946DB6B2846984705EBD0 +:101E700046152B791A075CBF43F008032B7101E06C +:101E8000002AF4D109B0F0BD2DE9F047074688B02B +:101E900007F5805468469A468846FFF7C9FE914682 +:101EA000FFF798FFE06DFFF7A5FD1F2829D9E06D2A +:101EB00020226946FFF7B0FE202822D103AD444618 +:101EC00005AB2E4603CE9E4220606160354604F18C +:101ED0000804F6D130682060B388A380DDE90023D0 +:101EE000C9E90023BDF80830AAF80030FFF7A6FEC4 +:101EF0004A4653464146384608B0BDE8F04700F030 +:101F000009BCFFF79BFE002008B0BDE8F087000089 +:101F10002DE9F84F0023C0E90133254B044640F872 +:101F2000183B0F46FFF750FF04F12800FFF752FF60 +:101F300004F1480804F582554646083530462036F7 +:101F4000FFF748FFAE42F9D104F580554FF48053B6 +:101F50004FF00009C5E91339C5F848800123EE6543 +:101F600004F5875804F58456C5F8549085F8583020 +:101F700085F86030083608F108084FF0000A4FF085 +:101F8000000B46E908ABA6F11800FFF71DFF20364D +:101F900046F8289C4645F4D185F8C97017B1054824 +:101FA00000F0A2FB044B63612046BDE8F88F00BF40 +:101FB000044E0008DC4D00080064004010B5044BDE +:101FC000197804464A1C1A70FFF7A2FF204610BD7C +:101FD000144A00202DE9F047002950D0294B2A4F00 +:101FE000B7FBF1F599428CBF0A231123581EB5FBAC +:101FF000F3FC03FB1C53C4B22BB102280346F5D8F3 +:102000000020BDE8F0870CF1FF36B6F5806FF7D2FF +:10201000C4EBC40E0EF103034FEAE309C3F3C70395 +:10202000A4EB030809F1010A4FF47A755FFA88F00E +:1020300009FB05555AFA88F8B5FBF8F5B5F5617F47 +:10204000C1BF0EF1FF33C3F3C703E01AC0B25C1C7B +:1020500050FA84F40CFB04F4B7FBF4F4A142CFD1A2 +:10206000013BDBB20F2BCBD80138C0B20728C7D851 +:102070000021107116809170D3700120C1E70846CD +:10208000BFE700BF3F420F0040787D0170B50546B5 +:102090000E464FF47A746B695B6803F00103B34238 +:1020A00007D04FF47A7001F09FFC013CF3D1204639 +:1020B00070BD0120FCE7000030B54269936913F060 +:1020C000700F16D000230B4C936103F1840200EBD8 +:1020D000421211794D0709D5890707D5416954F88E +:1020E00023508D60117941F0040111710133032BEC +:1020F000EBD130BDF04D000873B51D46436916465F +:102100009A68D207044609D59A6801219960C2F3FA +:102110004002CDE900650021FFF76AFE63699A6815 +:10212000D1050BD59A684FF480719960C2F34022B3 +:10213000CDE9006501212046FFF75AFE63699A68E0 +:10214000D2030BD59A684FF480319960C2F34042B4 +:10215000CDE9006502212046FFF74AFE204602B085 +:10216000BDE87040FFF7A8BFF8B5044646690029EE +:102170006CD106F10C07386880076AD006EB0115B0 +:102180003868D5F8B00110F0040FD5F8B0011ABFC7 +:10219000C00840F00040400DA061D5F8B0C11CF06F +:1021A000020F1CBF40F08040A061D5F8B40106EBDF +:1021B000011100F00F0084F82400D1F8B801207755 +:1021C000D1F8B801000A6077D1F8B801000CA07707 +:1021D000D1F8B801000EE077D1F8BC0184F82000F6 +:1021E000D1F8BC01000A84F82100D1F8BC01000C30 +:1021F00084F82200D1F8BC11090E84F8231038218C +:10220000396004F1340004F1180104F1240551F897 +:10221000046B40F8046BA942F9D109880180C4E934 +:102220000A2321460023238651F8283B2046DB6BF6 +:10223000984704F58052204692F8C83043F00403D2 +:1022400082F8C830BDE8F840FFF736BF06F1100746 +:1022500091E7F8BD10B5044600F04EFA02460B4671 +:1022600052EA030102D0013A63F10003044908680D +:1022700020B12146BDE81040FFF776BF10BD00BF7A +:10228000104A0020F8B500F583511E46FFF7D0FC38 +:10229000DFF844C00831002404F1840500EB451543 +:1022A0002B795F070ED4DB060CD5D1E9007397427A +:1022B000B34107D243695CF824709F602B7943F0E7 +:1022C00004032B710134032C01F12001E4D1BDE89A +:1022D000F840FFF7B3BC00BFF04D000808B5FFF7AA +:1022E000A7FCFFF7E9FEBDE80840FFF7A7BC000028 +:1022F000F8B543690546986800F0E050B0F1E05F3A +:102300000F461FD0E8B1FFF793FC05F58354103456 +:10231000002606F1840305EB43131B791A0706D543 +:102320000136032E04F12004F3D1012007E05B07FE +:10233000F6D42146384600F039FA0028F0D1FFF7EC +:102340007DFCF8BD0120FCE700F5805008B5FFF7E3 +:102350006FFCC06DFFF74EFBFFF770FC43090CBF2D +:102360000120002008BD0000F8B51D4600231370B1 +:102370000F4606461446FFF7E7FF80F0010038706D +:1023800025B129463046FFF7B3FF2070F8BD0000A5 +:102390002DE9B8410C4615461F46804600F0ACF9C1 +:1023A0000B462178024609B9287850B14046FFF71C +:1023B00069FFFFF793FF3B462A462146FFF7D4FF0C +:1023C0000120BDE8B881000010B5FFF731FC174BC4 +:1023D0001A6C42F000721A641A6A42F000721A62B1 +:1023E0001A6A00F5805422F000721A62FFF726FC88 +:1023F00094F8C830DB0718D4B9B103211320FFF7D4 +:1024000017FC01F0C7F90321142001F0C3F90321DF +:10241000152001F0BFF994F8C83043F0010384F8A7 +:10242000C830BDE81040FFF709BC10BD00380240BD +:102430002DE9F04700F5805588B095F8C930012B9B +:102440000446884616467FD8804F57F823200AB99D +:1024500047F82300D7F800A0C4F80C802674BAF11E +:10246000000F63D095F8C930012B6FD001212046B1 +:10247000FFF7AAFFFFF7DCFB6269136823F0020392 +:1024800013606269136843F00103136063690027F6 +:102490005F6101212046FFF7D1FBFFF7F7FD002820 +:1024A00000F09580E86DFFF793FA04F58359BA467A +:1024B00009F10809202200216846FEF795FF02A8CD +:1024C000FFF782FCCDF818A06A4609EB07030DF16F +:1024D000180E9446BCE80300F44518605960624643 +:1024E00003F10803F5D1DCF80000186020379CF8F0 +:1024F00004201A71602FDDD195F8C8306FF3820384 +:10250000002785F8C8306A4641462046ADF800707D +:10251000ADF802708DF80470FFF75CFD636948BB8D +:102520004FF400421A6008B0BDE8F08741F2D000D5 +:1025300002F078FB814610B15146FFF7E9FCC7F87D +:102540000090B9F1000F8DD10020ECE738680368E6 +:102550001B6B98470146002888D13868FFF734FF85 +:102560003868036832465B684146984700287FF424 +:102570007DAFE9E761221A609DF802309DF80320E3 +:102580001B06120402F4702203F040731343BDF8DB +:102590000020C2F3090213439DF804201205022E05 +:1025A00002F4E0020CBF4FF00041002113436269C6 +:1025B0000B43D361636913225A616269136823F084 +:1025C0000103136039462046FFF760FD08B96369CF +:1025D000A6E795F8C93093BB6169D1F8002242F0B3 +:1025E0000102C1F800226169D1F8002222F47C5274 +:1025F00022F00E02C1F800226169D1F8002242F4F3 +:102600006062C1F800226269C2F814326269C2F8DD +:102610000432626941F6FF71C2F80C126269C2F8B5 +:1026200040326269C2F8443263690122C3F81C2255 +:102630006269D2F8003223F00103C2F8003295F843 +:10264000C83043F0020385F8C8306CE7104A002018 +:1026500008B500F051F850EA0103024602D0421ECC +:1026600061F10001044B186810B10B46FFF744FDFF +:10267000BDE8084001F064B8104A002008B5002009 +:10268000FFF7E8FDBDE8084001F05AB808B50120A1 +:10269000FFF7E0FDBDE8084001F052B800B59BB07F +:1026A000EFF3098168226846FEF78CFEEFF305839D +:1026B000014B9B6BFEE700BF00ED00E008B5FFF7A4 +:1026C000EDFF000000B59BB0EFF30981682268467A +:1026D000FEF778FEEFF30583014B5B6BFEE700BF6F +:1026E00000ED00E0FEE700000FB408B5029801F02D +:1026F00011F9FEE701F038BC01F010BC13B56C46CF +:1027000084E80600031D94E8030083E80500012027 +:1027100002B010BD73B58568019155B11B885B0788 +:1027200007D4D0E900369B6B9847019AC1B2304676 +:10273000A847012002B070BDF0B5866889B0054693 +:102740000C465EB1BDF838305B070AD4D0E90037DB +:102750009B6B98472246C1B23846B047012009B06A +:10276000F0BD00220023CDE900230023ADF808309E +:102770000A4603AB01F10806106851681C4603C401 +:102780000832B2422346F7D1106820609288A280B6 +:10279000FFF7B2FF0423ADF808302B68CDE9000144 +:1027A000DB6B694628469847D8E7000030B50368D8 +:1027B0000968DD0FB5EBD17F23F0604421F0604262 +:1027C0004FEAD1700BD0002BB8BFA40C0029B8BFC2 +:1027D000920C944202D034BF0120002030BD9442BC +:1027E00005D1C1F38070C3F380738342F6D1944264 +:1027F0002CBF00200120F1E72DE9F041456A15B911 +:102800004162BDE8F0814B6823F06047C3F38A461C +:102810004FEAD37EC3F3807816EA230638BF3E46DC +:10282000AC462B465A68BEEBD27F22F060440AD0F9 +:10283000002A18DAA40CB44217D19D420FD10D60C2 +:10284000DEE71346EEE7A74207D102F08044C2F369 +:10285000807242450BD054B1EFE708D2EDE7CCF8D7 +:1028600000100B60CDE7B44201D0B442E5D81A683D +:102870009C46002AE5D11960C3E700002DE9F04726 +:10288000089D01F007044FEAD508224405F007052A +:1028900000EBD1004FF47F49944201D1BDE8F087AD +:1028A00004F0070705F0070A57453E4638BF56466D +:1028B000C6F10806111B8E4228BF0E46E10808EB40 +:1028C000D50E415C13F80EC0B94029FA06F721FA7B +:1028D0000AF1FFB28CEA010147FA0AF739408CEAA3 +:1028E000010C03F80EC034443544D5E780EA0120DA +:1028F000082341F2210201B24000002980B203F115 +:10290000FF33B8BF504013F0FF03F4D1704700000D +:1029100038B50C468D18A54200D138BD14F8011BFE +:10292000FFF7E4FFF7E7000042684AB1136843602D +:102930004389818901339BB29942438138BF8381A6 +:102940001046704770B588B0202204460D46684690 +:102950000021FEF749FD20460495FFF7E5FF0246FA +:1029600058B16B46054608AE1C4603CCB4422860FD +:102970006960234605F10805F6D1104608B070BD20 +:10298000082817D909280CD00A280CD00B280CD0FD +:102990000C280CD00D280CD00E2814BF402030205D +:1029A00070470C2070471020704714207047182083 +:1029B0007047202070470000082817D90C280CD930 +:1029C00010280CD914280CD918280CD920280CD977 +:1029D00030288CBF0F200E207047092070470A2036 +:1029E00070470B2070470C2070470D207047000087 +:1029F0002DE9F843078C072F04461ED9D0E9029829 +:102A000000254FF6FF73C5F12006A5F1200029FA35 +:102A100005F108FA06F628FA00F031430143C9B27D +:102A20001846FFF763FF0835402D0346EBD1E169F7 +:102A30003A46BDE8F843FFF76BBF4FF6FF70BDE8BD +:102A4000F883000010B54B6823B9CA8A63F3090202 +:102A5000CA8210BD04691A681C600361C38A013B05 +:102A6000C3824A60EFE700002DE9F84F1D46CB8A8C +:102A70000F46C3F309010529814692460B4630D023 +:102A80000020AAB207F11A049EB2042E1FFA80F8A1 +:102A90000FD8904503F1010306D3FB8A0A4462F381 +:102AA0000903FB8201201AE01AF80060E6540130A5 +:102AB000EAE79045F1D2A1F1050B1C237C68BBFB32 +:102AC000F3F203FB12BB1FFA8BF6002C45D14846EC +:102AD000FFF72AFF044638B978606FF00200BDE8BE +:102AE000F88F4FF00008E6E7002606607860ADB288 +:102AF0004FF0000B454510D90AEB0803221D13F8CF +:102B0000011B9155B1B208F101081B291FFA88F881 +:102B10002BD0454506F10106F1D8FB8AC3F3090223 +:102B2000154465F30903BCE7013292B21C462368E1 +:102B3000002BF9D16B1F0B441C21B3FBF1F30133C4 +:102B40009BB29A42D3D2BBF1000FD0D14846FFF7D7 +:102B5000EBFE20B9C4F800B0BFE70122E7E7C0F8F8 +:102B600000B05E4620600446C1E74545D5D94846D9 +:102B7000FFF7DAFE08B92060AFE7C0F800B0002622 +:102B800020600446B6E700002DE9F04F2DED028BE2 +:102B90001C4683B05B69019207468846002B00F013 +:102BA0009A80238C2BB1E269002A00F09480072BD5 +:102BB00035D807F10C00FFF7B7FE054638B96FF0BE +:102BC0000205284603B0BDEC028BBDE8F08F14224D +:102BD0000021FEF709FC228CE16905F10800FEF7EF +:102BE000F1FB208C013080B2FFF7E6FEFFF7C8FE54 +:102BF000013880B22084013028746369228C1B78EC +:102C00002A4403F01F0363F03F0348F000411372AE +:102C1000384669602946FFF7EFFD0125D1E700F14D +:102C20000C034FF0000908EE103A4FF0800A4E46B0 +:102C30004D4618EE100AFFF777FE83460028BED0F7 +:102C400014220021FEF7D0FB002E3AD1019BABF8F5 +:102C5000083002220BF1080E1FFA82FC0CF1010071 +:102C6000BCF1060F218C80B201D88E422BD3FFF726 +:102C7000A3FEFFF785FE62691278013802F01F0299 +:102C80008E4208BF4FF0400A42EA49121BFA80F117 +:102C90004AEA020A013048F0004281F808A08BF8A5 +:102CA0001000CBF8042059463846FFF7A5FD238CC9 +:102CB0000135B3422DB289F001094FF0000AB8D1B5 +:102CC0007FE70022C6E7E169895D0EF80210013650 +:102CD000B6B20132C0E76FF0010572E7F8B51546EC +:102CE0000E463022002104461F46FEF77DFB069B60 +:102CF0006360B5F5001F079BA76034BF6A094FF6F4 +:102D0000FF72A36297B2E66104F1100000239A42B9 +:102D100006D800230360A782E3822383E360F8BD23 +:102D20000660013330462036F1E7000003781BB916 +:102D30004BB2002BC8BF017070470000007870478D +:102D4000F8B50C46C969074611B9238C002B37D159 +:102D5000257E1F2D34D8387828BB228C072A2CD802 +:102D6000268A36F003032BD14FF6FF70FFF7D0FD14 +:102D700020F001003102400441EA0561400C41EAC3 +:102D800040254FF6FF72234629463846FFF7FCFEE2 +:102D9000002807DD626913780133DBB21F2B88BF7F +:102DA00000231370F8BD218A2D0645EA012505434D +:102DB0002046FFF71DFE0246E5E76FF00300F1E74E +:102DC0006FF00100EEE7000070B58AB004461646C9 +:102DD0000021282268461D46FEF706FBBDF8383064 +:102DE000ADF810300F9B05939DF840308DF81830EA +:102DF000119B07936946BDF84830ADF82030204656 +:102E0000CDE90265FFF79CFF0AB070BD2DE9F041E6 +:102E1000D36905460C4616460BB9138C5BBB377E4F +:102E20001F2F28D895F80080B8F1000F26D0304623 +:102E3000FFF7DEFD3378210241EAC33141EA0801A0 +:102E4000338A41EA076141EA03410246334641F0D1 +:102E500080012846FFF798FE00280ADD3378012B11 +:102E600007D1726913780133DBB21F2B88BF0023AF +:102E70001370BDE8F0816FF00100FAE76FF0030016 +:102E8000F7E70000F0B58BB004460D461746002169 +:102E9000282268461E46FEF7A7FA9DF84C305A1EB7 +:102EA000534253418DF800309DF84030ADF810305A +:102EB000119B05939DF848308DF81830149B0793AB +:102EC0006A46BDF85430ADF8203029462046CDE999 +:102ED0000276FFF79BFF0BB0F0BD0000406A00B127 +:102EE00004307047436A1A68426202691A600361DB +:102EF000C38A013BC38270472DE9F041D0F820809E +:102F0000194E14461D464146002709B9BDE8F08117 +:102F1000D1E90223A21A65EB0303964277EB030380 +:102F20001ED2036A8B420DD1FFF78CFD036A1B682A +:102F3000036203690B60C38A0161016A013BC382BA +:102F40008846E2E7FFF77EFD0B68C8F800300369AA +:102F50000B60C38A0161013BC382D8F80010D4E73B +:102F600088460968D1E700BF80841E002DE9F04F34 +:102F70008BB00D46DDF8509014469B4680460028E5 +:102F800000F01981B9F1000F00F01581531E3F2B9D +:102F900000F21181012A03D1BBF1000F40F00B8137 +:102FA0000023CDE90833B8F81430B5EBC30F4FEA6E +:102FB000C30703D300200BB0BDE8F08F2B199F424D +:102FC000D8F80C303ABF7F1BFFB227461BB9D8F8A0 +:102FD0001030002B7AD0272D4ED8C5F12806B742E5 +:102FE0004FF000032CBFF6B23E4600932946D8F8B6 +:102FF000080008AB3246FFF741FCA7EB060A354450 +:103000005FFA8AFAB8F8143003F10053053BDB008D +:103010000493D8F80C3003932821039B13B1BAF121 +:10302000000F2CD1D8F8100040B1BAF1000F05D034 +:10303000009608AB5246691AFFF720FC38B2002F01 +:10304000B8D066070AD00AAB03EBD401624211F88C +:10305000083C02F00702134101F8083C082C3CD957 +:10306000102C40F2B580202C40F2B780BBF1000F4D +:1030700000F09C80082334E0BA460026C2E7049B97 +:10308000E02B28BFE02306930B44AB42059314D9F1 +:103090005A1B03980096924534BF5246D2B2691A21 +:1030A00008AB04300792FFF7E9FB079A1644AAEB36 +:1030B000020A1544F6B25FFA8AFA049B069A059949 +:1030C0009B1A0493039B1B680393A6E70093D8F80D +:1030D000080008AB3A462946AEE7BBF1000F13D013 +:1030E0000123B4EBC30F6CD0082C12D89DF820300C +:1030F000621E23FA02F2D50706D54FF0FF3202FA1C +:1031000004F423438DF820309DF8203089F80030F6 +:1031100051E7102C12D8BDF82030621E23FA02F2BB +:10312000D10706D54FF0FF3202FA04F42343ADF87D +:103130002030BDF82030A9F800303CE7202C0FD813 +:103140000899631E21FA03F3DA0705D54FF0FF3221 +:1031500002FA04F40C430894089BC9F800302AE7EB +:10316000402C2BD0DDE90865611EC4F12102A4F1D9 +:10317000210326FA01F105FA02F225FA03F31143BD +:103180001943CB0712D50122A4F12003C4F1200179 +:1031900002FA03F322FA01F1A240524243EA010388 +:1031A00063EB430332432B43CDE90823DDE90823D6 +:1031B000C9E90023FFE66FF00100FCE66FF00800AC +:1031C000F9E6082CA0D9102CB3D9202CEED8C3E7EF +:1031D000BBF1000FADD0022383E7BBF1000FBBD0E2 +:1031E00004237EE730B5012A144638BF0124402C61 +:1031F00085B028BF40240025012ACDE9025518D802 +:103200001B788DF8083063070AD004AB03EBD405B4 +:10321000624215F8083C02F00702934005F8083CAA +:10322000009103462246002102A8FFF727FB05B0C4 +:1032300030BD082AE4D9102A03D81B88ADF808301D +:10324000E1E7202A8DBFD3E900231B680293CDE973 +:103250000223D8E710B5CB681BB98B600B618B825A +:1032600010BD04691A681C600361C38A013BC382F4 +:10327000CA60F0E703064CBFC0F3C03002207047BD +:1032800008B50246FFF7F6FF022806D15306C2F33F +:103290000F2001D100F0030008BDC2F30740FBE797 +:1032A0002DE9F04F93B0CDE903230A680446104698 +:1032B000FFF7E0FF022814BFC2F306260026002A0B +:1032C0000D46824680F2F28112F0C04940F0EE8154 +:1032D000097B002900F0EA81022803D02378B34259 +:1032E00040F0E781C2F304630693104602F07F03C7 +:1032F0000593FFF7C5FF059B29444FEA834848EA39 +:103300000A4848EA4668CE7800230022CDE908231F +:10331000F309834648EA0008029367D0059B0093AF +:1033200002466768534608A92046B847002800F0BF +:10333000C381276A4FB9414604F10C00FFF702FB35 +:10334000074690B96FF0020054E03B6998450DD0F4 +:103350003F68002FF9D1414604F10C00FFF7F2FA63 +:1033600007460028EED0236A3B60276297F817C013 +:1033700006F01F08CCF3840CACEB08001FFA80FEAB +:103380000028B8BF0EF12000A8EB0C031FFA83FE43 +:10339000D7E90221B8BF00B2002B0793BEBF0EF1E0 +:1033A00020031BB2079352EA010338D0039BDFF8D6 +:1033B00024E39A1A049B4FF0000C63EB010196453D +:1033C0007CEB01032BD36B7B97F81AE0734519D183 +:1033D000029B002B78D0012821DC7868F8B9DFF84F +:1033E000F0C2944570EB010316D337E0276A27B982 +:1033F0006FF00C0013B0BDE8F08F3B699845B5D075 +:103400003F68F4E7B24890427CEB010301D300200F +:10341000F0E7029B002BFAD0079B0F2B17DCFA7DFD +:10342000B30002F0030203F07C031343FB7539463B +:103430002046FFF707FB6B7BBB76029B3BB9FB7D0E +:10344000C3F38402013262F38603FB75D0E76A7B23 +:10345000BB7E9A42DBD1029B002B35D0B309022BF5 +:1034600032D0039BBB60049BFB60142200210DA89B +:10347000FDF7BAFF039B0A93049B0B932B1D0C9340 +:103480002B7BADF83EB0013BDBB2ADF83C30069B88 +:103490008DF84230059B8DF8433094F82C308DF830 +:1034A00040A083F001038DF844308DF84180A3687B +:1034B0000AA920469847FB7DC3F38403013303F038 +:1034C0001F039B02FB82A2E7FB7DC6F34012B2EB17 +:1034D000D31F40F0F480C3F38403434540F0F280EF +:1034E000029A2B7BB609002A4DD0F2075DD4032B3C +:1034F00040F2EB80039BBB60049BFB602B7BAE1D0B +:10350000033BDBB23246394604F10C00FFF7ACFA5C +:1035100000280CDA39462046FFF794FAFB7DC3F306 +:103520008403013303F01F039B02FB820AE7DDE9FA +:103530000884AB883B834FF6FF73C9F12000A9F1E3 +:10354000200228FA09F104FA00F0014324FA02F2F9 +:1035500011431846C9B2FFF7C9F909F10809B9F1D1 +:10356000400F0346E9D1B8822A7B033AD2B23146F2 +:10357000FFF7CEF9FB7DB882DA43C2F3C01262F3E3 +:10358000C713FB7543E786B92E1D013BDBB23246FC +:10359000394604F10C00FFF767FA0028BADB2A7BF2 +:1035A000B88A013AD2B23146E2E7F98AC1F3090199 +:1035B000013B0429DAB25BD8281D002307F11B0662 +:1035C0009A4208D910F801CB06F801C00131013345 +:1035D0000529DBB2F4D103990A9104990B91934226 +:1035E00007F11B010C9138BF043379680D9134BF8A +:1035F00055FA83F300230E93FB8AADF83EB0C3F374 +:1036000009031A44069B8DF84230059B8DF8433020 +:1036100094F82C30ADF83C2083F001038DF8443051 +:1036200000238DF840A08DF841807B602A7BB88A0A +:10363000013A291DFFF76CF93B8BB882834203D115 +:10364000A3680AA92046984720460AA9FFF702FE68 +:10365000FB7DBA8AC3F38403013303F01F039B028B +:10366000FB823B8B9A420CBF00206FF01000C1E63A +:103670007B68002BAFD0052001E01C3033461E686C +:10368000002EFAD1091A081D2E1D184401EB090C51 +:10369000BCF11B0F5FFA89F39DD89A429BD916F8AB +:1036A000013B00F8013B09F10109EFE76FF0090068 +:1036B000A0E66FF00A009DE66FF00B009AE66FF04F +:1036C0000D0097E66FF00E0094E66FF00F0091E6A4 +:1036D00040420F0080841E00EFF3098305494A6BC6 +:1036E00022F001024A63683383F30988002383F3DD +:1036F0001188704700EF00E0302080F3118862B637 +:103700000C4B0D4AD96821F4E0610904090C0A4305 +:10371000DA60D3F8FC20094942F08072C3F8FC203B +:103720000A6842F001020A602022DA7783F8220058 +:10373000704700BF00ED00E00003FA05001000E054 +:1037400010B5302383F311880E4B5B6813F40063CC +:1037500014D0F1EE103AEFF30984683C4FF0807317 +:10376000E361094BDB6B236684F3098800F090F872 +:1037700010B1064BA36110BD054BFBE783F3118825 +:10378000F9E700BF00ED00E000EF00E043060008AD +:103790004606000800F1604303F561430901C9B220 +:1037A00083F80013012200F01F039A4043099B0095 +:1037B00003F1604303F56143C3F880211A60704749 +:1037C00000230375826803691B6899689142FBD2E4 +:1037D0005A680360426010605860704700230375A8 +:1037E000826803691B6899689142FBD85A68036034 +:1037F000426010605860704708B50846302383F374 +:1038000011880B7D032B05D0042B0DD02BB983F32E +:10381000118808BD8B6900221A604FF0FF33836165 +:10382000FFF7CEFF0023F2E7D1E9003213605A60C0 +:10383000F3E70000FFF7C4BF054BD96808751868A7 +:1038400002681A60536001220275D860FCF7E4BE7A +:10385000204A002030B50C4BDD684B1C87B0044675 +:103860000FD02B46094A684600F06CF92046FFF756 +:10387000E3FF009B13B1684600F06EF9A86907B03A +:1038800030BDFFF7D9FFF9E7204A0020F9370008DB +:10389000044B1A68DB6890689B68984294BF0020CC +:1038A00001207047204A0020084B10B51C68D868DA +:1038B00022681A60536001222275DC60FFF78EFFD8 +:1038C00001462046BDE81040FCF7A6BE204A002075 +:1038D000044B1A68DB6892689B689A4201D9FFF72B +:1038E000E3BF7047204A002038B5074C0749084815 +:1038F000012300252370656000F03AFC0223237049 +:1039000085F3118838BD00BF884C0020484E000860 +:10391000204A002008B572B6044B186500F0ECFA96 +:1039200000F0A0FB024B03221A70FEE7204A0020A1 +:10393000884C002000F046B9EFF3118020B9EFF376 +:103940000583302282F311887047000010B530B92A +:10395000EFF30584C4F3080414B180F3118810BD9B +:10396000FFF7B6FF84F31188F9E700008B600223AC +:1039700008618B82084670478368A3F1840243F88C +:10398000142C026943F8442C426943F8402C094A3C +:1039900043F8242CC26843F8182C022203F80C2C9C +:1039A000002203F80B2C044A43F8102CA3F120004A +:1039B000704700BF31060008204A002008B5FFF715 +:1039C000DBFFBDE80840FFF735BF0000024BDB68B6 +:1039D00098610F20FFF730BF204A0020302383F387 +:1039E0001188FFF7F3BF000008B50146302383F3C9 +:1039F00011880820FFF72EFF002383F3118808BDEC +:103A0000064BDB6839B1426818605A601360436046 +:103A10000420FFF71FBF4FF0FF307047204A0020FF +:103A20000368984206D01A6802605060996118468F +:103A3000FFF700BF7047000010B503689C68A24202 +:103A40000CD85C688A600B604C6021605960996892 +:103A50008A1A9A604FF0FF33836010BD1B68121BF7 +:103A6000ECE700000A2938BF0A2170B504460D466C +:103A70000A26601900F076FB00F062FB041BA542E9 +:103A800003D8751C2E460446F3E70A2E04D9BDE878 +:103A90007040012000F0ACBB70BD0000F8B5144BC5 +:103AA0000D46D96103F1100141600A2A196982604B +:103AB00038BF0A22016048601861A818144600F057 +:103AC00043FB0A2700F03CFB431BA342064606D3F8 +:103AD0007C1C281900F046FB27463546F2E70A2FE2 +:103AE00004D9BDE8F840012000F082BBF8BD00BF5A +:103AF000204A0020F8B506460D4600F021FB0F4A8B +:103B0000134653F8107F9F4206D12A46014630469D +:103B1000BDE8F840FFF7C2BFD169BB68441A2C1951 +:103B200028BF2C46A34202D92946FFF79BFF224615 +:103B300031460348BDE8F840FFF77EBF204A002029 +:103B4000304A002010B4C0E9032300235DF8044B81 +:103B50004361FFF7CFBF000010B5194C23699842AD +:103B60000DD0D0E90032816813605A609A680A4427 +:103B70009A60002303604FF0FF33A36110BD23461A +:103B8000026843F8102F53600022026022699A42B3 +:103B900003D1BDE8104000F0DFBA936881680B44A0 +:103BA000936000F0CDFA2269E1699268441AA2425A +:103BB000E4D91144BDE81040091AFFF753BF00BF14 +:103BC000204A00202DE9F047DFF8BC8008F11007FB +:103BD0002C4ED8F8105000F0B3FAD8F81C40AA6860 +:103BE000031B9A423ED81444D5E900324FF0000935 +:103BF000C8F81C4013605A60C5F80090D8F810301F +:103C0000B34201D100F0A8FA89F31188D5E9033154 +:103C100028469847302383F311886B69002BD8D04E +:103C200000F08EFA6A69A0EB04094A4582460DD27B +:103C3000022000F0DDFA0022D8F81030B34208D19B +:103C400051462846BDE8F047FFF728BF121A224424 +:103C5000F2E712EB090938BF4A4629463846FFF712 +:103C6000EBFEB5E7D8F81030B34208D01444211A5F +:103C7000C8F81C00A960BDE8F047FFF7F3BEBDE837 +:103C8000F08700BF304A0020204A00200020704703 +:103C9000FEE70000704700004FF0FF307047000063 +:103CA000BFF34F8F024AD368DB03FCD4704700BFD9 +:103CB000003C024008B5094B1B7873B9FFF7F0FFD1 +:103CC000074B1A69002ABFBF064A5A6002F18832C0 +:103CD0005A601A6822F480621A6008BD904C002075 +:103CE000003C02402301674508B50B4B1B7893B994 +:103CF000FFF7D6FF094B1A6942F000421A611A68B1 +:103D000042F480521A601A6822F480521A601A68CB +:103D100042F480621A6008BD904C0020003C0240D2 +:103D20000728F0B516D80C4C0C4923787BB90C4DFC +:103D30000E4608234FF0006255F8047B46F8042B2A +:103D4000013B13F0FF033A44F6D10123237051F8ED +:103D50002000F0BD0020FCE7B44C0020944C002073 +:103D6000544E0008014B53F820007047544E000891 +:103D700008207047072810B5044601D9002010BD5F +:103D8000FFF7CEFF064B53F824301844C21A0BB984 +:103D90000120F4E712680132F0D1043BF6E700BFDE +:103DA000544E0008072810B5044621D8FFF778FFC5 +:103DB000FFF780FF0F4AF323D360C300DBB243F465 +:103DC000007343F002031361136943F480331361FA +:103DD000FFF766FFFFF7A4FF074B53F8241000F02E +:103DE0003DF9FFF781FF2046BDE81040FFF7C2BF55 +:103DF000002010BD003C0240544E0008F8B512F0FF +:103E00000103144642D185182E4A954257D82E4BAD +:103E10001B6813F0010352D02C4DFFF74BFFF32327 +:103E2000EB60FFF73DFF40F20127032C15D824F08B +:103E300001046618254C401A40F20117B14223696B +:103E400000EB010524D123F001032361FFF74CFFB0 +:103E50000120F8BD043C0430E7E78307E7D12B6974 +:103E600023F440732B612B693B432B6151F8046BA6 +:103E70000660BFF34F8FFFF713FF03689E42E9D040 +:103E80002B6923F001032B61FFF72EFF0020E0E7F1 +:103E900023F44073236123693B4323610B882B8008 +:103EA000BFF34F8FFFF7FCFE2D8831F8023BADB218 +:103EB000AB42C3D0236923F001032361E4E7184632 +:103EC000C7E700BF0000080800380240003C02407D +:103ED000084908B50B7828B11BB9FFF7EBFE0123A1 +:103EE0000B7008BD002BFCD0BDE808400870FFF740 +:103EF000FBBE00BF904C00204FF480214FF00050DB +:103F000000F0AEB80846114600F0AEBE012000F049 +:103F1000ABBE0000084600F0C5BE000070B582B020 +:103F2000FFF70AFD0E4E054600F00AF9326890428E +:103F300037BF0C4A0B49516814682EBFD1E90041C4 +:103F4000013151600419034641F1000128460191F5 +:103F50003360FFF7FBFC0199204602B070BD00BF43 +:103F6000B84C0020C04C002070B582B0FFF7E4FCD4 +:103F7000104E054600F0E4F83268904237BF0E4A12 +:103F80000D49516814682EBFD1E9004101315160DB +:103F9000041941F100010346284601913360FFF7FF +:103FA000D5FC01994FF47A7200232046FCF720F9E2 +:103FB00002B070BDB84C0020C04C002010B50244C7 +:103FC000064BD2B2904200D110BD441C00B253F84F +:103FD000200041F8040BE0B2F4E700BF5028004095 +:103FE0000F4B30B51C6F240407D41C6F44F40074CD +:103FF0001C671C6F44F400441C670A4C236843F49C +:10400000807323600244084BD2B2904200D130BD8D +:10401000441C00B251F8045B43F82050E0B2F4E7CE +:1040200000380240007000405028004007B50122CF +:1040300001A90020FFF7C2FF019803B05DF804FB5F +:1040400013B50446FFF7F2FFA04205D0012201A9F3 +:1040500000200194FFF7C4FF02B010BD70470000BC +:104060007047000070470000074B45F255521A6038 +:1040700002225A6040F6FF729A604CF6CC421A60F7 +:10408000024B01221A70704700300040CC4C0020D7 +:10409000034B1B781BB1034B4AF6AA221A607047E8 +:1040A000CC4C002000300040034B1A681AB9034A78 +:1040B000D2F874281A607047C84C002000300240C3 +:1040C000024B4FF08072C3F87428704700300240F2 +:1040D00008B5FFF7E9FF024B1868C0F3407008BD50 +:1040E000C84C002008B5FFF7DFFF024B1868C0F38B +:1040F000007008BDC84C002070470000FEE70000BB +:104100000A4B0B480B4A90420BD30B4BDA1C121A8A +:10411000C11E22F003028B4238BF00220021FDF7AE +:1041200063B953F8041B40F8041BECE71050000877 +:10413000C44F0020C44F0020C44F002000F0CAB874 +:104140004FF08043586A70474FF080430022586315 +:104150001A610222DA6070474FF080430022DA6071 +:10416000704700004FF0804358637047FEE700003F +:1041700070B51B4B01630025044686B0586085620C +:104180000E46FFF7B9FA04F11003C4E904334FF007 +:10419000FF33C4E90635C4E90044A560E562FFF7D2 +:1041A000CFFF2B460246C4E9082304F134010D4A2F +:1041B000256580232046FFF7D9FB0123E0600A4AEA +:1041C0000375009272680192B268CDE90223074B31 +:1041D0006846CDE90435FFF7F1FB06B070BD00BFBE +:1041E000884C0020744E0008794E00086D4100088C +:1041F000024AD36A1843D062704700BF204A0020A9 +:104200004B6843608B688360CB68C3600B69436114 +:104210004B6903628B6943620B680360704700005F +:1042200008B5234B23481A6942F0FF021A611A6944 +:1042300022F0FF021A611A691A6B42F0FF021A6338 +:104240001A6D42F0FF021A651B4A1B6D1146FFF7FB +:10425000D7FF02F11C0100F58060FFF7D1FF02F1EA +:10426000380100F58060FFF7CBFF02F1540100F543 +:104270008060FFF7C5FF02F1700100F58060FFF775 +:10428000BFFF02F18C0100F58060FFF7B9FF02F17A +:10429000A80100F58060FFF7B3FF02F1C40100F54B +:1042A0008060FFF7ADFFBDE8084000F08DB800BFAB +:1042B0000038024000000240804E000808B500F0BF +:1042C00019FAFFF711FBBDE80840FFF7EDBE00004B +:1042D000704700000F4B1A6C42F001021A641A6E0C +:1042E00042F001021A660C4A1B6E936843F0010308 +:1042F00093604FF0804331229A624FF0FF32DA62CE +:1043000000229A615A63DA605A6001225A611A6087 +:10431000704700BF00380240002004E04FF08042A8 +:1043200008B51169D3680B40D9B2C9439B07116125 +:1043300007D5302383F31188FFF7FCFA002383F3BA +:10434000118808BD1E4B1A6962F0FF021A611A69D2 +:10435000D2B21A614FF0FF301A695A6958610021D0 +:104360005A6959615A691A6A62F080521A621A6A65 +:1043700002F080521A621A6A5A6A58625A6A59627C +:104380005A6A1A6C42F080521A641A6E42F08052D5 +:104390001A661A6E0B4A106840F480701060186F2D +:1043A00000F44070B0F5007F1EBF4FF480301867F6 +:1043B0001967536823F40073536000F073B900BFAA +:1043C00000380240007000403B4B3C4A1A643C4AB3 +:1043D0004FF4404111601A6842F001021A601A68F5 +:1043E0009007FCD59A6822F003029A60324B9A68D3 +:1043F00012F00C02FBD1196801F0F90119609A6002 +:104400001A6842F480321A601A689103FCD55A6F18 +:1044100042F001025A67284B5A6F9207FCD5294A8D +:104420005A601A6842F080721A60254A536858042C +:10443000FCD5214B1A689101FCD5234AC3F884208E +:104440001A6842F080621A601A681201FCD51F4A8D +:104450009A600322C3F88C204FF00062C3F89420C6 +:104460001B4B1A681B4B9A421B4B21D11B4A1168EC +:104470001B4A91421CD140F203121A60164A13687B +:1044800003F00F03032BFAD10B4B9A6842F00202A0 +:104490009A609A6802F00C02082AFAD15A6C42F427 +:1044A00080425A645A6E42F480425A665B6E70478C +:1044B00040F20372E1E700BF003802400004001040 +:1044C000007000400419400208300024009488382D +:1044D000002004E011640020003C024000ED00E0F8 +:1044E00041C20F41074A08B5536903F00103536104 +:1044F00023B1054A13680BB150689847BDE80840DE +:10450000FFF71EB9003C0140D04C0020074A08B517 +:10451000536903F00203536123B1054A93680BB159 +:10452000D0689847BDE80840FFF70AB9003C014051 +:10453000D04C0020074A08B5536903F004035361C7 +:1045400023B1054A13690BB150699847BDE808408B +:10455000FFF7F6B8003C0140D04C0020074A08B5F0 +:10456000536903F00803536123B1054A93690BB102 +:10457000D0699847BDE80840FFF7E2B8003C014029 +:10458000D04C0020074A08B5536903F0100353616B +:1045900023B1054A136A0BB1506A9847BDE8084039 +:1045A000FFF7CEB8003C0140D04C0020164B10B5B0 +:1045B0005C6904F478725A61A30604D5134A936ABD +:1045C0000BB1D06A9847600604D5104A136B0BB143 +:1045D000506B9847210604D50C4A936B0BB1D06BF6 +:1045E0009847E20504D5094A136C0BB1506C984703 +:1045F000A30504D5054A936C0BB1D06C9847BDE870 +:104600001040FFF79DB800BF003C0140D04C002097 +:10461000194B10B55C6904F47C425A61620504D5FB +:10462000164A136D0BB1506D9847230504D5134AF4 +:10463000936D0BB1D06D9847E00404D50F4A136E0B +:104640000BB1506E9847A10404D50C4A936E0BB180 +:10465000D06E9847620404D5084A136F0BB1506FAF +:104660009847230404D5054A936F0BB1D06F984740 +:10467000BDE81040FFF764B8003C0140D04C00207A +:1046800008B5034800F0E8F8BDE80840FFF758B85F +:10469000504D002008B5FFF741FEBDE80840FFF788 +:1046A0004FB80000062108B50846FFF773F8062149 +:1046B0000720FFF76FF806210820FFF76BF80621A7 +:1046C0000920FFF767F806210A20FFF763F80621A3 +:1046D0001720FFF75FF806212820FFF75BF8072176 +:1046E0001C20FFF757F8BDE808400C212620FFF7F3 +:1046F00051B8000008B5FFF725FE00F07BF800F088 +:104700003DF8FFF7E5FDBDE80840FFF717BD0000E5 +:10471000026843681143016003B118477047000005 +:10472000143000F0C5B900004FF0FF33143000F032 +:10473000BFB90000383000F03BBA00004FF0FF3343 +:10474000383000F035BA0000143000F08BB90000AA +:104750004FF0FF31143000F085B90000383000F020 +:10476000E5B900004FF0FF32383000F0DFB900004B +:10477000012914BF6FF013000020704700F058B8F3 +:1047800037B515460E4A026000224260C0E9022297 +:104790000122044602740B46009000F15C014FF4C4 +:1047A0008072143000F034F900942B464FF480727C +:1047B00004F5AE7104F1380000F0ACF903B030BD7F +:1047C000604F000838B5C36904460D461BB9042183 +:1047D0000844FFF79DFF294604F1140000F026F974 +:1047E000002806DA201D4FF40061BDE83840FFF7CD +:1047F0008FBF38BD0023054A19460133102BC2E98B +:10480000001102F10802F8D1704700BFD04C00201F +:10481000026843681143016003B118477047000004 +:10482000024AD36843F0C003D3607047004400409D +:1048300010B5054C054A00212046FFF7A1FF044AA8 +:10484000044BC4E9972310BD504D002021480008B7 +:104850000044004040787D012DE9F041D0F85C62D1 +:10486000F7683368DA0504469DB20DD5302383F32B +:1048700011884FF480610430FFF7CAFF6FF4807332 +:104880003360002383F31188302383F3118804F10C +:10489000040815F02F033AD183F31188380615D593 +:1048A000290613D5302383F3118804F1380000F072 +:1048B00065F900284EDA0821201DFFF7A9FF4FF601 +:1048C0007F733B40F360002383F311887A0616D58B +:1048D0006B0614D5302383F31188D4E913239A424D +:1048E0000AD1236C43B127F040073F041021201D5B +:1048F0003F0CFFF78DFFF760002383F31188D4F896 +:104900006822D36843B3BDE8F041106918472B070C +:1049100014D015F0080F0CBF00214FF48071E80788 +:1049200048BF41F02001AA0748BF41F040016B0792 +:1049300048BF41F080014046FFF76AFFAD0673684B +:1049400005D594F8641220461940FFF73BFF3568FF +:10495000ADB29EE77060B6E7BDE8F081F8B51546E8 +:1049600082680669AA420B46816938BF8568761A53 +:10497000B54204460BD218462A46FCF723FDA3692C +:104980002B44A361A3685B1BA3602846F8BD0CD928 +:1049900018463246FCF716FDAF1BE1683A46304434 +:1049A000FCF710FDE3683B44EBE718462A46FCF7AA +:1049B00009FDE368E5E7000083689342F7B5154613 +:1049C000044638BF8568D0E90460361AB5420BD278 +:1049D0002A46FCF7F7FC63692B446361A368284609 +:1049E0005B1BA36003B0F0BD0DD932460191FCF70B +:1049F000E9FC0199E068AF1B3A463144FCF7E2FC60 +:104A0000E3683B44E9E72A46FCF7DCFCE368E4E7BB +:104A100010B50A440024C361029B8460C0E9000011 +:104A2000C0E90511C1600261036210BD08B5D0E99B +:104A30000532934201D1826882B982680132826074 +:104A40005A1C42611970D0E904329A4224BFC368EB +:104A500043610021FEF7E4FF002008BD4FF0FF3066 +:104A6000FBE7000070B5302304460E4683F311883F +:104A7000A568A5B1A368A269013BA360531CA3610B +:104A800015782269934224BFE368A361E3690BB1FF +:104A900020469847002383F31188284607E03146D3 +:104AA0002046FEF7ADFF0028E2DA85F3118870BDDD +:104AB0002DE9F74F04460E4617469846D0F81C904D +:104AC0004FF0300A8AF311884FF0000B154665B19C +:104AD0002A4631462046FFF741FF034660B941466A +:104AE0002046FEF78DFF0028F1D0002383F31188C4 +:104AF000781B03B0BDE8F08FB9F1000F03D001902F +:104B00002046C847019B8BF31188ED1A1E448AF397 +:104B10001188DCE7C0E90511C160C3611144009B45 +:104B20008260C0E90000016103627047F8B5044685 +:104B30000D461646302383F31188A768A7B1A368F2 +:104B4000013BA36063695A1C62611D70D4E90432A1 +:104B50009A4224BFE3686361E3690BB1204698473A +:104B6000002080F3118807E031462046FEF748FF19 +:104B70000028E2DA87F31188F8BD0000D0E90523A8 +:104B80009A4210B501D182687AB982680132826096 +:104B90005A1C82611C7803699A4224BFC3688361EE +:104BA0000021FEF73DFF204610BD4FF0FF30FBE730 +:104BB0002DE9F74F04460E4617469846D0F81C904C +:104BC0004FF0300A8AF311884FF0000B154665B19B +:104BD0002A4631462046FFF7EFFE034660B94146BC +:104BE0002046FEF70DFF0028F1D0002383F3118843 +:104BF000781B03B0BDE8F08FB9F1000F03D001902E +:104C00002046C847019B8BF31188ED1A1E448AF396 +:104C10001188DCE70B460146184600F02DB800006D +:104C200000F040B8012838BF012010B504462046E6 +:104C300000F030F830B900F007F808B900F00CF8CF +:104C40008047F4E710BD0000024B1868BFF35B8F8C +:104C5000704700BFBC4F002008B5062000F084F864 +:104C60000120FFF715F80000024B0A4601461868BC +:104C7000FFF748B91C23002010B5054C13462CB192 +:104C80000A4601460220AFF3008010BD2046FCE733 +:104C900000000000024B01461868FFF737B900BF5B +:104CA0001C230020024B01461868FFF733B900BFF0 +:104CB0001C23002010B501390244904201D100208C +:104CC00005E0037811F8014FA34201D0181B10BD75 +:104CD0000130F2E72DE9F041A3B1C91A1778014478 +:104CE000044603F1FF3C8C42204601D9002009E034 +:104CF0000578BD4204F10104F5D10CEB0405D6188A +:104D0000A54201D1BDE8F08115F8018D16F801ED3D +:104D1000F045F5D0E7E700001F2938B504460D46F9 +:104D200004D9162303604FF0FF3038BD426C12B136 +:104D300052F821304BB9204600F030F82A4601469F +:104D40002046BDE8384000F017B8012B0AD0591CA6 +:104D500003D1162303600120E7E7002442F8254031 +:104D6000284698470020E0E7024B01461868FFF705 +:104D7000D3BF00BF1C23002038B5074D00230446D5 +:104D8000084611462B60FEF787FF431C02D12B68B3 +:104D900003B1236038BD00BFC04F0020FEF776BFCF +:104DA000034611F8012B03F8012B002AF9D17047B3 +:104DB0006F72672E6172647570696C6F742E4152E8 +:104DC0004B5F47505300000040A2E4F16468910635 +:104DD0000041A3E5F265699207000000426164208A +:104DE00043414E496661636520696E6465782E00B3 +:104DF0008000000000800000000080000000000033 +:104E000000000000491C000831240008912300081C +:104E1000591C00088D1C0008891E00085D1C000834 +:104E20006D1C0008611C0008691C0008651C000856 +:104E3000B11D0008711C0008FD260008811C000837 +:104E4000851D000863300000444E0008784A0020A9 +:104E5000884C00200040000000400000004000009E +:104E600000400000000001000000020000000200FD +:104E7000000002006D61696E0069646C65000000ED +:104E8000A000902A00000000AAAAAAAA50000024AC +:104E9000FFFB000000770000009009000100000502 +:104EA00000000000AAAAAAA501000080FFCF000010 +:104EB00000000000000000000000000000000000F2 +:104EC000AAAAAAAA00000000FFFF0000000000003C +:104ED000000000000000000000000000AAAAAAAA2A +:104EE00000000000FFFF00000000000000000000C4 +:104EF0000000000000000000AAAAAAAA000000000A +:104F0000FFFF0000000000000000000000000000A3 +:104F100000000000AAAAAAAA00000000FFFF0000EB +:104F20000000000000000000000000000000000081 +:104F3000AAAAAAAA00000000FFFF000000000000CB +:104F40000000000000000000000000000A00000057 +:104F5000000000000300000000000000000000004E +:104F6000000000003D470008294700086547000889 +:104F7000514700085D4700084947000835470008C9 +:104F8000214700087147000898B2FF7F0100000028 +:104F900051000000000000000000070000000000B9 +:104FA00040420F00FE2A0100D2040000202300200E +:104FB00000000000000000000000000000000000F1 +:104FC00000000000000000000000000000000000E1 +:104FD00000000000000000000000000000000000D1 +:104FE00000000000000000000000000000000000C1 +:104FF00000000000000000000000000000000000B1 +:1050000000000000000000000000000000000000A0 :00000001FF diff --git a/Tools/bootloaders/ARK_RTK_GPS_bl.bin b/Tools/bootloaders/ARK_RTK_GPS_bl.bin index 32aaef4daa86bf..cb886cefcad8e2 100755 Binary files a/Tools/bootloaders/ARK_RTK_GPS_bl.bin and b/Tools/bootloaders/ARK_RTK_GPS_bl.bin differ diff --git a/Tools/bootloaders/ARK_RTK_GPS_bl.hex b/Tools/bootloaders/ARK_RTK_GPS_bl.hex index 120b7a74c651af..74f82628901d96 100644 --- a/Tools/bootloaders/ARK_RTK_GPS_bl.hex +++ b/Tools/bootloaders/ARK_RTK_GPS_bl.hex @@ -1,1051 +1,1283 @@ :020000040800F2 -:1000000000070020E5040008E91300086913000850 -:10001000C11300086913000895130008E7040008DD -:10002000E7040008E7040008E70400080D390008A9 -:10003000E7040008E7040008E7040008E7040008F4 -:10004000E7040008E7040008E7040008E7040008E4 -:10005000E7040008E7040008393D0008653D000892 -:10006000913D0008BD3D0008E93D0008E704000897 -:10007000E7040008E7040008E7040008E7040008B4 -:10008000E7040008E7040008E7040008E526000884 -:1000900051270008A5270008F9270008153E000889 -:1000A000E7040008E7040008E7040008E704000884 -:1000B000893B0008E7040008E7040008E70400089B -:1000C000E7040008E7040008E7040008E704000864 -:1000D000E7040008E7040008912A0008E704000884 -:1000E0007D3E0008E7040008E7040008E704000874 -:1000F000E7040008E7040008E7040008E704000834 -:10010000E7040008E7040008E7040008E704000823 -:10011000E7040008E7040008E7040008E704000813 -:10012000E7040008E7040008E7040008E704000803 -:10013000E7040008E7040008E7040008E7040008F3 -:10014000E7040008E7040008E7040008E7040008E3 -:10015000E7040008E7040008E7040008E7040008D3 -:10016000E7040008E7040008E7040008E7040008C3 -:10017000E7040008E7040008E7040008E7040008B3 -:10018000E7040008E7040008E7040008E7040008A3 -:10019000E7040008E7040008E7040008E704000893 -:1001A000E7040008E7040008E7040008E704000883 -:1001B000E7040008E7040008E7040008E704000873 -:1001C000E7040008E7040008E7040008E704000863 -:1001D000E7040008E7040008E7040008E704000853 -:1001E00053B94AB9002908BF00281CBF4FF0FF319E -:1001F0004FF0FF3000F074B9ADF1080C6DE904CE9A -:1002000000F006F8DDF804E0DDE9022304B07047F1 -:100210002DE9F047089D04468E46002B4DD18A42B9 -:10022000944669D9B2FA82F252B101FA02F3C2F1EC -:10023000200120FA01F10CFA02FC41EA030E94407D -:100240004FEA1C48210CBEFBF8F61FFA8CF708FB9E -:1002500016E341EA034306FB07F199420AD91CEB76 -:10026000030306F1FF3080F01F81994240F21C81A8 -:10027000023E63445B1AA4B2B3FBF8F008FB1033F0 -:1002800044EA034400FB07F7A7420AD91CEB040425 -:1002900000F1FF3380F00A81A74240F207816444F5 -:1002A000023840EA0640E41B00261DB1D44000237A -:1002B000C5E900433146BDE8F0878B4209D9002DDE -:1002C00000F0EF800026C5E9000130463146BDE868 -:1002D000F087B3FA83F6002E4AD18B4202D38242D2 -:1002E00000F2F980841A61EB030301209E46002D81 -:1002F000E0D0C5E9004EDDE702B9FFDEB2FA82F2D6 -:10030000002A40F09280A1EB0C014FEA1C471FFA33 -:100310008CFE0126200CB1FBF7F307FB131140EA1A -:1003200001410EFB03F0884208D91CEB010103F1E7 -:10033000FF3802D2884200F2CB804346091AA4B2A9 -:10034000B1FBF7F007FB101144EA01440EFB00FE7D -:10035000A64508D91CEB040400F1FF3102D2A645E2 -:1003600000F2BB800846A4EB0E0440EA03409CE781 -:10037000C6F12007B34022FA07FC4CEA030C20FA2E -:1003800007F401FA06F31C43F9404FEA1C4900FA4E -:1003900006F3B1FBF9F8200C1FFA8CFE09FB1811CB -:1003A00040EA014108FB0EF0884202FA06F20BD93E -:1003B0001CEB010108F1FF3A80F08880884240F28E -:1003C0008580A8F102086144091AA4B2B1FBF9F0D2 -:1003D00009FB101144EA014100FB0EFE8E4508D9CD -:1003E0001CEB010100F1FF346CD28E456AD9023852 -:1003F000614440EA0840A0FB0294A1EB0E01A14237 -:10040000C846A64656D353D05DB1B3EB080261EBA4 -:100410000E0101FA07F722FA06F3F1401F43C5E97E -:10042000007100263146BDE8F087C2F12003D840B4 -:100430000CFA02FC21FA03F3914001434FEA1C47F6 -:100440001FFA8CFEB3FBF7F007FB10360B0C43EAE8 -:10045000064300FB0EF69E4204FA02F408D91CEB98 -:10046000030300F1FF382FD29E422DD90238634496 -:100470009B1B89B2B3FBF7F607FB163341EA034136 -:1004800006FB0EF38B4208D91CEB010106F1FF3885 -:1004900016D28B4214D9023E6144C91A46EA00467C -:1004A00038E72E46284605E70646E3E61846F8E60E -:1004B0004B45A9D2B9EB020864EB0C0E0138A3E757 -:1004C0004646EAE7204694E74046D1E7D0467BE738 -:1004D000023B614432E7304609E76444023842E7B0 -:1004E000704700BF02E000F000F8FEE772B63A483D -:1004F00080F30888394880F3098839484EF6085156 -:10050000CEF20001086040F20000CCF200004EF68E -:100510003471CEF200010860BFF34F8FBFF36F8FCD -:1005200040F20000C0F2F0004EF68851CEF2000119 -:100530000860BFF34F8FBFF36F8F4FF00000E1EE05 -:10054000100A4EF63C71CEF200010860062080F3DE -:100550001488BFF36F8F03F059FA03F035FA03F0F4 -:100560007FFA4FF055301F491B4A91423CBF41F87A -:10057000040BFAE71C49194A91423CBF41F8040BAD -:10058000FAE71A491A4A1B4B9A423EBF51F8040B2C -:1005900042F8040BF8E700201749184A91423CBF83 -:1005A00041F8040BFAE703F013FA03F0A7FA144C2E -:1005B000144DAC4203DA54F8041B8847F9E700F005 -:1005C00041F8114C114DAC4203DA54F8041B884732 -:1005D000F9E703F0FBB9000000070020002300202A -:1005E000000000080001002000070020684100080A -:1005F000002300202423002028230020A0390020ED -:10060000E0010008E0010008E0010008E001000846 -:100610002DE9F04F2DED108AC1F80CD0C3689D462E -:10062000BDEC108ABDE8F08F002383F311882846C3 -:10063000A047002002F040FEFEE702F0C5FD00DF0B -:10064000FEE70000F8B503F0FFF8074603F04AF9AB -:10065000054600283FD12C4B9F423CD001339F429E -:100660003CD02A4B27F0FF029A423AD1F8B200F070 -:1006700063FB2E4642F2107400F064FB08B10024C4 -:10068000264600F0F9FF80B3032000F045F800246F -:10069000264635B11E4B9F4203D003F01BF90024C0 -:1006A0002646002003F0DAF81A4B1B691B0422D4FB -:1006B0000EB100F047F800F0A3FB00F08BFD00F056 -:1006C00095FE0546CCB100F091FE401BA04214D926 -:1006D00000F038F8F3E72E460024CDE70446012663 -:1006E000CAE706464FF47A74C6E7002CD1D04FF41F -:1006F0007A740126CDE70024DDE700F035FC4FF4E5 -:100700007A7002F0DFFDDDE7010007B0000008B0FD -:10071000263A09B000040240084B187003280CD890 -:10072000DFE800F008050208022000F0B5BD022055 -:1007300000F0A8BD024B00225A6070472823002019 -:100740002C23002010B500F097FF30B1204B03227E -:100750001A70204B00225A6010BD1F4B1F4A1C46C6 -:1007600019680131F8D004339342F9D162681C4B07 -:100770009A42F1D91B4B9B6803F1006303F5803368 -:100780009A42E9D203F07AF803F08CF8002000F0E6 -:100790003BFD0220FFF7C0FF134B1A6C00221A64C6 -:1007A000196E1A66196E596C5A64596E5A665B6EE8 -:1007B00072B64FF0E0232021C3F8084DD4E900328F -:1007C00081F311889D4683F308881047C4E700BF72 -:1007D000282300202C23002000000108200001080D -:1007E000FFFF00080023002000380240094A136878 -:1007F00049F2690099B21B0C00FB01331360064BF0 -:10080000186844F2506182B2000C01FB02001860CB -:1008100080B27047202300201C23002010B5002147 -:100820001022044600F054FD034B03CB20606160AE -:100830001868A06010BD00BF107AFF1F2DE9F041BD -:10084000ADF54E7D0DF134086CAC40F275120746E3 -:100850000D460EA80021C8F8001000F039FD4FF435 -:10086000C4720021204600F033FD00F0BFFD254B8F -:100870004FF47A72B0FBF2F0186093E8070001239E -:1008800084E807000DF5E9702382FFF7C7FF4FF4F6 -:10089000A4431D49238406A803F09AFB192384F876 -:1008A00032310DF2E32206AB0DF1300C1E4603CEC1 -:1008B000664510605160334602F10802F6D1337884 -:1008C000137041460122204600F094FD002303935B -:1008D000AB7E029305F11903019380B20123CDE9A8 -:1008E00004800093E97E05A3D3E90023384601F094 -:1008F00017FA0DF54E7DBDE8F08100BF9E6AC42158 -:10090000818A46EE34230020E03F00082DE9F043C1 -:10091000224DBBB000F06AFDAB6840F2ED22C31A75 -:10092000934232D906AFA8602B46282200213846D0 -:1009300001F0DEFB05F10E0000F0C2FC00260446CB -:100940005FFA80F905F10E08F3B2F100994501F163 -:10095000280107D908EB06030822384601F0C8FB36 -:100960000136F1E708230122CDE9023205340C4BB0 -:100970000193A4B230230093CDE9047405A3D3E915 -:100980000023297B074801F0CBF93BB0BDE8F08399 -:10099000AFF3008078F6339F93CACD8D7833002073 -:1009A000853300204C330020F0B58B8A013B9BB28D -:1009B000C92BC9B006460C4647D8274D2F7B27BB0D -:1009C00005F10C03009308223B463946204601F00E -:1009D00053FA7B1CFAB2D9001F46A38A013B9A4204 -:1009E00005DA0E322A44009200230822EEE70023A3 -:1009F0000022C5E900230023AB6085F8D730C5F895 -:100A0000D8302B7B0BB9E37E2B738122002106ADFE -:100A100027A800F05DFC0122294627A800F0B8FDB8 -:100A200000230393A37E029304F1190380B2019380 -:100A30002823CDE90450E17E0093304604A3D3E996 -:100A4000002301F06DF9FFF761FF49B0F0BD00BF71 -:100A500026417272DF25D7B77833002070B50D4676 -:100A600014461E4601F0F2F850B9022E10D1012CA6 -:100A70000ED112A3D3E90023C5E90023012007E02A -:100A8000282C10D005D8012C09D0052C0FD000201F -:100A900070BD302CFBD10BA3D3E90023ECE70BA3F3 -:100AA000D3E90023E8E70BA3D3E90023E4E70BA392 -:100AB000D3E90023E0E700BFAFF30080401DA12091 -:100AC00026812A0B78F6339F93CACD8D9E6AC42166 -:100AD000818A46EE26417272DF25D7B7F017304A79 -:100AE00039059E562DE9F04F8DB002AF80460D4678 -:100AF00001F0ACF8044600285CD12B7E022B1BD100 -:100B0000EB8A012B18D100F071FC0646FFF76EFE50 -:100B100003464FF4C870DFF81C92B3FBF0F206F501 -:100B2000167602FB103316FA83F3C9F80030EB7E19 -:100B300033B97B4B00221A702C37BD46BDE8F08FCD -:100B4000AB8AE6B2013BB34204F101040CD907F1D0 -:100B500008031E44E10000960023082201F0F8017A -:100B6000284601F089F9EBE707F11800FFF756FE78 -:100B7000324607F1180107F1080003F0F7F90028E1 -:100B8000D7D10F2E08D8664B1E70D9F80030A3F5C8 -:100B90001673C9F80030CFE7FB1DF87101460093CA -:100BA00007220346284601F067F9F979404601F02B -:100BB00045F8C1E7EB8A282B26D010D8012B1ED090 -:100BC000052BB9D1BFF34F8F5649574BCA6802F472 -:100BD000E0621343CB60BFF34F8F00BFFDE7302BC4 -:100BE000AAD16B7E514C0133627BDBB29342E94662 -:100BF00003D1EA7E237B9A420BD0CD469CE729465F -:100C00004046FFF71BFE97E729464046FFF7CCFE1C -:100C100092E74FF0000807F11803A7F81880102298 -:100C2000009341460123284601F026F9AE8A023E90 -:100C3000B6B2F31C9B109B000733DB08A9EBC30380 -:100C40009D460DF1080A1FFA88F34FEAC8019E423B -:100C500001F110010AD90AEB0803009308220023CE -:100C6000284601F009F908F10108ECE794F8D700EB -:100C700000F0D4FAD4F8D810054619B994F8D70082 -:100C800000F0DCFAD4F8D83033449D4205D294F811 -:100C9000D7000021013000F0D1FA4FEA960B4FF057 -:100CA00000081FFA88F18B45D4E9003209D90AEB14 -:100CB000880103EB8800012200F012FB08F1010813 -:100CC000EFE7F31842F10002C4E90032D4F8D8305B -:100CD00094F8D70006EB0308C4F8D88000F09EFA19 -:100CE000804509D394F8D730D4F8D8000133401B9D -:100CF00084F8D730C4F8D800FF2E0D4D09D8002352 -:100D0000237300F0AFFA00F0B7FC288108B9FFF7B1 -:100D100019FD23689B0A01332B810023A3606CE734 -:100D20004533002000ED00E00400FA057833002090 -:100D30003423002048330020014B1870704700BF57 -:100D40004023002030B54FF00054244B22689A42D3 -:100D500085B007D002F0D0FD0446A8B90024204693 -:100D600005B030BD1E4B627D1A701E48237D037393 -:100D70001D49C9220E3000F099FA2046E0220021D8 -:100D800000F0A6FA0124EAE7184A194D136C43F063 -:100D900000731364AA6D174B9A42DFD12B6E013B8F -:100DA0007E2BDBD8144A07CA01AB83E8070018463C -:100DB000032100F02FFC6B6D83424FF00003CDD177 -:100DC0002A6D8A4201BFAB65054B2A6E1A7003BFBC -:100DD0000A4BEA6D1A601C46C1E700BF9AAD44C5D4 -:100DE0004023002078330020160000200038024005 -:100DF000006600405041A0B0586600401823002013 -:100E00002DE9FF474C4C00F037FC022363710023AF -:100E100002934A4B2081D3F800C0BCF57A7F12D3ED -:100E2000474B484FB7FBFCF69C458CBF0A23112368 -:100E3000581EB6FBF3F503FB1562C1B2002A3ED083 -:100E400002280346F4D89DF80B303F493F485A1E0C -:100E50009DF80A30013B1B0443EA0253BDF8082009 -:100E6000013A13434B6001F0CFFE00230193384B4E -:100E7000384900933848394B4FF4805200F0B8FE9F -:100E8000374B197811B1344800F0D8FE00F0AEFAB3 -:100E90000546FFF7ABFC4FF4C873B0FBF3F202FB5F -:100EA000130305F5167010FA83F02E4B186002F04C -:100EB00019FD08B10F23238104B0BDE8F0876B1E34 -:100EC000B3F5806FBFD2C1EBC10E0EF103034FEA41 -:100ED000E309C3F3C703A1EB030809F1010A4FF4C7 -:100EE0007A705FFA88F609FB00005AFA88F8B0FBBE -:100EF000F8F0B0F5617F08D90EF1FF33C3F3C703F3 -:100F0000C91ACEB2591E0F2914D8721E072A8CBFD7 -:100F100000220122991901FB0551B7FBF1F7BC45ED -:100F200091D1002A8FD0ADF808508DF80A308DF895 -:100F30000B6088E71346EDE73423002018230020D8 -:100F40003F420F0040787D011023002090340020A4 -:100F50005D0A0008442300204C330020E50A000805 -:100F600040230020483300202DE9F04F91A7D7E916 -:100F700000670FF24829D9E90089874D93B0DFF85F -:100F800044B2864C284600F02FFF0DF1300A07903E -:100F900070B310220021504600F09AF9079B197B8C -:100FA0004FF0000261F303028DF830205868996811 -:100FB0000EAA03C21B680D9A63F31C029DF8303021 -:100FC0000D9243F020038DF830300023524619462D -:100FD000584601F029FE079028B9284600F008FF7E -:100FE000079B2370CEE72378072B3CD8013323706F -:100FF00018220021504600F06BF9DFF8C8B1684CA8 -:10100000002319465246584601F036FE014670BB91 -:10101000102208A800F05CF9636983F480636361BF -:1010200000F0E6F90B4612A9024611E903000DF1A2 -:10103000240C8CE803009DF83410C1F303008906EA -:101040004CBF0E99BDF838C08DF82C0046BFC1F3D7 -:101050001C0C4CF00041CCF30A010891284608A969 -:1010600001F08EF8CCE7284600F0C2FEC0E7284623 -:1010700000F0ECFD0446002848D1DFF84CB100F048 -:10108000B5F9DBF80030984240D300F0AFF9079093 -:10109000FFF7ACFB079A8DF8204003464FF4C87069 -:1010A00002F51672B3FBF0F101FB103312FA83F371 -:1010B000CBF80030DFF814B19BF8001011B9012310 -:1010C0008DF8203050460791FFF7A8FB0799C1F132 -:1010D0001004E4B2062C28BF0624224651440DF128 -:1010E000210000F0E3F808AB0393182302930134C6 -:1010F0002C4B0193E4B20123009304943B46324607 -:10110000284600F0A5FD00238BF8003000F06EF9B2 -:10111000254A264C1368C31AB3F57A7F30D3106082 -:1011200000F066F902460B46284600F06BFE2846A2 -:1011300000F08CFD20B3237BDFF894B0002B14BFAC -:10114000032302238BF8053000F050F94FF47A7333 -:101150000122B0FBF3F05146CBF80000584600F0F6 -:10116000EFF918230293124B019380B240F255130A -:10117000CDE903A0009342464B46284600F068FDA7 -:10118000237B2BB1FFF7C2FB237B002B7FF4F7AE51 -:1011900013B0BDE8F08F00BF4C3300205D34002059 -:1011A00000000240443300205834002078330020EF -:1011B0005C340020401DA12026812A0BF1C6A7C166 -:1011C000D068080F903400204833002045330020B9 -:1011D0003423002070B502F0D7F9094E094D308054 -:1011E000002428683388834208D902F0C7F92B68A5 -:1011F00004440133B4F5803F2B60F2D370BD00BFCF -:101200008C3400206034002002F082BA00F10060CB -:10121000920000F5803002F005BA0000054B1A6814 -:10122000054B1B889B1A834202D9104402F0A6B9D1 -:1012300000207047603400208C34002038B5084D01 -:10124000044629B128682044BDE8384002F0B6B908 -:101250002868204402F09AF90028F3D038BD00BF76 -:1012600060340020064991F8243033B10023086A25 -:1012700081F824300822FFF7C9BF0120704700BF62 -:1012800064340020022802BF024B4FF080629A6152 -:10129000704700BF00000240022802BF024B4FF41B -:1012A00080629A61704700BF0000024010B50023C1 -:1012B000934203D0CC5CC4540133F9E710BD000065 -:1012C00003460246D01A12F9011B0029FAD17047D1 -:1012D00002440346934202D003F8011BFAE7704729 -:1012E0002DE9F8431F4D144695F8242007468846FB -:1012F00052BBDFF870909CB395F824302BB92022B4 -:10130000FF2148462F62FFF7E3FF95F82400C0F164 -:101310000802A24228BF2246D6B24146920005EBFF -:101320008000FFF7C3FF95F82430A41B1E44F6B2DB -:10133000082E17449044E4B285F82460DBD1FFF70F -:1013400091FF0028D7D108E02B6A03EB8203834288 -:10135000CFD0FFF787FF0028CBD10020BDE8F8836E -:101360000120FBE76434002000B59BB0EFF3098156 -:1013700068226846FFF79AFFEFF30583044B9A6BE8 -:10138000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE71B -:1013900000ED00E000B59BB0EFF3098168226846DC -:1013A000FFF784FFEFF30583044B9A6B9A6A9A6AFE -:1013B0009A6A9A6A9A6A9B6AFEE700BF00ED00E0AB -:1013C00000B59BB0EFF3098168226846FFF76EFF16 -:1013D000EFF30583034B5A6B9A6A9A6A9A6A9A6A80 -:1013E0009B6AFEE700ED00E0FEE7000002F0CAB9EC -:1013F00002F0A2B92DE9F0470D46044600219046BF -:10140000284640F27912FFF763FF2346202200218D -:10141000284600F06DFE231D02222021284600F000 -:1014200067FE631D03222221284600F061FEA31DF2 -:1014300003222521284600F05BFE04F10803102258 -:101440002821284600F054FE04F110030822382118 -:10145000284600F04DFE04F11103082240212846E1 -:1014600000F046FE04F1120308224821284600F04D -:101470003FFE04F1140320225021284600F038FEDC -:1014800004F1180340227021284600F031FE04F1D7 -:1014900020030822B021284600F02AFE04F121038F -:1014A0000822B821284600F023FE04F12207C026B6 -:1014B0003B46314608222846083600F019FEB6F5AC -:1014C000A07F07F10107F3D104F13203082231466E -:1014D000284600F00DFE002704F1330A94F832305C -:1014E0004FEAC7099F4209F5A47615D3B8F1000F5A -:1014F00008D1314604F599730722284600F0F8FD1B -:1015000009F24F16274694F832213B1B93420CD325 -:10151000F01DC008BDE8F0870AEB0703082231463A -:10152000284600F0E5FD0137D8E707F233133146CE -:101530000822284600F0DCFD08360137E3E700000A -:1015400013B504460846002101602346C0F8031085 -:101550002022019000F0CCFD0198231D02222021C1 -:1015600000F0C6FD0198631D0322222100F0C0FD9A -:101570000198A31D0322252100F0BAFD019804F172 -:1015800008031022282100F0B3FD072002B010BD8F -:10159000F8B50E4605461446002181223046FFF775 -:1015A00097FE2B4608220021304600F0A1FD7CB9B1 -:1015B0006B1C07220821304600F09AFD0F240123FE -:1015C0006A785F1C013B934204D3E01DC008F8BD5C -:1015D0000824F4E7EB1921460822304600F088FD84 -:1015E00008343B46ECE7000030B5094D0A4491420F -:1015F0000DD011F8013B5840082340F30004013B93 -:101600002C4013F0FF0384EA5000F6D1EFE730BD21 -:101610002083B8EDF7B54FF0FF33DFF854C0DFF8A3 -:1016200054E000EB81011A4688421CD050F8044B6C -:10163000019401AF042417F8015B82EA05620825D2 -:10164000DB18164605F1FF355241002EBCBF83EA78 -:101650000C0382EA0E0215F0FF05F1D1013C14F0F3 -:10166000FF04E8D1E0E7D843D14303B0F0BD00BFA9 -:101670009336EAA9EBE1F04273B5364A1068516837 -:101680006B4603C36A4634493448082302F07EFCA3 -:10169000044670B9324A106851686B4603C36A4603 -:1016A00030492E48082302F071FC044620BB0A2072 -:1016B00020E00369B3F5E02FECD8428B522AE9D140 -:1016C000294A024402F110018B42E3D3103B234923 -:1016D00000209D1AFFF788FF2A46064604F11801EC -:1016E0000020FFF781FFA3689E42D3D1E3689842B0 -:1016F000D0D1002002B070BD0369B3F5E02F20D82F -:10170000B0F86620522A1ED1174A024402F15C0149 -:101710008B421AD35C3B114900209D1AFFF764FFEE -:101720002A46064604F164010020FFF75DFFA26827 -:10173000964203460BD1E068834214BF0D2000207F -:10174000D8E70B20D6E70C20D4E71020D2E70D20F5 -:10175000D0E700BFFC3F0008DCFF060000000108E6 -:101760000540000890FF06000800FFF72DE9F04152 -:10177000C56915B9C161BDE8F0814B6823F06047C8 -:10178000C3F38A464FEAD37EC3F3807816EA230672 -:1017900038BF3E46AC462B465A68BEEBD27F22F09D -:1017A00060440AD0002A18DAA40CB44217D19D4232 -:1017B0000FD10D60DEE71346EEE7A74207D102F036 -:1017C0008044C2F3807242450BD054B1EFE708D297 -:1017D000EDE7CCF800100B60CDE7B44201D0B44285 -:1017E000E5D81A689C46002AE5D11960C3E70000D5 -:1017F0002DE9F047089D01F007044FEAD50822447F -:1018000005F0070500EBD1004FF47F49944201D168 -:10181000BDE8F08704F0070705F0070A57453E4684 -:1018200038BF5646C6F10806111B8E4228BF0E4629 -:10183000E10808EBD50E415C13F80EC0B94029FA57 -:1018400006F721FA0AF1FFB28CEA010147FA0AF71A -:1018500039408CEA010C03F80EC034443544D5E716 -:1018600080EA0120082341F2210201B24000002950 -:1018700080B203F1FF33B8BF504013F0FF03F4D13F -:101880007047000038B50C468D18A54200D138BD10 -:1018900014F8011BFFF7E4FFF7E7000002684AB104 -:1018A00013680360C388018901339BB29942C380E6 -:1018B00038BF03811046704770B588B020220446B7 -:1018C0000D4668460021FFF703FD20460495FFF70B -:1018D000E5FF024658B16B46054608AE1C4603CCF0 -:1018E000B44228606960234605F10805F6D1104628 -:1018F00008B070BD082817D909280CD00A280CD0C8 -:101900000B280CD00C280CD00D280CD00E2814BF9E -:101910004020302070470C20704710207047142062 -:10192000704718207047202070470000082817D9FA -:101930000C280CD910280CD914280CD918280CD92B -:1019400020280CD930288CBF0F200E20704709208A -:1019500070470A2070470B2070470C2070470D20FD -:101960007047000010B54B6823B9CA8A63F30902B7 -:10197000CA8210BDC4681A681C60C360438A013BF8 -:1019800043824A60EFE700002DE9F84F1D46CB8AFD -:101990000F46C3F309010529814692460B4630D014 -:1019A0000020AAB207F11A049EB2042E1FFA80F892 -:1019B0000FD8904503F1010306D3FB8A0A4462F372 -:1019C0000903FB8201201AE01AF80060E654013096 -:1019D000EAE79045F1D2A1F1050B1C237C68BBFB23 -:1019E000F3F203FB12BB1FFA8BF6002C45D14846DD -:1019F000FFF754FF044638B978606FF00200BDE885 -:101A0000F88F4FF00008E6E7002606607860ADB278 -:101A10004FF0000B454510D90AEB0803221D13F8BF -:101A2000011B9155B1B208F101081B291FFA88F872 -:101A30002BD0454506F10106F1D8FB8AC3F3090214 -:101A4000154465F30903BCE7013292B21C462368D2 -:101A5000002BF9D16B1F0B441C21B3FBF1F30133B5 -:101A60009BB29A42D3D2BBF1000FD0D14846FFF7C8 -:101A700015FF20B9C4F800B0BFE70122E7E7C0F8BE -:101A800000B05E4620600446C1E74545D5D94846CA -:101A9000FFF704FF08B92060AFE7C0F800B00026E8 -:101AA00020600446B6E700002DE9F04F2DED028BD3 -:101AB00083B0CDE90013BDF83C5007469146002A9B -:101AC00000F092802DB10E9B002B00F08D80072D31 -:101AD00032D807F10C00FFF7E1FE044638B96FF089 -:101AE0000204204603B0BDEC028BBDE8F08F142247 -:101AF0000021FFF7EDFB0E992A4604F10800FFF7DD -:101B0000D5FB681CC0B2FFF711FFFFF7F3FE20748E -:101B100099F80030013814FA80F003F01F0363F0E5 -:101B20003F030372009B43F0004161603846214649 -:101B3000FFF71CFE0124D4E700F10C034FF000086E -:101B400008EE103A4FF0800A4646444618EE100A56 -:101B5000FFF7A4FE83460028C1D014220021FFF71E -:101B6000B7FBC6BB019BABF8083002200E9B00F10F -:101B7000080299195BFA82F20130C0B2082801D03C -:101B8000AE422AD3FFF7D2FEFFF7B4FE99F8002049 -:101B9000009B411E02F01F0242EA4812AE4208BFFB -:101BA0004FF0400A5BFA81F14AEA020A43F0004230 -:101BB00081F808A08BF81000CBF80420594638466D -:101BC000FFF7D4FD0134AE4224B288F001084FF093 -:101BD000000ABBD185E70020C8E711F801CB02F865 -:101BE00001CB0136B6B2C7E76FF0010479E7000018 -:101BF000F8B515460E462822002104461F46FFF779 -:101C000067FB069B6360B5F5001F079BA76034BFA9 -:101C10006A094FF6FF72236204F10C0097B20023A9 -:101C20009A4205D80023036027826382A382F8BD0D -:101C30000660013330462036F2E7000003781BB916 -:101C40004BB2002BC8BF017070470000007870478E -:101C50002DE9F74FDDF83C90BDF830500D9E9DF812 -:101C60003840BDF84070804692469B46B9F1000F5F -:101C700001D1002F51D11F2C4FD898F80000B0B9D6 -:101C8000072F47D835F0030347D13A4649464FF668 -:101C9000FF70FFF7F7FD20F001002D02400445EA38 -:101CA0000464400C44EA40244FF6FF7321E040EA0C -:101CB0000520072F40EA0464F6D900254FF6FF738C -:101CC000C5F12000A5F120022AFA05F10BFA00F077 -:101CD00001432BFA02F211431846C9B2FFF7C0FDC7 -:101CE0000835402D0346EBD13A464946FFF7CAFD79 -:101CF0000346CDE90097324621464046FFF7D4FE21 -:101D000033780133DBB21F2B88BF0023337003B05D -:101D1000BDE8F08F6FF00300F9E76FF00100F6E720 -:101D20002DE9F04F85B09246DDF848800F9D9DF873 -:101D300040209DF84490BDF84C7006469B46B8F193 -:101D4000000F01D1002F48D11F2A46D83378002B2D -:101D500046D00C0244EA02649DF8381044EAC934C3 -:101D600044EA01441C43072F44F0800432D9002385 -:101D70004FF6FF72C3F1200CA3F120002AFA03F101 -:101D80000BFA0CFC41EA0C012BFA00F00143C9B23A -:101D900010460393FFF764FD039B0833402B024674 -:101DA000E8D13A464146FFF76DFD0346CDE900878D -:101DB0002A4621463046FFF777FEB9F1010F06D1DA -:101DC0002B780133DBB21F2B88BF00232B7005B0AB -:101DD000BDE8F08F4FF6FF73E8E76FF00100F6E71C -:101DE0006FF00300F3E70000C06900B104307047F2 -:101DF000C3691A68C261C2681A60C360438A013B42 -:101E0000438270472DE9F041D0F81880194E1446EE -:101E10001D464146002709B9BDE8F081D1E90223FA -:101E2000A21A65EB0303964277EB03031ED2836984 -:101E30008B420DD1FFF796FD83691B688361C368F0 -:101E40000B60438AC1608169013B43828846E2E7B7 -:101E5000FFF788FD0B68C8F80030C3680B60438A41 -:101E6000C160013B4382D8F80010D4E78846096876 -:101E7000D1E700BF80841E002DE9F04F8BB00D46E6 -:101E8000DDF8509014469B468046002800F01981EA -:101E9000B9F1000F00F01581531E3F2B00F21181A4 -:101EA000012A03D1BBF1000F40F00B810023CDE9E3 -:101EB0000833B8F81430B5EBC30F4FEAC30703D3A8 -:101EC00000200BB0BDE8F08F2B199F42D8F80C30E2 -:101ED0003ABF7F1BFFB227461BB9D8F81030002B42 -:101EE0007AD0272D4ED8C5F12806B7424FF000030F -:101EF0002CBFF6B23E4600932946D8F8080008AB3E -:101F00003246FFF775FCA7EB060A35445FFA8AFAFA -:101F1000B8F8143003F10053053BDB000493D8F804 -:101F20000C3003932821039B13B1BAF1000F2CD17D -:101F3000D8F8100040B1BAF1000F05D0009608ABF8 -:101F40005246691AFFF754FC38B2002FB8D0660722 -:101F50000AD00AAB03EBD401624211F8083C02F04C -:101F60000702134101F8083C082C3CD9102C40F220 -:101F7000B580202C40F2B780BBF1000F00F09C80B0 -:101F8000082334E0BA460026C2E7049BE02B28BFB2 -:101F9000E02306930B44AB42059314D95A1B0398D4 -:101FA0000096924534BF5246D2B2691A08AB04304B -:101FB0000792FFF71DFC079A1644AAEB020A154484 -:101FC000F6B25FFA8AFA049B069A05999B1A049363 -:101FD000039B1B680393A6E70093D8F8080008AB9F -:101FE0003A462946AEE7BBF1000F13D00123B4EB0C -:101FF000C30F6CD0082C12D89DF82030621E23FA33 -:1020000002F2D50706D54FF0FF3202FA04F423435B -:102010008DF820309DF8203089F8003051E7102CE1 -:1020200012D8BDF82030621E23FA02F2D10706D57D -:102030004FF0FF3202FA04F42343ADF82030BDF82C -:102040002030A9F800303CE7202C0FD80899631EF7 -:1020500021FA03F3DA0705D54FF0FF3202FA04F450 -:102060000C430894089BC9F800302AE7402C2BD079 -:10207000DDE90865611EC4F12102A4F1210326FAFD -:1020800001F105FA02F225FA03F311431943CB07D4 -:1020900012D50122A4F12003C4F1200102FA03F3B6 -:1020A00022FA01F1A240524243EA010363EB4303E7 -:1020B00032432B43CDE90823DDE90823C9E9002396 -:1020C000FFE66FF00100FCE66FF00800F9E6082C6F -:1020D000A0D9102CB3D9202CEED8C3E7BBF1000F48 -:1020E000ADD0022383E7BBF1000FBBD004237EE712 -:1020F00030B5012A144638BF0124402C85B028BFD2 -:1021000040240025012ACDE9025518D81B788DF806 -:10211000083063070AD004AB03EBD405624215F81C -:10212000083C02F00702934005F8083C0091034682 -:102130002246002102A8FFF75BFB05B030BD082A4C -:10214000E4D9102A03D81B88ADF80830E1E7202A2B -:102150008DBFD3E900231B680293CDE90223D8E7A2 -:1021600010B5CB681BB98B600B618B8210BDC46846 -:102170001A681C60C360438A013B4382CA60F0E76F -:102180002DE9F04F95B0CDE904230B6804460D46C8 -:102190001806C3F3C01147BFC3F3C03BC3F3062601 -:1021A0004FF0020B0E46002B80F2018213F0C04963 -:1021B00040F0FD812A7B002A00F0F981BBF1020F7B -:1021C00003D02078B04240F0F581C3F3046008905A -:1021D00003F07F00069069B3C3F3074A2A44069BC5 -:1021E00092F80380760646EA0B4646EA83460022CA -:1021F0000023CDE90A235FEAD81346EA0A060393CF -:102200006CD0069B009367685B4652460AA920463D -:10221000B847002800F0D181A76997B9314604F189 -:102220000C00FFF749FB0746D8B96FF0020015B064 -:10223000BDE8F08FC3F30F2A590608BF0AF0030A5E -:10224000CCE73B699E420DD03F68002FF9D1314663 -:1022500004F10C00FFF730FB07460028E5D0A36926 -:102260003B60A761FE7D08F01F03C6F38406F01AE9 -:102270001FFA80FC0028B8BF0CF120000793A3EBE5 -:1022800006031FFA83FCD7E90221B8BF00B2002B76 -:102290000993BEBF0CF120031BB2099352EA01035C -:1022A00033D0049EDFF8D0C2B21A059E66EB01015E -:1022B0000026944576EB010327D395F80DE097F8B7 -:1022C0001AC0E64514D1039B002B76D001281CDCF4 -:1022D000A848904276EB010314D336E0A76917B9FA -:1022E0006FF00C00A3E73B699E42BBD03F68F6E766 -:1022F000A048904276EB010301D3002097E7039BAF -:10230000002BFAD0099B0F2B18DCFA7D4FEA8803CB -:1023100002F0030203F07C031343FB7539462046A9 -:10232000FFF720FB6B7BBB76039B3BB9FB7DC3F3C5 -:102330008402013262F38603FB75D1E76A7BBB7EC0 -:102340009A42DAD1039B002B37D04FEA9813022B25 -:1023500033D0049BBB60059BFB60142200210FA8B7 -:10236000FEF7B6FF049B0C93059B0D932B1D0E935C -:102370002B7BADF846A0013BDBB2ADF84430079BA8 -:102380008DF84930089B8DF84A30069B8DF84B300C -:1023900094F824308DF848B083F001038DF84C3068 -:1023A0000CA9A36820469847FB7DC3F3840301333F -:1023B00003F01F039B02FB829FE7FB7DC8F34012E3 -:1023C000B2EBD31F40F0FC80079AC3F3840393421F -:1023D00040F0F98003992B7B4FEA981200294ED0E8 -:1023E000D2075ED4032B40F2F180049BBB60059BB7 -:1023F000FB602B7BAE1D033BDBB23246394604F15A -:102400000C00FFF7C1FA00280DDA20463946FFF725 -:10241000A9FAFB7DC3F38403013303F01F039B027E -:10242000FB82032003E7DDE90A84AB883B834FF698 -:10243000FF73C9F12000A9F1200228FA09F104FA7A -:1024400000F0014324FA02F211431846C9B2FFF723 -:1024500007FA09F10809B9F1400F0346E9D1B8823A -:102460002A7B033AD2B23146FFF70CFAFB7DB882E1 -:10247000DA43C2F3C01262F3C713FB753DE782B9BA -:102480002E1D013BDBB23246394604F10C00FFF74A -:102490007BFA0028B9DB2A7BB88A013AD2B23146EE -:1024A000E2E7F98AC1F30901013B0429DAB25BD8FA -:1024B000281D002307F11B069A4208D910F801CB0A -:1024C00006F801C0013101330529DBB2F4D10499CA -:1024D0000C9105990D91934207F11B010E9138BFA4 -:1024E000043379680F9134BF55FA83F300231093B6 -:1024F000FB8AADF846A0C3F309031A44079B8DF885 -:102500004930089B8DF84A30069B8DF84B3094F883 -:102510002430ADF8442083F001038DF84C300023C3 -:102520008DF848B07B602A7BB88A013A291DFFF7F5 -:10253000A9F93B8BB882834203D1A3680CA920463A -:10254000984720460CA9FFF70BFEFB7DB88AC3F322 -:102550008403013303F01F039B02FB823B8B9842F1 -:1025600014BF1120002062E67B68002BAFD005204D -:1025700006E000BF40420F0080841E001C3033463E -:102580001E68002EFAD1091A081D2E1D184401EBF1 -:10259000090CBCF11B0F5FFA89F398D89A4296D9BF -:1025A00016F8013B00F8013B09F10109EFE76FF074 -:1025B00009003CE66FF00A0039E66FF00B0036E6E2 -:1025C0006FF00D0033E66FF00E0030E66FF00F0095 -:1025D0002DE600BF404BF0B51C6C404E44F000743B -:1025E0001C641D6E45F000751D661B6E3C4B9B6A9E -:1025F000D3F80052354045F00105C3F80052D3F836 -:102600000042344044EA002040F00100C3F80002D8 -:10261000002952D00020C3F81C020546C3F804026A -:10262000C3F80C02C3F8140203EBC00401301C28E9 -:10263000C4F84052C4F84452F6D100254FF0010CC2 -:1026400096781488F70748BFD3F804720CFA04F0A0 -:1026500044BF0743C3F80472B70742BFD3F80C72F4 -:102660000743C3F80C72760742BFD3F814620643DF -:10267000C3F8146203EBC4045668C4F84062966859 -:10268000C4F84462D3F81C4201352043A942C3F880 -:102690001C0202F10C02D3D1D3F8002222F0010275 -:1026A000C3F800220C4B1A6C22F000721A641A6EE6 -:1026B00022F000721A661B6EF0BD0122C3F84012B0 -:1026C000C3F84412C3F80412C3F81412C3F80C225E -:1026D000C3F81C22E0E700BF003802400000FFFF03 -:1026E00090340020184A916A08B58B688B6013F00B -:1026F000010104D013F00C0F18BF4FF48031D8053E -:1027000006D513F4406F14BF41F4003141F00201CB -:10271000D80306D513F4402F14BF41F4802141F0B3 -:102720000401D3690BB108489847202383F311882B -:102730000648002100F0EEFD002383F31188BDE878 -:10274000084001F017B900BF9034002098340020F1 -:1027500038B5124CA36ADD68AA0712D05A6922F074 -:1027600002025A61A36913B1012120469847202330 -:1027700083F311880A48002100F0CCFD002383F385 -:102780001188EB0606D5A36A1021D960236A0BB124 -:1027900002489847BDE8384001F0ECB8903400207A -:1027A000A034002038B5124CA36A1D69AA0712D0C4 -:1027B0005A6922F010025A61A36913B1022120461E -:1027C0009847202383F311880A48002100F0A2FDD6 -:1027D000002383F31188EB0606D5A36A1021196143 -:1027E000236A0BB102489847BDE8384001F0C2B8EF -:1027F00090340020A034002038B50F4CA36A5D68E7 -:102800005D602A070AD5042222701A6822F00202AB -:102810001A60636A13B10021204698476B0706D5FA -:10282000A36A9969236A13B1034809049847BDE86C -:10283000384001F09FB800BF9034002010B50E4C16 -:10284000204600F0CFF90D4BA3620B21132000F0BE -:10285000B1F90B21142000F0ADF90B21152000F087 -:10286000A9F90B21162000F0A5F90022BDE81040BF -:1028700011460E20FFF7AEBE9034002000640040E9 -:10288000114B984210B5044609D1104B1A6C42F016 -:1028900000721A641A6E42F000721A661B6EA36A06 -:1028A00001221A60A36A5A68D20707D56268516884 -:1028B0001268D9611A60064A5A6110BD01210820C8 -:1028C00000F01EFCEEE700BF90340020003802400C -:1028D0005B87010003291AD8DFE801F0020A0F1410 -:1028E000836A9B6813F0E05F14BF012000207047EB -:1028F000836A9868C0F380607047836A9868C0F301 -:10290000C0607047836A9868C0F300707047002009 -:102910007047000010B5032925D8DFE801F0022533 -:10292000292D836A9968C1F30161183103EB011302 -:10293000107884064CBF54689488C0F300114FEAA5 -:10294000410148BF41EAC40100F00F004CBF41F013 -:10295000040141EA4451586041F001019068D26895 -:102960009860DA60196010BD836A03F5C073DFE711 -:10297000836A03F5C873DBE7836A03F5D073D7E78F -:1029800001290AD002290FD081B9836ADA68920737 -:1029900001D1186903E001207047836AD86810F0FC -:1029A000030018BF01207047836AF2E700207047D8 -:1029B00010B539B9836AD96889071BD11B699C078F -:1029C00004D110BD012915D00229FAD1816AD1F8AC -:1029D000C031D1F8C441D1F8C8011061D1F8CC019F -:1029E0005061202008610869800717D1486940F0CC -:1029F000100012E0816AD1F8B031D1F8B441D1F8B9 -:102A0000B8011061D1F8BC0150612020C860C868CD -:102A1000800703D1486940F002004861C3F34000D9 -:102A2000C3F38001000140EA4111107920F0300029 -:102A30000143117189064BBF91681189DB085B0D59 -:102A40004CBF63F31C0163F30A01137948BF916023 -:102A500064F3030313714FEA14234FEA144458BF7D -:102A6000118113705480ACE7024AD36843F0C0036D -:102A7000D360704700440040044B5A6810439A6882 -:102A800058600AB1181D1047704700BFBC340020C1 -:102A90002DE9F0413C4ED6F85C52EF682B68DA0520 -:102AA0009CB20CD5202383F311884FF40070FFF7FC -:102AB000E3FF6FF480732B60002383F311882023DE -:102AC00083F31188DFF8C08014F02F0339D183F32A -:102AD0001188380613D5210611D5202383F31188D8 -:102AE0002A4800F001FA00284CDA0820FFF7C4FF5A -:102AF0004FF67F733B40EB60002383F311887A0627 -:102B000015D5630613D5202383F31188D6E9132343 -:102B10009A4209D1336C3BB127F040073F041020A3 -:102B20003F0CFFF7A9FFEF60002383F31188D6F86D -:102B30006422D3680BB110699847BDE8F04100F0FA -:102B400019BF230712D014F0080F0CBF00208020FB -:102B5000E10748BF40F02000A20748BF40F0400016 -:102B6000630748BF40F48070FFF786FFA4066B68D8 -:102B700005D596F860124046194000F057FA2C68C7 -:102B8000A4B2A1E76860B7E7BC340020F4340020A9 -:102B900010B5054C054A0021204600F025FA044BEB -:102BA000C4F85C3210BD00BFBC340020692A0008A4 -:102BB0000044004000F1604303F561430901C9B2DC -:102BC00083F80013012200F01F039A4043099B0081 -:102BD00003F1604303F56143C3F880211A60704735 -:102BE000FFF72CBE012300F10802C0E902220370A6 -:102BF00000F110020023C0E90422C0E90633C0E955 -:102C0000083343607047000010B52023044683F367 -:102C10001188022303704160FFF732FE0423237002 -:102C2000002383F3118810BD2DE9F0411F460446AF -:102C30000D461646202383F3118800F108082378F7 -:102C4000052B0DD029462046FFF744FE40B1204613 -:102C500032462946FFF75EFE002080F3118808E027 -:102C60003946404600F03AFB0028E8D0002383F3C1 -:102C70001188BDE8F08100002DE9F0411F460446AF -:102C80000D461646202383F3118800F1100823789F -:102C9000052B0DD029462046FFF772FE40B1204695 -:102CA00032462946FFF784FE002080F3118808E0B1 -:102CB0003946404600F012FB0028E8D0002383F399 -:102CC0001188BDE8F0810000F8B5154682680669F4 -:102CD000AA420B46816938BF8568761AB542044618 -:102CE0000BD218462A46FEF7E1FAA3692B44A361EA -:102CF000A3685B1BA3602846F8BD0CD91846324672 -:102D0000FEF7D4FAAF1BE1683A463044FEF7CEFA3C -:102D1000E3683B44EBE718462A46FEF7C7FAE36848 -:102D2000E5E7000083689342F7B51546044638BFCF -:102D30008568D0E90460361AB5420BD22A46FEF700 -:102D4000B5FA63692B446361A36828465B1BA360E3 -:102D500003B0F0BD0DD932460191FEF7A7FA0199F3 -:102D6000E068AF1B3A463144FEF7A0FAE3683B4403 -:102D7000E9E72A46FEF79AFAE368E4E710B50A4461 -:102D80000024C361029B8460C0E90000C0E9051112 -:102D9000C1600261036210BD08B5D0E905329342FB -:102DA00001D1826882B98268013282605A1C426114 -:102DB0001970D0E904329A4224BFC36843610021EC -:102DC00000F09CFA002008BD4FF0FF30FBE7000048 -:102DD00070B5202304460E4683F31188A568A5B17B -:102DE000A368A269013BA360531CA3611578226903 -:102DF000934224BFE368A361E3690BB1204698477F -:102E0000002383F31188284607E03146204600F06E -:102E100065FA0028E2DA85F3118870BD2DE9F74FD5 -:102E200004460E4617469846D0F81C904FF0200AEC -:102E30008AF311884FF0000B154665B12A463146DA -:102E40002046FFF741FF034660B94146204600F0A7 -:102E500045FA0028F1D0002383F31188781B03B0D2 -:102E6000BDE8F08FB9F1000F03D001902046C847AC -:102E7000019B8BF31188ED1A1E448AF31188DCE75D -:102E8000C0E90511C160C3611144009B8260C0E9C3 -:102E90000000016103627047F8B504460D4616460E -:102EA000202383F31188A768A7B1A368013BA3601F -:102EB00063695A1C62611D70D4E904329A4224BFCE -:102EC000E3686361E3690BB120469847002080F313 -:102ED000118807E03146204600F000FA0028E2DAC7 -:102EE00087F31188F8BD0000D0E905239A4210B598 -:102EF00001D182687AB98268013282605A1C82618B -:102F00001C7803699A4224BFC3688361002100F0E2 -:102F1000F5F9204610BD4FF0FF30FBE72DE9F74FE4 -:102F200004460E4617469846D0F81C904FF0200AEB -:102F30008AF311884FF0000B154665B12A463146D9 -:102F40002046FFF7EFFE034660B94146204600F0F9 -:102F5000C5F90028F1D0002383F31188781B03B052 -:102F6000BDE8F08FB9F1000F03D001902046C847AB -:102F7000019B8BF31188ED1A1E448AF31188DCE75C -:102F8000026843681143016003B1184770470000AD -:102F90001430FFF743BF00004FF0FF331430FFF74A -:102FA0003DBF00003830FFF7B9BF00004FF0FF33DE -:102FB0003830FFF7B3BF00001430FFF709BF00003F -:102FC0004FF0FF311430FFF703BF00003830FFF738 -:102FD00063BF00004FF0FF323830FFF75DBF0000E5 -:102FE00000207047FFF7D4BD37B515460E4A026082 -:102FF00000224260C0E902220122044602740B460C -:10300000009000F15C014FF480721430FFF7B6FEBF -:1030100000942B464FF4807204F5AE7104F1380031 -:10302000FFF72EFF03B030BD1040000838B5C3696C -:1030300004460D461BB904210844FFF7A1FF2946A9 -:1030400004F11400FFF7A8FE002806DA201D4FF453 -:103050008061BDE83840FFF793BF38BD024B0022C6 -:10306000C3E900339A6070472437002000230374BB -:103070008268054B1B6899689142FBD25A680360CD -:1030800042601060586070472437002008B5202344 -:1030900083F31188037C032B05D0042B0DD02BB9AF -:1030A00083F3118808BD436900221A604FF0FF3393 -:1030B0004361FFF7DBFF0023F2E7D0E90032136042 -:1030C0005A60F3E7002303748268054B1B68996814 -:1030D0009142FBD85A6803604260106058607047A4 -:1030E00024370020054B19690874186802681A60B3 -:1030F0005360186101230374FDF78ABA2437002056 -:1031000030B54B1C0B4D87B0044610D02B690A4AD2 -:1031100001A800F01BF92046FFF7E4FF049B13B160 -:1031200001A800F04FF92B69586907B030BDFFF7CF -:10313000D9FFF8E7243700208D30000838B50C4D52 -:1031400041612B6981689A689142044603D8BDE8C1 -:103150003840FFF78BBF1846FFF7B4FF01232C61FF -:10316000014623742046BDE83840FDF751BA00BF40 -:1031700024370020044B1A681B6990689B689842AA -:1031800094BF0020012070472437002010B5084C60 -:10319000236820691A6822605460012223611A742E -:1031A000FFF790FF01462069BDE81040FDF730BAF7 -:1031B0002437002008B5FFF7DDFF18B1BDE808404F -:1031C000FFF7E4BF08BD0000FFF7E0BFFEE7000027 -:1031D00010B50C4CFFF742FF00F0AAF80A49802214 -:1031E000204600F031F8012344F8180C037400F075 -:1031F0009DFB002383F3118862B60448BDE81040AC -:1032000000F042B84C370020384000084840000821 -:1032100000F012B9EFF3118020B9EFF305832022FB -:1032200082F311887047000010B530B9EFF30584C0 -:10323000C4F3080414B180F3118810BDFFF7BAFF7E -:1032400084F31188F9E7000082600222028270474D -:103250008368A3F17C0243F80C2C026943F83C2CF0 -:10326000426943F8382C074A43F81C2CC26843F8DB -:10327000102C022203F8082C002203F8072CA3F1DB -:10328000180070472906000810B5202383F3118821 -:10329000FFF7DEFF00210446FFF750FF002383F312 -:1032A0001188204610BD0000024B1B6958610F2099 -:1032B000FFF718BF24370020202383F31188FFF77E -:1032C000F3BF000008B50146202383F311880820CE -:1032D000FFF716FF002383F3118808BD49B1064BA1 -:1032E00042681B6918605A60136043600420FFF74E -:1032F00007BF4FF0FF307047243700200368984223 -:1033000006D01A680260506059611846FFF7AEBED9 -:103310007047000038B504460D462068844200D14D -:1033200038BD036823605C604561FFF79FFEF4E7EA -:10333000054B03F11402C3E905224FF0FF310022CF -:10334000C3E90712704700BF2437002070B51C4E38 -:10335000C0E9032305460C4600F06EFB334653F8E4 -:10336000142F9A420DD13062C5E901242A600A2C3B -:103370002CBF00190A30C6E90555BDE8704000F0C1 -:1033800049BB316A431AE31838BF1C469368A3420D -:1033900002D9081900F04CFB73699A6894420CD862 -:1033A0005A68AC602B606A6015609A685D60121B99 -:1033B0009A604FF0FF33F36170BD1B68A41AECE70D -:1033C0002437002038B51B4C636998420DD0D0E9F2 -:1033D000003213605A6000228168C2609A680A4411 -:1033E0009A604FF0FF33E36138BD2246036842F82C -:1033F000143F002193425A60C16003D1BDE83840B8 -:1034000000F010BB9A688168256A0A449A6000F04F -:1034100013FB63699A68411B8A42E5D9AB181D1AF0 -:10342000092D206A98BF01F10A02BDE83840104416 -:1034300000F0FEBA243700202DE9F041184C002797 -:1034400004F11406656900F0F7FA236AAA68C11A44 -:103450008A4215D813442362D5E9003213605A60BA -:103460006369D5F80C80EF60B34201D100F0DAFA5D -:1034700087F311882869C047202383F31188E1E787 -:103480006169B14209D013441B1ABDE8F0410A2B0F -:103490002CBFC0180A3000F0CBBABDE8F08100BFE5 -:1034A0002437002000207047FEE70000704700002E -:1034B0004FF0FF3070470000BFF34F8F024AD368D0 -:1034C000DB03FCD4704700BF003C024008B5094B49 -:1034D0001B7873B9FFF7F0FF074B1A69002ABFBFCB -:1034E000064A5A6002F188325A601A6822F48062F1 -:1034F0001A6008BDE0380020003C02402301674507 -:1035000008B50B4B1B7893B9FFF7D6FF094B1A6927 -:1035100042F000421A611A6842F480521A601A6836 -:1035200022F480521A601A6842F480621A6008BD60 -:10353000E0380020003C02400728F0B516D80C4CBB -:103540000C4923787BB90C4D0E4608234FF00062DE -:1035500055F8047B46F8042B013B13F0FF033A4473 -:10356000F6D10123237051F82000F0BD0020FCE7C4 -:1035700004390020E438002060400008014B53F873 -:10358000200070476040000808207047072810B5E9 -:10359000044601D9002010BDFFF7CEFF064B53F8BB -:1035A00024301844C21A0BB90120F4E71268013222 -:1035B000F0D1043BF6E700BF60400008072838B5AB -:1035C000044628D8FFF726FEFFF776FFFFF77EFFB9 -:1035D000124AF323D360E300DBB243F4007343F0F9 -:1035E00002031361136943F48033136105462046D7 -:1035F000FFF762FFFFF7A0FF094B53F8241000F01C -:103600003BF92846FFF77CFFFFF70EFE2046BDE89A -:103610003840FFF7BBBF002038BD00BF003C024070 -:103620006040000812F001032DE9F04105460E4606 -:1036300014464BD18118334A914261D8324B1B68F2 -:1036400013F001035CD0314FFFF7E4FDFFF73EFFBD -:10365000F323FB60FFF730FF314640F20128032CD3 -:1036600018D824F00104294E0C446D1A40F20118B8 -:10367000A142336905EB01072AD123F0010333612D -:10368000FFF73EFFFFF7D0FD0120BDE8F081043CCD -:103690000435E4E7AB07E4D13B6923F440733B61B5 -:1036A0003B6943EA08033B6151F8046B2E60BFF3AA -:1036B0004F8FFFF701FF2B689E42E8D03B6923F054 -:1036C00001033B61FFF71CFFFFF7AEFD0020DCE7C5 -:1036D00023F440733361336943EA080333610B8891 -:1036E0003B80BFF34F8FFFF7E7FE3F8831F8023B87 -:1036F000BFB2BB42BCD0336923F001033361E1E7C1 -:103700001846C2E70000080800380240003C0240AA -:10371000084908B50B7828B11BB9FFF7D7FE01237C -:103720000B7008BD002BFCD0BDE808400870FFF707 -:10373000E7BE00BFE038002070B582B0FFF76AFD39 -:103740000E4E054600F078F93268904237BF0C4AB9 -:103750000B49516814682EBFD1E900410131516015 -:103760000419034641F10001284601913360FFF737 -:103770005BFD0199204602B070BD00BF08390020F2 -:103780001039002070B582B0FFF744FD104E054699 -:1037900000F052F93268904237BF0E4A0D49516825 -:1037A00014682EBFD1E9004101315160041941F183 -:1037B00000010346284601913360FFF735FD01996A -:1037C0004FF47A7200232046FCF70AFD02B070BD68 -:1037D000083900201039002010B50244064BD2B23F -:1037E000904200D110BD441C00B253F8200041F8B3 -:1037F000040BE0B2F4E700BF502800400F4B30B597 -:103800001C6F240407D41C6F44F400741C671C6FE5 -:1038100044F400441C670A4C236843F4807323601B -:103820000244084BD2B2904200D130BD441C00B2D9 -:1038300051F8045B43F82050E0B2F4E7003802404E -:10384000007000405028004007B5012201A9002067 -:10385000FFF7C2FF019803B05DF804FB13B50446FF -:10386000FFF7F2FFA04205D0012201A90020019438 -:10387000FFF7C4FF02B010BD70470000074B45F2D0 -:1038800055521A6002225A6040F6FF729A604CF656 -:10389000CC421A60024B01221A707047003000407F -:1038A0001C390020034B1B781BB1034B4AF6AA229C -:1038B0001A6070471C39002000300040034B1A6822 -:1038C0001AB9034AD2F874281A60704718390020D0 -:1038D00000300240024B4FF08072C3F874287047EA -:1038E0000030024008B5FFF7E9FF024B1868C0F34B -:1038F000407008BD1839002008B5FFF7DFFF024B04 -:103900001868C0F3007008BD18390020EFF3098370 -:1039100005494A6B22F001024A63683383F3098840 -:10392000002383F31188704700EF00E0202080F32C -:10393000118862B60C4B0D4AD96821F4E061090484 -:10394000090C0A43DA60D3F8FC20094942F080727E -:10395000C3F8FC200A6842F001020A601022DA77FC -:1039600083F82200704700BF00ED00E00003FA0575 -:10397000001000E010B5202383F311880E4B5B6824 -:1039800013F4006314D0F1EE103AEFF30984683CAD -:103990004FF08073E361094BDB6B236684F3098886 -:1039A000FFF7E8FB10B1064BA36110BD054BFBE729 -:1039B00083F31188F9E700BF00ED00E000EF00E0BD -:1039C0003B0600083E06000870470000FEE70000C6 -:1039D0000A4B0B480B4A90420BD30B4BDA1C121AC2 -:1039E000C11E22F003028B4238BF00220021FDF7E6 -:1039F0006FBC53F8041B40F8041BECE78C41000833 -:103A0000A0390020A0390020A03900207047000014 -:103A100000F080B84FF08043002258631A61022200 -:103A2000DA6070474FF080430022DA607047000090 -:103A30004FF08043586370474FF08043586A704797 -:103A40004B6843608B688360CB68C3600B694361DC -:103A50004B6903628B6943620B6803607047000027 -:103A600008B5234B23481A6942F0FF021A611A690C -:103A700022F0FF021A611A691A6B42F0FF021A6300 -:103A80001A6D42F0FF021A651B4A1B6D1146FFF7C3 -:103A9000D7FF02F11C0100F58060FFF7D1FF02F1B2 -:103AA000380100F58060FFF7CBFF02F1540100F50B -:103AB0008060FFF7C5FF02F1700100F58060FFF73D -:103AC000BFFF02F18C0100F58060FFF7B9FF02F142 -:103AD000A80100F58060FFF7B3FF02F1C40100F513 -:103AE0008060FFF7ADFFBDE8084000F097B800BF69 -:103AF00000380240000002408040000808B500F095 -:103B000017FAFFF765FBBDE80840FFF7D7BE0000D6 -:103B100070470000104B1A6C42F001021A641A6ED2 -:103B200042F001021A660D4A1B6E936843F00103CE -:103B300093604FF0804331229A624FF0FF32DA6295 -:103B400000229A615A63DA605A6001225A610821A0 -:103B50001A601C20FFF72EB800380240002004E055 -:103B60004FF0804208B51169D3680B40D9B2C94300 -:103B70009B07116107D5202383F31188FFF748FBCA -:103B8000002383F3118808BD08B5FFF7E9FFBDE8FE -:103B90000840FFF7EFBE00001E4B1A6962F0FF02FB -:103BA0001A611A69D2B21A614FF0FF301A695A6964 -:103BB000586100215A6959615A691A6A62F0805243 -:103BC0001A621A6A02F080521A621A6A5A6A5862B3 -:103BD0005A6A59625A6A1A6C42F080521A641A6E12 -:103BE00042F080521A661A6E0B4A106840F48070D8 -:103BF0001060186F00F44070B0F5007F1EBF4FF4E6 -:103C0000803018671967536823F40073536000F01D -:103C10006FB900BF00380240007000403B4B3C4A87 -:103C20001A643C4A4FF4404111601A6842F00102A4 -:103C30001A601A689007FCD59A6822F003029A600D -:103C4000324B9A6812F00C02FBD1196801F0F901AD -:103C500019609A601A6842F480321A601A689103F7 -:103C6000FCD55A6F42F001025A67284B5A6F9207EF -:103C7000FCD5294A5A601A6842F080721A60254AB7 -:103C800053685804FCD5214B1A689101FCD5234A8E -:103C9000C3F884201A6842F080621A601A68120120 -:103CA000FCD51F4A9A600322C3F88C204FF00062B3 -:103CB000C3F894201B4B1A681B4B9A421B4B21D113 -:103CC0001B4A11681B4A91421CD140F203121A6030 -:103CD000164A136803F00F03032BFAD10B4B9A68B3 -:103CE00042F002029A609A6802F00C02082AFAD1A5 -:103CF0005A6C42F480425A645A6E42F480425A66C8 -:103D00005B6E704740F20372E1E700BF003802408B -:103D10000004001000700040041940020830002424 -:103D200000948838002004E011640020003C024028 -:103D300000ED00E041C20F41084A08B5516913681F -:103D40000B4003F00103536123B1054A13680BB123 -:103D500050689847BDE80840FFF70CBE003C0140A2 -:103D600020390020084A08B5516913680B4003F058 -:103D70000203536123B1054A93680BB1D068984799 -:103D8000BDE80840FFF7F6BD003C014020390020A7 -:103D9000084A08B5516913680B4003F004035361E6 -:103DA00023B1054A13690BB150699847BDE8084033 -:103DB000FFF7E0BD003C014020390020084A08B56B -:103DC000516913680B4003F00803536123B1054A9E -:103DD00093690BB1D0699847BDE80840FFF7CABDA9 -:103DE000003C014020390020084A08B55169136899 -:103DF0000B4003F01003536123B1054A136A0BB162 -:103E0000506A9847BDE80840FFF7B4BD003C014048 -:103E100020390020174B10B55A691C68144004F46F -:103E200078725A61A30604D5134A936A0BB1D06A1B -:103E30009847600604D5104A136B0BB1506B984736 -:103E4000210604D50C4A936B0BB1D06B9847E20561 -:103E500004D5094A136C0BB1506C9847A30504D5DF -:103E6000054A936C0BB1D06C9847BDE81040FFF742 -:103E700081BD00BF003C0140203900201A4B10B525 -:103E80005A691C68144004F47C425A61620504D5E6 -:103E9000164A136D0BB1506D9847230504D5134A8C -:103EA000936D0BB1D06D9847E00404D50F4A136EA3 -:103EB0000BB1506E9847A10404D50C4A936E0BB118 -:103EC000D06E9847620404D5084A136F0BB1506F47 -:103ED0009847230404D5054A936F0BB1D06F9847D8 -:103EE000BDE81040FFF746BD003C014020390020EE -:103EF000062108B50846FEF75DFE06210720FEF7FD -:103F000059FE06210820FEF755FE06210920FEF77E -:103F100051FE06210A20FEF74DFE06211720FEF76E -:103F200049FEBDE8084006212820FEF743BE0000F8 -:103F300008B5FFF731FE00F00BF8FEF751FEFFF772 -:103F400051F8FFF7E5FDBDE80840FFF761BD00004F -:103F50000023054A19460133102BC2E9001102F172 -:103F60000802F8D1704700BF2039002010B5013990 -:103F70000244904201D1002005E0037811F8014F7E -:103F8000A34201D0181B10BD0130F2E72DE9F0412A -:103F9000A3B1C91A17780144044603F1FF3C8C42CF -:103FA000204601D9002009E00578BD4204F1010452 -:103FB000F5D10CEB0405D618A54201D1BDE8F0817E -:103FC00015F8018D16F801EDF045F5D0E7E7000092 -:103FD000034611F8012B03F8012B002AF9D1704791 -:103FE0006F72672E6172647570696C6F742E4152C6 -:103FF0004B5F52544B5F47505300000040A2E4F126 -:10400000646891060041A3E5F2656992070000002B -:1040100000000000AD2F0008992F0008D52F0008E0 -:10402000C12F0008CD2F0008B92F0008A52F0008C8 -:10403000912F0008E12F00086D61696E00000000FB -:1040400069646C650000000040400008683700208B -:10405000E038002001000000CD3100080000000021 -:104060000040000000400000004000000040000050 -:104070000000010000000200000002000000020039 -:10408000A000902A00000000AAAAAAAA50000024BA -:10409000FFFB000000770000009009000100000510 -:1040A00000000000AAAAAAA501000080FFEF0000FE -:1040B0000000000000000000000000000000000000 -:1040C000AAAAAAAA00000000FFFF0000000000004A -:1040D000000000000000000000000000AAAAAAAA38 -:1040E00000000000FFFF00000000000000000000D2 -:1040F0000000000000000000AAAAAAAA0000000018 -:10410000FFFF0000000000000000000000000000B1 -:1041100000000000AAAAAAAA00000000FFFF0000F9 -:10412000000000000000000000000000000000008F -:10413000AAAAAAAA00000000FFFF000000000000D9 -:104140000000000000000000000000000A00000065 -:10415000000000000300000000000000000000005C -:10416000B0C0FF7F0100000052000000000000000E -:1041700000000700000000006400000000000000D4 -:0C41800040420F00FE2A0100D2040000A3 +:1000000000070020F5040008DD26000895260008FA +:10001000BD26000895260008B5260008F70400084C +:10002000F7040008F7040008F7040008D1360008B8 +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008DD440008054500081F +:100060002D450008554500087D450008F7040008A7 +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F704000849260008F0 +:100090007526000885260008F7040008A545000815 +:1000A000F7040008F7040008F7040008F704000844 +:1000B0008D460008F7040008F7040008F70400085C +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008F704000879460008F704000850 +:1000E00009460008F7040008F7040008F7040008B0 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008F7040008A3 +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E000C512000800000000000000000000000030 +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600003F0C6FD03F058FE4FF055301F491B4AFB +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE703F0A4FD5E +:1005B00003F080FE144C154DAC4203DA54F8041BD2 +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E703F08CBD000700209E +:1005E000002300200000000808ED00E000010020CA +:1005F00000070020904F00080023002080230020E7 +:1006000080230020C44F0020E0010008E40100081E +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002003F0CAF95D +:10064000FEE703F02DF900DFFEE70000F8B500F04B +:100650004BFE03F0E7FC074603F036FD0546002895 +:100660003FD12C4B9F423CD001339F423CD02A4B80 +:1006700027F0FF029A423AD1F8B200F041FC2E4630 +:1006800042F2107400F042FC08B10024264601F04A +:1006900019F980B3032000F045F80024264635B14F +:1006A0001E4B9F4203D003F007FD00242646002086 +:1006B00003F0C2FC1A4B1B691B0422D40EB100F0DC +:1006C00047F800F08FFC00F011FE02F00FF805462D +:1006D000CCB102F00BF8401BA04214D900F038F85E +:1006E000F3E72E460024CDE704460126CAE7064676 +:1006F0004FF47A74C6E7002CD1D04FF47A740126F7 +:10070000CDE70024DDE700F0B5FC4FF47A7003F08C +:1007100067F9DDE7010007B0000008B0263A09B02C +:1007200000040240084B187003280CD8DFE800F0E2 +:1007300008050208022000F037BE022000F02ABEA1 +:10074000024B00225A60704780230020842300203F +:1007500010B501F0B7F830B1204B03221A70204BCE +:1007600000225A6010BD1F4B1F4A1C4619680131F8 +:10077000F8D004339342F9D162681C4B9A42F1D904 +:100780001B4B9B6803F1006303F580339A42E9D267 +:1007900003F066FC03F078FC002000F0C1FD0220AD +:1007A000FFF7C0FF134B1A6C00221A64196E1A6609 +:1007B000196E596C5A64596E5A665B6E72B64FF078 +:1007C000E0233021C3F8084DD4E9003281F31188C9 +:1007D0009D4683F308881047C4E700BF80230020AC +:1007E000842300200000010820000108FFFF00080A +:1007F0000023002000380240094A136849F26900CA +:1008000099B21B0C00FB01331360064B186844F2CD +:10081000506182B2000C01FB0200186080B2704788 +:10082000182300201423002010B5002110220446B4 +:1008300000F0D6FD034B03CB206061601868A06018 +:1008400010BD00BF107AFF1F2DE9F041ADF54E7DC0 +:100850000DF134086CAC40F2751207460D460EA837 +:100860000021C8F8001000F0BBFD4FF4C472002155 +:10087000204600F0B5FD01F039FF254B4FF47A72A8 +:10088000B0FBF2F0186093E80700022384E8070049 +:100890000DF5E9702382FFF7C7FF4FF4A4431D490C +:1008A000238406A804F078FA192384F832310DF273 +:1008B000E32206AB0DF1300C1E4603CE66451060F8 +:1008C0005160334602F10802F6D133781370414685 +:1008D0000122204600F0D0FD00230393AB7E02935B +:1008E00005F11903019380B20123CDE9048000933F +:1008F000E97E05A3D3E90023384602F0BFFA0DF5DF +:100900004E7DBDE8F08100BF9E6AC421818A46EE1B +:100910008C230020A84D00082DE9F0412C4C237AAF +:10092000DAB080460D465BBB27A9284600F0B4FE2E +:100930000746002842D19DF89D60C82E3ED801464A +:100940004FF4A662204600F04BFD4FF48073C4F8CC +:10095000F8314FF40073C4F80C334FF44073C4F80B +:10096000203432460DF19E0104F1090000F026FD0D +:1009700026449DF89C30777223720BB9EB7E23726C +:100980008122002106AC27A800F02AFD0122214681 +:1009900027A800F0BDFE00230393AB7E029305F170 +:1009A000190380B201932823CDE904400093E97E26 +:1009B00005A3D3E90023404602F060FA5AB0BDE82F +:1009C000F08100BFAFF3008026417272DF25D7B7F8 +:1009D000A8440020F0B5254E4FF48A7505FB00654C +:1009E000F1B096F8D83085F8DC300024D8222146C2 +:1009F00085F8E8403AA800F0F3FC06F1090000F0A1 +:100A0000E7FCD5F8E4308DF8F000C2B206AF06F18D +:100A100009010DF1F100CDE93A3400F0CFFC39467F +:100A200001223AA800F0A0FE80B2CDE904700823AC +:100A30000127CDE9023706F1D80301933023009353 +:100A4000317A0B4807A3D3E9002302F017FAA0423A +:100A500006DD01F04BFEC5F8E000384671B0F0BD90 +:100A60002046FBE778F6339F93CACD8DA84400203B +:100A7000A43300202DE9F0411D4D1E4E1E4F86B0BF +:100A8000284602F027FA034658B30024CDE9034470 +:100A9000ADF81440027B8DF81420996840680294E8 +:100AA00003AA03C21B68DFF8548043F0004302939B +:100AB00001F01EFE821941F10003009402A938469C +:100AC00001F0E0F8A04205DD284602F007FA88F8B8 +:100AD0000040D5E798F80030072B05D8013388F897 +:100AE000003006B0BDE8F081014802F0F7F9F8E700 +:100AF000A433002040420F00D8330020DD490020FD +:100B000070B50D4614461E4602F014F950B9022E77 +:100B100010D1012C0ED112A3D3E90023C5E9002383 +:100B2000012007E0282C10D005D8012C09D0052C75 +:100B30000FD0002070BD302CFBD10BA3D3E90023D4 +:100B4000ECE70BA3D3E90023E8E70BA3D3E90023E9 +:100B5000E4E70BA3D3E90023E0E700BFAFF3008095 +:100B6000401DA12026812A0B78F6339F93CACD8D94 +:100B70009E6AC421818A46EE26417272DF25D7B76C +:100B8000F017304A39059E5638B505460E4C0021FF +:100B9000013500F0E7FBA4F82C55B4F82C0500F063 +:100BA000C9FB78B1B4F82C0500F0D4FB014648B974 +:100BB000B4F82C0500F0D6FBB4F82C350133A4F8BA +:100BC0002C35EAE738BD00BFA844002010B50A4B19 +:100BD0000A4A1A6003F5805393F860203AB9DC6D35 +:100BE0002CB1204600F0E6FE204604F015F8BDE8E2 +:100BF0001040034800F0DEBED8330020004E00084D +:100C0000204400202DE9F04F8FB000AF05460C4680 +:100C100002F090F8002849D1237E022B1BD1E38AF1 +:100C2000012B18D101F062FD0646FFF7E5FD0346F2 +:100C30004FF4C870DFF8C482B3FBF0F206F5167605 +:100C400002FB103316FA83F3C8F80030E37E33B9A1 +:100C5000A34B00221A703C37BD46BDE8F08F07F168 +:100C60002401204600F0D6FC0028F4D107F114003E +:100C7000FFF7DAFD97F8264007F11401224607F145 +:100C8000270004F013F80028E2D10F2C08D8944B69 +:100C90001C70D8F80030A3F51673C8F80030DAE7F6 +:100CA00097F82410284602F03DF8D4E7E38A282B71 +:100CB0002BD010D8012B23D0052BCCD1BFF34F8FD5 +:100CC0008849894BCA6802F4E0621343CB60BFF3E2 +:100CD0004F8F00BFFDE7302BBDD1844EE17E327ACD +:100CE0009142B8D1607E3146002291F8DC508542B5 +:100CF00000F0A5800132042A01F58A71F5D1AAE736 +:100D000021462846FFF7A0FDA5E721462846FFF724 +:100D100003FEA0E7B2F8EC507B6005F103094FEA4F +:100D200099094FEA8902D11DC908A8EBC1039D4664 +:100D3000EB460021584600F053FB04F1EE012A4631 +:100D40003144584600F03AFB7B6813B9012000F0AB +:100D5000E7FA96F8D20000F0EDFA044630B93072A6 +:100D600000F008FB204600F0DBFAB1E0D6F8D42012 +:100D70003AB996F8D200B6F82C25824201D8FFF78E +:100D800003FFD6F8D4202A44944208D296F8D20021 +:100D9000B6F82C250130824201D8FFF7F5FE7068C5 +:100DA0005FFA89F2594600F023FB08B9C54679E09D +:100DB000726896F8D2002A447260D6F8D42005EB07 +:100DC0000209C6F8D49000F0B5FA814509D396F827 +:100DD000D220D6F8D4000132001B86F8D220C6F803 +:100DE000D400FF2D0FD80024347200F0C3FA20463F +:100DF00000F096FA00F066FD3D4B188108B9FFF748 +:100E0000A7FCC54627E7BB6896F8D9000AFB036232 +:100E1000FB68D2F8E41082F8E83001F58061C2F88E +:100E2000E030C2F8E410FFF7D5FDFFF723FE96F897 +:100E3000D920013202F0030286F8D920B6E74FF438 +:100E40008A7A0AFB02F505F1EA013144204600F0F6 +:100E5000B7FCF86000287FF4FEAE3544012285F827 +:100E6000E82001F043FCD5F8E020D6ED007ADFED74 +:100E7000216A801A192838BF192040F6B8329042EA +:100E800028BF1046B8EE677A07EE900AF8EEE77AC8 +:100E900067EEA67ADFED186AE7EE267AFCEEE77ACF +:100EA000C6ED007A96F8D930BB60BA6873680AFB61 +:100EB00002F4321992F8E81059B1D2F8E4108B42DA +:100EC000E8463FF427AF002182F8E810C2F8E010AE +:100ED000C5467368064A9B0A01331381BBE600BF0F +:100EE0009D33002000ED00E00400FA05A844002036 +:100EF0008C230020CDCCCC3D6666663FA03300201D +:100F0000014B1870704700BF9823002030B54FF098 +:100F100000542B4B22689A4285B007D003F0DEF8CC +:100F2000044620BB0024204605B030BD254B627D21 +:100F300025481A70237D03724FF48073C0F8F8318E +:100F40004FF40073C0F80C3300254FF44073C0F821 +:100F500020341E49C0F8E450C922093000F02EFAAE +:100F60002046E022294600F03BFA0124DBE7184A3C +:100F7000184D136C43F000731364AA6D164B9A421C +:100F8000D0D12B6E013B7E2BCCD8144A07CA01ABC3 +:100F900083E807001846032100F062FC6B6D834272 +:100FA0004FF00003BED12A6D8A4201BFAB65054BED +:100FB0002A6E1A7003BF0A4BEA6D1A601C46B2E72C +:100FC0009AAD44C598230020A844002016000020B4 +:100FD00000380240006600405041A0B05866004012 +:100FE0001023002037B51A4D00F06CFC02236B7102 +:100FF000184B288119681848012201F015FA0023BE +:101000000193164B164900931648174B4FF4805224 +:1010100001F060FE154B197811B1124801F082FE03 +:1010200001F064FB0446FFF7E7FB4FF4C873B0FB25 +:10103000F3F202FB130304F5167010FA83F00C4B65 +:10104000186003F041F808B10F232B8103B030BDC5 +:101050008C23002010230020D8330020010B00082F +:101060009C230020A4330020050C000898230020B6 +:10107000A03300202DE9F04F2DED028B0FF238291F +:10108000D9E90089834C93B00BAE9FED7E8BFFF7BF +:10109000F1FC814FDFF828A200230A93ADF8343029 +:1010A0000B9373604FF0000B5B468DED008B0125B9 +:1010B0000DF11D0207A938468DF81C508DF81DB0A2 +:1010C00001F062F99DF81C30002B40F0A58020460D +:1010D00001F030FE0646002845D1704F01F006FBB6 +:1010E0003B6898423FD301F001FB8246FFF784FB47 +:1010F0004FF4C873B0FBF3F202FB13030AF516704A +:1011000010FA83F03860664F97F800B0CBF1100A00 +:10111000BBF1000F14BF33462B465FFA8AFA0EA8C4 +:101120008DF82830FFF780FBBAF1060F28BF4FF08B +:10113000060A0EAB03EB0B0152460DF1290000F03D +:101140003DF90AAB0393182302930AF10102554BB0 +:10115000D2B2CDE90053049220464CA3D3E9002338 +:1011600001F02EFE3E7001F0C1FA4F4A4F4D136858 +:10117000C31AB3F57A7F2ED3106001F0B9FA024694 +:101180000B46204601F0B4FE204601F0D3FD10B31B +:101190002B7A474E002B14BF03230223737101F0F7 +:1011A000A5FA0EAF4FF47A730122B0FBF3F0394683 +:1011B0003060304600F006FA182302933D4B01934D +:1011C00080B240F25513CDE90370009342464B467E +:1011D000204601F0F5FD2B7A93B101F087FA002645 +:1011E00007464FF48A7A95F8D900304400F003009E +:1011F0000AFB005393F8E82092B30136042EF2D193 +:10120000C82002F0EDFB2B7A002B7FF43DAF13B02A +:10121000BDEC028BBDE8F08FDAF8143083F4806304 +:10122000CAF81430594610220EA800F0D9F80DF172 +:101230001E0308AA0AA9384600F022FE96E8030019 +:101240000FAB83E803009DF834308DF844300A9BDF +:101250000E930EA9DDE90823204602F01DF821E7D0 +:10126000D3F8E02042B12B68FA2B38BFFA23BA1A20 +:101270000533B2EB430FC0D3FFF7ACFB0028BCD162 +:10128000BEE700BF0000000000000000401DA120DC +:1012900026812A0BA4330020D8330020A03300205D +:1012A0009D3300209C330020D8490020A844002012 +:1012B0008C230020DC490020F1C6A7C1D068080FAC +:1012C0000000024008B5054800F074FEBDE8084083 +:1012D000034A0449002003F099BC00BFD833002022 +:1012E000184A0020CD0B00087047000070B502F0CE +:1012F0003BFD094E094D3080002428683388834225 +:1013000008D902F02BFD2B6804440133B4F5803F6B +:101310002B60F2D370BD00BF0C4A0020E0490020D2 +:1013200002F0D2BD00F10060920000F5803002F0C2 +:1013300061BD0000054B1A68054B1B889B1A834250 +:1013400002D9104402F00ABD00207047E049002095 +:101350000C4A0020024B1B68184402F007BD00BF76 +:10136000E0490020024B1B68184402F017BD00BF83 +:10137000E0490020064991F8243033B10023086A7F +:1013800081F824300822FFF7CDBF0120704700BF4D +:10139000E4490020022802BF024B4FF080629A61AC +:1013A000704700BF00000240022802BF024B4FF40A +:1013B00080629A61704700BF0000024010B50023B0 +:1013C000934203D0CC5CC4540133F9E710BD000054 +:1013D00003460246D01A12F9011B0029FAD17047C0 +:1013E00002440346934202D003F8011BFAE7704718 +:1013F0002DE9F8431F4D144695F8242007468846EA +:1014000052BBDFF870909CB395F824302BB92022A2 +:10141000FF2148462F62FFF7E3FF95F82400C0F153 +:101420000802A24228BF2246D6B24146920005EBEE +:101430008000FFF7C3FF95F82430A41B1E44F6B2CA +:10144000082E17449044E4B285F82460DBD1FFF7FE +:1014500091FF0028D7D108E02B6A03EB8203834277 +:10146000CFD0FFF787FF0028CBD10020BDE8F8835D +:101470000120FBE7E44900202DE9F0470D46044632 +:1014800000219046284640F27912FFF7A9FF234633 +:1014900020220021284601F0A1FE231D0222202146 +:1014A000284601F09BFE631D03222221284601F0FD +:1014B00095FEA31D03222521284601F08FFE04F18D +:1014C000080310222821284601F088FE04F11003A9 +:1014D00008223821284601F081FE04F11103082278 +:1014E0004021284601F07AFE04F112030822482127 +:1014F000284601F073FE04F11403202250212846EF +:1015000001F06CFE04F1180340227021284601F01E +:1015100065FE04F120030822B021284601F05EFE9A +:1015200004F121030822B821284601F057FE04F1F6 +:101530002207C0263B46314608222846083601F0DD +:101540004DFEB6F5A07F07F10107F3D104F1320398 +:1015500008223146284601F041FE002704F1330AF3 +:1015600094F832304FEAC7099F4209F5A47615D3A3 +:10157000B8F1000F08D1314604F5997307222846C7 +:1015800001F02CFE09F24F16274694F832213B1B3E +:1015900093420CD3F01DC008BDE8F0870AEB0703A7 +:1015A00008223146284601F019FE0137D8E707F234 +:1015B000331331460822284601F010FE0836013761 +:1015C000E3E7000013B50446084600210160234606 +:1015D000C0F803102022019001F000FE0198231DA5 +:1015E0000222202101F0FAFD0198631D032222212D +:1015F00001F0F4FD0198A31D0322252101F0EEFD69 +:10160000019804F108031022282101F0E7FD0720CA +:1016100002B010BDF7B50023047F00910E460722EB +:101620001946054601F09EFC731C0093012200231D +:101630000721284601F096FCC4B9B31C009305228B +:1016400023460821284601F08DFC0D243746B27848 +:10165000BB1B934211D32B7FA88A0734E408BBB984 +:10166000844294BF0020012003B0F0BDAB8ADB00B0 +:10167000083BDB08B3700824E8E7FB1C0093214615 +:1016800000230822284601F06DFC08340137DEE70C +:10169000201A18BF0120E7E7F7B50023047F009167 +:1016A0000E4608221946054601F05CFC731CC4B9BD +:1016B0000822009311462346284601F053FC1024CB +:1016C000012372785F1C013B934211D32B7FA88AC0 +:1016D0000734E408BBB9844294BF0020012003B062 +:1016E000F0BDAB8ADB00083BDB0873700824E7E73A +:1016F000F3190093214600230822284601F032FC0A +:1017000008343B46DDE7201A18BF0120E7E7000058 +:10171000F8B50E4605461446002181223046FFF7F3 +:101720005FFE2B4608220021304601F057FD7CB9B0 +:101730006B1C07220821304601F050FD0F240123C5 +:101740006A785F1C013B934204D3E01DC008F8BDDA +:101750000824F4E7EB1921460822304601F03EFD4B +:1017600008343B46ECE70000F8B50E460546144643 +:101770000021CE223046FFF733FE2B4628220021DF +:10178000304601F02BFD7CB905F108030822282121 +:10179000304601F023FD30242F462A7A7B1B9342EA +:1017A00004D3E01DC008F8BD2824F5E707F10903BC +:1017B00021460822304601F011FD08340137ECE7DC +:1017C000F7B5047F00910E46012310220021054643 +:1017D00001F0C8FBC4B9B31C0093092223461021B1 +:1017E000284601F0BFFB192437467288BB1B9A427A +:1017F00011D82B7FA88A0734E408BBB9844294BF70 +:101800000020012003B0F0BDAB8ADB00103BDB08F9 +:1018100073801024E8E73B1D009321460023082233 +:10182000284601F09FFB08340137DEE7201A18BF75 +:101830000120E7E730B5094D0A4491420DD011F877 +:10184000013B5840082340F30004013B2C4013F0B7 +:10185000FF0384EA5000F6D1EFE730BD2083B8EDF6 +:10186000F7B54FF0FF33DFF854C0DFF854E000EB7A +:1018700081011A4688421CD050F8044B019401AFF4 +:10188000042417F8015B82EA05620825DB18164676 +:1018900005F1FF355241002EBCBF83EA0C0382EAFA +:1018A0000E0215F0FF05F1D1013C14F0FF04E8D160 +:1018B000E0E7D843D14303B0F0BD00BF9336EAA9B7 +:1018C000EBE1F042F7B5354A106851686B4603C347 +:1018D0006A4633493348082303F0F8F9044688BBC5 +:1018E0000A25314A106851686B4603C36A462F497E +:1018F0002C48082303F0EAF90446002845D0036980 +:10190000B3F5E02F41D8B0F86620522A3DD1284ADD +:10191000024402F15C018B4237D35C3B2149002039 +:101920009E1AFFF787FF3246074604F16401002044 +:10193000FFF780FFA3689F4227D1E368984208BF62 +:10194000002522E00369B3F5E02F25D8428B522A07 +:1019500020D1174A024402F110018B4218D3103BE8 +:10196000104900209D1AFFF765FF2A46064604F13C +:1019700018010020FFF75EFFA3689E4202D1E368D2 +:10198000984201D00D25ACE70025284603B0F0BDF4 +:101990001025A6E70C25A4E70B25A2E7C44D0008F7 +:1019A000DCFF060000000108CD4D000890FF060096 +:1019B0000800FFF710B5037C044613B9006803F074 +:1019C0006DF9204610BD00000023BFF35B8FC3609C +:1019D000BFF35B8FBFF35B8F8360BFF35B8F704799 +:1019E000BFF35B8F0068BFF35B8F704770B5054630 +:1019F0000C30FFF7F5FF05F1080604463046FFF707 +:101A0000EFFFA04206D930466D68FFF7E9FF254495 +:101A1000281A70BD3046FFF7E3FF201AF9E70000EF +:101A200070B50546406898B105F10800FFF7D8FF8A +:101A300005F10C0604463046FFF7D2FF84423046DB +:101A400094BF6D680025FFF7CBFF013C2C44201AA2 +:101A500070BD000038B50C460546FFF7C7FFA04231 +:101A600010D305F10800FFF7BBFF04446868B4FB1E +:101A7000F0F100FB1144BFF35B8F0120AC60BFF3BA +:101A80005B8F38BD0020FCE72DE9F0411446074686 +:101A90000D46FFF7C5FF844228BF0446D4B1B846BF +:101AA00058F80C6B4046FFF79BFF304428604046D7 +:101AB0007E68FFF795FF331A9C4203D86C600120C3 +:101AC000BDE8F0816B60A41B3B68AB602044E8601C +:101AD0000220F5E72046F3E738B50C460546FFF748 +:101AE0009FFFA04210D305F10C00FFF779FF0444DB +:101AF0006868B4FBF0F100FB1144BFF35B8F012079 +:101B0000EC60BFF35B8F38BD0020FCE72DE9FF419F +:101B1000884669460746FFF7B7FF6C4606B204EBF6 +:101B2000C6060025B44209D06268206808EB0501AA +:101B3000FFF744FC636808341D44F3E72946384640 +:101B4000FFF7CAFF284604B0BDE8F081F8B50546A6 +:101B50000C300F46FFF744FF05F1080604463046F7 +:101B6000FFF73EFFA042304688BF6C68FFF738FFA2 +:101B7000201A386020B130462C68FFF731FF20442E +:101B8000F8BD000073B5144606460D46FFF72EFF5C +:101B9000844228BF04460190DCB101A93046FFF71A +:101BA000D5FF019B33B93268C5E90233C5E900248A +:101BB00001200CE09C4238BF0194286001986860C5 +:101BC0008442F5D93368AB60241AEC60022002B07D +:101BD00070BD2046FBE700002DE9FF410F46694636 +:101BE000FFF7D0FF6C4600B204EBC0050026AC4204 +:101BF00009D0D4F8048054F8081BB8194246FFF7FE +:101C0000DDFB4644F3E7304604B0BDE8F081000058 +:101C100038B50546FFF7E0FF044601462846FFF7C2 +:101C200019FF204638BD0000302383F3118862B6C7 +:101C300070470000002383F3118862B670470000EC +:101C400010B4026854681A4623465DF8044B1847DE +:101C50000120704700207047002070477047000047 +:101C6000002070470E20704700F5805090F8C800A3 +:101C7000C0F340007047000000F5805090F9C900A3 +:101C800070470000F7B50C68BDF8207014F00054E0 +:101C90001E466FD10B7B082B6CD8FFF7C5FF45693B +:101CA000AB685B010CD4AB681B0108D4AC6814F0C2 +:101CB00080545DD1FFF7BEFF204603B0F0BD012484 +:101CC0000B6804F1180C002BB8BFDB004FEA0C1CAA +:101CD000B4BF43F004035B0545F80C300B680FFA02 +:101CE00084FC13F0804F18BF05EB0C1E05EB0C1C99 +:101CF0001EBFDEF8803143F00203CEF880310B7B4B +:101D0000CCF8843105EB04158B68C5F88C314B6831 +:101D1000C5F88831DCF8803143F00103CCF880311C +:101D200000EB441541F268031D4403EB44130344E4 +:101D3000C5E9002608330D4601F10C0C55F804EBFB +:101D400043F804EB6545F9D184342D881D8000EB00 +:101D5000441407F00303257925F00B052B43237169 +:101D6000FFF768FF0097334600F0E2FC0120A4E78C +:101D70000224A5E74FF0FF309FE7000013B500F500 +:101D800080540191E06DFFF74BFE1F280AD901999D +:101D9000E06D2022FFF7BAFEA0F12003584258411F +:101DA00002B010BD0020FBE708B500F58050FFF73A +:101DB0003BFFC06DFFF708FEBDE80840FFF73ABFE4 +:101DC00000220260828142608260704710B500226A +:101DD0000023C0E900230023044603810C30FFF7F1 +:101DE000EFFF204610BD0000F0B5054600F580501D +:101DF0000C4690F8C83013F0040FC3F3800108BFFD +:101E0000114661F3820304F1840680F8C83005EBC3 +:101E1000461389B01B79D8072ED57AB319072DD46C +:101E20006846FFF7D3FF05EB441303F5835303F133 +:101E3000180703AA103318685968144603C40833F6 +:101E4000BB422246F7D1186820609B88A380DDE959 +:101E50000E23CDE900230123ADF808302B68694635 +:101E6000DB6B2846984705EB46152B791A075CBFB4 +:101E700043F008032B7101E0002AF4D109B0F0BD52 +:101E80002DE9F047074688B007F5805468469A4622 +:101E90008846FFF7C9FE9146FFF798FFE06DFFF710 +:101EA000A5FD1F2829D9E06D20226946FFF7B0FE65 +:101EB000202822D103AD444605AB2E4603CE9E42D8 +:101EC00020606160354604F10804F6D13068206076 +:101ED000B388A380DDE90023C9E90023BDF80830F9 +:101EE000AAF80030FFF7A6FE4A4653464146384658 +:101EF00008B0BDE8F04700F009BCFFF79BFE0020EA +:101F000008B0BDE8F08700002DE9F84F0023C0E9D4 +:101F10000133254B044640F8183B0F46FFF750FFAE +:101F200004F12800FFF752FF04F1480804F5825538 +:101F30004646083530462036FFF748FFAE42F9D115 +:101F400004F580554FF480534FF00009C5E913396B +:101F5000C5F848800123EE6504F5875804F58456DA +:101F6000C5F8549085F8583085F86030083608F187 +:101F700008084FF0000A4FF0000B46E908ABA6F145 +:101F80001800FFF71DFF203646F8289C4645F4D17F +:101F900085F8C97017B1054800F0A2FB044B6361D6 +:101FA0002046BDE8F88F00BF004E0008D84D00085D +:101FB0000064004010B5044B197804464A1C1A709E +:101FC000FFF7A2FF204610BD144A00202DE9F0477C +:101FD000002950D0294B2A4FB7FBF1F599428CBF0D +:101FE0000A231123581EB5FBF3FC03FB1C53C4B298 +:101FF0002BB102280346F5D80020BDE8F0870CF18C +:10200000FF36B6F5806FF7D2C4EBC40E0EF10303B2 +:102010004FEAE309C3F3C703A4EB030809F1010A7C +:102020004FF47A755FFA88F009FB05555AFA88F87B +:10203000B5FBF8F5B5F5617FC1BF0EF1FF33C3F312 +:10204000C703E01AC0B25C1C50FA84F40CFB04F421 +:10205000B7FBF4F4A142CFD1013BDBB20F2BCBD8BD +:102060000138C0B20728C7D80021107116809170BE +:10207000D3700120C1E70846BFE700BF3F420F0011 +:1020800040787D0170B505460E464FF47A746B6951 +:102090005B6803F00103B34207D04FF47A7001F09C +:1020A0009FFC013CF3D1204670BD0120FCE70000FD +:1020B00030B54269936913F0700F16D000230B4CB2 +:1020C000936103F1840200EB421211794D0709D5A7 +:1020D000890707D5416954F823508D60117941F083 +:1020E000040111710133032BEBD130BDEC4D00081D +:1020F00073B51D46436916469A68D207044609D54A +:102100009A6801219960C2F34002CDE9006500217F +:10211000FFF76AFE63699A68D1050BD59A684FF498 +:1021200080719960C2F34022CDE90065012120460B +:10213000FFF75AFE63699A68D2030BD59A684FF489 +:1021400080319960C2F34042CDE90065022120460A +:10215000FFF74AFE204602B0BDE87040FFF7A8BF77 +:10216000F8B50446466900296CD106F10C073868B9 +:1021700080076AD006EB01153868D5F8B00110F079 +:10218000040FD5F8B0011ABFC00840F00040400D60 +:10219000A061D5F8B0C11CF0020F1CBF40F0804018 +:1021A000A061D5F8B40106EB011100F00F0084F82E +:1021B0002400D1F8B8012077D1F8B801000A60777F +:1021C000D1F8B801000CA077D1F8B801000EE07783 +:1021D000D1F8BC0184F82000D1F8BC01000A84F8D1 +:1021E0002100D1F8BC01000C84F82200D1F8BC1108 +:1021F000090E84F823103821396004F1340004F109 +:10220000180104F1240551F8046B40F8046BA9424D +:10221000F9D109880180C4E90A23214600232386D5 +:1022200051F8283B2046DB6B984704F58052204646 +:1022300092F8C83043F0040382F8C830BDE8F84093 +:10224000FFF736BF06F1100791E7F8BD10B5044659 +:1022500000F04EFA02460B4652EA030102D0013A60 +:1022600063F100030449086820B12146BDE810402D +:10227000FFF776BF10BD00BF104A0020F8B500F58B +:1022800083511E46FFF7D0FCDFF844C0083100241C +:1022900004F1840500EB45152B795F070ED4DB06AE +:1022A0000CD5D1E900739742B34107D243695CF87A +:1022B00024709F602B7943F004032B710134032CAD +:1022C00001F12001E4D1BDE8F840FFF7B3BC00BF45 +:1022D000EC4D000808B5FFF7A7FCFFF7E9FEBDE8E5 +:1022E0000840FFF7A7BC0000F8B5436905469868A9 +:1022F00000F0E050B0F1E05F0F461FD0E8B1FFF70B +:1023000093FC05F583541034002606F1840305EB95 +:1023100043131B791A0706D50136032E04F1200456 +:10232000F3D1012007E05B07F6D42146384600F0E0 +:1023300039FA0028F0D1FFF77DFCF8BD0120FCE759 +:1023400000F5805008B5FFF76FFCC06DFFF74EFB3E +:10235000FFF770FC43090CBF0120002008BD0000FE +:10236000F8B51D46002313700F4606461446FFF7C6 +:10237000E7FF80F00100387025B129463046FFF7AD +:10238000B3FF2070F8BD00002DE9B8410C4615469A +:102390001F46804600F0ACF90B462178024609B989 +:1023A000287850B14046FFF769FFFFF793FF3B469F +:1023B0002A462146FFF7D4FF0120BDE8B88100007E +:1023C00010B5FFF731FC174B1A6C42F000721A641B +:1023D0001A6A42F000721A621A6A00F5805422F0FA +:1023E00000721A62FFF726FC94F8C830DB0718D495 +:1023F000B9B103211320FFF717FC01F0C7F903213E +:10240000142001F0C3F90321152001F0BFF994F85D +:10241000C83043F0010384F8C830BDE81040FFF72E +:1024200009BC10BD003802402DE9F04700F5805589 +:1024300088B095F8C930012B0446884616467FD8E7 +:10244000804F57F823200AB947F82300D7F800A097 +:10245000C4F80C802674BAF1000F63D095F8C93027 +:10246000012B6FD001212046FFF7AAFFFFF7DCFB0D +:102470006269136823F0020313606269136843F012 +:1024800001031360636900275F6101212046FFF7A4 +:10249000D1FBFFF7F7FD002800F09580E86DFFF70E +:1024A00093FA04F58359BA4609F10809202200215C +:1024B0006846FEF795FF02A8FFF782FCCDF818A04A +:1024C0006A4609EB07030DF1180E9446BCE80300B9 +:1024D000F44518605960624603F10803F5D1DCF851 +:1024E0000000186020379CF804201A71602FDDD19D +:1024F00095F8C8306FF38203002785F8C8306A4624 +:1025000041462046ADF80070ADF802708DF80470B9 +:10251000FFF75CFD636948BB4FF400421A6008B0E6 +:10252000BDE8F08741F2D00002F078FB814610B19F +:102530005146FFF7E9FCC7F80090B9F1000F8DD1C3 +:102540000020ECE7386803681B6B984701460028B9 +:1025500088D13868FFF734FF3868036832465B6813 +:102560004146984700287FF47DAFE9E761221A6071 +:102570009DF802309DF803201B06120402F470221D +:1025800003F040731343BDF80020C2F30902134364 +:102590009DF804201205022E02F4E0020CBF4FF059 +:1025A00000410021134362690B43D3616369132225 +:1025B0005A616269136823F00103136039462046AB +:1025C000FFF760FD08B96369A6E795F8C93093BBCA +:1025D0006169D1F8002242F00102C1F8002261696C +:1025E000D1F8002222F47C5222F00E02C1F800221F +:1025F0006169D1F8002242F46062C1F80022626988 +:10260000C2F814326269C2F80432626941F6FF719D +:10261000C2F80C126269C2F840326269C2F84432F0 +:1026200063690122C3F81C226269D2F8003223F0E8 +:102630000103C2F8003295F8C83043F0020385F870 +:10264000C8306CE7104A002008B500F051F850EA95 +:102650000103024602D0421E61F10001044B1868DA +:1026600010B10B46FFF744FDBDE8084001F064B827 +:10267000104A002008B50020FFF7E8FDBDE808403B +:1026800001F05AB808B50120FFF7E0FDBDE80840A9 +:1026900001F052B800B59BB0EFF30981682268469B +:1026A000FEF78CFEEFF30583014B9B6BFEE700BF4B +:1026B00000ED00E008B5FFF7EDFF000000B59BB0AE +:1026C000EFF3098168226846FEF778FEEFF3058391 +:1026D000014B5B6BFEE700BF00ED00E0FEE7000092 +:1026E0000FB408B5029801F011F9FEE701F038BC0B +:1026F00001F010BC13B56C4684E80600031D94E895 +:10270000030083E80500012002B010BD73B58568A1 +:10271000019155B11B885B0707D4D0E900369B6B4C +:102720009847019AC1B23046A847012002B070BD57 +:10273000F0B5866889B005460C465EB1BDF8383004 +:102740005B070AD4D0E900379B6B98472246C1B299 +:102750003846B047012009B0F0BD00220023CDE982 +:1027600000230023ADF808300A4603AB01F1080648 +:10277000106851681C4603C40832B2422346F7D1A0 +:10278000106820609288A280FFF7B2FF0423ADF8A2 +:1027900008302B68CDE90001DB6B69462846984775 +:1027A000D8E7000030B503680968DD0FB5EBD17FCD +:1027B00023F0604421F060424FEAD1700BD0002B2F +:1027C000B8BFA40C0029B8BF920C944202D034BF09 +:1027D0000120002030BD944205D1C1F38070C3F3C5 +:1027E00080738342F6D194422CBF00200120F1E790 +:1027F0002DE9F041456A15B94162BDE8F0814B68A9 +:1028000023F06047C3F38A464FEAD37EC3F3807850 +:1028100016EA230638BF3E46AC462B465A68BEEB46 +:10282000D27F22F060440AD0002A18DAA40CB44205 +:1028300017D19D420FD10D60DEE71346EEE7A742A8 +:1028400007D102F08044C2F3807242450BD054B1EC +:10285000EFE708D2EDE7CCF800100B60CDE7B4420B +:1028600001D0B442E5D81A689C46002AE5D1196027 +:10287000C3E700002DE9F047089D01F007044FEA87 +:10288000D508224405F0070500EBD1004FF47F493D +:10289000944201D1BDE8F08704F0070705F0070A6C +:1028A00057453E4638BF5646C6F10806111B8E42B4 +:1028B00028BF0E46E10808EBD50E415C13F80EC0A8 +:1028C000B94029FA06F721FA0AF1FFB28CEA0101B0 +:1028D00047FA0AF739408CEA010C03F80EC0344479 +:1028E0003544D5E780EA0120082341F2210201B2F4 +:1028F0004000002980B203F1FF33B8BF504013F00D +:10290000FF03F4D17047000038B50C468D18A5427E +:1029100000D138BD14F8011BFFF7E4FFF7E7000012 +:1029200042684AB1136843604389818901339BB28D +:102930009942438138BF83811046704770B588B093 +:10294000202204460D4668460021FEF749FD204638 +:102950000495FFF7E5FF024658B16B46054608AE01 +:102960001C4603CCB44228606960234605F1080583 +:10297000F6D1104608B070BD082817D909280CD028 +:102980000A280CD00B280CD00C280CD00D280CD009 +:102990000E2814BF4020302070470C2070471020B4 +:1029A000704714207047182070472020704700009F +:1029B000082817D90C280CD910280CD914280CD9A0 +:1029C00018280CD920280CD930288CBF0F200E20B5 +:1029D0007047092070470A2070470B2070470C2071 +:1029E00070470D20704700002DE9F843078C072F32 +:1029F00004461ED9D0E9029800254FF6FF73C5F1B1 +:102A00002006A5F1200029FA05F108FA06F628FAB1 +:102A100000F031430143C9B21846FFF763FF0835A0 +:102A2000402D0346EBD1E1693A46BDE8F843FFF794 +:102A30006BBF4FF6FF70BDE8F883000010B54B6820 +:102A400023B9CA8A63F30902CA8210BD04691A68ED +:102A50001C600361C38A013BC3824A60EFE7000048 +:102A60002DE9F84F1D46CB8A0F46C3F3090105290E +:102A7000814692460B4630D00020AAB207F11A04D4 +:102A80009EB2042E1FFA80F80FD8904503F101037F +:102A900006D3FB8A0A4462F30903FB8201201AE091 +:102AA0001AF80060E6540130EAE79045F1D2A1F14E +:102AB000050B1C237C68BBFBF3F203FB12BB1FFA64 +:102AC0008BF6002C45D14846FFF72AFF044638B95B +:102AD00078606FF00200BDE8F88F4FF00008E6E77D +:102AE000002606607860ADB24FF0000B454510D966 +:102AF0000AEB0803221D13F8011B9155B1B208F12E +:102B000001081B291FFA88F82BD0454506F101065C +:102B1000F1D8FB8AC3F30902154465F30903BCE746 +:102B2000013292B21C462368002BF9D16B1F0B4473 +:102B30001C21B3FBF1F301339BB29A42D3D2BBF118 +:102B4000000FD0D14846FFF7EBFE20B9C4F800B023 +:102B5000BFE70122E7E7C0F800B05E462060044608 +:102B6000C1E74545D5D94846FFF7DAFE08B92060E8 +:102B7000AFE7C0F800B0002620600446B6E70000CA +:102B80002DE9F04F2DED028B1C4683B05B6901925D +:102B900007468846002B00F09A80238C2BB1E2690F +:102BA000002A00F09480072B35D807F10C00FFF7BE +:102BB000B7FE054638B96FF00205284603B0BDECF4 +:102BC000028BBDE8F08F14220021FEF709FC228C55 +:102BD000E16905F10800FEF7F1FB208C013080B2BD +:102BE000FFF7E6FEFFF7C8FE013880B2208401300F +:102BF00028746369228C1B782A4403F01F0363F056 +:102C00003F0348F000411372384669602946FFF7D8 +:102C1000EFFD0125D1E700F10C034FF0000908EEAC +:102C2000103A4FF0800A4E464D4618EE100AFFF754 +:102C300077FE83460028BED014220021FEF7D0FB89 +:102C4000002E3AD1019BABF8083002220BF1080E9E +:102C50001FFA82FC0CF10100BCF1060F218C80B23E +:102C600001D88E422BD3FFF7A3FEFFF785FE6269E2 +:102C70001278013802F01F028E4208BF4FF0400A5E +:102C800042EA49121BFA80F14AEA020A013048F08E +:102C9000004281F808A08BF81000CBF804205946B8 +:102CA0003846FFF7A5FD238C0135B3422DB289F0DC +:102CB00001094FF0000AB8D17FE70022C6E7E169B9 +:102CC000895D0EF802100136B6B20132C0E76FF02E +:102CD000010572E7F8B515460E463022002104467C +:102CE0001F46FEF77DFB069B6360B5F5001F079B43 +:102CF000A76034BF6A094FF6FF72A36297B2E6611C +:102D000004F1100000239A4206D800230360A78232 +:102D1000E3822383E360F8BD06600133304620364A +:102D2000F1E7000003781BB94BB2002BC8BF01705C +:102D30007047000000787047F8B50C46C96907462F +:102D400011B9238C002B37D1257E1F2D34D838782C +:102D500028BB228C072A2CD8268A36F003032BD1D5 +:102D60004FF6FF70FFF7D0FD20F001003102400464 +:102D700041EA0561400C41EA40254FF6FF722346C7 +:102D800029463846FFF7FCFE002807DD6269137804 +:102D90000133DBB21F2B88BF00231370F8BD218ADB +:102DA0002D0645EA012505432046FFF71DFE024694 +:102DB000E5E76FF00300F1E76FF00100EEE70000D8 +:102DC00070B58AB0044616460021282268461D4682 +:102DD000FEF706FBBDF83830ADF810300F9B0593B9 +:102DE0009DF840308DF81830119B07936946BDF867 +:102DF0004830ADF820302046CDE90265FFF79CFF52 +:102E00000AB070BD2DE9F041D36905460C4616465F +:102E10000BB9138C5BBB377E1F2F28D895F8008029 +:102E2000B8F1000F26D03046FFF7DEFD33782102DF +:102E300041EAC33141EA0801338A41EA076141EAC4 +:102E400003410246334641F080012846FFF798FED1 +:102E500000280ADD3378012B07D17269137801331A +:102E6000DBB21F2B88BF00231370BDE8F0816FF029 +:102E70000100FAE76FF00300F7E70000F0B58BB050 +:102E800004460D4617460021282268461E46FEF7D6 +:102E9000A7FA9DF84C305A1E534253418DF800302A +:102EA0009DF84030ADF81030119B05939DF84830E7 +:102EB0008DF81830149B07936A46BDF85430ADF86E +:102EC000203029462046CDE90276FFF79BFF0BB064 +:102ED000F0BD0000406A00B104307047436A1A68D0 +:102EE000426202691A600361C38A013BC382704770 +:102EF0002DE9F041D0F82080194E14461D46414678 +:102F0000002709B9BDE8F081D1E90223A21A65EBD7 +:102F10000303964277EB03031ED2036A8B420DD163 +:102F2000FFF78CFD036A1B68036203690B60C38AA9 +:102F30000161016A013BC3828846E2E7FFF77EFD3B +:102F40000B68C8F8003003690B60C38A0161013B5C +:102F5000C382D8F80010D4E788460968D1E700BFDB +:102F600080841E002DE9F04F8BB00D46DDF85090A7 +:102F700014469B468046002800F01981B9F1000FE5 +:102F800000F01581531E3F2B00F21181012A03D15D +:102F9000BBF1000F40F00B810023CDE90833B8F8F6 +:102FA0001430B5EBC30F4FEAC30703D300200BB0B7 +:102FB000BDE8F08F2B199F42D8F80C303ABF7F1B29 +:102FC000FFB227461BB9D8F81030002B7AD0272D36 +:102FD0004ED8C5F12806B7424FF000032CBFF6B219 +:102FE0003E4600932946D8F8080008AB3246FFF762 +:102FF00041FCA7EB060A35445FFA8AFAB8F81430A8 +:1030000003F10053053BDB000493D8F80C30039325 +:103010002821039B13B1BAF1000F2CD1D8F810006E +:1030200040B1BAF1000F05D0009608AB5246691ABC +:10303000FFF720FC38B2002FB8D066070AD00AABE1 +:1030400003EBD401624211F8083C02F0070213417D +:1030500001F8083C082C3CD9102C40F2B580202CFB +:1030600040F2B780BBF1000F00F09C80082334E0F1 +:10307000BA460026C2E7049BE02B28BFE023069354 +:103080000B44AB42059314D95A1B03980096924502 +:1030900034BF5246D2B2691A08AB04300792FFF728 +:1030A000E9FB079A1644AAEB020A1544F6B25FFA46 +:1030B0008AFA049B069A05999B1A0493039B1B6842 +:1030C0000393A6E70093D8F8080008AB3A462946D0 +:1030D000AEE7BBF1000F13D00123B4EBC30F6CD0EC +:1030E000082C12D89DF82030621E23FA02F2D50770 +:1030F00006D54FF0FF3202FA04F423438DF8203056 +:103100009DF8203089F8003051E7102C12D8BDF816 +:103110002030621E23FA02F2D10706D54FF0FF32AB +:1031200002FA04F42343ADF82030BDF82030A9F8AA +:1031300000303CE7202C0FD80899631E21FA03F3D6 +:10314000DA0705D54FF0FF3202FA04F40C43089475 +:10315000089BC9F800302AE7402C2BD0DDE9086530 +:10316000611EC4F12102A4F1210326FA01F105FA3E +:1031700002F225FA03F311431943CB0712D50122BA +:10318000A4F12003C4F1200102FA03F322FA01F1B1 +:10319000A240524243EA010363EB430332432B4311 +:1031A000CDE90823DDE90823C9E90023FFE66FF034 +:1031B0000100FCE66FF00800F9E6082CA0D9102CFD +:1031C000B3D9202CEED8C3E7BBF1000FADD002235A +:1031D00083E7BBF1000FBBD004237EE730B5012AA3 +:1031E000144638BF0124402C85B028BF4024002558 +:1031F000012ACDE9025518D81B788DF808306307ED +:103200000AD004AB03EBD405624215F8083C02F087 +:103210000702934005F8083C00910346224600212E +:1032200002A8FFF727FB05B030BD082AE4D9102A11 +:1032300003D81B88ADF80830E1E7202A8DBFD3E919 +:1032400000231B680293CDE90223D8E710B5CB68B1 +:103250001BB98B600B618B8210BD04691A681C60FE +:103260000361C38A013BC382CA60F0E703064CBF17 +:10327000C0F3C0300220704708B50246FFF7F6FFE2 +:10328000022806D15306C2F30F2001D100F003003B +:1032900008BDC2F30740FBE72DE9F04F93B0CDE93D +:1032A00003230A6804461046FFF7E0FF022814BF14 +:1032B000C2F306260026002A0D46824680F2F281DD +:1032C00012F0C04940F0EE81097B002900F0EA814C +:1032D000022803D02378B34240F0E781C2F30463AD +:1032E0000693104602F07F030593FFF7C5FF059B89 +:1032F00029444FEA834848EA0A4848EA4668CE78B3 +:1033000000230022CDE90823F309834648EA000898 +:10331000029367D0059B009302466768534608A94D +:103320002046B847002800F0C381276A4FB94146BC +:1033300004F10C00FFF702FB074690B96FF00200A2 +:1033400054E03B6998450DD03F68002FF9D14146C4 +:1033500004F10C00FFF7F2FA07460028EED0236ACA +:103360003B60276297F817C006F01F08CCF3840C67 +:10337000ACEB08001FFA80FE0028B8BF0EF1200059 +:10338000A8EB0C031FFA83FED7E90221B8BF00B2F5 +:10339000002B0793BEBF0EF120031BB2079352EA26 +:1033A000010338D0039BDFF824E39A1A049B4FF003 +:1033B000000C63EB010196457CEB01032BD36B7B87 +:1033C00097F81AE0734519D1029B002B78D0012899 +:1033D00021DC7868F8B9DFF8F0C2944570EB01039E +:1033E00016D337E0276A27B96FF00C0013B0BDE899 +:1033F000F08F3B699845B5D03F68F4E7B2489042FA +:103400007CEB010301D30020F0E7029B002BFAD0F4 +:10341000079B0F2B17DCFA7DB30002F0030203F0C9 +:103420007C031343FB7539462046FFF707FB6B7B94 +:10343000BB76029B3BB9FB7DC3F38402013262F38E +:103440008603FB75D0E76A7BBB7E9A42DBD1029B89 +:10345000002B35D0B309022B32D0039BBB60049BF9 +:10346000FB60142200210DA8FDF7BAFF039B0A930D +:10347000049B0B932B1D0C932B7BADF83EB0013BB3 +:10348000DBB2ADF83C30069B8DF84230059B8DF8E1 +:10349000433094F82C308DF840A083F001038DF870 +:1034A00044308DF84180A3680AA920469847FB7DE7 +:1034B000C3F38403013303F01F039B02FB82A2E7E3 +:1034C000FB7DC6F34012B2EBD31F40F0F480C3F390 +:1034D0008403434540F0F280029A2B7BB609002A10 +:1034E0004DD0F2075DD4032B40F2EB80039BBB6011 +:1034F000049BFB602B7BAE1D033BDBB2324639469F +:1035000004F10C00FFF7ACFA00280CDA394620462B +:10351000FFF794FAFB7DC3F38403013303F01F0329 +:103520009B02FB820AE7DDE90884AB883B834FF608 +:10353000FF73C9F12000A9F1200228FA09F104FA69 +:1035400000F0014324FA02F211431846C9B2FFF712 +:10355000C9F909F10809B9F1400F0346E9D1B88268 +:103560002A7B033AD2B23146FFF7CEF9FB7DB8820F +:10357000DA43C2F3C01262F3C713FB7543E786B99F +:103580002E1D013BDBB23246394604F10C00FFF739 +:1035900067FA0028BADB2A7BB88A013AD2B23146F0 +:1035A000E2E7F98AC1F30901013B0429DAB25BD8E9 +:1035B000281D002307F11B069A4208D910F801CBF9 +:1035C00006F801C0013101330529DBB2F4D10399BA +:1035D0000A9104990B91934207F11B010C9138BF9A +:1035E000043379680D9134BF55FA83F300230E93A9 +:1035F000FB8AADF83EB0C3F309031A44069B8DF86D +:103600004230059B8DF8433094F82C30ADF83C20C7 +:1036100083F001038DF8443000238DF840A08DF82D +:1036200041807B602A7BB88A013A291DFFF76CF93B +:103630003B8BB882834203D1A3680AA920469847EE +:1036400020460AA9FFF702FEFB7DBA8AC3F3840372 +:10365000013303F01F039B02FB823B8B9A420CBF9A +:1036600000206FF01000C1E67B68002BAFD0052072 +:1036700001E01C3033461E68002EFAD1091A081DDD +:103680002E1D184401EB090CBCF11B0F5FFA89F3E6 +:103690009DD89A429BD916F8013B00F8013B09F1ED +:1036A0000109EFE76FF00900A0E66FF00A009DE660 +:1036B0006FF00B009AE66FF00D0097E66FF00E00CA +:1036C00094E66FF00F0091E640420F0080841E00E8 +:1036D000EFF3098305494A6B22F001024A6368331C +:1036E00083F30988002383F31188704700EF00E01B +:1036F000302080F3118862B60C4B0D4AD96821F452 +:10370000E0610904090C0A43DA60D3F8FC20094996 +:1037100042F08072C3F8FC200A6842F001020A609D +:103720002022DA7783F82200704700BF00ED00E026 +:103730000003FA05001000E010B5302383F3118870 +:103740000E4B5B6813F4006314D0F1EE103AEFF304 +:103750000984683C4FF08073E361094BDB6B23669F +:1037600084F3098800F090F810B1064BA36110BDF6 +:10377000054BFBE783F31188F9E700BF00ED00E09C +:1037800000EF00E0430600084606000800F1604331 +:1037900003F561430901C9B283F80013012200F067 +:1037A0001F039A4043099B0003F1604303F5614303 +:1037B000C3F880211A60704700230375826803698B +:1037C0001B6899689142FBD25A680360426010609E +:1037D0005860704700230375826803691B68996805 +:1037E0009142FBD85A68036042601060586070478D +:1037F00008B50846302383F311880B7D032B05D0D1 +:10380000042B0DD02BB983F3118808BD8B690022DE +:103810001A604FF0FF338361FFF7CEFF0023F2E71A +:10382000D1E9003213605A60F3E70000FFF7C4BF2C +:10383000054BD9680875186802681A605360012240 +:103840000275D860FCF7E8BE204A002030B50C4B6A +:10385000DD684B1C87B004460FD02B46094A6846EA +:1038600000F06CF92046FFF7E3FF009B13B16846B8 +:1038700000F06EF9A86907B030BDFFF7D9FFF9E78E +:10388000204A0020F1370008044B1A68DB68906872 +:103890009B68984294BF002001207047204A002076 +:1038A000084B10B51C68D86822681A605360012262 +:1038B0002275DC60FFF78EFF01462046BDE8104010 +:1038C000FCF7AABE204A0020044B1A68DB68926805 +:1038D0009B689A4201D9FFF7E3BF7047204A002056 +:1038E00038B5074C07490848012300252370656057 +:1038F00000F03AFC0223237085F3118838BD00BF25 +:10390000884C0020444E0008204A002008B572B6BA +:10391000044B186500F0ECFA00F0A0FB024B032208 +:103920001A70FEE7204A0020884C002000F046B9BB +:10393000EFF3118020B9EFF30583302282F3118871 +:103940007047000010B530B9EFF30584C4F30804E4 +:1039500014B180F3118810BDFFF7B6FF84F311880E +:10396000F9E700008B60022308618B8208467047EC +:103970008368A3F1840243F8142C026943F8442CB1 +:10398000426943F8402C094A43F8242CC26843F8A2 +:10399000182C022203F80C2C002203F80B2C044AEA +:1039A00043F8102CA3F12000704700BF3106000837 +:1039B000204A002008B5FFF7DBFFBDE80840FFF70D +:1039C00035BF0000024BDB6898610F20FFF730BF66 +:1039D000204A0020302383F31188FFF7F3BF000053 +:1039E00008B50146302383F311880820FFF72EFF26 +:1039F000002383F3118808BD064BDB6839B14268A8 +:103A000018605A60136043600420FFF71FBF4FF037 +:103A1000FF307047204A00200368984206D01A6899 +:103A20000260506099611846FFF700BF70470000C0 +:103A300010B503689C68A2420CD85C688A600B6071 +:103A40004C602160596099688A1A9A604FF0FF3380 +:103A5000836010BD1B68121BECE700000A2938BF09 +:103A60000A2170B504460D460A26601900F076FB5F +:103A700000F062FB041BA54203D8751C2E460446C9 +:103A8000F3E70A2E04D9BDE87040012000F0ACBB7A +:103A900070BD0000F8B5144B0D46D96103F110015B +:103AA00041600A2A1969826038BF0A2201604860B1 +:103AB0001861A818144600F043FB0A2700F03CFBED +:103AC000431BA342064606D37C1C281900F046FB84 +:103AD00027463546F2E70A2F04D9BDE8F840012011 +:103AE00000F082BBF8BD00BF204A0020F8B50646B2 +:103AF0000D4600F021FB0F4A134653F8107F9F42FA +:103B000006D12A4601463046BDE8F840FFF7C2BF5D +:103B1000D169BB68441A2C1928BF2C46A34202D98C +:103B20002946FFF79BFF224631460348BDE8F8408F +:103B3000FFF77EBF204A0020304A002010B4C0E9C1 +:103B4000032300235DF8044B4361FFF7CFBF000060 +:103B500010B5194C236998420DD0D0E90032816824 +:103B600013605A609A680A449A60002303604FF019 +:103B7000FF33A36110BD2346026843F8102F536042 +:103B80000022026022699A4203D1BDE8104000F091 +:103B9000DFBA936881680B44936000F0CDFA226924 +:103BA000E1699268441AA242E4D91144BDE8104088 +:103BB000091AFFF753BF00BF204A00202DE9F04744 +:103BC000DFF8BC8008F110072C4ED8F8105000F038 +:103BD000B3FAD8F81C40AA68031B9A423ED8144492 +:103BE000D5E900324FF00009C8F81C4013605A6054 +:103BF000C5F80090D8F81030B34201D100F0A8FA0F +:103C000089F31188D5E9033128469847302383F397 +:103C100011886B69002BD8D000F08EFA6A69A0EB8E +:103C200004094A4582460DD2022000F0DDFA002246 +:103C3000D8F81030B34208D151462846BDE8F047C5 +:103C4000FFF728BF121A2244F2E712EB090938BF26 +:103C50004A4629463846FFF7EBFEB5E7D8F810305C +:103C6000B34208D01444211AC8F81C00A960BDE86A +:103C7000F047FFF7F3BEBDE8F08700BF304A0020F1 +:103C8000204A002000207047FEE700007047000037 +:103C90004FF0FF3070470000BFF34F8F024AD368E8 +:103CA000DB03FCD4704700BF003C024008B5094B61 +:103CB0001B7873B9FFF7F0FF074B1A69002ABFBFE3 +:103CC000064A5A6002F188325A601A6822F4806209 +:103CD0001A6008BD904C0020003C0240230167455B +:103CE00008B50B4B1B7893B9FFF7D6FF094B1A6940 +:103CF00042F000421A611A6842F480521A601A684F +:103D000022F480521A601A6842F480621A6008BD78 +:103D1000904C0020003C02400728F0B516D80C4C0F +:103D20000C4923787BB90C4D0E4608234FF00062F6 +:103D300055F8047B46F8042B013B13F0FF033A448B +:103D4000F6D10123237051F82000F0BD0020FCE7DC +:103D5000B44C0020944C0020504E0008014B53F806 +:103D600020007047504E000808207047072810B503 +:103D7000044601D9002010BDFFF7CEFF064B53F8D3 +:103D800024301844C21A0BB90120F4E7126801323A +:103D9000F0D1043BF6E700BF504E0008072810B5ED +:103DA000044621D8FFF778FFFFF780FF0F4AF3237F +:103DB000D360C300DBB243F4007343F0020313612A +:103DC000136943F480331361FFF766FFFFF7A4FF25 +:103DD000074B53F8241000F03DF9FFF781FF204610 +:103DE000BDE81040FFF7C2BF002010BD003C0240FC +:103DF000504E0008F8B512F00103144642D1851860 +:103E00002E4A954257D82E4B1B6813F0010352D00F +:103E10002C4DFFF74BFFF323EB60FFF73DFF40F224 +:103E20000127032C15D824F001046618254C401AEC +:103E300040F20117B142236900EB010524D123F0C0 +:103E400001032361FFF74CFF0120F8BD043C04305F +:103E5000E7E78307E7D12B6923F440732B612B69D4 +:103E60003B432B6151F8046B0660BFF34F8FFFF7A4 +:103E700013FF03689E42E9D02B6923F001032B61F5 +:103E8000FFF72EFF0020E0E723F44073236123694E +:103E90003B4323610B882B80BFF34F8FFFF7FCFE62 +:103EA0002D8831F8023BADB2AB42C3D0236923F079 +:103EB00001032361E4E71846C7E700BF00000808D4 +:103EC00000380240003C0240084908B50B7828B190 +:103ED0001BB9FFF7EBFE01230B7008BD002BFCD0D4 +:103EE000BDE808400870FFF7FBBE00BF904C002003 +:103EF0004FF480214FF0005000F0AEB80846114654 +:103F000000F0AEBE012000F0ABBE0000084600F09D +:103F1000C5BE000070B582B0FFF70AFD0E4E054623 +:103F200000F00AF93268904237BF0C4A0B495168D9 +:103F300014682EBFD1E900410131516004190346D4 +:103F400041F10001284601913360FFF7FBFC019924 +:103F5000204602B070BD00BFB84C0020C04C00200D +:103F600070B582B0FFF7E4FC104E054600F0E4F8AF +:103F70003268904237BF0E4A0D49516814682EBF0F +:103F8000D1E9004101315160041941F100010346BA +:103F9000284601913360FFF7D5FC01994FF47A72FE +:103FA00000232046FCF724F902B070BDB84C002075 +:103FB000C04C002010B50244064BD2B2904200D152 +:103FC00010BD441C00B253F8200041F8040BE0B2CD +:103FD000F4E700BF502800400F4B30B51C6F24049D +:103FE00007D41C6F44F400741C671C6F44F4004435 +:103FF0001C670A4C236843F4807323600244084B17 +:10400000D2B2904200D130BD441C00B251F8045BE2 +:1040100043F82050E0B2F4E700380240007000405E +:104020005028004007B5012201A90020FFF7C2FF78 +:10403000019803B05DF804FB13B50446FFF7F2FFE7 +:10404000A04205D0012201A900200194FFF7C4FF7E +:1040500002B010BD704700007047000070470000BC +:10406000074B45F255521A6002225A6040F6FF7221 +:104070009A604CF6CC421A60024B01221A707047CB +:1040800000300040CC4C0020034B1B781BB1034B8D +:104090004AF6AA221A607047CC4C0020003000403B +:1040A000034B1A681AB9034AD2F874281A60704789 +:1040B000C84C002000300240024B4FF08072C3F821 +:1040C000742870470030024008B5FFF7E9FF024B43 +:1040D0001868C0F3407008BDC84C002008B5FFF751 +:1040E000DFFF024B1868C0F3007008BDC84C002009 +:1040F00070470000FEE700000A4B0B480B4A904255 +:104100000BD30B4BDA1C121AC11E22F003028B4296 +:1041100038BF00220021FDF763B953F8041B40F8B3 +:10412000041BECE710500008C44F0020C44F0020CF +:10413000C44F002000F0CAB84FF08043586A70475F +:104140004FF08043002258631A610222DA60704700 +:104150004FF080430022DA60704700004FF0804348 +:1041600058637047FEE7000070B51B4B01630025E4 +:10417000044686B0586085620E46FFF7B9FA04F12E +:104180001003C4E904334FF0FF33C4E90635C4E932 +:104190000044A560E562FFF7CFFF2B460246C4E965 +:1041A000082304F134010D4A256580232046FFF7DA +:1041B000D9FB0123E0600A4A0375009272680192FC +:1041C000B268CDE90223074B6846CDE90435FFF715 +:1041D000F1FB06B070BD00BF884C0020704E000897 +:1041E000754E000865410008024AD36A1843D06240 +:1041F000704700BF204A00204B6843608B68836093 +:10420000CB68C3600B6943614B6903628B6943628E +:104210000B6803607047000008B5234B23481A69F8 +:1042200042F0FF021A611A6922F0FF021A611A694C +:104230001A6B42F0FF021A631A6D42F0FF021A6510 +:104240001B4A1B6D1146FFF7D7FF02F11C0100F559 +:104250008060FFF7D1FF02F1380100F58060FFF7C1 +:10426000CBFF02F1540100F58060FFF7C5FF02F1BA +:10427000700100F58060FFF7BFFF02F18C0100F5CF +:104280008060FFF7B9FF02F1A80100F58060FFF739 +:10429000B3FF02F1C40100F58060FFF7ADFFBDE898 +:1042A000084000F08DB800BF003802400000024016 +:1042B0007C4E000808B500F019FAFFF711FBBDE8C5 +:1042C0000840FFF7EDBE0000704700000F4B1A6C6E +:1042D00042F001021A641A6E42F001021A660C4A98 +:1042E0001B6E936843F0010393604FF080433122CB +:1042F0009A624FF0FF32DA6200229A615A63DA6002 +:104300005A6001225A611A60704700BF00380240AB +:10431000002004E04FF0804208B51169D3680B40DB +:10432000D9B2C9439B07116107D5302383F31188A4 +:10433000FFF7FCFA002383F3118808BD1E4B1A69AE +:1043400062F0FF021A611A69D2B21A614FF0FF30AF +:104350001A695A69586100215A6959615A691A6A79 +:1043600062F080521A621A6A02F080521A621A6A65 +:104370005A6A58625A6A59625A6A1A6C42F08052F2 +:104380001A641A6E42F080521A661A6E0B4A10684E +:1043900040F480701060186F00F44070B0F5007F3A +:1043A0001EBF4FF4803018671967536823F40073F9 +:1043B000536000F073B900BF003802400070004045 +:1043C0003B4B3C4A1A643C4A4FF4404111601A6826 +:1043D00042F001021A601A689007FCD59A6822F030 +:1043E00003029A60324B9A6812F00C02FBD11968F2 +:1043F00001F0F90119609A601A6842F480321A607B +:104400001A689103FCD55A6F42F001025A67284B93 +:104410005A6F9207FCD5294A5A601A6842F0807296 +:104420001A60254A53685804FCD5214B1A6891013B +:10443000FCD5234AC3F884201A6842F080621A60CF +:104440001A681201FCD51F4A9A600322C3F88C2017 +:104450004FF00062C3F894201B4B1A681B4B9A4222 +:104460001B4B21D11B4A11681B4A91421CD140F2BF +:1044700003121A60164A136803F00F03032BFAD1D4 +:104480000B4B9A6842F002029A609A6802F00C02A2 +:10449000082AFAD15A6C42F480425A645A6E42F4A5 +:1044A00080425A665B6E704740F20372E1E700BFDC +:1044B000003802400004001000700040041940025F +:1044C0000830002400948838002004E011640020A3 +:1044D000003C024000ED00E041C20F41074A08B530 +:1044E000536903F00103536123B1054A13680BB10B +:1044F00050689847BDE80840FFF71EB9003C0140EE +:10450000D04C0020074A08B5536903F002035361F9 +:1045100023B1054A93680BB1D0689847BDE80840BD +:10452000FFF70AB9003C0140D04C0020074A08B50B +:10453000536903F00403536123B1054A13690BB1B6 +:1045400050699847BDE80840FFF7F6B8003C0140C5 +:10455000D04C0020074A08B5536903F008035361A3 +:1045600023B1054A93690BB1D0699847BDE808406B +:10457000FFF7E2B8003C0140D04C0020074A08B5E4 +:10458000536903F01003536123B1054A136A0BB159 +:10459000506A9847BDE80840FFF7CEB8003C01409C +:1045A000D04C0020164B10B55C6904F478725A6147 +:1045B000A30604D5134A936A0BB1D06A98476006E4 +:1045C00004D5104A136B0BB1506B9847210604D5E4 +:1045D0000C4A936B0BB1D06B9847E20504D5094A9E +:1045E000136C0BB1506C9847A30504D5054A936C26 +:1045F0000BB1D06C9847BDE81040FFF79DB800BFE5 +:10460000003C0140D04C0020194B10B55C6904F40B +:104610007C425A61620504D5164A136D0BB1506D88 +:104620009847230504D5134A936D0BB1D06D984775 +:10463000E00404D50F4A136E0BB1506E9847A104E5 +:1046400004D50C4A936E0BB1D06E9847620404D522 +:10465000084A136F0BB1506F9847230404D5054ADD +:10466000936F0BB1D06F9847BDE81040FFF764B867 +:10467000003C0140D04C002008B5034800F0E8F8A9 +:10468000BDE80840FFF758B8504D002008B5FFF7C7 +:1046900041FEBDE80840FFF74FB80000062108B50D +:1046A0000846FFF773F806210720FFF76FF8062189 +:1046B0000820FFF76BF806210920FFF767F80621AD +:1046C0000A20FFF763F806211720FFF75FF806219D +:1046D0002820FFF75BF807211C20FFF757F8BDE8FB +:1046E00008400C212620FFF751B8000008B5FFF75D +:1046F00025FE00F07BF800F03DF8FFF7E5FDBDE892 +:104700000840FFF717BD00000268436811430160CD +:1047100003B1184770470000143000F0C5B900001D +:104720004FF0FF33143000F0BFB90000383000F014 +:104730003BBA00004FF0FF33383000F035BA0000CC +:10474000143000F08BB900004FF0FF31143000F04E +:1047500085B90000383000F0E5B900004FF0FF32B5 +:10476000383000F0DFB90000012914BF6FF01300EA +:104770000020704700F058B837B515460E4A026061 +:1047800000224260C0E902220122044602740B4664 +:10479000009000F15C014FF48072143000F034F9A5 +:1047A00000942B464FF4807204F5AE7104F138008A +:1047B00000F0ACF903B030BD5C4F000838B5C369F8 +:1047C00004460D461BB904210844FFF79DFF294606 +:1047D00004F1140000F026F9002806DA201D4FF439 +:1047E0000061BDE83840FFF78FBF38BD0023054AA0 +:1047F00019460133102BC2E9001102F10802F8D169 +:10480000704700BFD04C002002684368114301602C +:1048100003B1184770470000024AD36843F0C00351 +:10482000D36070470044004010B5054C054A002194 +:104830002046FFF7A1FF044A044BC4E9972310BDAB +:10484000504D0020194800080044004040787D0188 +:104850002DE9F041D0F85C62F7683368DA05044668 +:104860009DB20DD5302383F311884FF4806104305D +:10487000FFF7CAFF6FF480733360002383F311885E +:10488000302383F3118804F1040815F02F033AD183 +:1048900083F31188380615D5290613D5302383F301 +:1048A000118804F1380000F065F900284EDA08217B +:1048B000201DFFF7A9FF4FF67F733B40F3600023F5 +:1048C00083F311887A0616D56B0614D5302383F34B +:1048D0001188D4E913239A420AD1236C43B127F0FB +:1048E00040073F041021201D3F0CFFF78DFFF760AC +:1048F000002383F31188D4F86822D36843B3BDE85A +:10490000F041106918472B0714D015F0080F0CBFA1 +:1049100000214FF48071E80748BF41F02001AA0749 +:1049200048BF41F040016B0748BF41F0800140465D +:10493000FFF76AFFAD06736805D594F86412204648 +:104940001940FFF73BFF3568ADB29EE77060B6E7F0 +:10495000BDE8F081F8B5154682680669AA420B46A3 +:10496000816938BF8568761AB54204460BD218466D +:104970002A46FCF723FDA3692B44A361A3685B1BB4 +:10498000A3602846F8BD0CD918463246FCF716FD40 +:10499000AF1BE1683A463044FCF710FDE3683B4446 +:1049A000EBE718462A46FCF709FDE368E5E7000057 +:1049B00083689342F7B51546044638BF8568D0E949 +:1049C0000460361AB5420BD22A46FCF7F7FC63693D +:1049D0002B446361A36828465B1BA36003B0F0BD52 +:1049E0000DD932460191FCF7E9FC0199E068AF1B53 +:1049F0003A463144FCF7E2FCE3683B44E9E72A46E7 +:104A0000FCF7DCFCE368E4E710B50A440024C3616A +:104A1000029B8460C0E90000C0E90511C160026129 +:104A2000036210BD08B5D0E90532934201D1826816 +:104A300082B98268013282605A1C42611970D0E9E1 +:104A400004329A4224BFC36843610021FEF7E4FFA9 +:104A5000002008BD4FF0FF30FBE7000070B53023A9 +:104A600004460E4683F31188A568A5B1A368A26920 +:104A7000013BA360531CA36115782269934224BFB4 +:104A8000E368A361E3690BB120469847002383F3F1 +:104A90001188284607E031462046FEF7ADFF002882 +:104AA000E2DA85F3118870BD2DE9F74F04460E4612 +:104AB00017469846D0F81C904FF0300A8AF31188B8 +:104AC0004FF0000B154665B12A4631462046FFF7E8 +:104AD00041FF034660B941462046FEF78DFF00289E +:104AE000F1D0002383F31188781B03B0BDE8F08F69 +:104AF000B9F1000F03D001902046C847019B8BF30A +:104B00001188ED1A1E448AF31188DCE7C0E905110B +:104B1000C160C3611144009B8260C0E90000016173 +:104B200003627047F8B504460D461646302383F3FA +:104B30001188A768A7B1A368013BA36063695A1CE9 +:104B400062611D70D4E904329A4224BFE368636154 +:104B5000E3690BB120469847002080F3118807E0F5 +:104B600031462046FEF748FF0028E2DA87F3118835 +:104B7000F8BD0000D0E905239A4210B501D1826842 +:104B80007AB98268013282605A1C82611C7803699A +:104B90009A4224BFC36883610021FEF73DFF20468F +:104BA00010BD4FF0FF30FBE72DE9F74F04460E46EE +:104BB00017469846D0F81C904FF0300A8AF31188B7 +:104BC0004FF0000B154665B12A4631462046FFF7E7 +:104BD000EFFE034660B941462046FEF70DFF002870 +:104BE000F1D0002383F31188781B03B0BDE8F08F68 +:104BF000B9F1000F03D001902046C847019B8BF309 +:104C00001188ED1A1E448AF31188DCE70B46014631 +:104C1000184600F02DB8000000F040B8012838BF59 +:104C2000012010B50446204600F030F830B900F0FD +:104C300007F808B900F00CF88047F4E710BD000051 +:104C4000024B1868BFF35B8F704700BFBC4F00205A +:104C500008B5062000F084F80120FFF715F80000E1 +:104C6000024B0A4601461868FFF748B91C2300208A +:104C700010B5054C13462CB10A4601460220AFF38D +:104C8000008010BD2046FCE700000000024B0146FA +:104C90001868FFF737B900BF1C230020024B0146FC +:104CA0001868FFF733B900BF1C23002010B5013985 +:104CB0000244904201D1002005E0037811F8014F31 +:104CC000A34201D0181B10BD0130F2E72DE9F041DD +:104CD000A3B1C91A17780144044603F1FF3C8C4282 +:104CE000204601D9002009E00578BD4204F1010405 +:104CF000F5D10CEB0405D618A54201D1BDE8F08131 +:104D000015F8018D16F801EDF045F5D0E7E7000044 +:104D10001F2938B504460D4604D9162303604FF009 +:104D2000FF3038BD426C12B152F821304BB92046E9 +:104D300000F030F82A4601462046BDE8384000F031 +:104D400017B8012B0AD0591C03D116230360012088 +:104D5000E7E7002442F82540284698470020E0E78E +:104D6000024B01461868FFF7D3BF00BF1C23002089 +:104D700038B5074D00230446084611462B60FEF760 +:104D800087FF431C02D12B6803B1236038BD00BFED +:104D9000C04F0020FEF776BF034611F8012B03F841 +:104DA000012B002AF9D170476F72672E617264750A +:104DB00070696C6F742E41524B5F52544B5F475079 +:104DC0005300000040A2E4F1646891060041A3E5AD +:104DD000F2656992070000004261642043414E4938 +:104DE0006661636520696E6465782E00800000004E +:104DF00000800000000080000000000000000000B3 +:104E0000411C00082924000889230008511C0008BF +:104E1000851C0008811E0008551C0008651C000840 +:104E2000591C0008611C00085D1C0008A91D000831 +:104E3000691C0008F5260008791C00087D1D000883 +:104E400063300000404E0008784A0020884C002063 +:104E50000040000000400000004000000040000052 +:104E6000000001000000020000000200000002003B +:104E70006D61696E0069646C65000000A000902A95 +:104E800000000000AAAAAAAA50000024FFFB00000C +:104E900000770000009009000100000500000000FC +:104EA000AAAAAAA501000080FFCF00000000000010 +:104EB000000000000000000000000000AAAAAAAA4A +:104EC00000000000FFFF00000000000000000000E4 +:104ED0000000000000000000AAAAAAAA000000002A +:104EE000FFFF0000000000000000000000000000C4 +:104EF00000000000AAAAAAAA00000000FFFF00000C +:104F000000000000000000000000000000000000A1 +:104F1000AAAAAAAA00000000FFFF000000000000EB +:104F2000000000000000000000000000AAAAAAAAD9 +:104F300000000000FFFF0000000000000000000073 +:104F400000000000000000000A0000000000000057 +:104F5000030000000000000000000000000000004E +:104F600035470008214700085D4700084947000809 +:104F700055470008414700082D4700081947000819 +:104F8000694700089CB2FF7F01000000000000009C +:104F900052000000000000000000070000000000B8 +:104FA00040420F00FE2A0100D2040000202300200E +:104FB00000000000000000000000000000000000F1 +:104FC00000000000000000000000000000000000E1 +:104FD00000000000000000000000000000000000D1 +:104FE00000000000000000000000000000000000C1 +:104FF00000000000000000000000000000000000B1 +:1050000000000000000000000000000000000000A0 :00000001FF diff --git a/Tools/bootloaders/AeroFox-Airspeed-DLVR_bl.bin b/Tools/bootloaders/AeroFox-Airspeed-DLVR_bl.bin index 52a8d08b19330c..6ecf3bd9743e61 100755 Binary files a/Tools/bootloaders/AeroFox-Airspeed-DLVR_bl.bin and b/Tools/bootloaders/AeroFox-Airspeed-DLVR_bl.bin differ diff --git a/Tools/bootloaders/AeroFox-Airspeed_bl.bin b/Tools/bootloaders/AeroFox-Airspeed_bl.bin index cf1c41f5dede97..03d0aecf8a2425 100755 Binary files a/Tools/bootloaders/AeroFox-Airspeed_bl.bin and b/Tools/bootloaders/AeroFox-Airspeed_bl.bin differ diff --git a/Tools/bootloaders/AeroFox-GNSS_F9P_bl.bin b/Tools/bootloaders/AeroFox-GNSS_F9P_bl.bin index 302e89c7cf4ac3..c83805c9feb01f 100755 Binary files a/Tools/bootloaders/AeroFox-GNSS_F9P_bl.bin and b/Tools/bootloaders/AeroFox-GNSS_F9P_bl.bin differ diff --git a/Tools/bootloaders/AeroFox-PMU_bl.bin b/Tools/bootloaders/AeroFox-PMU_bl.bin index 69d9f3b68e7131..359a9d498bb3c8 100755 Binary files a/Tools/bootloaders/AeroFox-PMU_bl.bin and b/Tools/bootloaders/AeroFox-PMU_bl.bin differ diff --git a/Tools/bootloaders/BETAFPV-F405_bl.bin b/Tools/bootloaders/BETAFPV-F405_bl.bin new file mode 100644 index 00000000000000..bbc0f20d09e28b Binary files /dev/null and b/Tools/bootloaders/BETAFPV-F405_bl.bin differ diff --git a/Tools/bootloaders/BETAFPV-F405_bl.hex b/Tools/bootloaders/BETAFPV-F405_bl.hex new file mode 100644 index 00000000000000..be0553cc247074 --- /dev/null +++ b/Tools/bootloaders/BETAFPV-F405_bl.hex @@ -0,0 +1,898 @@ +:020000040800F2 +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E3010008B52F000820 +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E30100085D3200088532000872 +:10006000AD320008D5320008FD320008E301000877 +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E3010008253300083C +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B000F9330008E3010008E3010008E301000848 +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E00089330008E3010008E3010008E301000888 +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E30100086927000853 +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F01F054FF1D +:1002500002F04EFE4FF055301F491B4A91423CBF01 +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE701F032FF02F07CFEAC +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E701F01ABF00060020002200204D +:1002D0000000000808ED00E00000002000060020FB +:1002E000C0370008002200204022002040220020C9 +:1002F000602E0020E0010008E0010008E001000895 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F082FAFEE701F07C +:10033000EBF900DFFEE7000038B500F061FB01F0EB +:10034000ABFE054601F0CEFE0446D8B90F4B9D42E8 +:100350001AD001339D4218BF044641F2883504BFCC +:1003600001240025002001F0A1FE0CB100F076F878 +:1003700000F0EAFC00F09AFB284600F0B7F800F025 +:100380006DF8F9E70025EDE70546EBE7010007B05A +:1003900008B500F05DFBA0F120035842584108BDAC +:1003A00007B541F21203022101A8ADF8043000F0B4 +:1003B0006DFB03B05DF804FB38B5302383F311887F +:1003C000174803680BB101F0FFFA164A14480023DE +:1003D0004FF47A7101F0EEFA002383F31188124C86 +:1003E000236813B12368013B2360636813B163681A +:1003F000013B63600D4D2B7833B963687BB90220F4 +:1004000000F01CFC322363602B78032B07D1636858 +:100410002BB9022000F012FC4FF47A73636038BDF0 +:1004200040220020B9030008602300205822002049 +:10043000084B187003280CD8DFE800F00805020804 +:10044000022000F0F3BB022000F0E6BB024B0022CA +:100450005A60704758220020602300201F4B204A1A +:1004600010B51C461968013136D004339342F9D1D6 +:100470006268A24230D31B4B9B6803F1006303F513 +:1004800040439A4228D2002000F02AFB0220FFF7C6 +:10049000CFFF154B1A6C00221A64196E1A66196E7A +:1004A000596C5A64596E5A665A6E1A6942F0005273 +:1004B0001A611A6922F000521A611B6972B64FF074 +:1004C000E0233021C3F8084DD4E9003281F31188CC +:1004D0009D4683F30888104710BD00BF00C0000888 +:1004E00020C0000800220020003802402DE9F04F13 +:1004F00093B0AA4B00902022FF210AA89D6800F02B +:10050000CDFBA74A1378A3B9A64801210360117057 +:10051000302383F3118803680BB101F055FAA24A26 +:10052000A04800234FF47A7101F044FA002383F3CA +:100530001188009B13B19D4B009A1A609C4A009C45 +:100540001378032B1EBF00231370984A4FF0000A44 +:1005500018BF5360D3465646D146012000F066FBD3 +:1005600024B1924B1B68002B00F01182002000F098 +:100570006FFA0390039B002BF2DB012000F04CFB91 +:10058000039B213B162BE8D801A252F823F000BFB1 +:10059000ED05000815060008A90600085B0500081F +:1005A0005B0500085B050008330700080309000825 +:1005B0001D0800087F080008A7080008CD080008EB +:1005C0005B050008DF0800085B050008510900080A +:1005D0008D0600085B05000895090008F90500086C +:1005E0008D0600085B0500087F0800080220FFF761 +:1005F000CFFE002840F0F581009B0221BAF1000FE8 +:1006000008BF1C4605A841F21233ADF8143000F0C3 +:100610003DFAA2E74FF47A7000F01AFA071EEBDBFE +:100620000220FFF7B5FE0028E6D0013F052F00F2BB +:10063000DA81DFE807F0030A0D101336052305936E +:10064000042105A800F022FA17E054480421F9E734 +:1006500058480421F6E758480421F3E74FF01C08F6 +:10066000404600F03FFA08F104080590042105A86F +:1006700000F00CFAB8F12C0FF2D1012000FA07F7C4 +:1006800047EA0B0B5FFA8BFB4FF0000900F052FBBF +:1006900026B10BF00B030B2B08BF0024FFF780FEE5 +:1006A0005BE746480421CDE7002EA5D00BF00B03F5 +:1006B0000B2BA1D10220FFF76BFE074600289BD031 +:1006C000012000F00DFA0220FFF7B2FE00265FFACB +:1006D00086F8404600F014FA044690B100214046E6 +:1006E00000F01EFA01360028F1D1BA46044641F264 +:1006F0001213022105A8ADF814303E4600F0C6F9E9 +:100700002BE70120FFF794FE2546244B9B68AB4264 +:1007100007D9284600F0E6F9013040F0678104353A +:10072000F3E7234B00251D70204BBA465D603E4623 +:10073000ACE7002E3FF460AF0BF00B030B2B7FF404 +:100740005BAF0220FFF774FE322000F081F9B0F1B8 +:100750000008FFF651AF18F003077FF44DAF0F4AC2 +:10076000926808EB050393423FF646AFB8F5807FE9 +:100770003FF742AF124B0193B84523DD4FF47A7037 +:1007800000F066F90390039A002AFFF635AF019B4B +:10079000039A03F8012B0137EDE700BF0022002088 +:1007A0005C23002040220020B903000860230020C1 +:1007B0005822002004220020082200200C220020C1 +:1007C0005C220020C820FFF7E3FD074600283FF425 +:1007D00013AF1F2D11D8C5F1200242450AAB25F0F9 +:1007E000030028BF424683490192184400F030FAC2 +:1007F000019A8048FF2100F051FA4FEAA8037D4991 +:100800000193C8F38702284600F050FA06460028F4 +:100810003FF46DAF019B05EB830537E70220FFF73F +:10082000B7FD00283FF4E8AE00F0A6F900283FF439 +:10083000E3AE0027B846704B9B68BB4218D91F2F08 +:1008400011D80A9B01330ED027F0030312AA1344D8 +:1008500053F8203C05934046042205A900F09EFA77 +:1008600004378046E7E7384600F03CF90590F2E7A8 +:10087000CDF81480042105A800F008F906E700234C +:10088000642104A8049300F0F7F800287FF4B4AEC4 +:100890000220FFF77DFD00283FF4AEAE049800F083 +:1008A00053F90590E6E70023642104A8049300F0BF +:1008B000E3F800287FF4A0AE0220FFF769FD0028CE +:1008C0003FF49AAE049800F04FF9EAE70220FFF7F0 +:1008D0005FFD00283FF490AE00F05EF9E1E70220F2 +:1008E000FFF756FD00283FF487AE05A9142000F05D +:1008F00059F904210746049004A800F0C7F83946C6 +:10090000B9E7322000F0A4F8071EFFF675AEBB076A +:100910007FF472AE384A926807EB090393423FF6C0 +:100920006BAE0220FFF734FD00283FF465AE27F0E0 +:1009300003074F44B9453FF4A9AE484600F0D2F84A +:100940000421059005A800F0A1F809F10409F1E7D8 +:100950004FF47A70FFF71CFD00283FF44DAE00F015 +:100960000BF9002844D00A9B01330BD008220AA9B6 +:10097000002000F09BF900283AD02022FF210AA88D +:1009800000F08CF9FFF70CFD1C4800F057FF13B086 +:10099000BDE8F08F002E3FF42FAE0BF00B030B2BB6 +:1009A0007FF42AAE0023642105A8059300F064F8C3 +:1009B000074600287FF420AE0220FFF7E9FC8046BE +:1009C00000283FF419AEFFF7EBFC41F2883000F04D +:1009D00035FF059800F0E0F9464600F0ABF93C46DB +:1009E000BBE5064652E64FF0000905E6BA467EE64C +:1009F00037467CE65C22002000220020A086010011 +:100A00007047000070B50F4B1B780133DBB2012B30 +:100A10000C4611D80C4D29684FF47A730E6AA2FB6C +:100A20000332014622462846B047844204D1074B90 +:100A300000221A70012070BD4FF4FA7000F0FEFE23 +:100A40000020F8E710220020082600209423002030 +:100A500007B50023024601210DF107008DF807308C +:100A6000FFF7D0FF20B19DF8070003B05DF804FB4D +:100A70004FF0FF30F9E700000A4608B50421FFF700 +:100A8000C1FF80F00100C0B2404208BD30B4054C47 +:100A90002368DD69044B0A46AC460146204630BC5B +:100AA000604700BF08260020A086010070B501F055 +:100AB000E5F9094E094D30800024286833888342C7 +:100AC00008D901F0D5F92B6804440133B4F5404F3F +:100AD0002B60F2D370BD00BF962300206823002056 +:100AE00001F08EBA00F1006000F5404000687047E8 +:100AF00000F10060920000F5404001F00DBA0000E6 +:100B0000054B1A68054B1B889B1A834202D9104477 +:100B100001F0AEB900207047682300209623002022 +:100B200038B5084D044629B128682044BDE838404E +:100B300001F0BEB92868204401F0A2F90028F3D0E2 +:100B400038BD00BF6823002010F003030AD1B0F5C0 +:100B5000047F05D200F10050A0F51040D0F8003815 +:100B6000184670470023FBE700F10050A0F5104045 +:100B7000D0F8100A70470000064991F8243033B1CC +:100B80000023086A81F824300822FFF7B1BF012052 +:100B9000704700BF6C230020014B1868704700BFEE +:100BA000002004E070B5194B1D68194B0138C5F3DE +:100BB0000B0408442D0C04221E88A6420BD15C684D +:100BC0000A46013C824213460FD214F9016F4EB11E +:100BD00002F8016BF6E7013A03F10803ECD1814218 +:100BE0000B4602D22C2203F8012B0A4A0524168850 +:100BF000AE4204D1984284BF967803F8016B013C61 +:100C000002F10402F3D1581A70BD00BF002004E0C5 +:100C1000DC340008C8340008022802BF024B4FF43D +:100C200000129A61704700BF00040240022802BF10 +:100C3000014B20229A61704700040240022801BF44 +:100C4000024A536983F02003536170470004024055 +:100C500010B50023934203D0CC5CC4540133F9E7B0 +:100C600010BD000010B5013810F9013F3BB191F9FA +:100C700000409C4203D11AB10131013AF4E71AB1A4 +:100C800091F90020981A10BD1046FCE70346024671 +:100C9000D01A12F9011B0029FAD170470244034609 +:100CA000934202D003F8011BFAE770472DE9F8439D +:100CB0001F4D144695F824200746884652BBDFF89E +:100CC00070909CB395F824302BB92022FF21484620 +:100CD0002F62FFF7E3FF95F82400C0F10802A2425B +:100CE00028BF2246D6B24146920005EB8000FFF7AE +:100CF000AFFF95F82430A41B1E44F6B2082E17440B +:100D00009044E4B285F82460DBD1FFF735FF00287A +:100D1000D7D108E02B6A03EB82038342CFD0FFF7E1 +:100D20002BFF0028CBD10020BDE8F8830120FBE792 +:100D30006C230020024B1A78024B1A70704700BFD8 +:100D4000942300201022002010B50F4C0F4800F013 +:100D5000B5F821460D4800F0DDF824680C48626DB6 +:100D6000D2F8043843F00203C2F8043800F066FDFC +:100D70000849204600F0D4F9626DD2F8043823F017 +:100D80000203C2F8043810BDA83500080826002068 +:100D900040420F00B03500087047000030B5094DE3 +:100DA0000A4491420DD011F8013B5840082340F30A +:100DB0000004013B2C4013F0FF0384EA5000F6D1FD +:100DC000EFE730BD2083B8ED02684368114301604E +:100DD00003B118477047000013B5446BD4F894343E +:100DE0001A681178042915D1217C022912D11979A8 +:100DF000128901238B4013420CD101A904F14C004C +:100E000001F032FFD4F89444019B21790246206816 +:100E100000F0D0F902B010BD143001F0B5BE0000F2 +:100E20004FF0FF33143001F0AFBE00004C3001F042 +:100E300087BF00004FF0FF334C3001F081BF00004E +:100E4000143001F083BE00004FF0FF31143001F088 +:100E50007DBE00004C3001F053BF00004FF0FF3268 +:100E60004C3001F04DBF00000020704710B5D0F8A5 +:100E700094341A6811780429044617D1017C022998 +:100E800014D15979528901238B4013420ED1143069 +:100E900001F016FE024648B1D4F894444FF4807332 +:100EA00061792068BDE8104000F072B910BD000003 +:100EB000406BFFF7DBBF0000704700007FB5124BAF +:100EC000036000234360C0E90233012502260F4B73 +:100ED000057404460290019300F1840229460096AD +:100EE0004FF48073143001F0C7FD094B0294CDE933 +:100EF000006304F523724FF48073294604F14C001B +:100F000001F08EFE04B070BDFC340008B10E000884 +:100F1000D90D00080B68302282F311880A7903EB9F +:100F2000820290614A79093243F822008A7912B12B +:100F300003EB820398610223C0F894140374002029 +:100F400080F311887047000038B5037F044613B161 +:100F500090F85430ABB9201D01250221FFF734FF72 +:100F600004F1140025776FF0010100F08FFC84F884 +:100F7000545004F14C006FF00101BDE8384000F01E +:100F800085BC38BD10B5012104460430FFF71CFFB5 +:100F90000023237784F8543010BD000038B5044690 +:100FA0000025143001F080FD04F14C00257701F09C +:100FB0004FFE201D84F854500121FFF705FF204605 +:100FC000BDE83840FFF752BF90F8443003F06003AB +:100FD000202B07D190F84520212A4FF0000303D899 +:100FE0001F2A06D800207047222AFBD1C0E90E3301 +:100FF00003E0034A82630722C2630364012070474F +:101000001122002037B5D0F894341A6811780429D9 +:1010100004461AD1017C022917D1197912890123BA +:101020008B40134211D100F14C05284601F0D0FE4F +:1010300058B101A9284601F017FED4F89444019B49 +:1010400021790246206800F0B5F803B030BD0000F9 +:10105000F0B500EB810385B09E6904460D46FEB1F4 +:10106000302383F3118804EB8507301D0821FFF737 +:10107000ABFEFB685B691B6806F14C001BB101907D +:1010800001F000FE019803A901F0EEFD024648B10F +:10109000039B2946204600F08DF8002383F3118836 +:1010A00005B0F0BDFB685A691268002AF5D01B8AAA +:1010B000013B1340F1D104F14402EAE7093138B5AC +:1010C00050F82140DCB1302383F31188D4F8942404 +:1010D0001368527903EB8203DB689B695D6845B155 +:1010E00004216018FFF770FE294604F1140001F096 +:1010F000F1FC2046FFF7BAFE002383F3118838BDC8 +:101100007047000001F050B8012303700023C0E9CC +:101110000133C36183620362C36243620363704746 +:1011200038B50446302383F311880025C0E9035500 +:10113000C0E90555416001F047F80223237085F3AB +:101140001188284638BD000070B500EB81030546C4 +:101150005069DA600E46144618B110220021FFF7DC +:101160009DFDA06918B110220021FFF797FD3146BF +:101170002846BDE8704001F0F1B80000826802F036 +:10118000011282600022C0E90422826101F072B97A +:10119000F0B400EB81044789E4680125A4698D401F +:1011A0003D43458123600023A2606360F0BC01F0F1 +:1011B0008DB90000F0B400EB81040789E4680125D3 +:1011C00064698D403D43058123600023A260636014 +:1011D000F0BC01F007BA000070B5022300250446F8 +:1011E0000370C0E90255C0E90455C564856180F803 +:1011F000345001F04FF863681B6823B1294620463C +:10120000BDE87040184770BD0378052B10B5044643 +:101210000AD080F850300523037043681B680BB177 +:10122000042198470023A36010BD00000178052920 +:1012300006D190F85020436802701B6803B118472C +:101240007047000070B590F83430044613B10023A5 +:1012500080F8343004F14402204601F02DF963682F +:101260009B68B3B994F8443013F0600535D0002181 +:10127000204601F0CDFB0021204601F0BFFB636852 +:101280001B6813B1062120469847062384F83430A2 +:1012900070BD204698470028E4D0B4F84A30E26B8D +:1012A0009A4288BFE36394F94430E56B002B4FF01A +:1012B000300380F20381002D00F0F280092284F8CF +:1012C000342083F311880021D4E90E232046FFF750 +:1012D00071FF002383F31188DAE794F8452003F0C7 +:1012E0007F0343EA022340F20232934200F0C580BA +:1012F00021D8B3F5807F48D00DD8012B3FD0022BE9 +:1013000000F09380002BB2D104F14C02A2630222C0 +:10131000E2632364C1E7B3F5817F00F09B80B3F5FE +:10132000407FA4D194F84630012BA0D1B4F84C30C2 +:1013300043F0020332E0B3F5006F4DD017D8B3F598 +:10134000A06F31D0A3F5C063012B90D8636894F8E7 +:1013500046205E6894F84710B4F848302046B047FD +:10136000002884D04368A3630368E3631AE0B3F5FD +:10137000106F36D040F6024293427FF478AF5C4B58 +:10138000A3630223E3630023C3E794F84630012BF1 +:101390007FF46DAFB4F84C3023F00203C4E90E556E +:1013A000A4F84C30256478E7B4F84430B3F5A06F66 +:1013B0000ED194F8463084F84E30204600F0C2FF3B +:1013C00063681B6813B101212046984703232370EB +:1013D0000023C4E90E339CE704F14F03A363012308 +:1013E000C3E72378042B10D1302383F311882046E0 +:1013F000FFF7C4FE85F311880321636884F84F501A +:1014000021701B680BB12046984794F84630002B9A +:10141000DED084F84F300423237063681B68002BF0 +:10142000D6D0022120469847D2E794F848301D06CE +:1014300003F00F0120460AD501F030F8012804D04E +:1014400002287FF414AF2B4B9AE72B4B98E701F05F +:1014500017F8F3E794F84630002B7FF408AF94F8C0 +:10146000483013F00F01B3D01A06204602D501F020 +:10147000E3FAADE701F0D6FAAAE794F84630002B7C +:101480007FF4F5AE94F8483013F00F01A0D01B069E +:10149000204602D501F0BCFA9AE701F0AFFA97E7CF +:1014A000142284F8342083F311882B462A462946D7 +:1014B0002046FFF76DFE85F31188E9E65DB1152240 +:1014C00084F8342083F311880021D4E90E232046C8 +:1014D000FFF75EFEFDE60B2284F8342083F31188CB +:1014E0002B462A4629462046FFF764FEE3E700BF65 +:1014F0002C350008243500082835000838B590F848 +:1015000034300446002B3ED0063BDAB20F2A34D8E2 +:101510000F2B32D8DFE803F0373131082232313176 +:101520003131313131313737C56BB0F84A309D42F6 +:1015300014D2C3681B8AB5FBF3F203FB12556DB9D5 +:10154000302383F311882B462A462946FFF732FEC3 +:1015500085F311880A2384F834300EE0142384F8CC +:101560003430302383F3118800231A46194620466D +:10157000FFF70EFE002383F3118838BD036C03B11F +:1015800098470023E7E70021204601F041FA0021B7 +:10159000204601F033FA63681B6813B10621204628 +:1015A00098470623D7E7000010B590F83430142B85 +:1015B000044629D017D8062B05D001D81BB110BD81 +:1015C000093B022BFBD80021204601F021FA002123 +:1015D000204601F013FA63681B6813B10621204608 +:1015E0009847062319E0152BE9D10B2380F83430F6 +:1015F000302383F3118800231A461946FFF7DAFDDA +:10160000002383F31188DAE7C3689B695B68002BCA +:10161000D5D1036C03B19847002384F83430CEE76A +:1016200000230375826803691B6899689142FBD2A5 +:101630005A68036042601060586070470023037569 +:10164000826803691B6899689142FBD85A680360F5 +:10165000426010605860704708B50846302383F335 +:1016600011880B7D032B05D0042B0DD02BB983F3F0 +:10167000118808BD8B6900221A604FF0FF33836127 +:10168000FFF7CEFF0023F2E7D1E9003213605A6082 +:10169000F3E70000FFF7C4BF054BD9680875186869 +:1016A00002681A60536001220275D860FEF72ABEF4 +:1016B0009823002030B50C4BDD684B1C87B00446E6 +:1016C0000FD02B46094A684600F074F92046FFF710 +:1016D000E3FF009B13B1684600F076F9A86907B0F4 +:1016E00030BDFFF7D9FFF9E798230020591600080D +:1016F000044B1A68DB6890689B68984294BF00208E +:101700000120704798230020084B10B51C68D8684A +:1017100022681A60536001222275DC60FFF78EFF99 +:1017200001462046BDE81040FEF7ECBD982300209E +:10173000044B1A68DB6892689B689A4201D9FFF7EC +:10174000E3BF70479823002038B5074C0749084885 +:10175000012300252370656001F072FB02232370D2 +:1017600085F3118838BD00BF0026002034350008FD +:101770009823002000F05EB9EFF3118020B9EFF359 +:101780000583302282F311887047000010B530B90C +:10179000EFF30584C4F3080414B180F3118810BD7D +:1017A000FFF7C6FF84F31188F9E70000034A516888 +:1017B00053685B1A9842FBD8704700BF001000E0E6 +:1017C0008B60022308618B82084670478368A3F10F +:1017D000840243F8142C026943F8442C426943F80C +:1017E000402C094A43F8242CC26843F8182C0222E2 +:1017F00003F80C2C002203F80B2C044A43F8102C9D +:10180000A3F12000704700BF1D03000898230020AB +:1018100008B5FFF7DBFFBDE80840FFF73BBF00005E +:10182000024BDB6898610F20FFF736BF982300203A +:10183000302383F31188FFF7F3BF000008B501469A +:10184000302383F311880820FFF734FF002383F34C +:10185000118808BD064BDB6839B1426818605A60D0 +:10186000136043600420FFF725BF4FF0FF3070473F +:10187000982300200368984206D01A6802605060DE +:1018800099611846FFF706BF7047000038B5044657 +:101890000D462068844200D138BD036823605C6037 +:1018A0008561FFF7F7FEF4E710B503689C68A24274 +:1018B0000CD85C688A600B604C6021605960996844 +:1018C0008A1A9A604FF0FF33836010BD1B68121BA9 +:1018D000ECE700000A2938BF0A2170B504460D461E +:1018E0000A26601901F0A6FA01F092FA041BA5423B +:1018F00003D8751C2E460446F3E70A2E04D9BDE82A +:101900007040012001F0DCBA70BD0000F8B5144B46 +:101910000D46D96103F1100141600A2A19698260FC +:1019200038BF0A22016048601861A818144601F007 +:1019300073FA0A2701F06CFA431BA342064606D34A +:101940007C1C281901F076FA27463546F2E70A2F63 +:1019500004D9BDE8F840012001F0B2BAF8BD00BFDB +:1019600098230020F8B506460D4601F051FA0F4ABB +:10197000134653F8107F9F4206D12A46014630464F +:10198000BDE8F840FFF7C2BFD169BB68441A2C1903 +:1019900028BF2C46A34202D92946FFF79BFF2246C7 +:1019A00031460348BDE8F840FFF77EBF982300208A +:1019B000A823002010B4C0E9032300235DF8044BE2 +:1019C0004361FFF7CFBF000010B5194C236998425F +:1019D0000DD0D0E90032816813605A609A680A44D9 +:1019E0009A60002303604FF0FF33A36110BD2346CC +:1019F000026843F8102F53600022026022699A4265 +:101A000003D1BDE8104001F00FBA936881680B4420 +:101A1000936001F0FDF92269E1699268441AA242DB +:101A2000E4D91144BDE81040091AFFF753BF00BFC5 +:101A3000982300202DE9F047DFF8BC8008F110075B +:101A40002C4ED8F8105001F0E3F9D8F81C40AA68E1 +:101A5000031B9A423ED81444D5E900324FF00009E6 +:101A6000C8F81C4013605A60C5F80090D8F81030D0 +:101A7000B34201D101F0D8F989F31188D5E90331D6 +:101A800028469847302383F311886B69002BD8D000 +:101A900001F0BEF96A69A0EB04094A4582460DD2FD +:101AA000022001F00DFA0022D8F81030B34208D11C +:101AB00051462846BDE8F047FFF728BF121A2244D6 +:101AC000F2E712EB090938BF4A4629463846FFF7C4 +:101AD000EBFEB5E7D8F81030B34208D01444211A11 +:101AE000C8F81C00A960BDE8F047FFF7F3BEBDE8E9 +:101AF000F08700BFA8230020982300200020704713 +:101B0000FEE70000704700004FF0FF307047000014 +:101B100002290CD0032904D00129074818BF00204E +:101B20007047032A05D8054800EBC20070470448F7 +:101B300070470020704700BF0C36000820220020AC +:101B4000C035000870B59AB00546084601A914468C +:101B500000F0C2F801A8FFF799F8431C5B00C5E943 +:101B600000340022237003236370C6B201AB023439 +:101B70001046D1B28E4204F1020401D81AB070BDF1 +:101B800013F8011B04F8021C04F8010C0132F0E701 +:101B900008B5302383F311880348FFF733FA002395 +:101BA00083F3118808BD00BF0826002090F8443058 +:101BB00003F01F02012A07D190F845200B2A03D118 +:101BC0000023C0E90E3315E003F06003202B08D199 +:101BD000B0F848302BB990F84520212A03D81F2AA5 +:101BE00004D8FFF7F1B9222AEBD0FAE7034A82635F +:101BF0000722C26303640120704700BF182200203F +:101C000007B5052917D8DFE801F0191603191920BF +:101C1000302383F31188104A01900121FFF794FAD1 +:101C200001980E4A0221FFF78FFA0D48FFF7B6F927 +:101C3000002383F3118803B05DF804FB302383F3A2 +:101C400011880748FFF780F9F2E7302383F3118802 +:101C50000348FFF797F9EBE7603500088435000883 +:101C60000826002038B50C4D0C4C0D492A4604F1CD +:101C70000800FFF767FF05F1CA0204F110000949E7 +:101C8000FFF760FF05F5CA7204F118000649BDE8C8 +:101C90003840FFF757BF00BFD02A00202022002085 +:101CA000403500084A3500085535000870B504462F +:101CB00008460D46FEF7EAFFC6B220460134037817 +:101CC0000BB9184670BD32462946FEF7CBFF0028F7 +:101CD000F3D10120F6E700002DE9F84F05460C4648 +:101CE000FEF7D4FF2B49C6B22846FFF7DFFF08B145 +:101CF0000536F6B228492846FFF7D8FF08B1103656 +:101D0000F6B2632E0DD8DFF88C80DFF88C90234F6D +:101D1000DFF890A0DFF890B02E7846B92670BDE8C5 +:101D2000F88F29462046BDE8F84F01F0AFBB252EBD +:101D30002BD1072241462846FEF794FF58B9DBF81D +:101D400000302360DBF804306360DBF80830A36008 +:101D500007350C34E0E7082249462846FEF782FFA3 +:101D600098B90F4BA21C197809090232C95D02F813 +:101D7000041C13F8011B01F00F015345C95D02F863 +:101D8000031CF0D118340835C6E704F8016B01359F +:101D9000C2E700BF2C360008553500084136000860 +:101DA000107AFF1F1C7AFF1F34360008BFF34F8FD5 +:101DB000024AD368DB03FCD4704700BF003C0240FA +:101DC00008B5094B1B7873B9FFF7F0FF074B1A6989 +:101DD000002ABFBF064A5A6002F188325A601A6868 +:101DE00022F480621A6008BD2E2D0020003C0240C3 +:101DF0002301674508B50B4B1B7893B9FFF7D6FF56 +:101E0000094B1A6942F000421A611A6842F4805282 +:101E10001A601A6822F480521A601A6842F48062CA +:101E20001A6008BD2E2D0020003C02400B28F0B5A2 +:101E300016D80C4C0C4923787BB90C4D0E460C235C +:101E40004FF0006255F8047B46F8042B013B13F079 +:101E5000FF033A44F6D10123237051F82000F0BD6E +:101E60000020FCE7602D0020302D002054360008B3 +:101E7000014B53F820007047543600080C2070477F +:101E80000B2810B5044601D9002010BDFFF7CEFF86 +:101E9000064B53F824301844C21A0BB90120F4E75A +:101EA00012680132F0D1043BF6E700BF5436000857 +:101EB0000B2838B5044628D8FFF75EFCFFF776FFFD +:101EC000FFF77EFF124AF323D360E300DBB243F453 +:101ED000007343F002031361136943F48033136109 +:101EE00005462046FFF762FFFFF7A0FF094B53F8B6 +:101EF000241000F0E9F82846FFF77CFFFFF746FCC6 +:101F00002046BDE83840FFF7BBBF002038BD00BF0A +:101F1000003C02405436000812F001032DE9F04164 +:101F200005460E4614464BD18218B2F1016F61D8B6 +:101F3000314B1B6813F001035CD0304FFFF71CFCE2 +:101F4000FFF73EFFF323FB60FFF730FF314640F21F +:101F50000128032C18D824F00104284E0C446D1AD3 +:101F600040F20118A142336905EB01072AD123F0A1 +:101F700001033361FFF73EFFFFF708FC0120BDE8D6 +:101F8000F081043C0435E4E7AB07E4D13B6923F47A +:101F900040733B613B6943EA08033B6151F8046BC2 +:101FA0002E60BFF34F8FFFF701FF2B689E42E8D0F2 +:101FB0003B6923F001033B61FFF71CFFFFF7E6FBE2 +:101FC0000020DCE723F440733361336943EA0803FC +:101FD00033610B883B80BFF34F8FFFF7E7FE3F88ED +:101FE00031F8023BBFB2BB42BCD0336923F00103DE +:101FF0003361E1E71846C2E700380240003C024086 +:10200000084908B50B7828B11BB9FFF7D9FE0123A1 +:102010000B7008BD002BFCD0BDE808400870FFF72E +:10202000E9BE00BF2E2D002010B50244064BD2B2EF +:10203000904200D110BD441C00B253F8200041F87A +:10204000040BE0B2F4E700BF502800400F4B30B55E +:102050001C6F240407D41C6F44F400741C671C6FAD +:1020600044F400441C670A4C236843F480732360E3 +:102070000244084BD2B2904200D130BD441C00B2A1 +:1020800051F8045B43F82050E0B2F4E70038024016 +:10209000007000405028004007B5012201A900202F +:1020A000FFF7C2FF019803B05DF804FB13B50446C7 +:1020B000FFF7F2FFA04205D0012201A90020019400 +:1020C000FFF7C4FF02B010BD70470000034B1A6851 +:1020D0001AB9034AD2F874281A607047642D002098 +:1020E0000030024008B5FFF7F1FF024B1868C0F35B +:1020F000407008BD642D002070470000FEE700001E +:102100000A4B0B480B4A90420BD30B4BDA1C121AAA +:10211000C11E22F003028B4238BF00220021FEF7CD +:10212000BDBD53F8041B40F8041BECE70038000861 +:10213000602E0020602E0020602E002070B5D0E9B7 +:1021400015439E6800224FF0FF3504EB4213510106 +:10215000D3F800090028BEBFD3F8000940F0804042 +:10216000C3F80009D3F8000B0028BEBFD3F8000B5A +:1021700040F08040C3F8000B013263189642C3F868 +:102180000859C3F8085BE0D24FF00113C4F81C38BB +:1021900070BD0000890141F02001016103699B06C7 +:1021A000FCD41220FFF702BB10B5054C2046FEF709 +:1021B000ABFF4FF0A0436365024BA36510BD00BFAA +:1021C000682D0020A836000870B50378012B05465D +:1021D00050D12A4B446D98421BD1294B5A6B42F087 +:1021E00080025A635A6D42F080025A655A6D5A69EC +:1021F00042F080025A615A6922F080025A610E212F +:1022000043205B6900F022FC1E4BE3601E4BC4F8C8 +:1022100000380023C4F8003EC02323606E6D4FF4E5 +:102220000413A3633369002BFCDA012333610C2010 +:10223000FFF7BCFA3369DB07FCD41220FFF7B6FACC +:102240003369002BFCDA0026A6602846FFF776FFEC +:102250006B68C4F81068DB68C4F81468C4F81C68BC +:102260004BB90A4BA3614FF0FF336361A36843F09E +:102270000103A36070BD064BF4E700BF682D00208A +:10228000003802404014004003002002003C30C0EF +:10229000083C30C0F8B5446D054600212046FFF7E4 +:1022A00079FFA96D00234FF001128F68C4F834380C +:1022B0004FF00066C4F81C284FF0FF3004EB4312C7 +:1022C00001339F42C2F80069C2F8006BC2F80809E6 +:1022D000C2F8080BF2D20B686A6DEB6563621023DB +:1022E0001361166916F01006FBD11220FFF75EFA93 +:1022F000D4F8003823F4FE63C4F80038A36943F42B +:10230000402343F01003A3610923C4F81038C4F834 +:1023100014380A4BEB604FF0C043C4F8103B084B35 +:10232000C4F8003BC4F81069C4F80039EB6D03F140 +:10233000100243F48013EA65A362F8BD84360008F6 +:1023400040800010426D90F84E10D2F8003823F40F +:10235000FE6343EA0113C2F8003870472DE9F843E1 +:1023600000EB8103456DDA68166806F00306731EFC +:10237000022B05EB41130C4680460FFA81F94FEA18 +:1023800041104FF00001C3F8101B4FF0010104F1A0 +:10239000100398BFB60401FA03F391698EBF334E60 +:1023A00006F1805606F5004600293AD0578A04F116 +:1023B0005801490137436F50D5F81C180B43C5F835 +:1023C0001C382B180021C3F8101953690127611E0E +:1023D000A7409BB3138A928B9B08012A88BF534363 +:1023E000D8F85C20981842EA034301F1400205EB5B +:1023F0008202C8F85C00214653602846FFF7CAFEF7 +:1024000008EB8900C3681B8A43EA8453483464019B +:102410001E432E51D5F81C381F43C5F81C78BDE863 +:10242000F88305EB4917D7F8001B21F40041C7F8E2 +:10243000001BD5F81C1821EA0303C0E704F13F0391 +:1024400005EB83030A4A5A6028462146FFF7A2FE9D +:1024500005EB4910D0F8003923F40043C0F80039E7 +:10246000D5F81C3823EA0707D7E700BF0080001023 +:1024700000040002826D1268C265FFF75FBE0000B3 +:102480005831436D49015B5813F4004004D013F4F4 +:10249000001F0CBF02200120704700004831436D2F +:1024A00049015B5813F4004004D013F4001F0CBF23 +:1024B000022001207047000000EB8101CB68196AFF +:1024C0000B6813604B6853607047000000EB81039A +:1024D00030B5DD68AA691368D36019B9402B84BF91 +:1024E000402313606B8A1468426D1C44013CB4FBAA +:1024F000F3F46343033323F0030302EB411043EA95 +:10250000C44343F0C043C0F8103B2B6803F00303FF +:10251000012B09B20ED1D2F8083802EB411013F4A6 +:10252000807FD0F8003B14BF43F0805343F000534A +:10253000C0F8003B02EB4112D2F8003B43F00443E9 +:10254000C2F8003B30BD00002DE9F041244D6E6D16 +:1025500006EB40130446D3F8087BC3F8087B380722 +:102560000AD5D6F81438190706D505EB8403214699 +:10257000DB6828465B689847FA071FD5D6F81438F9 +:10258000DB071BD505EB8403D968CCB98B69488A76 +:102590005A68B2FBF0F600FB16228AB91868DA68AE +:1025A00090420DD2121AC3E90024302383F311881C +:1025B0000B482146FFF78AFF84F31188BDE8F081BC +:1025C000012303FA04F26B8923EA02036B81CB68CF +:1025D000002BF3D021460248BDE8F041184700BF68 +:1025E000682D002000EB810370B5DD68436D6C69D8 +:1025F0002668E6604A0156BB1A444FF40020C2F830 +:1026000010092A6802F00302012A0AB20ED1D3F897 +:10261000080803EB421410F4807FD4F8000914BFBB +:1026200040F0805040F00050C4F8000903EB421223 +:10263000D2F8000940F00440C2F80009D3F8340889 +:10264000012202FA01F10143C3F8341870BD19B92F +:10265000402E84BF4020206020682E8A8419013CCF +:10266000B4FBF6F440EAC44040F000501A44C6E718 +:102670002DE9F8433B4D6E6D06EB40130446D3F84D +:102680000889C3F8088918F0010F4FEA40171AD0DB +:10269000D6F81038DB0716D505EB8003D9684B69EF +:1026A0001868DA68904230D2121A4FF000091A60A6 +:1026B000C3F80490302383F3118821462846FFF79E +:1026C00091FF89F3118818F0800F1CD0D6F83438A8 +:1026D0000126A640334216D005EB84036D6DD3F876 +:1026E0000CC0DCF814200134E4B2D2F800E005EBB1 +:1026F00004342F445168714515D3D5F8343823EA92 +:102700000606C5F83468BDE8F883012303FA04F22D +:102710002B8923EA02032B818B68002BD3D021461F +:1027200028469847CFE7BCF81000AEEB0103834280 +:1027300028BF0346D7F8180980B2B3EB800FE2D860 +:102740009068A0F1040959F8048FC4F80080A0EB48 +:1027500009089844B8F1040FF5D818440B44906068 +:102760005360C7E7682D00202DE9F74FA24C656D37 +:102770006E69AB691E4016F480586E6107D0204622 +:10278000FEF72AFD03B0BDE8F04F00F047BC002E75 +:1027900012DAD5F8003E98489B071EBFD5F8003ED8 +:1027A00023F00303C5F8003ED5F8043823F00103F5 +:1027B000C5F80438FEF73AFD370505D58E48FFF712 +:1027C000BDFC8D48FEF720FDB0040CD5D5F80838C7 +:1027D00013F0060FEB6823F470530CBF43F410534F +:1027E00043F4A053EB6031071BD56368DB681BB96A +:1027F000AB6923F00803AB612378052B0CD1D5F826 +:10280000003E7D489A071EBFD5F8003E23F0030323 +:10281000C5F8003EFEF70AFD6368DB680BB1764839 +:102820009847F30274D4B70227D5D4F85490DFF850 +:10283000C8B100274FF0010A09EB4712D2F8003B5C +:1028400003F44023B3F5802F11D1D2F8003B002BC5 +:102850000DDA62890AFA07F322EA0303638104EBC3 +:102860008703DB68DB6813B1394658469847A36D88 +:1028700001379B68FFB29F42DED9F00617D5676D1E +:102880003A6AC2F30A1002F00F0302F4F012B2F532 +:10289000802F00F08580B2F5402F08D104EB830330 +:1028A0000022DB681B6A07F5805790426AD130032B +:1028B000D5F8184813D5E10302D50020FFF744FEF0 +:1028C000A20302D50120FFF73FFE630302D50220D9 +:1028D000FFF73AFE270302D50320FFF735FE750305 +:1028E0007FF550AFE00702D50020FFF7C1FEA1073A +:1028F00002D50120FFF7BCFE620702D50220FFF7D8 +:10290000B7FE23077FF53EAF0320FFF7B1FE39E79F +:10291000636DDFF8E4A0019300274FF00109A36D78 +:102920009B685FFA87FB9B453FF67DAF019B03EBFE +:102930004B13D3F8001901F44021B1F5802F1FD1BA +:10294000D3F8001900291BDAD3F8001941F090419F +:10295000C3F80019D3F800190029FBDB5946606D54 +:10296000FFF718FC218909FA0BF321EA03032381FD +:1029700004EB8B03DB689B6813B1594650469847BC +:102980000137CCE7910708BFD7F80080072A98BF26 +:1029900003F8018B02F1010298BF4FEA182884E77F +:1029A000023304EB830207F580575268D2F818C04F +:1029B000DCF80820DCE9001CA1EB0C0C00218842AB +:1029C0000AD104EB830463689B699A6802449A60A5 +:1029D0005A6802445A606AE711F0030F08BFD7F83B +:1029E00000808C4588BF02F8018B01F1010188BF8E +:1029F0004FEA1828E3E700BF682D0020436D03EB82 +:102A00004111D1F8003B43F40013C1F8003B70477B +:102A1000436D03EB4111D1F8003943F40013C1F8C1 +:102A200000397047436D03EB4111D1F8003B23F4AB +:102A30000013C1F8003B7047436D03EB4111D1F81F +:102A4000003923F40013C1F80039704700F16043E6 +:102A500003F561430901C9B283F80013012200F0B4 +:102A60001F039A4043099B0003F1604303F5614350 +:102A7000C3F880211A60704730B5039C017204339B +:102A800004FB0325C0E90653049B03630021059B57 +:102A9000C160C0E90000C0E90422C0E90842C0E901 +:102AA0000A11436330BD0000416A0022C0E90411ED +:102AB000C0E90A22C2606FF00101FEF7E7BE000024 +:102AC000D0E90432934201D1C2680AB9181D704797 +:102AD0000020704703691960C2680132C260C26990 +:102AE000134482690361934224BF436A0361002156 +:102AF000FEF7C0BE38B504460D46E3683BB16269D7 +:102B0000131D1268A3621344E362002007E0237AD6 +:102B100033B929462046FEF79DFE0028EDDA38BD80 +:102B20006FF00100FBE70000C368C269013BC360AE +:102B30004369134482694361934224BF436A4361FA +:102B400000238362036B03B11847704770B53023CD +:102B5000044683F31188866A3EB9FFF7CBFF05462A +:102B600018B186F31188284670BDA36AE26A13F88B +:102B7000015BA362934202D32046FFF7D5FF0023F7 +:102B800083F31188EFE700002DE9F84F04460E4665 +:102B9000174698464FF0300989F311880025AA4658 +:102BA000D4F828B0BBF1000F09D141462046FFF709 +:102BB000A1FF20B18BF311882846BDE8F88FD4E936 +:102BC0000A12A7EB050B521A934528BF9346BBF197 +:102BD000400F1BD9334601F1400251F8040B43F872 +:102BE000040B9142F9D1A36A40334036A3624035C9 +:102BF000D4E90A239A4202D32046FFF795FF8AF3CD +:102C00001188BD42D8D289F31188C9E730465A46A7 +:102C1000FEF71EF8A36A5B445E44A3625D44E7E7E7 +:102C200010B5029C0172043303FB0421C0E90613B2 +:102C30000023C0E90A33039B0363049BC460C0E91B +:102C40000000C0E90422C0E90842436310BD00004F +:102C5000026AC260426AC0E904220022C0E90A2274 +:102C60006FF00101FEF712BED0E904239A4201D1B0 +:102C7000C26822B9184650F8043B0B607047002325 +:102C80001846FAE7C368C2690133C3604369134455 +:102C900082694361934224BF436A43610021FEF786 +:102CA000E9BD000038B504460D46E3683BB1236931 +:102CB0001A1DA262E2691344E362002007E0237A4E +:102CC00033B929462046FEF7C5FD0028EDDA38BDA8 +:102CD0006FF00100FBE7000003691960C268013A68 +:102CE000C260C269134482690361934224BF436A8C +:102CF000036100238362036B03B118477047000030 +:102D000070B530230D460446114683F31188866A58 +:102D10002EB9FFF7C7FF10B186F3118870BDA36A03 +:102D20001D70A36AE26A01339342A36204D3E1698E +:102D300020460439FFF7D0FF002080F31188EDE72B +:102D40002DE9F84F04460D46904699464FF0300A5B +:102D50008AF311880026B346A76A4FB94946204630 +:102D6000FFF7A0FF20B187F311883046BDE8F88F48 +:102D7000D4E90A073A1AA8EB0607974228BF174674 +:102D8000402F1BD905F1400355F8042B40F8042BC4 +:102D90009D42F9D1A36A4033A3624036D4E90A23A5 +:102DA0009A4204D3E16920460439FFF795FF8BF37B +:102DB00011884645D9D28AF31188CDE729463A468B +:102DC000FDF746FFA36A3B443D44A3623E44E5E76A +:102DD000D0E904239A4217D1C3689BB1836A8BB1AF +:102DE000043B9B1A0ED01360C368013BC360C369E8 +:102DF0001A44836902619A4224BF436A0361002333 +:102E000083620123184670470023FBE700F030B9C6 +:102E10004FF08043586A70474FF080430022586358 +:102E20001A610222DA6070474FF080430022DA60B4 +:102E3000704700004FF0804358637047FEE7000082 +:102E400070B51B4B01630025044686B0586085624F +:102E50000E4600F0BFF804F11003C4E904334FF04C +:102E6000FF33C4E90635C4E90044A560E562FFF715 +:102E7000CFFF2B460246C4E9082304F134010D4A72 +:102E8000256580232046FEF79BFC0123E0600A4A6B +:102E90000375009272680192B268CDE90223074B74 +:102EA0006846CDE90435FEF7B3FC06B070BD00BF3F +:102EB00000260020B4360008B93600083D2E000870 +:102EC000024AD36A1843D062704700BF982300209B +:102ED0004B6843608B688360CB68C3600B69436158 +:102EE0004B6903628B6943620B68036070470000A3 +:102EF00008B5264B26481A6940F2FF110A431A61A9 +:102F00001A6922F4FF7222F001021A611A691A6B1F +:102F10000A431A631A6D0A431A651E4A1B6D11464D +:102F2000FFF7D6FF02F11C0100F58060FFF7D0FF2C +:102F300002F1380100F58060FFF7CAFF02F1540189 +:102F400000F58060FFF7C4FF02F1700100F58060BA +:102F5000FFF7BEFF02F18C0100F58060FFF7B8FFBC +:102F600002F1A80100F58060FFF7B2FF02F1C40191 +:102F700000F58060FFF7ACFF02F1E00100F5806032 +:102F8000FFF7A6FFBDE8084000F0EEB800380240A9 +:102F900000000240C036000808B500F059FAFEF7FC +:102FA000D3FBFFF793F8BDE80840FEF75BBE0000D7 +:102FB00070470000EFF3098305494A6B22F00102D4 +:102FC0004A63683383F30988002383F311887047C9 +:102FD00000EF00E0302080F3118862B60C4B0D4A00 +:102FE000D96821F4E0610904090C0A43DA60D3F8D6 +:102FF000FC20094942F08072C3F8FC200A6842F0C4 +:1030000001020A602022DA7783F82200704700BFAD +:1030100000ED00E00003FA05001000E010B53023D9 +:1030200083F311880E4B5B6813F4006314D0F1EE48 +:10303000103AEFF30984683C4FF08073E361094B69 +:10304000DB6B236684F30988FEF752FB10B1064B55 +:10305000A36110BD054BFBE783F31188F9E700BFBF +:1030600000ED00E000EF00E02F030008320300084D +:103070000F4B1A6C42F001021A641A6E42F0010200 +:103080001A660C4A1B6E936843F0010393604FF07D +:10309000804353229A624FF0FF32DA6200229A6133 +:1030A0005A63DA605A6001225A611A60704700BFA1 +:1030B00000380240002004E04FF0804208B511695A +:1030C000D3680B40D9B2C9439B07116107D53023A0 +:1030D00083F31188FEF74EFB002383F3118808BDAC +:1030E0001F4B1A696FEAC2526FEAD2521A611A690B +:1030F000C2F308021A614FF0FF301A695A69586129 +:1031000000215A6959615A691A6A62F080521A623A +:103110001A6A02F080521A621A6A5A6A58625A6A25 +:1031200059625A6A1A6C42F080521A641A6E42F05E +:1031300080521A661A6E0B4A106840F48070106054 +:10314000186F00F44070B0F5007F1EBF4FF4803060 +:1031500018671967536823F40073536000F054B97B +:103160000038024000700040334B4FF080521A6428 +:10317000324A4FF4404111601A6842F001021A606D +:103180001A689107FCD59A6822F003029A602A4BCC +:103190009A6812F00C02FBD1196801F0F90119606C +:1031A0009A601A6842F480321A601A689203FCD559 +:1031B0005A6F42F001025A671F4B5A6F9007FCD5B5 +:1031C0001F4A5A601A6842F080721A601B4A53689C +:1031D0005904FCD5184B1A689201FCD5194A9A601B +:1031E000194B1A68194B9A42194B21D1194A116887 +:1031F000194A91421CD140F205121A60144A136810 +:1032000003F00F03052BFAD10B4B9A6842F0020230 +:103210009A609A6802F00C02082AFAD15A6C42F4B9 +:1032200080425A645A6E42F480425A665B6E70471E +:1032300040F20572E1E700BF003802400070004034 +:103240000854400700948838002004E011640020EE +:10325000003C024000ED00E041C20F41074A08B5C2 +:10326000536903F00103536123B1054A13680BB19D +:1032700050689847BDE80840FFF7D0BE003C0140C9 +:10328000E02D0020074A08B5536903F0020353619B +:1032900023B1054A93680BB1D0689847BDE8084050 +:1032A000FFF7BCBE003C0140E02D0020074A08B5F6 +:1032B000536903F00403536123B1054A13690BB149 +:1032C00050699847BDE80840FFF7A8BE003C0140A0 +:1032D000E02D0020074A08B5536903F00803536145 +:1032E00023B1054A93690BB1D0699847BDE80840FE +:1032F000FFF794BE003C0140E02D0020074A08B5CE +:10330000536903F01003536123B1054A136A0BB1EB +:10331000506A9847BDE80840FFF780BE003C014076 +:10332000E02D0020164B10B55C6904F478725A61E8 +:10333000A30604D5134A936A0BB1D06A9847600676 +:1033400004D5104A136B0BB1506B9847210604D576 +:103350000C4A936B0BB1D06B9847E20504D5094A30 +:10336000136C0BB1506C9847A30504D5054A936CB8 +:103370000BB1D06C9847BDE81040FFF74FBE00BFBF +:10338000003C0140E02D0020194B10B55C6904F4AD +:103390007C425A61620504D5164A136D0BB1506D1B +:1033A0009847230504D5134A936D0BB1D06D984708 +:1033B000E00404D50F4A136E0BB1506E9847A10478 +:1033C00004D50C4A936E0BB1D06E9847620404D5B5 +:1033D000084A136F0BB1506F9847230404D5054A70 +:1033E000936F0BB1D06F9847BDE81040FFF716BE42 +:1033F000003C0140E02D002008B5FFF75DFEBDE870 +:103400000840FFF70BBE0000062108B50846FFF78D +:103410001DFB06210720FFF719FB06210820FFF7F7 +:1034200015FB06210920FFF711FB06210A20FFF7F3 +:103430000DFB06211720FFF709FB06212820FFF7C7 +:1034400005FBBDE8084007211C20FFF7FFBA00007C +:1034500008B5FFF745FE00F00BF8FDF753FEFDF74A +:103460002BFDFFF7A5FDBDE80840FFF7CFBC00002E +:103470000023054A19460133102BC2E9001102F15D +:103480000802F8D1704700BFE02D0020034611F874 +:10349000012B03F8012B002AF9D1704753544D3307 +:1034A00032463F3F3F0053544D333246343078006C +:1034B00053544D3332463432780053544D333246F0 +:1034C0003434365858000000012033000010410009 +:1034D00001105A00031059000710310000000000CD +:1034E0009C34000813040000A634000819040000EE +:1034F000B034000821040000BA34000800000000C5 +:10350000350E0008210E00085D0E0008490E000867 +:10351000550E0008410E00082D0E0008190E000877 +:10352000690E00080000000001000000000000001B +:103530006330000030350008F02300200026002012 +:103540004172647550696C6F740025424F4152445A +:10355000252D424C002553455249414C2500000081 +:10356000020000000000000051100008BD1000081B +:1035700040004000A02A0020B02A002002000000E5 +:10358000000000000300000000000000011100081E +:103590000000000010000000C02A00200000000011 +:1035A0000100000000000000682D00200101020061 +:1035B000011C0008111B0008AD1B0008911B00082E +:1035C00043000000C835000809024300020100C0A2 +:1035D0003209040000010202010005240010010567 +:1035E00024010001042402020524060001070582CB +:1035F000030800FF09040100020A0000000705019A +:103600000240000007058102400000001200000097 +:10361000143600081201100102000040091241573F +:1036200000020102030100000403090425424F4186 +:1036300052442500424554414650562D46343035BB +:10364000003031323334353637383941424344451E +:103650004600000000400000004000000040000064 +:103660000040000000000100000002000000020015 +:103670000000020000000200000002000000020042 +:10368000000002000000000045120008FD140008C0 +:10369000A915000840004000C82D0020C82D0020BA +:1036A00001000000D82D0020800000004001000033 +:1036B000030000006D61696E0069646C65000000C4 +:1036C0000001806A00000000AAAAAAAA0001006402 +:1036D000FFFF00000000000000A00A0040040001FD +:1036E00000000000AAAAAAAA40000001DFFF000013 +:1036F00000000000000000000000000000000000CA +:10370000AAAAAAAA00000000FFFF00000000000013 +:10371000000000000000000000000000AAAAAAAA01 +:1037200000000000FFFF000000000000000000009B +:103730000000000000000000AAAAAAAA00000000E1 +:10374000FFFF00000000000000000000000000007B +:1037500000000000AAAAAAAA00000000FFFF0000C3 +:103760000000000000000000000000000000000059 +:10377000AAAAAAAA00000000FFFF000000000000A3 +:103780000000000000000000000000000A0000002F +:103790000000000003000000000000000000000026 +:1037A0000000000000000000000000000000000019 +:1037B0000000000000000000000000000000000009 +:1037C000650400000000000000400F000000000041 +:1037D000FF009600000000080096000000000800AE +:1037E000040000002836000800000000000000006F +:1037F00000000000000000000000000000000000C9 +:00000001FF diff --git a/Tools/bootloaders/BirdCANdy_bl.bin b/Tools/bootloaders/BirdCANdy_bl.bin index 4c3fd6689d9b53..d1858f4735aee3 100755 Binary files a/Tools/bootloaders/BirdCANdy_bl.bin and b/Tools/bootloaders/BirdCANdy_bl.bin differ diff --git a/Tools/bootloaders/BirdCANdy_bl.elf b/Tools/bootloaders/BirdCANdy_bl.elf index 5b1c66aa0b9ee6..2a38b21e51206f 100755 Binary files a/Tools/bootloaders/BirdCANdy_bl.elf and b/Tools/bootloaders/BirdCANdy_bl.elf differ diff --git a/Tools/bootloaders/BirdCANdy_bl.hex b/Tools/bootloaders/BirdCANdy_bl.hex index 515351a6fb5d9a..2f9950b2c8cbc8 100644 --- a/Tools/bootloaders/BirdCANdy_bl.hex +++ b/Tools/bootloaders/BirdCANdy_bl.hex @@ -1,1035 +1,1283 @@ :020000040800F2 -:1000000000070020E5040008A915000829150008CC -:10001000811500082915000855150008E704000897 -:10002000E7040008E7040008E7040008893700082F -:10003000E7040008E7040008E7040008E7040008F4 -:10004000E7040008E7040008E7040008E7040008E4 -:10005000E7040008E7040008B53B0008E13B00089E -:100060000D3C0008393C0008653C0008E704000826 -:10007000E7040008E7040008E7040008E7040008B4 -:10008000E7040008E7040008E70400086125000809 -:10009000CD2500082126000875260008913C00089F -:1000A000E7040008E7040008E7040008E704000884 -:1000B000053A0008E7040008E7040008E704000820 -:1000C000E7040008E7040008E7040008E704000864 -:1000D000E7040008E7040008E7040008E704000854 -:1000E000F93C0008E7040008E7040008E7040008FA -:1000F000E7040008E7040008E7040008E704000834 -:10010000E7040008E7040008E7040008E704000823 -:10011000E7040008E7040008E7040008E704000813 -:10012000E7040008E7040008E7040008E704000803 -:10013000E7040008E7040008E7040008E7040008F3 -:10014000E7040008E7040008E7040008E7040008E3 -:10015000E7040008E7040008E70400080D29000888 -:10016000E7040008E7040008E7040008E7040008C3 -:10017000E7040008E7040008E7040008E7040008B3 -:10018000E7040008E7040008E7040008E7040008A3 -:10019000E7040008E7040008E7040008E704000893 -:1001A000E7040008E7040008E7040008E704000883 -:1001B000E7040008E7040008E7040008E704000873 -:1001C000E7040008E7040008E7040008E704000863 -:1001D000E7040008E7040008E7040008E704000853 -:1001E00053B94AB9002908BF00281CBF4FF0FF319E -:1001F0004FF0FF3000F074B9ADF1080C6DE904CE9A -:1002000000F006F8DDF804E0DDE9022304B07047F1 -:100210002DE9F047089D04468E46002B4DD18A42B9 -:10022000944669D9B2FA82F252B101FA02F3C2F1EC -:10023000200120FA01F10CFA02FC41EA030E94407D -:100240004FEA1C48210CBEFBF8F61FFA8CF708FB9E -:1002500016E341EA034306FB07F199420AD91CEB76 -:10026000030306F1FF3080F01F81994240F21C81A8 -:10027000023E63445B1AA4B2B3FBF8F008FB1033F0 -:1002800044EA034400FB07F7A7420AD91CEB040425 -:1002900000F1FF3380F00A81A74240F207816444F5 -:1002A000023840EA0640E41B00261DB1D44000237A -:1002B000C5E900433146BDE8F0878B4209D9002DDE -:1002C00000F0EF800026C5E9000130463146BDE868 -:1002D000F087B3FA83F6002E4AD18B4202D38242D2 -:1002E00000F2F980841A61EB030301209E46002D81 -:1002F000E0D0C5E9004EDDE702B9FFDEB2FA82F2D6 -:10030000002A40F09280A1EB0C014FEA1C471FFA33 -:100310008CFE0126200CB1FBF7F307FB131140EA1A -:1003200001410EFB03F0884208D91CEB010103F1E7 -:10033000FF3802D2884200F2CB804346091AA4B2A9 -:10034000B1FBF7F007FB101144EA01440EFB00FE7D -:10035000A64508D91CEB040400F1FF3102D2A645E2 -:1003600000F2BB800846A4EB0E0440EA03409CE781 -:10037000C6F12007B34022FA07FC4CEA030C20FA2E -:1003800007F401FA06F31C43F9404FEA1C4900FA4E -:1003900006F3B1FBF9F8200C1FFA8CFE09FB1811CB -:1003A00040EA014108FB0EF0884202FA06F20BD93E -:1003B0001CEB010108F1FF3A80F08880884240F28E -:1003C0008580A8F102086144091AA4B2B1FBF9F0D2 -:1003D00009FB101144EA014100FB0EFE8E4508D9CD -:1003E0001CEB010100F1FF346CD28E456AD9023852 -:1003F000614440EA0840A0FB0294A1EB0E01A14237 -:10040000C846A64656D353D05DB1B3EB080261EBA4 -:100410000E0101FA07F722FA06F3F1401F43C5E97E -:10042000007100263146BDE8F087C2F12003D840B4 -:100430000CFA02FC21FA03F3914001434FEA1C47F6 -:100440001FFA8CFEB3FBF7F007FB10360B0C43EAE8 -:10045000064300FB0EF69E4204FA02F408D91CEB98 -:10046000030300F1FF382FD29E422DD90238634496 -:100470009B1B89B2B3FBF7F607FB163341EA034136 -:1004800006FB0EF38B4208D91CEB010106F1FF3885 -:1004900016D28B4214D9023E6144C91A46EA00467C -:1004A00038E72E46284605E70646E3E61846F8E60E -:1004B0004B45A9D2B9EB020864EB0C0E0138A3E757 -:1004C0004646EAE7204694E74046D1E7D0467BE738 -:1004D000023B614432E7304609E76444023842E7B0 -:1004E000704700BF02E000F000F8FEE772B63A483D -:1004F00080F30888394880F3098839484EF6085156 -:10050000CEF20001086040F20000CCF200004EF68E -:100510003471CEF200010860BFF34F8FBFF36F8FCD -:1005200040F20000C0F2F0004EF68851CEF2000119 -:100530000860BFF34F8FBFF36F8F4FF00000E1EE05 -:10054000100A4EF63C71CEF200010860062080F3DE -:100550001488BFF36F8F03F097F903F073F903F07A -:10056000BDF94FF055301F491B4A91423CBF41F83D -:10057000040BFAE71C49194A91423CBF41F8040BAD -:10058000FAE71A491A4A1B4B9A423EBF51F8040B2C -:1005900042F8040BF8E700201749184A91423CBF83 -:1005A00041F8040BFAE703F051F903F0E5F9144CB4 -:1005B000144DAC4203DA54F8041B8847F9E700F005 -:1005C00041F8114C114DAC4203DA54F8041B884732 -:1005D000F9E703F039B900000007002000230020EC -:1005E000000000080001002000070020684000080B -:1005F00000230020242300202823002098390020F5 -:10060000E0010008E0010008E0010008E001000846 -:100610002DE9F04F2DED108AC1F80CD0C3689D462E -:10062000BDEC108ABDE8F08F002383F311882846C3 -:10063000A047002002F07EFDFEE702F003FD00DF90 -:10064000FEE700002DE9F04103F03CF8074603F017 -:1006500087F80546C0BB284B9F4235D001339F42E7 -:1006600035D0264B27F0FF029A4234D1F8B200F081 -:1006700049FAA84642F2107400F04EFC08B100247A -:10068000A04600F045FA064648B354BB464635B18D -:100690001B4B9F4203D003F05BF80024264600204A -:1006A00003F01AF80EB100F02DF800F093FC00F002 -:1006B00079FE00F07BFF0546B4B900F03DFD4FF434 -:1006C0007A7002F03DFDF7E7A8460024D4E704461F -:1006D0004FF00108D0E780464FF47A74CCE7044627 -:1006E000D5E74FF47A74D2E700F060FF431BA342D2 -:1006F000E3D900F007F8DCE7010007B0000008B01C -:10070000263A09B01E4B1F4A10B51C461968013124 -:1007100034D004339342F9D162681B4B9A422DD9ED -:100720001A4B9B6803F1006303F580339A4225D28C -:1007300002F0E2FF02F0F4FF002000F04DFE144B47 -:100740000220187000F084FE124B1A6C00221A640A -:10075000196E1A66196E596C5A64596E5A665B6E38 -:1007600072B64FF0E0232021C3F8084DD4E90032DF -:1007700081F311889D4683F30888104710BD00BFA0 -:100780000000010820000108FFFF000800230020EE -:100790002823002000380240094A136849F2690002 -:1007A00099B21B0C00FB01331360064B186844F22E -:1007B000506182B2000C01FB0200186080B27047E9 -:1007C000202300201C23002010B500211022044605 -:1007D00000F05AFE034B03CB206061601868A060F4 -:1007E00010BD00BF107AFF1F2DE9F043224DBBB0B2 -:1007F00000F0DCFEAB6840F2ED22C31A934232D91E -:1008000006AFA8602B4628220021384601F0DCFB09 -:1008100005F10E0000F030FE002604465FFA80F974 -:1008200005F10E08F3B2F100994501F1280107D94D -:1008300008EB06030822384601F0C6FB0136F1E753 -:1008400008230122CDE9023205340C4B0193A4B2F6 -:1008500030230093CDE9047405A3D3E90023297B59 -:10086000074801F0C9F93BB0BDE8F083AFF3008061 -:1008700078F6339F93CACD8D703300207D330020EE -:100880004433002070B50D4614461E4601F04AF967 -:1008900050B9022E10D1012C0ED112A3D3E900239E -:1008A000C5E90023012007E0282C10D005D8012C31 -:1008B00009D0052C0FD0002070BD302CFBD10BA32C -:1008C000D3E90023ECE70BA3D3E90023E8E70BA36C -:1008D000D3E90023E4E70BA3D3E90023E0E700BF5B -:1008E000AFF30080401DA12026812A0B78F6339FAC -:1008F00093CACD8D9E6AC421818A46EE26417272CA -:10090000DF25D7B7F017304A39059E5613B5044690 -:100910002346084620220021019001F055FB227950 -:100920000198032A234628BF032203F8042F20211D -:10093000022201F049FB62790198072A234628BF69 -:10094000072203F8052F2221032201F03DFBA279A3 -:100950000198072A234628BF072203F8062F2521DE -:10096000032201F031FB019804F108031022282131 -:1009700001F02AFB382002B010BD00002DE9F04F35 -:10098000FFB01FAD0CAE40F2751280460F4620A896 -:100990000021296000F078FD48220021304600F057 -:1009A00073FD00F003FE554B4FF47A72B0FBF2F08A -:1009B000186093E80700012386E807000DF1520054 -:1009C0003382FFF701FF41F20443338406AB18463C -:1009D0004B4903F03BFA172230642946304686F82B -:1009E0003C20FFF793FF10AB04460146082228463F -:1009F00001F0EAFA0822A1180DF14103284601F09E -:100A0000E3FA0DF14203082204F11001284601F037 -:100A1000DBFA11AB202204F11801284601F0D4FAC8 -:100A200012AB402204F13801284601F0CDFA14AB94 -:100A3000082204F17801284601F0C6FA0DF15103AD -:100A4000082204F18001284601F0BEFA04F1880A68 -:100A50000DF1520904F5847B4B4651460822284685 -:100A60000AF1080A01F0B0FAD34509F10109F3D1FE -:100A700019AB08225946284601F0A6FA04F58874F5 -:100A80004FF0000996F834304B450AD9B36B214634 -:100A90004B440822284601F097FA083409F101096D -:100AA000F0E74FF0000996F83C304B4504EBC901E4 -:100AB00008D9336C08224B44284601F085FA09F125 -:100AC0000109F0E700230393BB7E0293073107F18E -:100AD00019030193C1F3CF010123CDE90451009320 -:100AE000F97E04A3D3E90023404601F085F87FB0E6 -:100AF000BDE8F08F9E6AC421818A46EE2C23002037 -:100B00005C3E0008014B1870704700BF382300207E -:100B1000F0B5334B1C7B85B034B1324B0E221A81B9 -:100B20000024204605B0F0BD2F4A1068516802AB82 -:100B300003C308232D492E480DEB030203F064F98B -:100B4000054630B9274B2B480A221A8100F0E8FCF1 -:100B5000E6E70169B1F5E02F06D9224B26480B22C2 -:100B60001A8100F0DDFCDCE7438B40F21442934233 -:100B700007D01C490C2008811946204800F0D0FC01 -:100B8000CFE71F4A024402F11003994204D2154BE9 -:100B90001C4810221A81E4E710398E1A20461449A5 -:100BA00000F008FD3246074605F11801204600F026 -:100BB00001FDAB689F4202D1EB6898420AD0094B15 -:100BC0000D221A810090D5E902123B460E4800F032 -:100BD000A7FCA5E70D4800F0A3FC0124A1E700BF96 -:100BE000703300202C230020053F0008DCFF0600A6 -:100BF00000000108743E0008803E0008923E000894 -:100C00000800FFF7B03E0008CD3E0008F63E0008A1 -:100C10002DE9F04FADB006AF80460C4600F082FFE4 -:100C2000054600285AD1237E022B1BD1E38A012BD3 -:100C300018D100F0BBFC0646FFF7AEFD03464FF4AB -:100C4000C870DFF8D092B3FBF0F206F5167602FB1F -:100C5000103316FA83F3C9F80030E37E33B9A84B9A -:100C600000221A709C37BD46BDE8F08FA38AEEB211 -:100C7000013BB34205F101050BD93B1D1E44E900C0 -:100C800000960023082201F0F801204601F060F8E8 -:100C9000ECE707F11400FFF797FD324607F1140166 -:100CA000381D03F0A1F80028D9D10F2E08D8944B95 -:100CB0001E70D9F80030A3F51673C9F80030D1E7DB -:100CC000FB1CF8700146009307220346204601F002 -:100CD0003FF8F978404600F01DFFC3E7E38A282B70 -:100CE00026D010D8012B1ED0052BBBD1BFF34F8FC0 -:100CF0008449854BCA6802F4E0621343CB60BFF3BA -:100D00004F8F00BFFDE7302BACD1637E7F4D0133A9 -:100D10006A7BDBB29342E94603D1E27E2B7B9A42A7 -:100D200065D0CD469EE721464046FFF727FE99E76E -:100D3000A38A013B9BB2C92B94D8744D2E7B26BB52 -:100D400005F10C030093082233463146204600F09B -:100D5000FFFF731CF2B2D9001E46A38A013B9A42E0 -:100D600005DA0E322A44009200230822EEE700231F -:100D70000022C5E900230023AB6085F8D730C5F811 -:100D8000D8302B7B0BB9E37E2B73002507F11409B8 -:100D90003B1D082229464846C7E90155FD6001F080 -:100DA00013F93B7A05F1010AAB424FEACA0608D9AA -:100DB000FB6808222B443146484601F005F95546A8 -:100DC000EFE7C6F3CF06E17ECDE904960023039357 -:100DD000A37E0293193428230093019446A3D3E9F8 -:100DE0000023404600F008FFFFF7FEFC3AE74FF013 -:100DF000000807F11403A7F814801022009341465D -:100E00000123204600F0A4FFA68A023EB6B2F31CDE -:100E10009B109B000733DB08A9EBC3039D460DF134 -:100E2000180A1FFA88F34FEAC801B34201F1100112 -:100E30000AD20AEB0803009308220023204600F0A0 -:100E400087FF08F10108ECE795F8D70000F0CEFA2B -:100E5000D5F8D83004461BB995F8D70000F0D6FA7B -:100E6000D5F8D83033449C4204D295F8D7000130ED -:100E700000F0CCFA4FEA960B4FF000081FFA88F109 -:100E80008B45D5E9003209D90AEB880103EB8800CC -:100E9000012200F001FB08F10108EFE7F31842F12D -:100EA0000002C5E90032D5F8D83095F8D70006EB36 -:100EB0000308C5F8D88000F099FA804509D395F861 -:100EC000D730D5F8D8000133001B85F8D730C5F8E6 -:100ED000D800FF2E08D800232B7300F0A9FAFFF7E3 -:100EE00017FE08B1FFF70EFC2B68094A9B0A013375 -:100EF00013810023AB6014E726417272DF25D7B758 -:100F00003D33002000ED00E00400FA0570330020BE -:100F10002C2300204033002030B54FF00054244BE8 -:100F200022689A4285B007D002F024FC0446A8B992 -:100F30000024204605B030BD1E4B627D1A701E484D -:100F4000237D03731D49C9220E3000F08BFA204621 -:100F5000E022002100F098FA0124EAE7184A194D2E -:100F6000136C43F000731364AA6D174B9A42DFD1E0 -:100F70002B6E013B7E2BDBD8144A07CA01AB83E8FA -:100F800007001846032100F02BFB6B6D83424FF0E6 -:100F90000003CDD12A6D8A4201BFAB65054B2A6E95 -:100FA0001A7003BF0A4BEA6D1A601C46C1E700BF06 -:100FB0009AAD44C53823002070330020160000206D -:100FC00000380240006600405041A0B05866004022 -:100FD000182300202DE9FF474B4C022363710023A7 -:100FE00002934A4BD3F800C0BCF57A7F12D3484B2A -:100FF000484FB7FBFCF69C458CBF0A231123581EB3 -:10100000B6FBF3F503FB1562C1B2002A3ED00228FD -:101010000346F4D89DF80B303F4940485A1E9DF8CE -:101020000A30013B1B0443EA0253BDF80820013A91 -:1010300013434B6001F026FD00230193384B3949DF -:1010400000933948394B4FF4805200F03DFD384B46 -:10105000197811B1344800F05DFD00F0A7FA05469B -:10106000FFF79AFB4FF4C873B0FBF3F202FB1303D4 -:1010700005F5167010FA83F02E4B186002F070FB25 -:1010800008B10F23238104B0BDE8F0876B1EB3F5D0 -:10109000806FBFD2C1EBC10E0EF103034FEAE3092B -:1010A000C3F3C703A1EB030809F1010A4FF47A70F7 -:1010B0005FFA88F609FB00005AFA88F8B0FBF8F0EE -:1010C000B0F5617F08D90EF1FF33C3F3C703C91A26 -:1010D000CEB2591E0F2914D8721E072A8CBF0022C7 -:1010E0000122991901FB0551B7FBF1F7BC4591D1DC -:1010F000002A8FD0ADF808508DF80A308DF80B60BB -:1011000088E71346EDE700BF2C23002018230020BA -:101110003F420F0040787D011023002088340020DA -:10112000850800083C23002044330020110C0008EF -:1011300038230020403300202DE9F04F91A7D7E954 -:1011400000670FF24829D9E90089874D93B0DFF88D -:1011500044B2864C284600F0B3FD0DF1300A0790EA -:1011600070B310220021504600F08EF9079B197BC6 -:101170004FF0000261F303028DF83020586899683F -:101180000EAA03C21B680D9A63F31C029DF830304F -:101190000D9243F020038DF830300023524619465B -:1011A000584601F07FFC079028B9284600F08CFDD6 -:1011B000079B2370CEE72378072B3CD8013323709D -:1011C00018220021504600F05FF9DFF8C8B1684CE2 -:1011D000002319465246584601F08CFC014670BB6C -:1011E000102208A800F050F9636983F020036361BE -:1011F00000F0DEF90B4612A9024611E903000DF1D9 -:10120000240C8CE803009DF83410C1F30300890618 -:101210004CBF0E99BDF838C08DF82C0046BFC1F305 -:101220001C0C4CF00041CCF30A010891284608A997 -:1012300000F012FFCCE7284600F046FDC0E7284644 -:1012400000F070FC0446002848D1DFF84CB100F0F3 -:10125000ADF9DBF80030984240D300F0A7F90790D1 -:10126000FFF79AFA079A8DF8204003464FF4C870AA -:1012700002F51672B3FBF0F101FB103312FA83F39F -:10128000CBF80030DFF814B19BF8001011B901233E -:101290008DF8203050460791FFF796FA0799C1F173 -:1012A0001004E4B2062C28BF0624224651440DF156 -:1012B000210000F0D7F808AB039318230293013400 -:1012C0002C4B0193E4B20123009304943B46324635 -:1012D000284600F029FC00238BF8003000F066F966 -:1012E000254A264C1368C31AB3F57A7F31D31060B0 -:1012F00000F05EF902460B46284600F0EFFC284657 -:1013000000F010FC28B3237BDFF894B0002B14BF4F -:10131000032302238BF8053000F048F94FF47A7369 -:101320005146B0FBF3F0CBF800005846FFF7EEFA59 -:10133000182307300293124B0193C0F3CF0040F201 -:101340005513CDE903A0009342464B46284600F0D2 -:10135000EBFB237B2BB1FFF747FA237B002B7FF4BA -:10136000F6AE13B0BDE8F08F4433002055340020B2 -:10137000000002403C330020503400207033002035 -:1013800054340020401DA12026812A0BF1C6A7C19C -:10139000D068080F88340020403300203D330020FF -:1013A0002C23002070B502F02DF8094E094D308035 -:1013B000002428683388834208D902F01DF82B687E -:1013C00004440133B4F5803F2B60F2D370BD00BFFD -:1013D000843400205834002002F0D8B800F10060B6 -:1013E000920000F5803002F05BB80000054B1A68EF -:1013F000054B1B889B1A834202D9104401F0FCBFA5 -:1014000000207047583400208434002038B5074D40 -:1014100004462868204401F0F7FF28B928682044D2 -:10142000BDE8384002F008B838BD00BF583400208D -:10143000064991F8243033B10023086A81F824303A -:101440000822FFF7CBBF0120704700BF5C340020AB -:10145000022802BF024B4FF400129A61704700BF8E -:101460000000024010B50023934203D0CC5CC4546A -:101470000133F9E710BD000003460246D01A12F905 -:10148000011B0029FAD1704702440346934202D05F -:1014900003F8011BFAE770472DE9F8431F4D144686 -:1014A00095F824200746884652BBDFF870909CB31D -:1014B00095F824302BB92022FF2148462F62FFF7F0 -:1014C000E3FF95F82400C0F10802A24228BF22469B -:1014D000D6B24146920005EB8000FFF7C3FF95F8B6 -:1014E0002430A41B1E44F6B2082E17449044E4B2E4 -:1014F00085F82460DBD1FFF79BFF0028D7D108E0F7 -:101500002B6A03EB82038342CFD0FFF791FF0028C1 -:10151000CBD10020BDE8F8830120FBE75C3400203C -:101520000FB4002004B0704700B59BB0EFF3098101 -:1015300068226846FFF796FFEFF30583044B9A6B2A -:10154000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE759 -:1015500000ED00E000B59BB0EFF30981682268461A -:10156000FFF780FFEFF30583044B9A6B9A6A9A6A40 -:101570009A6A9A6A9A6A9B6AFEE700BF00ED00E0E9 -:1015800000B59BB0EFF3098168226846FFF76AFF58 -:10159000EFF30583034B5A6B9A6A9A6A9A6A9A6ABE -:1015A0009B6AFEE700ED00E0FEE7000002F028B8CD -:1015B00002F000B830B5094D0A4491420DD011F83F -:1015C000013B5840082340F30004013B2C4013F03A -:1015D000FF0384EA5000F6D1EFE730BD2083B8ED79 -:1015E000F7B54FF0FF33DFF854C0DFF854E000EBFD -:1015F00081011A4688421CD050F8044B019401AF77 -:10160000042417F8015B82EA05620825DB181646F8 -:1016100005F1FF355241002EBCBF83EA0C0382EA7C -:101620000E0215F0FF05F1D1013C14F0FF04E8D1E2 -:10163000E0E7D843D14303B0F0BD00BF9336EAA939 -:10164000EBE1F0422DE9F041C56915B9C161BDE892 -:10165000F0814B6823F06047C3F38A464FEAD37E9C -:10166000C3F3807816EA230638BF3E46AC462B46C5 -:101670005A68BEEBD27F22F060440AD0002A18DA02 -:10168000A40CB44217D19D420FD10D60DEE7134682 -:10169000EEE7A74207D102F08044C2F380724245D0 -:1016A0000BD054B1EFE708D2EDE7CCF800100B6097 -:1016B000CDE7B44201D0B442E5D81A689C46002A6E -:1016C000E5D11960C3E700002DE9F047089D01F05E -:1016D00007044FEAD508224405F0070500EBD100C6 -:1016E0004FF47F49944201D1BDE8F08704F0070729 -:1016F00005F0070A57453E4638BF5646C6F108066C -:10170000111B8E4228BF0E46E10808EBD50E415C46 -:1017100013F80EC0B94029FA06F721FA0AF1FFB210 -:101720008CEA010147FA0AF739408CEA010C03F808 -:101730000EC034443544D5E780EA0120082341F245 -:10174000210201B24000002980B203F1FF33B8BF8B -:10175000504013F0FF03F4D17047000038B50C4639 -:101760008D18A54200D138BD14F8011BFFF7E4FF26 -:10177000F7E7000002684AB113680360C388018973 -:1017800001339BB29942C38038BF03811046704732 -:1017900070B588B0202204460D4668460021FFF748 -:1017A00073FE20460495FFF7E5FF024658B16B46ED -:1017B000054608AE1C4603CCB44228606960234647 -:1017C00005F10805F6D1104608B070BD082817D9F4 -:1017D00009280CD00A280CD00B280CD00C280CD0CF -:1017E0000D280CD00E2814BF4020302070470C204C -:1017F0007047102070471420704718207047202031 -:1018000070470000082817D90C280CD910280CD9CB -:1018100014280CD918280CD920280CD930288CBFB2 -:101820000F200E207047092070470A2070470B20B8 -:1018300070470C2070470D207047000010B54B68B2 -:1018400023B9CA8A63F30902CA8210BDC4681A6840 -:101850001C60C360438A013B43824A60EFE700009B -:101860002DE9F84F1D46CB8A0F46C3F3090106291F -:10187000814692460B4630D00020AAB207F11904E7 -:101880009EB2052E1FFA80F80FD8904503F1010390 -:1018900006D3FB8A0A4462F30903FB8201201AE0A3 -:1018A0001AF80060E6540130EAE79045F1D2A1F160 -:1018B000060B1C237C68BBFBF3F203FB12BB1FFA75 -:1018C0008BF6002C45D14846FFF754FF044638B943 -:1018D00078606FF00200BDE8F88F4FF00008E6E78F -:1018E000002606607860ADB24FF0000B454510D978 -:1018F0000AEB0803221D13F8011B9155B1B208F140 -:1019000001081B291FFA88F82BD0454506F101066E -:10191000F1D8FB8AC3F30902154465F30903BCE758 -:10192000013292B21C462368002BF9D1AB1F0B4445 -:101930001C21B3FBF1F301339BB29A42D3D2BBF12A -:10194000000FD0D14846FFF715FF20B9C4F800B00A -:10195000BFE70122E7E7C0F800B05E46206004461A -:10196000C1E74545D5D94846FFF704FF08B92060CF -:10197000AFE7C0F800B0002620600446B6E70000DC -:101980002DE9F04F2DED028B83B0CDE90013BDF8AA -:101990003C5007469146002A00F092802DB10E9BE4 -:1019A000002B00F08D80072D32D807F10C00FFF7D7 -:1019B000E1FE044638B96FF00204204603B0BDECE6 -:1019C000028BBDE8F08F14220021FFF75DFD0E9918 -:1019D0002A4604F10800FFF745FD681CC0B2FFF776 -:1019E00011FFFFF7F3FE207499F80030013814FA64 -:1019F00080F003F01F0363F03F030372009B43F08A -:101A00000041616038462146FFF71CFE0124D4E7FF -:101A100000F10C034FF0000808EE103A4FF0800A76 -:101A20004646444618EE100AFFF7A4FE83460028F7 -:101A3000C1D014220021FFF727FDC6BB019BABF8E4 -:101A4000083002200E9B00F1080299195BFA82F21D -:101A50000130C0B2082801D0AE422AD3FFF7D2FE2F -:101A6000FFF7B4FE99F80020009B411E02F01F0210 -:101A700042EA4812AE4208BF4FF0400A5BFA81F1D9 -:101A80004AEA020A43F0004281F808A08BF81000ED -:101A9000CBF8042059463846FFF7D4FD0134AE4256 -:101AA00024B288F001084FF0000ABBD185E700207E -:101AB000C8E711F801CB02F801CB0136B6B2C7E78F -:101AC0006FF0010479E70000F8B515460E462822AC -:101AD000002104461F46FFF7D7FC069B6360B5F55F -:101AE000001F079BA76034BF6A094FF6FF7223628D -:101AF00004F10C0097B200239A4205D8002303603A -:101B000027826382A382F8BD066001333046203607 -:101B1000F2E7000003781BB94BB2002BC8BF01707D -:101B200070470000007870472DE9F74FDDF83C90D2 -:101B3000BDF830500D9E9DF83840BDF8407080468D -:101B400092469B46B9F1000F01D1002F51D11F2CB5 -:101B50004FD898F80000B0B9072F47D835F00303E5 -:101B600047D13A4649464FF6FF70FFF7F7FD20F0A0 -:101B700001002D02400445EA0464400C44EA40247C -:101B80004FF6FF7321E040EA0520072F40EA046486 -:101B9000F6D900254FF6FF73C5F12000A5F120020C -:101BA0002AFA05F10BFA00F001432BFA02F2114375 -:101BB0001846C9B2FFF7C0FD0835402D0346EBD1EA -:101BC0003A464946FFF7CAFD0346CDE9009732463B -:101BD00021464046FFF7D4FE33780133DBB21F2B9A -:101BE00088BF0023337003B0BDE8F08F6FF00300AF -:101BF000F9E76FF00100F6E72DE9F04F85B0924666 -:101C0000DDF848800F9D9DF840209DF84490BDF878 -:101C10004C7006469B46B8F1000F01D1002F48D109 -:101C20001F2A46D83378002B46D00C0244EA0264BF -:101C30009DF8381044EAC93444EA01441C43072F94 -:101C400044F0800432D900234FF6FF72C3F1200C18 -:101C5000A3F120002AFA03F10BFA0CFC41EA0C0173 -:101C60002BFA00F00143C9B210460393FFF764FD5D -:101C7000039B0833402B0246E8D13A464146FFF722 -:101C80006DFD0346CDE900872A4621463046FFF721 -:101C900077FEB9F1010F06D12B780133DBB21F2B90 -:101CA00088BF00232B7005B0BDE8F08F4FF6FF739F -:101CB000E8E76FF00100F6E76FF00300F3E70000DC -:101CC000C06900B104307047C3691A68C261C26854 -:101CD0001A60C360438A013B438270472DE9F0419B -:101CE000D0F81880194E14461D464146002709B900 -:101CF000BDE8F081D1E90223A21A65EB0303964205 -:101D000077EB03031ED283698B420DD1FFF796FD5B -:101D100083691B688361C3680B60438AC160816902 -:101D2000013B43828846E2E7FFF788FD0B68C8F86D -:101D30000030C3680B60438AC160013B4382D8F81E -:101D40000010D4E788460968D1E700BF80841E00F0 -:101D50002DE9F04F8BB00D46DDF8509014469B46B0 -:101D60008046002800F01981B9F1000F00F01581BC -:101D7000531E3F2B00F21181012A03D1BBF1000F4A -:101D800040F00B810023CDE90833B8F81430B5EBEF -:101D9000C30F4FEAC30703D300200BB0BDE8F08F99 -:101DA0002B199F42D8F80C303ABF7F1BFFB2274651 -:101DB0001BB9D8F81030002B7AD02F2D4ED8C5F192 -:101DC0003006B7424FF000032CBFF6B23E460093F8 -:101DD0002946D8F8080008AB3246FFF775FCA7EB98 -:101DE000060A35445FFA8AFAB8F8143003F1005352 -:101DF000063BDB000493D8F80C3003933021039B9F -:101E000013B1BAF1000F2CD1D8F8100040B1BAF1DB -:101E1000000F05D0009608AB5246691AFFF754FC34 -:101E200038B2002FB8D066070AD00AAB03EBD40152 -:101E3000624211F8083C02F00702134101F8083C25 -:101E4000082C3CD9102C40F2B580202C40F2B780F1 -:101E5000BBF1000F00F09C80082334E0BA46002656 -:101E6000C2E7049BE02B28BFE02306930B44AB4260 -:101E7000059314D95A1B03980096924534BF5246D5 -:101E8000D2B2691A08AB04300792FFF71DFC079A1B -:101E90001644AAEB020A1544F6B25FFA8AFA049BCA -:101EA000069A05999B1A0493039B1B680393A6E764 -:101EB0000093D8F8080008AB3A462946AEE7BBF1D4 -:101EC000000F13D00123B4EBC30F6CD0082C12D831 -:101ED0009DF82030621E23FA02F2D50706D54FF096 -:101EE000FF3202FA04F423438DF820309DF82030AD -:101EF00089F8003051E7102C12D8BDF82030621E4E -:101F000023FA02F2D10706D54FF0FF3202FA04F4A9 -:101F10002343ADF82030BDF82030A9F800303CE76D -:101F2000202C0FD80899631E21FA03F3DA0705D590 -:101F30004FF0FF3202FA04F40C430894089BC9F8EE -:101F400000302AE7402C2BD0DDE90865611EC4F182 -:101F50002102A4F1210326FA01F105FA02F225FA81 -:101F600003F311431943CB0712D50122A4F1200337 -:101F7000C4F1200102FA03F322FA01F1A240524215 -:101F800043EA010363EB430332432B43CDE90823C8 -:101F9000DDE90823C9E90023FFE66FF00100FCE654 -:101FA0006FF00800F9E6082CA0D9102CB3D9202C2A -:101FB000EED8C3E7BBF1000FADD0022383E7BBF13E -:101FC000000FBBD004237EE730B5012A144638BF8A -:101FD0000124402C85B028BF40240025012ACDE9EA -:101FE000025518D81B788DF8083063070AD004AB67 -:101FF00003EBD405624215F8083C02F00702934057 -:1020000005F8083C009103462246002102A8FFF78C -:102010005BFB05B030BD082AE4D9102A03D81B8821 -:10202000ADF80830E1E7202A8DBFD3E900231B6813 -:102030000293CDE90223D8E710B5CB681BB98B60BA -:102040000B618B8210BDC4681A681C60C360438A30 -:10205000013B4382CA60F0E72DE9F04FD1F80080E0 -:1020600093B018F0800FCDE90323C8F3C01219BF55 -:10207000C8F3C03BC8F306264FF0020B1646B8F172 -:10208000000F04460D4680F2D18118F0C04305933D -:1020900040F0CC810B7B002B00F0C881BBF1020F1C -:1020A00003D00178B14240F0C48108F07F0106916D -:1020B0006AB3C8F3074A2B44069A93F8039076064E -:1020C00046EA0B4646EA82465FEAD91346EA0A0622 -:1020D000079300F0908000220023CDE90A23069B9D -:1020E000009367685B4652460AA92046B847002815 -:1020F0007ED0A7699FB9314604F10C00FFF748FB79 -:102100000746E0B96FF0020013B0BDE8F08FC8F3E6 -:102110000F2A18F07F0F08BF0AF0030ACBE73B69CC -:102120009E420DD03F68002FF9D1314604F10C00DA -:10213000FFF72EFB07460028E4D0A3693B60A761A8 -:10214000DDE90A2300264FF6FF70C6F1200E22FAC1 -:1021500006F103FA0EFEA6F1200C23FA0CFC41EA6C -:102160000E0141EA0C01C9B2083609920893FFF743 -:10217000E3FA402EDDE90832E7D1B882FB7D09F0B1 -:102180001F06C3F384039B1BD7E9022198B2002BDF -:10219000BCBF00F120031BB252EA0100C8F304687F -:1021A0000FD00398821A049860EB0101A74890426F -:1021B0004FF000028A4104D3079A002A5BD0012B1A -:1021C00023DDFA7D4FEA890302F0030203F07C036A -:1021D0001343FB7539462046FFF730FB079BA3B935 -:1021E000FB7DC3F38402013262F38603FB7504E0D6 -:1021F0006FF00B0088E7A76917B96FF00C0083E751 -:102200003B699E42BAD03F68F6E719F0400F32D0E2 -:10221000039BBB60049BFB60142200210DA8FFF709 -:1022200033F9039B0A93049B0B932B1D0C932B7B7D -:10223000ADF83EA0013BDBB2ADF83C30069B8DF81B -:10224000433094F824308DF840B083F001038DF8CA -:1022500044308DF84160A3688DF842800AA9204679 -:102260009847FB7DC3F38403013303F01F039B02F4 -:10227000FB82002048E7FB7DC9F34012B2EBD31F7D -:1022800040F0DA80C3F38403B34240F0D88007996A -:102290002B7B4FEA9912002934D0D20741D4032B6B -:1022A00040F2D080039BBB60049BFB602B7BAE1D88 -:1022B000033BDBB23246394604F10C00FFF7D0FA9B -:1022C00000280DDA20463946FFF7B8FAFB7DC3F344 -:1022D0008403013303F01F039B02FB82032013E7F7 -:1022E000AB883B832A7B033AB88AD2B23146FFF7E8 -:1022F00035FAFB7DB882DA43C2F3C01262F3C7132A -:10230000FB75B6E76AB92E1D013BDBB23246394692 -:1023100004F10C00FFF7A4FA0028D3DB2A7B013A72 -:10232000E2E7F98AC1F30901013B0529DAB259D87C -:10233000281D002307F11A0C9A4208D910F801EB66 -:102340000CF801E0013101330629DBB2F4D1039925 -:102350000A9104990B91934207F11A010C9138BF2D -:10236000043379680D9134BF55FA83F300230E933B -:10237000FB8AADF83EA0C3F309031A44069B8DF80F -:10238000433094F82430ADF83C2083F001038DF8FD -:10239000443000238DF840B08DF841608DF84280C4 -:1023A0007B602A7BB88A013A291DFFF7D7F93B8B5E -:1023B000B882834203D1A3680AA9204698472046E1 -:1023C0000AA9FFF739FEFB7DB88AC3F38403013302 -:1023D00003F01F039B02FB823B8B984214BF11202A -:1023E000002091E67B68002BB1D0062001E01C3074 -:1023F0006346D3F800C0BCF1000FF8D1091A081DDC -:1024000005F1040C00EB030905989DF8143001EB6D -:10241000000EBEF11B0F9AD89A4298D91CF8013BC6 -:1024200009F8013B059B01330593EDE76FF00900C7 -:102430006AE66FF00A0067E66FF00D0064E66FF081 -:102440000E0061E66FF00F005EE600BF80841E00A4 -:10245000404BF0B51C6C404E44F000741C641D6E83 -:1024600045F000751D661B6E3C4B9B6AD3F800520D -:10247000354045F00105C3F80052D3F8004234401E -:1024800044EA002040F00100C3F80002002952D0C5 -:102490000020C3F81C020546C3F80402C3F80C026E -:1024A000C3F8140203EBC00401301C28C4F84052E6 -:1024B000C4F84452F6D100254FF0010C96781488E8 -:1024C000F70748BFD3F804720CFA04F044BF07437F -:1024D000C3F80472B70742BFD3F80C720743C3F8BE -:1024E0000C72760742BFD3F814620643C3F8146235 -:1024F00003EBC4045668C4F840629668C4F84462AA -:10250000D3F81C4201352043A942C3F81C0202F152 -:102510000C02D3D1D3F8002222F00102C3F800222A -:102520000C4B1A6C22F000721A641A6E22F00072C0 -:102530001A661B6EF0BD0122C3F84012C3F84412A4 -:10254000C3F80412C3F81412C3F80C22C3F81C22F7 -:10255000E0E700BF003802400000FFFF88340020A1 -:10256000184A916A08B58B688B6013F0010104D09A -:1025700013F00C0F18BF4FF48031D80506D513F4B3 -:10258000406F14BF41F4003141F00201D80306D579 -:1025900013F4402F14BF41F4802141F00401D369AA -:1025A0000BB108489847202383F31188064800217F -:1025B00000F0EEFD002383F31188BDE8084001F030 -:1025C00017B900BF883400209034002038B5124C71 -:1025D000A36ADD68AA0712D05A6922F002025A6182 -:1025E000A36913B1012120469847202383F3118862 -:1025F0000A48002100F0CCFD002383F31188EB068C -:1026000006D5A36A1021D960236A0BB10248984706 -:10261000BDE8384001F0ECB8883400209834002040 -:1026200038B5124CA36A1D69AA0712D05A6922F064 -:1026300010025A61A36913B1022120469847202352 -:1026400083F311880A48002100F0A2FD002383F3E0 -:102650001188EB0606D5A36A10211961236A0BB114 -:1026600002489847BDE8384001F0C2B888340020DD -:102670009834002038B50F4CA36A5D685D602A0766 -:102680000AD5042222701A6822F002021A60636AD4 -:1026900013B10021204698476B0706D5A36A9969B4 -:1026A000236A13B1034809049847BDE8384001F094 -:1026B0009FB800BF8834002010B50E4C204600F0B3 -:1026C000CFF90D4BA3620B21132000F0B1F90B21C0 -:1026D000142000F0ADF90B21152000F0A9F90B2111 -:1026E000162000F0A5F90022BDE8104011460E208A -:1026F000FFF7AEBE8834002000640040114B9842C2 -:1027000010B5044609D1104B1A6C42F000721A64DD -:102710001A6E42F000721A661B6EA36A01221A60DA -:10272000A36A5A68D20707D5626851681268D961EE -:102730001A60064A5A6110BD0121082000F01EFCF3 -:10274000EEE700BF88340020003802405B870100BC -:1027500003291AD8DFE801F0020A0F14836A9B6884 -:1027600013F0E05F14BF012000207047836A98686F -:10277000C0F380607047836A9868C0F3C060704798 -:10278000836A9868C0F300707047002070470000AB -:1027900010B5032925D8DFE801F00225292D836A29 -:1027A0009968C1F30161183103EB011310788406B5 -:1027B0004CBF54689488C0F300114FEA410148BFF0 -:1027C00041EAC40100F00F004CBF41F0040141EAAE -:1027D0004451586041F001019068D2689860DA6015 -:1027E000196010BD836A03F5C073DFE7836A03F5E0 -:1027F000C873DBE7836A03F5D073D7E701290AD0F2 -:1028000002290FD081B9836ADA68920701D1186969 -:1028100003E001207047836AD86810F0030018BFF6 -:1028200001207047836AF2E70020704710B539B97C -:10283000836AD96889071BD11B699C0704D110BD25 -:10284000012915D00229FAD1816AD1F8C031D1F815 -:10285000C441D1F8C8011061D1F8CC0150612020E9 -:1028600008610869800717D1486940F0100012E03C -:10287000816AD1F8B031D1F8B441D1F8B801106112 -:10288000D1F8BC0150612020C860C868800703D11E -:10289000486940F002004861C3F34000C3F380017F -:1028A000000140EA4111107920F03000014311711C -:1028B00089064BBF91681189DB085B0D4CBF63F340 -:1028C0001C0163F30A01137948BF916064F30303A9 -:1028D00013714FEA14234FEA144458BF1181137047 -:1028E0005480ACE7024AD36843F0C003D36070471A -:1028F00000140140044B5A6810439A6858600AB1AA -:10290000181D1047704700BFB43400202DE9F04176 -:102910003C4ED6F85C52EF682B68DA059CB20CD5B9 -:10292000202383F311884FF40070FFF7E3FF6FF467 -:1029300080732B60002383F31188202383F3118895 -:10294000DFF8C08014F02F0339D183F311883806E3 -:1029500013D5210611D5202383F311882A4800F0CE -:1029600001FA00284CDA0820FFF7C4FF4FF67F7306 -:102970003B40EB60002383F311887A0615D563068C -:1029800013D5202383F31188D6E913239A4209D162 -:10299000336C3BB127F040073F0410203F0CFFF79A -:1029A000A9FFEF60002383F31188D6F86422D3686F -:1029B0000BB110699847BDE8F04100F019BF23073B -:1029C00012D014F0080F0CBF00208020E10748BF90 -:1029D00040F02000A20748BF40F04000630748BF16 -:1029E00040F48070FFF786FFA4066B6805D596F863 -:1029F00060124046194000F057FA2C68A4B2A1E7D3 -:102A00006860B7E7B4340020EC34002010B5054C02 -:102A1000054A0021204600F025FA044BC4F85C3238 -:102A200010BD00BFB4340020E528000800140140A8 -:102A300000F1604303F561430901C9B283F8001353 -:102A4000012200F01F039A4043099B0003F16043F9 -:102A500003F56143C3F880211A607047FFF72CBE6D -:102A6000012300F10802C0E90222037000F1100204 -:102A70000023C0E90422C0E90633C0E908334360FB -:102A80007047000010B52023044683F31188022309 -:102A900003704160FFF732FE04232370002383F3A9 -:102AA000118810BD2DE9F0411F4604460D4616461B -:102AB000202383F3118800F108082378052B0DD01B -:102AC00029462046FFF744FE40B1204632462946BB -:102AD000FFF75EFE002080F3118808E0394640468B -:102AE00000F03AFB0028E8D0002383F31188BDE80A -:102AF000F08100002DE9F0411F4604460D461646C0 -:102B0000202383F3118800F110082378052B0DD0C2 -:102B100029462046FFF772FE40B12046324629463C -:102B2000FFF784FE002080F3118808E03946404614 -:102B300000F012FB0028E8D0002383F31188BDE8E1 -:102B4000F0810000F8B5154682680669AA420B4676 -:102B5000816938BF8568761AB54204460BD218469B -:102B60002A46FEF77FFCA3692B44A361A3685B1B85 -:102B7000A3602846F8BD0CD918463246FEF772FC11 -:102B8000AF1BE1683A463044FEF76CFCE3683B4417 -:102B9000EBE718462A46FEF765FCE368E5E7000028 -:102BA00083689342F7B51546044638BF8568D0E977 -:102BB0000460361AB5420BD22A46FEF753FC63690D -:102BC0002B446361A36828465B1BA36003B0F0BD80 -:102BD0000DD932460191FEF745FC0199E068AF1B23 -:102BE0003A463144FEF73EFCE3683B44E9E72A46B7 -:102BF000FEF738FCE368E4E710B50A440024C3613B -:102C0000029B8460C0E90000C0E90511C160026157 -:102C1000036210BD08B5D0E90532934201D1826844 -:102C200082B98268013282605A1C42611970D0E90F -:102C300004329A4224BFC3684361002100F09CFA29 -:102C4000002008BD4FF0FF30FBE7000070B52023E7 -:102C500004460E4683F31188A568A5B1A368A2694E -:102C6000013BA360531CA36115782269934224BFE2 -:102C7000E368A361E3690BB120469847002383F31F -:102C80001188284607E03146204600F065FA002802 -:102C9000E2DA85F3118870BD2DE9F74F04460E4640 -:102CA00017469846D0F81C904FF0200A8AF31188F6 -:102CB0004FF0000B154665B12A4631462046FFF716 -:102CC00041FF034660B94146204600F045FA00281E -:102CD000F1D0002383F31188781B03B0BDE8F08F97 -:102CE000B9F1000F03D001902046C847019B8BF338 -:102CF0001188ED1A1E448AF31188DCE7C0E905113A -:102D0000C160C3611144009B8260C0E900000161A1 -:102D100003627047F8B504460D461646202383F338 -:102D20001188A768A7B1A368013BA36063695A1C17 -:102D300062611D70D4E904329A4224BFE368636182 -:102D4000E3690BB120469847002080F3118807E023 -:102D50003146204600F000FA0028E2DA87F31188B5 -:102D6000F8BD0000D0E905239A4210B501D1826870 -:102D70007AB98268013282605A1C82611C780369C8 -:102D80009A4224BFC3688361002100F0F5F9204610 -:102D900010BD4FF0FF30FBE72DE9F74F04460E461C -:102DA00017469846D0F81C904FF0200A8AF31188F5 -:102DB0004FF0000B154665B12A4631462046FFF715 -:102DC000EFFE034660B94146204600F0C5F90028F1 -:102DD000F1D0002383F31188781B03B0BDE8F08F96 -:102DE000B9F1000F03D001902046C847019B8BF337 -:102DF0001188ED1A1E448AF31188DCE702684368E3 -:102E00001143016003B11847704700001430FFF709 -:102E100043BF00004FF0FF331430FFF73DBF000009 -:102E20003830FFF7B9BF00004FF0FF333830FFF7FD -:102E3000B3BF00001430FFF709BF00004FF0FF31AF -:102E40001430FFF703BF00003830FFF763BF000006 -:102E50004FF0FF323830FFF75DBF000000207047B1 -:102E6000FFF7D4BD37B515460E4A02600022426016 -:102E7000C0E902220122044602740B46009000F1D0 -:102E80005C014FF480721430FFF7B6FE00942B46BD -:102E90004FF4807204F5AE7104F13800FFF72EFF95 -:102EA00003B030BD103F000838B5C36904460D4675 -:102EB0001BB904210844FFF7A1FF294604F11400BF -:102EC000FFF7A8FE002806DA201D4FF48061BDE858 -:102ED0003840FFF793BF38BD024B0022C3E90033EF -:102EE0009A6070471C370020002303748268054BEA -:102EF0001B6899689142FBD25A6803604260106077 -:102F0000586070471C37002008B5202383F31188D0 -:102F1000037C032B05D0042B0DD02BB983F3118830 -:102F200008BD436900221A604FF0FF334361FFF789 -:102F3000DBFF0023F2E7D0E9003213605A60F3E7C9 -:102F4000002303748268054B1B6899689142FBD883 -:102F50005A68036042601060586070471C37002058 -:102F6000054B19690874186802681A605360186183 -:102F700001230374FDF74CBB1C37002030B54B1CFC -:102F80000B4D87B0044610D02B690A4A01A800F007 -:102F90001BF92046FFF7E4FF049B13B101A800F0E2 -:102FA0004FF92B69586907B030BDFFF7D9FFF8E733 -:102FB0001C370020092F000838B50C4D41612B69E2 -:102FC00081689A689142044603D8BDE83840FFF70B -:102FD0008BBF1846FFF7B4FF01232C610146237411 -:102FE0002046BDE83840FDF713BB00BF1C3700206A -:102FF000044B1A681B6990689B68984294BF002034 -:10300000012070471C37002010B5084C2368206948 -:103010001A6822605460012223611A74FFF790FF3E -:1030200001462069BDE81040FDF7F2BA1C370020C8 -:1030300008B5FFF7DDFF18B1BDE80840FFF7E4BFB2 -:1030400008BD0000FFF7E0BFFEE7000010B50C4C24 -:10305000FFF742FF00F0AAF80A498022204600F05C -:1030600031F8012344F8180C037400F09DFB002391 -:1030700083F3118862B60448BDE8104000F042B8FE -:1030800044370020383F0008483F000800F012B9DC -:10309000EFF3118020B9EFF30583202282F311882A -:1030A0007047000010B530B9EFF30584C4F308048D -:1030B00014B180F3118810BDFFF7BAFF84F31188B3 -:1030C000F9E7000082600222028270478368A3F160 -:1030D0007C0243F80C2C026943F83C2C426943F80B -:1030E000382C074A43F81C2CC26843F8102C0222E3 -:1030F00003F8082C002203F8072CA3F118007047EE -:103100002906000810B5202383F31188FFF7DEFF9E -:1031100000210446FFF750FF002383F31188204667 -:1031200010BD0000024B1B6958610F20FFF718BF4C -:103130001C370020202383F31188FFF7F3BF000022 -:1031400008B50146202383F311880820FFF716FFF6 -:10315000002383F3118808BD49B1064B42681B69FF -:1031600018605A60136043600420FFF707BF4FF0F8 -:10317000FF3070471C3700200368984206D01A6859 -:103180000260506059611846FFF7AEBE70470000FC -:1031900038B504460D462068844200D138BD036826 -:1031A00023605C604561FFF79FFEF4E7054B03F188 -:1031B0001402C3E905224FF0FF310022C3E90712D0 -:1031C000704700BF1C37002070B51C4EC0E90323B8 -:1031D00005460C4600F06EFB334653F8142F9A4216 -:1031E0000DD13062C5E901242A600A2C2CBF0019D8 -:1031F0000A30C6E90555BDE8704000F049BB316AA8 -:10320000431AE31838BF1C469368A34202D9081931 -:1032100000F04CFB73699A6894420CD85A68AC6011 -:103220002B606A6015609A685D60121B9A604FF0AF -:10323000FF33F36170BD1B68A41AECE71C37002054 -:1032400038B51B4C636998420DD0D0E90032136049 -:103250005A6000228168C2609A680A449A604FF0FE -:10326000FF33E36138BD2246036842F8143F002172 -:1032700093425A60C16003D1BDE8384000F010BBF2 -:103280009A688168256A0A449A6000F013FB6369B2 -:103290009A68411B8A42E5D9AB181D1A092D206A8C -:1032A00098BF01F10A02BDE83840104400F0FEBAB0 -:1032B0001C3700202DE9F041184C002704F11406BA -:1032C000656900F0F7FA236AAA68C11A8A4215D81C -:1032D00013442362D5E9003213605A606369D5F85C -:1032E0000C80EF60B34201D100F0DAFA87F3118865 -:1032F0002869C047202383F31188E1E76169B1425F -:1033000009D013441B1ABDE8F0410A2B2CBFC0188A -:103310000A3000F0CBBABDE8F08100BF1C370020B6 -:1033200000207047FEE70000704700004FF0FF30BC -:1033300070470000BFF34F8F024AD368DB03FCD411 -:10334000704700BF003C024008B5094B1B7873B9B9 -:10335000FFF7F0FF074B1A69002ABFBF064A5A6001 -:1033600002F188325A601A6822F480621A6008BD3D -:10337000D8380020003C02402301674508B50B4BBC -:103380001B7893B9FFF7D6FF094B1A6942F0004248 -:103390001A611A6842F480521A601A6822F4805244 -:1033A0001A601A6842F480621A6008BDD83800209A -:1033B000003C02400728F0B516D80C4C0C49237885 -:1033C0007BB90C4D0E4608234FF0006255F8047B84 -:1033D00046F8042B013B13F0FF033A44F6D10123D6 -:1033E000237051F82000F0BD0020FCE7FC380020DD -:1033F000DC380020603F0008014B53F82000704784 -:10340000603F000808207047072810B5044601D91E -:10341000002010BDFFF7CEFF064B53F824301844B0 -:10342000C21A0BB90120F4E712680132F0D1043B53 -:10343000F6E700BF603F0008072838B5044628D8E3 -:10344000FFF726FEFFF776FFFFF77EFF124AF32312 -:10345000D360E300DBB243F4007343F00203136173 -:10346000136943F48033136105462046FFF762FF7A -:10347000FFF7A0FF094B53F8241000F03BF9284652 -:10348000FFF77CFFFFF70EFE2046BDE83840FFF750 -:10349000BBBF002038BD00BF003C0240603F0008B9 -:1034A00012F001032DE9F04105460E4614464BD1BA -:1034B0008118334A914261D8324B1B6813F00103E3 -:1034C0005CD0314FFFF7E4FDFFF73EFFF323FB60D5 -:1034D000FFF730FF314640F20128032C18D824F0C2 -:1034E0000104294E0C446D1A40F20118A1423369BF -:1034F00005EB01072AD123F001033361FFF73EFFFB -:10350000FFF7D0FD0120BDE8F081043C0435E4E77D -:10351000AB07E4D13B6923F440733B613B6943EA69 -:1035200008033B6151F8046B2E60BFF34F8FFFF728 -:1035300001FF2B689E42E8D03B6923F001033B6109 -:10354000FFF71CFFFFF7AEFD0020DCE723F440731C -:103550003361336943EA080333610B883B80BFF36F -:103560004F8FFFF7E7FE3F8831F8023BBFB2BB4207 -:10357000BCD0336923F001033361E1E71846C2E7A9 -:103580000000080800380240003C0240084908B525 -:103590000B7828B11BB9FFF7D7FE01230B7008BDCC -:1035A000002BFCD0BDE808400870FFF7E7BE00BF65 -:1035B000D838002070B582B0FFF76AFD0E4E054680 -:1035C00000F078F93268904237BF0C4A0B495168D5 -:1035D00014682EBFD1E9004101315160041903463E -:1035E00041F10001284601913360FFF75BFD01992D -:1035F000204602B070BD00BF00390020083900200D -:1036000070B582B0FFF744FD104E054600F052F948 -:103610003268904237BF0E4A0D49516814682EBF78 -:10362000D1E9004101315160041941F10001034623 -:10363000284601913360FFF735FD01994FF47A7206 -:1036400000232046FCF7CCFD02B070BD00390020FD -:103650000839002010B50244064BD2B2904200D186 -:1036600010BD441C00B253F8200041F8040BE0B236 -:10367000F4E700BF502800400F4B30B51C6F240406 -:1036800007D41C6F44F400741C671C6F44F400449E -:103690001C670A4C236843F4807323600244084B80 -:1036A000D2B2904200D130BD441C00B251F8045B4C -:1036B00043F82050E0B2F4E70038024000700040C8 -:1036C0005028004007B5012201A90020FFF7C2FFE2 -:1036D000019803B05DF804FB13B50446FFF7F2FF51 -:1036E000A04205D0012201A900200194FFF7C4FFE8 -:1036F00002B010BD70470000074B45F255521A60EA -:1037000002225A6040F6FF729A604CF6CC421A6070 -:10371000024B01221A70704700300040143900201B -:10372000034B1B781BB1034B4AF6AA221A60704761 -:103730001439002000300040034B1A681AB9034ABC -:10374000D2F874281A607047103900200030024007 -:10375000024B4FF08072C3F874287047003002406B -:1037600008B5FFF7E9FF024B1868C0F3407008BDC9 -:103770001039002008B5FFF7DFFF024B1868C0F3CF -:10378000007008BD10390020EFF3098305494A6B2A -:1037900022F001024A63683383F30988002383F32C -:1037A0001188704700EF00E0202080F3118862B696 -:1037B0000C4B0D4AD96821F4E0610904090C0A4355 -:1037C000DA60D3F8FC20094942F08072C3F8FC208B -:1037D0000A6842F001020A601022DA7783F82200B8 -:1037E000704700BF00ED00E00003FA05001000E0A4 -:1037F00010B5202383F311880E4B5B6813F400632C -:1038000014D0F1EE103AEFF30984683C4FF0807366 -:10381000E361094BDB6B236684F30988FFF7E8FB60 -:1038200010B1064BA36110BD054BFBE783F3118874 -:10383000F9E700BF00ED00E000EF00E03B06000804 -:103840003E06000870470000FEE700000A4B0B48E8 -:103850000B4A90420BD30B4BDA1C121AC11E22F0FA -:1038600003028B4238BF00220021FDF70DBE53F842 -:10387000041B40F8041BECE78C400008983900203A -:1038800098390020983900207047000000F080B877 -:103890004FF08043002258631A610222DA607047B9 -:1038A0004FF080430022DA60704700004FF0804301 -:1038B000586370474FF08043586A70474B684360C5 -:1038C0008B688360CB68C3600B6943614B6903629B -:1038D0008B6943620B6803607047000008B5234B97 -:1038E00023481A6942F0FF021A611A6922F0FF02A6 -:1038F0001A611A691A6B42F0FF021A631A6D42F0DC -:10390000FF021A651B4A1B6D1146FFF7D7FF02F134 -:103910001C0100F58060FFF7D1FF02F1380100F5CE -:103920008060FFF7CBFF02F1540100F58060FFF7E4 -:10393000C5FF02F1700100F58060FFF7BFFF02F1E3 -:103940008C0100F58060FFF7B9FF02F1A80100F5D6 -:103950008060FFF7B3FF02F1C40100F58060FFF75C -:10396000ADFFBDE8084000F097B800BF0038024046 -:1039700000000240803F000808B500F017FAFFF78A -:1039800065FBBDE80840FFF7D7BE000070470000A8 -:10399000104B1A6C42F001021A641A6E42F00102D6 -:1039A0001A660D4A1B6E936843F0010393604FF053 -:1039B000804331229A624FF0FF32DA6200229A612C -:1039C0005A63DA605A6001225A6108211A601C2089 -:1039D000FFF72EB800380240002004E04FF080428C -:1039E00008B51169D3680B40D9B2C9439B0711616F -:1039F00007D5202383F31188FFF748FB002383F3C7 -:103A0000118808BD08B5FFF7E9FFBDE80840FFF7DA -:103A1000EFBE00001E4B1A6962F0FF021A611A69BC -:103A2000D2B21A614FF0FF301A695A695861002109 -:103A30005A6959615A691A6A62F080521A621A6A9E -:103A400002F080521A621A6A5A6A58625A6A5962B5 -:103A50005A6A1A6C42F080521A641A6E42F080520E -:103A60001A661A6E0B4A106840F480701060186F66 -:103A700000F44070B0F5007F1EBF4FF4803018672F -:103A80001967536823F40073536000F06FB900BFE7 -:103A900000380240007000403B4B3C4A1A643C4AEC -:103AA0004FF4404111601A6842F001021A601A682E -:103AB0009007FCD59A6822F003029A60324B9A680C -:103AC00012F00C02FBD1196801F0F90119609A603B -:103AD0001A6842F480321A601A689103FCD55A6F52 -:103AE00042F001025A67284B5A6F9207FCD5294AC7 -:103AF0005A601A6842F080721A60254A5368580466 -:103B0000FCD5214B1A689101FCD5234AC3F88420C7 -:103B10001A6842F080621A601A681201FCD51F4AC6 -:103B20009A600322C3F88C204FF00062C3F89420FF -:103B30001B4B1A681B4B9A421B4B21D11B4A116825 -:103B40001B4A91421CD140F203121A60164A1368B4 -:103B500003F00F03032BFAD10B4B9A6842F00202D9 -:103B60009A609A6802F00C02082AFAD15A6C42F460 -:103B700080425A645A6E42F480425A665B6E7047C5 -:103B800040F20372E1E700BF003802400004001079 -:103B9000007000400819400210300024009488385A -:103BA000002004E011640020003C024000ED00E031 -:103BB00041C20F41084A08B5516913680B4003F030 -:103BC0000103536123B1054A13680BB1506898474C -:103BD000BDE80840FFF70CBE003C0140183900204A -:103BE000084A08B5516913680B4003F0020353619A -:103BF00023B1054A93680BB1D0689847BDE80840E7 -:103C0000FFF7F6BD003C014018390020084A08B50E -:103C1000516913680B4003F00403536123B1054A53 -:103C200013690BB150699847BDE80840FFF7E0BD44 -:103C3000003C014018390020084A08B55169136852 -:103C40000B4003F00803536123B1054A93690BB19C -:103C5000D0699847BDE80840FFF7CABD003C014065 -:103C600018390020084A08B5516913680B4003F061 -:103C70001003536123B1054A136A0BB1506A984788 -:103C8000BDE80840FFF7B4BD003C014018390020F2 -:103C9000174B10B55A691C68144004F478725A61C5 -:103CA000A30604D5134A936A0BB1D06A98476006FD -:103CB00004D5104A136B0BB1506B9847210604D5FD -:103CC0000C4A936B0BB1D06B9847E20504D5094AB7 -:103CD000136C0BB1506C9847A30504D5054A936C3F -:103CE0000BB1D06C9847BDE81040FFF781BD00BF15 -:103CF000003C0140183900201A4B10B55A691C6865 -:103D0000144004F47C425A61620504D5164A136DCE -:103D10000BB1506D9847230504D5134A936D0BB131 -:103D2000D06D9847E00404D50F4A136E0BB1506E66 -:103D30009847A10404D50C4A936E0BB1D06E9847F6 -:103D4000620404D5084A136F0BB1506F98472304DF -:103D500004D5054A936F0BB1D06F9847BDE810406A -:103D6000FFF746BD003C014018390020062108B588 -:103D70000846FEF75DFE06210720FEF759FE0621E4 -:103D80000820FEF755FE06210920FEF751FE062108 -:103D90000A20FEF74DFE06211720FEF749FEBDE87A -:103DA000084006212820FEF743BE000008B5FFF7B3 -:103DB00031FE00F00BF8FEF751FEFFF751F8FFF768 -:103DC000E5FDBDE80840FFF761BD00000023054A9E -:103DD00019460133102BC2E9001102F10802F8D193 -:103DE000704700BF1839002010B5013902449042D5 -:103DF00001D1002005E0037811F8014FA34201D062 -:103E0000181B10BD0130F2E72DE9F041A3B1C91A2A -:103E100017780144044603F1FF3C8C42204601D947 -:103E2000002009E00578BD4204F10104F5D10CEB56 -:103E30000405D618A54201D1BDE8F08115F8018D21 -:103E400016F801EDF045F5D0E7E70000034611F85C -:103E5000012B03F8012B002AF9D170476F72672EEE -:103E60006172647570696C6F742E626972646361EB -:103E70006E6479004E6F20617070207369670A006C -:103E8000426164206677206C656E677468202575D2 -:103E90000A0042616420626F6172645F6964202578 -:103EA000752073686F756C642062652025750A0043 -:103EB0004261642066772064657363726970746F11 -:103EC00072206C656E6774682025750A0042616413 -:103ED0002061707020435243203078253038783A82 -:103EE000307825303878203078253038783A307876 -:103EF000253038780A00476F6F64206669726D77E5 -:103F00006172650A0040A2E4F16468910600000055 -:103F100000000000292E0008152E0008512E000870 -:103F20003D2E0008492E0008352E0008212E0008DD -:103F30000D2E00085D2E00086D61696E0000000006 -:103F400069646C6500000000403F00086037002095 -:103F5000D8380020010000004930000800000000AF -:103F60000040000000400000004000000040000051 -:103F7000000001000000020000000200000002003A -:103F80000004802A00000000AAAAAAAA0000402576 -:103F9000DFFF0000000000000080080010000A00A1 -:103FA000000000009AAAAAAA00000000FBFF00007F -:103FB0000000000088000000000000000000000079 -:103FC000AAAAAAAA00000000FFFF0000000000004B -:103FD000000000000000000000000000AAAAAAAA39 -:103FE00000000000FFFF00000000000000000000D3 -:103FF0000000000000000000AAAAAAAA0000000019 -:10400000FFFF0000000000000000000000000000B2 -:1040100000000000AAAAAAAA00000000FFFF0000FA -:104020000000000000000000000000000000000090 -:10403000AAAAAAAA00000000FFFF000000000000DA -:104040000000000000000000000000000A00000066 -:10405000000000000300000000000000000000005D -:10406000B0C1FF7F01000000140400000000000048 -:1040700000000700000000006400000000000000D5 -:0C40800040420F00FE2A0100D2040000A4 +:1000000000070020F5040008DD26000895260008FA +:10001000BD26000895260008B5260008F70400084C +:10002000F7040008F7040008F7040008D1360008B8 +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008DD440008054500081F +:100060002D450008554500087D450008F7040008A7 +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F704000849260008F0 +:100090007526000885260008F7040008A545000815 +:1000A000F7040008F7040008F7040008F704000844 +:1000B0008D460008F7040008F7040008F70400085C +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008F7040008F7040008F704000814 +:1000E00009460008F7040008F7040008F7040008B0 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008F7040008A3 +:10015000F7040008F7040008F704000879460008CF +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E000BD12000800000000000000000000000038 +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600003F0C6FD03F058FE4FF055301F491B4AFB +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE703F0A4FD5E +:1005B00003F080FE144C154DAC4203DA54F8041BD2 +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E703F08CBD000700209E +:1005E000002300200000000808ED00E000010020CA +:1005F00000070020884F00080023002080230020EF +:1006000080230020C44F0020E0010008E40100081E +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002003F0CAF95D +:10064000FEE703F02DF900DFFEE70000F8B500F04B +:1006500047FE03F0E7FC074603F036FD0546D0BB36 +:10066000294B9F4237D001339F4237D0274B27F089 +:10067000FF029A4235D1F8B200F03EFC2E4642F21B +:10068000107400F03FFC08B10024264601F014F974 +:1006900058B3032000F03EF80024264635B11C4B29 +:1006A0009F4203D003F008FD00242646002003F0FB +:1006B000C3FC0EB100F044F800F090FC00F012FE14 +:1006C00002F014F80546B4B900F0D0FC4FF47A708B +:1006D00003F086F9F7E72E460024D2E70446012608 +:1006E000CFE706464FF47A74CBE7002CD6D04FF410 +:1006F0007A740126D2E701F0F9FF431BA342E3D944 +:1007000000F01EF8DCE700BF010007B0000008B0F1 +:10071000263A09B0084B187003280CD8DFE800F01F +:1007200008050208022000F039BE022000F02EBEAB +:10073000024B00225A60704780230020842300204F +:1007400010B501F0B9F830B1204B03221A70204BDC +:1007500000225A6010BD1F4B1F4A1C461968013108 +:10076000F8D004339342F9D162681C4B9A42F1D914 +:100770001B4B9B6803F1006303F580339A42E9D277 +:1007800003F06EFC03F080FC002000F0C5FD0220A9 +:10079000FFF7C0FF134B1A6C00221A64196E1A6619 +:1007A000196E596C5A64596E5A665B6E72B64FF088 +:1007B000E0233021C3F8084DD4E9003281F31188D9 +:1007C0009D4683F308881047C4E700BF80230020BC +:1007D000842300200000010820000108FFFF00081A +:1007E0000023002000380240094A136849F26900DA +:1007F00099B21B0C00FB01331360064B186844F2DE +:10080000506182B2000C01FB0200186080B2704798 +:10081000182300201423002010B5002110220446C4 +:1008200000F0D8FD034B03CB206061601868A06026 +:1008300010BD00BF107AFF1F2DE9F041ADF54E7DD0 +:100840000DF134086CAC40F2751207460D460EA847 +:100850000021C8F8001000F0BDFD4FF4C472002163 +:10086000204600F0B7FD01F041FF274B4FF47A72AC +:10087000B0FBF2F0186093E80700022384E8070059 +:100880000DF5E9702382FFF7C7FF41F204431F49CA +:10089000238407A804F080FA172384F832310DF27C +:1008A000E32207AB0DF12C0C1E4603CE664510600B +:1008B0005160334602F10802F6D130681060B18809 +:1008C000B3799371918020464146012200F0CEFD1C +:1008D00000230393AB7E029305F11903019380B2C9 +:1008E0000123CDE904800093E97E05A3D3E9002329 +:1008F000384602F0C3FA0DF54E7DBDE8F08100BF29 +:100900009E6AC421818A46EE8C230020A84D0008EF +:100910002DE9F0412C4C237ADAB080460D465BBBC2 +:1009200027A9284600F0B2FE0746002842D19DF8CC +:100930009D60C82E3ED801464FF4A662204600F0C6 +:1009400049FD4FF48073C4F8F8314FF40073C4F8D4 +:100950000C334FF44073C4F8203432460DF19E013D +:1009600004F1090000F024FD26449DF89C307772C4 +:1009700023720BB9EB7E23728122002106AC27A8DB +:1009800000F028FD0122214627A800F0BBFE00232D +:100990000393AB7E029305F1190380B201932823E0 +:1009A000CDE904400093E97E05A3D3E90023404646 +:1009B00002F064FA5AB0BDE8F08100BFAFF30080E6 +:1009C00026417272DF25D7B7A8440020F0B5254E26 +:1009D0004FF48A7505FB0065F1B096F8D83085F8BC +:1009E000DC300024D822214685F8E8403AA800F0FF +:1009F000F1FC06F1090000F0E5FCD5F8E4308DF8D3 +:100A0000F000C2B206AF06F109010DF1F100CDE927 +:100A10003A3400F0CDFC394601223AA800F09EFE9F +:100A200080B2CDE9047008230127CDE9023706F131 +:100A3000D803019330230093317A0B4807A3D3E9FD +:100A4000002302F01BFAA04206DD01F04FFEC5F8BC +:100A5000E000384671B0F0BD2046FBE778F6339FE2 +:100A600093CACD8DA8440020A43300202DE9F04185 +:100A70001D4D1E4E1E4F86B0284602F02BFA03462F +:100A800058B30024CDE90344ADF81440027B8DF83F +:100A9000142099684068029403AA03C21B68DFF817 +:100AA000548043F00043029301F022FE821941F189 +:100AB0000003009402A9384601F0E4F8A04205DDE5 +:100AC000284602F00BFA88F80040D5E798F8003085 +:100AD000072B05D8013388F8003006B0BDE8F08157 +:100AE000014802F0FBF9F8E7A433002040420F0070 +:100AF000D8330020DD49002070B50D4614461E464F +:100B000002F018F950B9022E10D1012C0ED112A307 +:100B1000D3E90023C5E90023012007E0282C10D0E9 +:100B200005D8012C09D0052C0FD0002070BD302C29 +:100B3000FBD10BA3D3E90023ECE70BA3D3E90023FC +:100B4000E8E70BA3D3E90023E4E70BA3D3E90023F1 +:100B5000E0E700BFAFF30080401DA12026812A0BF3 +:100B600078F6339F93CACD8D9E6AC421818A46EE62 +:100B700026417272DF25D7B7F017304A39059E56E5 +:100B800038B505460E4C0021013500F0E7FBA4F80E +:100B90002C55B4F82C0500F0C9FB78B1B4F82C053D +:100BA00000F0D4FB014648B9B4F82C0500F0D6FBA0 +:100BB000B4F82C350133A4F82C35EAE738BD00BF72 +:100BC000A844002010B50A4B0A4A1A6003F5805366 +:100BD00093F860203AB9DC6D2CB1204600F0EAFEB3 +:100BE000204604F019F8BDE81040034800F0E2BECA +:100BF000D8330020FC4D0008204400202DE9F04FA0 +:100C00008FB000AF05460C4602F094F8002849D199 +:100C1000237E022B1BD1E38A012B18D101F066FD44 +:100C20000646FFF7E1FD03464FF4C870DFF8C482C3 +:100C3000B3FBF0F206F5167602FB103316FA83F3D7 +:100C4000C8F80030E37E33B9A34B00221A703C375A +:100C5000BD46BDE8F08F07F12401204600F0D4FC2A +:100C60000028F4D107F11400FFF7D6FD97F82640CD +:100C700007F11401224607F1270004F017F80028B5 +:100C8000E2D10F2C08D8944B1C70D8F80030A3F593 +:100C90001673C8F80030DAE797F82410284602F0F7 +:100CA00041F8D4E7E38A282B2BD010D8012B23D08E +:100CB000052BCCD1BFF34F8F8849894BCA6802F40A +:100CC000E0621343CB60BFF34F8F00BFFDE7302BD3 +:100CD000BDD1844EE17E327A9142B8D1607E3146F8 +:100CE000002291F8DC50854200F0A5800132042AF0 +:100CF00001F58A71F5D1AAE721462846FFF79CFD48 +:100D0000A5E721462846FFF703FEA0E7B2F8EC501E +:100D10007B6005F103094FEA99094FEA8902D11D69 +:100D2000C908A8EBC1039D46EB460021584600F0D8 +:100D300051FB04F1EE012A463144584600F038FBDD +:100D40007B6813B9012000F0E7FA96F8D20000F0B2 +:100D5000EDFA044630B9307200F008FB204600F08E +:100D6000DBFAB1E0D6F8D4203AB996F8D200B6F85A +:100D70002C25824201D8FFF703FFD6F8D4202A445D +:100D8000944208D296F8D200B6F82C25013082425F +:100D900001D8FFF7F5FE70685FFA89F2594600F056 +:100DA00021FB08B9C54679E0726896F8D2002A445A +:100DB0007260D6F8D42005EB0209C6F8D49000F092 +:100DC000B5FA814509D396F8D220D6F8D40001327D +:100DD000001B86F8D220C6F8D400FF2D0FD80024BF +:100DE000347200F0C3FA204600F096FA00F064FD79 +:100DF0003D4B188108B9FFF7A3FCC54627E7BB6840 +:100E000096F8D9000AFB0362FB68D2F8E41082F876 +:100E1000E83001F58061C2F8E030C2F8E410FFF775 +:100E2000D5FDFFF723FE96F8D920013202F0030228 +:100E300086F8D920B6E74FF48A7A0AFB02F505F165 +:100E4000EA013144204600F0B5FCF86000287FF448 +:100E5000FEAE3544012285F8E82001F047FCD5F8C4 +:100E6000E020D6ED007ADFED216A801A192838BF1C +:100E7000192040F6B832904228BF1046B8EE677A83 +:100E800007EE900AF8EEE77A67EEA67ADFED186AC9 +:100E9000E7EE267AFCEEE77AC6ED007A96F8D930CE +:100EA000BB60BA6873680AFB02F4321992F8E81062 +:100EB00059B1D2F8E4108B42E8463FF427AF002145 +:100EC00082F8E810C2F8E010C5467368064A9B0A2B +:100ED00001331381BBE600BF9D33002000ED00E02D +:100EE0000400FA05A84400208C230020CDCCCC3D82 +:100EF0006666663FA0330020014B1870704700BF44 +:100F00009823002030B54FF000542B4B22689A42B2 +:100F100085B007D003F0E2F8044620BB0024204649 +:100F200005B030BD254B627D25481A70237D0372C4 +:100F30004FF48073C0F8F8314FF40073C0F80C33ED +:100F400000254FF44073C0F820341E49C0F8E45027 +:100F5000C922093000F02CFA2046E022294600F090 +:100F600039FA0124DBE7184A184D136C43F000737B +:100F70001364AA6D164B9A42D0D12B6E013B7E2B87 +:100F8000CCD8144A07CA01AB83E8070018460321EE +:100F900000F060FC6B6D83424FF00003BED12A6D00 +:100FA0008A4201BFAB65054B2A6E1A7003BF0A4B1C +:100FB000EA6D1A601C46B2E79AAD44C5982300203A +:100FC000A8440020160000200038024000660040BF +:100FD0005041A0B0586600401023002037B51A4D8C +:100FE00000F06AFC02236B71184B288119681848BD +:100FF000012201F019FA00230193164B16490093C0 +:101000001648174B4FF4805201F064FE154B1978C7 +:1010100011B1124801F086FE01F068FB0446FFF7AB +:10102000E3FB4FF4C873B0FBF3F202FB130304F5C8 +:10103000167010FA83F00C4B186003F045F808B1F5 +:101040000F232B8103B030BD8C2300201023002000 +:10105000D8330020F90A00089C230020A433002084 +:10106000FD0B000898230020A03300202DE9F04F4D +:101070002DED028B0FF23829D9E90089834C93B00A +:101080000BAE9FED7E8BFFF7F1FC814FDFF828A2BE +:1010900000230A93ADF834300B9373604FF0000BCC +:1010A0005B468DED008B01250DF11D0207A9384629 +:1010B0008DF81C508DF81DB001F066F99DF81C30BC +:1010C000002B40F0A580204601F034FE06460028A3 +:1010D00045D1704F01F00AFB3B6898423FD301F0C5 +:1010E00005FB8246FFF780FB4FF4C873B0FBF3F2B9 +:1010F00002FB13030AF5167010FA83F03860664F8E +:1011000097F800B0CBF1100ABBF1000F14BF3346C3 +:101110002B465FFA8AFA0EA88DF82830FFF77CFB81 +:10112000BAF1060F28BF4FF0060A0EAB03EB0B0116 +:1011300052460DF1290000F03BF90AAB0393182346 +:1011400002930AF10102554BD2B2CDE90053049249 +:1011500020464CA3D3E9002301F032FE3E7001F09B +:10116000C5FA4F4A4F4D1368C31AB3F57A7F2ED391 +:10117000106001F0BDFA02460B46204601F0B8FEB1 +:10118000204601F0D7FD10B32B7A474E002B14BF39 +:1011900003230223737101F0A9FA0EAF4FF47A739F +:1011A0000122B0FBF3F039463060304600F004FA1B +:1011B000182302933D4B019380B240F25513CDE9C1 +:1011C0000370009342464B46204601F0F9FD2B7A0E +:1011D00093B101F08BFA002607464FF48A7A95F80E +:1011E000D900304400F003000AFB005393F8E820D4 +:1011F00092B30136042EF2D1C82002F0F1FB2B7A13 +:10120000002B7FF43DAF13B0BDEC028BBDE8F08F37 +:10121000DAF8143083F02003CAF81430594610224B +:101220000EA800F0D7F80DF11E0308AA0AA9384647 +:1012300000F026FE96E803000FAB83E803009DF85C +:1012400034308DF844300A9B0E930EA9DDE9082353 +:10125000204602F021F821E7D3F8E02042B12B68C4 +:10126000FA2B38BFFA23BA1A0533B2EB430FC0D3B7 +:10127000FFF7ACFB0028BCD1BEE700BF00000000B8 +:1012800000000000401DA12026812A0BA43300206D +:10129000D8330020A03300209D3300209C33002051 +:1012A000D8490020A84400208C230020DC490020DD +:1012B000F1C6A7C1D068080F0000024008B5054874 +:1012C00000F078FEBDE80840034A0449002003F01E +:1012D0009DBC00BFD8330020184A0020C50B000871 +:1012E0007047000070B502F03FFD094E094D308097 +:1012F000002428683388834208D902F02FFD2B6828 +:1013000004440133B4F5803F2B60F2D370BD00BFBD +:101310000C4A0020E049002002F0D6BD00F1006038 +:10132000920000F5803002F065BD0000054B1A68A0 +:10133000054B1B889B1A834202D9104402F00EBD54 +:1013400000207047E04900200C4A0020024B1B6837 +:10135000184402F00BBD00BFE0490020024B1B689F +:10136000184402F01BBD00BFE0490020064991F877 +:10137000243033B10023086A81F824300822FFF7B3 +:10138000CDBF0120704700BFE4490020022802BF02 +:10139000014B20229A61704700000240022802BFE0 +:1013A000024B4FF400129A61704700BF00000240E8 +:1013B00010B50023934203D0CC5CC4540133F9E749 +:1013C00010BD000003460246D01A12F9011B002985 +:1013D000FAD1704702440346934202D003F8011B3E +:1013E000FAE770472DE9F8431F4D144695F824207D +:1013F0000746884652BBDFF870909CB395F82430BE +:101400002BB92022FF2148462F62FFF7E3FF95F812 +:101410002400C0F10802A24228BF2246D6B24146AB +:10142000920005EB8000FFF7C3FF95F82430A41B62 +:101430001E44F6B2082E17449044E4B285F82460A6 +:10144000DBD1FFF793FF0028D7D108E02B6A03EB2D +:1014500082038342CFD0FFF789FF0028CBD1002041 +:10146000BDE8F8830120FBE7E44900202DE9F047BF +:101470000D46044600219046284640F27912FFF7B7 +:10148000A9FF234620220021284601F0A7FE231DA4 +:1014900002222021284601F0A1FE631D0322222101 +:1014A000284601F09BFEA31D03222521284601F0BA +:1014B00095FE04F1080310222821284601F08EFE33 +:1014C00004F1100308223821284601F087FE04F1B8 +:1014D000110308224021284601F080FE04F1120386 +:1014E00008224821284601F079FE04F11403202245 +:1014F0005021284601F072FE04F1180340227021A9 +:10150000284601F06BFE04F120030822B021284692 +:1015100001F064FE04F121030822B821284601F0FD +:101520005DFE04F12207C0263B46314608222846CC +:10153000083601F053FEB6F5A07F07F10107F3D19D +:1015400004F1320308223146284601F047FE002705 +:1015500004F1330A94F832304FEAC7099F4209F583 +:10156000A47615D3B8F1000F08D1314604F599736C +:101570000722284601F032FE09F24F16274694F85A +:1015800032213B1B93420CD3F01DC008BDE8F0870D +:101590000AEB070308223146284601F01FFE0137F7 +:1015A000D8E707F2331331460822284601F016FE29 +:1015B00008360137E3E7000013B50446084600216A +:1015C00001602346C0F803102022019001F006FEBE +:1015D0000198231D0222202101F000FE0198631DC5 +:1015E0000322222101F0FAFD0198A31D03222521E7 +:1015F00001F0F4FD019804F108031022282101F004 +:10160000EDFD072002B010BDF7B50023047F009167 +:101610000E4607221946054601F0A4FC731C0093F0 +:10162000012200230721284601F09CFCC4B9B31C09 +:101630000093052223460821284601F093FC0D243F +:101640003746B278BB1B934211D32B7FA88A07344D +:10165000E408BBB9844294BF0020012003B0F0BD70 +:10166000AB8ADB00083BDB08B3700824E8E7FB1C0F +:101670000093214600230822284601F073FC083419 +:101680000137DEE7201A18BF0120E7E7F7B500238E +:10169000047F00910E4608221946054601F062FCBF +:1016A000731CC4B90822009311462346284601F052 +:1016B00059FC1024012372785F1C013B934211D323 +:1016C0002B7FA88A0734E408BBB9844294BF00206A +:1016D000012003B0F0BDAB8ADB00083BDB08737070 +:1016E0000824E7E7F319009321460023082228463F +:1016F00001F038FC08343B46DDE7201A18BF012012 +:10170000E7E70000F8B50E460546144600218122A1 +:101710003046FFF75FFE2B4608220021304601F0DD +:101720005DFD7CB96B1C07220821304601F056FD97 +:101730000F2401236A785F1C013B934204D3E01D10 +:10174000C008F8BD0824F4E7EB192146082230460A +:1017500001F044FD08343B46ECE70000F8B50E46C6 +:10176000054614460021CE223046FFF733FE2B46B5 +:1017700028220021304601F031FD7CB905F1080333 +:1017800008222821304601F029FD30242F462A7AEC +:101790007B1B934204D3E01DC008F8BD2824F5E765 +:1017A00007F1090321460822304601F017FD0834ED +:1017B0000137ECE7F7B5047F00910E4601231022B4 +:1017C0000021054601F0CEFBC4B9B31C00930922E9 +:1017D00023461021284601F0C5FB1924374672889C +:1017E000BB1B9A4211D82B7FA88A0734E408BBB9E7 +:1017F000844294BF0020012003B0F0BDAB8ADB001F +:10180000103BDB0873801024E8E73B1D0093214662 +:1018100000230822284601F0A5FB08340137DEE743 +:10182000201A18BF0120E7E730B5094D0A4491425C +:101830000DD011F8013B5840082340F30004013B50 +:101840002C4013F0FF0384EA5000F6D1EFE730BDDF +:101850002083B8EDF7B54FF0FF33DFF854C0DFF861 +:1018600054E000EB81011A4688421CD050F8044B2A +:10187000019401AF042417F8015B82EA0562082590 +:10188000DB18164605F1FF355241002EBCBF83EA36 +:101890000C0382EA0E0215F0FF05F1D1013C14F0B1 +:1018A000FF04E8D1E0E7D843D14303B0F0BD00BF67 +:1018B0009336EAA9EBE1F042F7B5384A106851686F +:1018C0006B4603C36A4636493648082303F0FEF9DF +:1018D0000446002833D10A25334A106851686B4604 +:1018E00003C36A4631492F48082303F0EFF9044641 +:1018F000002849D00369B3F5E02F45D8B0F8661049 +:1019000040F2144291423FD1294A024402F15C0163 +:101910008B4239D35C3B234900209E1AFFF784FF9A +:101920003246074604F164010020FFF77DFFA368FB +:101930009F4229D1E368984208BF002524E003694B +:10194000B3F5E02F27D8418B40F21442914220D1C9 +:10195000174A024402F110018B4218D3103B11497F +:1019600000209D1AFFF760FF2A46064604F1180181 +:101970000020FFF759FFA3689E4202D1E368984216 +:1019800001D00D25A8E70025284603B0F0BD10259D +:10199000A2E70C25A0E70B259EE700BFC04D00087D +:1019A000DCFF060000000108C94D000890FF06009A +:1019B0000800FFF710B5037C044613B9006803F074 +:1019C0006DF9204610BD00000023BFF35B8FC3609C +:1019D000BFF35B8FBFF35B8F8360BFF35B8F704799 +:1019E000BFF35B8F0068BFF35B8F704770B5054630 +:1019F0000C30FFF7F5FF05F1080604463046FFF707 +:101A0000EFFFA04206D930466D68FFF7E9FF254495 +:101A1000281A70BD3046FFF7E3FF201AF9E70000EF +:101A200070B50546406898B105F10800FFF7D8FF8A +:101A300005F10C0604463046FFF7D2FF84423046DB +:101A400094BF6D680025FFF7CBFF013C2C44201AA2 +:101A500070BD000038B50C460546FFF7C7FFA04231 +:101A600010D305F10800FFF7BBFF04446868B4FB1E +:101A7000F0F100FB1144BFF35B8F0120AC60BFF3BA +:101A80005B8F38BD0020FCE72DE9F0411446074686 +:101A90000D46FFF7C5FF844228BF0446D4B1B846BF +:101AA00058F80C6B4046FFF79BFF304428604046D7 +:101AB0007E68FFF795FF331A9C4203D86C600120C3 +:101AC000BDE8F0816B60A41B3B68AB602044E8601C +:101AD0000220F5E72046F3E738B50C460546FFF748 +:101AE0009FFFA04210D305F10C00FFF779FF0444DB +:101AF0006868B4FBF0F100FB1144BFF35B8F012079 +:101B0000EC60BFF35B8F38BD0020FCE72DE9FF419F +:101B1000884669460746FFF7B7FF6C4606B204EBF6 +:101B2000C6060025B44209D06268206808EB0501AA +:101B3000FFF73EFC636808341D44F3E72946384646 +:101B4000FFF7CAFF284604B0BDE8F081F8B50546A6 +:101B50000C300F46FFF744FF05F1080604463046F7 +:101B6000FFF73EFFA042304688BF6C68FFF738FFA2 +:101B7000201A386020B130462C68FFF731FF20442E +:101B8000F8BD000073B5144606460D46FFF72EFF5C +:101B9000844228BF04460190DCB101A93046FFF71A +:101BA000D5FF019B33B93268C5E90233C5E900248A +:101BB00001200CE09C4238BF0194286001986860C5 +:101BC0008442F5D93368AB60241AEC60022002B07D +:101BD00070BD2046FBE700002DE9FF410F46694636 +:101BE000FFF7D0FF6C4600B204EBC0050026AC4204 +:101BF00009D0D4F8048054F8081BB8194246FFF7FE +:101C0000D7FB4644F3E7304604B0BDE8F08100005E +:101C100038B50546FFF7E0FF044601462846FFF7C2 +:101C200019FF204638BD0000302383F3118862B6C7 +:101C300070470000002383F3118862B670470000EC +:101C400010B4026854681A4623465DF8044B1847DE +:101C50000120704700207047002070477047000047 +:101C6000002070470E20704700F5805090F8C800A3 +:101C7000C0F340007047000000F5805090F9C900A3 +:101C800070470000F7B50C68BDF8207014F00054E0 +:101C90001E466FD10B7B082B6CD8FFF7C5FF45693B +:101CA000AB685B010CD4AB681B0108D4AC6814F0C2 +:101CB00080545DD1FFF7BEFF204603B0F0BD012484 +:101CC0000B6804F1180C002BB8BFDB004FEA0C1CAA +:101CD000B4BF43F004035B0545F80C300B680FFA02 +:101CE00084FC13F0804F18BF05EB0C1E05EB0C1C99 +:101CF0001EBFDEF8803143F00203CEF880310B7B4B +:101D0000CCF8843105EB04158B68C5F88C314B6831 +:101D1000C5F88831DCF8803143F00103CCF880311C +:101D200000EB441541F268031D4403EB44130344E4 +:101D3000C5E9002608330D4601F10C0C55F804EBFB +:101D400043F804EB6545F9D184342D881D8000EB00 +:101D5000441407F00303257925F00B052B43237169 +:101D6000FFF768FF0097334600F0E2FC0120A4E78C +:101D70000224A5E74FF0FF309FE7000013B500F500 +:101D800080540191E06DFFF74BFE1F280AD901999D +:101D9000E06D2022FFF7BAFEA0F12003584258411F +:101DA00002B010BD0020FBE708B500F58050FFF73A +:101DB0003BFFC06DFFF708FEBDE80840FFF73ABFE4 +:101DC00000220260828142608260704710B500226A +:101DD0000023C0E900230023044603810C30FFF7F1 +:101DE000EFFF204610BD0000F0B5054600F580501D +:101DF0000C4690F8C83013F0040FC3F3800108BFFD +:101E0000114661F3820304F1840680F8C83005EBC3 +:101E1000461389B01B79D8072ED57AB319072DD46C +:101E20006846FFF7D3FF05EB441303F5835303F133 +:101E3000180703AA103318685968144603C40833F6 +:101E4000BB422246F7D1186820609B88A380DDE959 +:101E50000E23CDE900230123ADF808302B68694635 +:101E6000DB6B2846984705EB46152B791A075CBFB4 +:101E700043F008032B7101E0002AF4D109B0F0BD52 +:101E80002DE9F047074688B007F5805468469A4622 +:101E90008846FFF7C9FE9146FFF798FFE06DFFF710 +:101EA000A5FD1F2829D9E06D20226946FFF7B0FE65 +:101EB000202822D103AD444605AB2E4603CE9E42D8 +:101EC00020606160354604F10804F6D13068206076 +:101ED000B388A380DDE90023C9E90023BDF80830F9 +:101EE000AAF80030FFF7A6FE4A4653464146384658 +:101EF00008B0BDE8F04700F009BCFFF79BFE0020EA +:101F000008B0BDE8F08700002DE9F84F0023C0E9D4 +:101F10000133254B044640F8183B0F46FFF750FFAE +:101F200004F12800FFF752FF04F1480804F5825538 +:101F30004646083530462036FFF748FFAE42F9D115 +:101F400004F580554FF480534FF00009C5E913396B +:101F5000C5F848800123EE6504F5875804F58456DA +:101F6000C5F8549085F8583085F86030083608F187 +:101F700008084FF0000A4FF0000B46E908ABA6F145 +:101F80001800FFF71DFF203646F8289C4645F4D17F +:101F900085F8C97017B1054800F0A2FB044B6361D6 +:101FA0002046BDE8F88F00BFFC4D0008D44D000866 +:101FB0000064004010B5044B197804464A1C1A709E +:101FC000FFF7A2FF204610BD144A00202DE9F0477C +:101FD000002950D0294B2A4FB7FBF1F599428CBF0D +:101FE0000A231123581EB5FBF3FC03FB1C53C4B298 +:101FF0002BB102280346F5D80020BDE8F0870CF18C +:10200000FF36B6F5806FF7D2C4EBC40E0EF10303B2 +:102010004FEAE309C3F3C703A4EB030809F1010A7C +:102020004FF47A755FFA88F009FB05555AFA88F87B +:10203000B5FBF8F5B5F5617FC1BF0EF1FF33C3F312 +:10204000C703E01AC0B25C1C50FA84F40CFB04F421 +:10205000B7FBF4F4A142CFD1013BDBB20F2BCBD8BD +:102060000138C0B20728C7D80021107116809170BE +:10207000D3700120C1E70846BFE700BF3F420F0011 +:1020800040787D0170B505460E464FF47A746B6951 +:102090005B6803F00103B34207D04FF47A7001F09C +:1020A0009FFC013CF3D1204670BD0120FCE70000FD +:1020B00030B54269936913F0700F16D000230B4CB2 +:1020C000936103F1840200EB421211794D0709D5A7 +:1020D000890707D5416954F823508D60117941F083 +:1020E000040111710133032BEBD130BDE84D000821 +:1020F00073B51D46436916469A68D207044609D54A +:102100009A6801219960C2F34002CDE9006500217F +:10211000FFF76AFE63699A68D1050BD59A684FF498 +:1021200080719960C2F34022CDE90065012120460B +:10213000FFF75AFE63699A68D2030BD59A684FF489 +:1021400080319960C2F34042CDE90065022120460A +:10215000FFF74AFE204602B0BDE87040FFF7A8BF77 +:10216000F8B50446466900296CD106F10C073868B9 +:1021700080076AD006EB01153868D5F8B00110F079 +:10218000040FD5F8B0011ABFC00840F00040400D60 +:10219000A061D5F8B0C11CF0020F1CBF40F0804018 +:1021A000A061D5F8B40106EB011100F00F0084F82E +:1021B0002400D1F8B8012077D1F8B801000A60777F +:1021C000D1F8B801000CA077D1F8B801000EE07783 +:1021D000D1F8BC0184F82000D1F8BC01000A84F8D1 +:1021E0002100D1F8BC01000C84F82200D1F8BC1108 +:1021F000090E84F823103821396004F1340004F109 +:10220000180104F1240551F8046B40F8046BA9424D +:10221000F9D109880180C4E90A23214600232386D5 +:1022200051F8283B2046DB6B984704F58052204646 +:1022300092F8C83043F0040382F8C830BDE8F84093 +:10224000FFF736BF06F1100791E7F8BD10B5044659 +:1022500000F04EFA02460B4652EA030102D0013A60 +:1022600063F100030449086820B12146BDE810402D +:10227000FFF776BF10BD00BF104A0020F8B500F58B +:1022800083511E46FFF7D0FCDFF844C0083100241C +:1022900004F1840500EB45152B795F070ED4DB06AE +:1022A0000CD5D1E900739742B34107D243695CF87A +:1022B00024709F602B7943F004032B710134032CAD +:1022C00001F12001E4D1BDE8F840FFF7B3BC00BF45 +:1022D000E84D000808B5FFF7A7FCFFF7E9FEBDE8E9 +:1022E0000840FFF7A7BC0000F8B5436905469868A9 +:1022F00000F0E050B0F1E05F0F461FD0E8B1FFF70B +:1023000093FC05F583541034002606F1840305EB95 +:1023100043131B791A0706D50136032E04F1200456 +:10232000F3D1012007E05B07F6D42146384600F0E0 +:1023300039FA0028F0D1FFF77DFCF8BD0120FCE759 +:1023400000F5805008B5FFF76FFCC06DFFF74EFB3E +:10235000FFF770FC43090CBF0120002008BD0000FE +:10236000F8B51D46002313700F4606461446FFF7C6 +:10237000E7FF80F00100387025B129463046FFF7AD +:10238000B3FF2070F8BD00002DE9B8410C4615469A +:102390001F46804600F0ACF90B462178024609B989 +:1023A000287850B14046FFF769FFFFF793FF3B469F +:1023B0002A462146FFF7D4FF0120BDE8B88100007E +:1023C00010B5FFF731FC174B1A6C42F000721A641B +:1023D0001A6A42F000721A621A6A00F5805422F0FA +:1023E00000721A62FFF726FC94F8C830DB0718D495 +:1023F000B9B103211320FFF717FC01F0C7F903213E +:10240000142001F0C3F90321152001F0BFF994F85D +:10241000C83043F0010384F8C830BDE81040FFF72E +:1024200009BC10BD003802402DE9F04700F5805589 +:1024300088B095F8C930012B0446884616467FD8E7 +:10244000804F57F823200AB947F82300D7F800A097 +:10245000C4F80C802674BAF1000F63D095F8C93027 +:10246000012B6FD001212046FFF7AAFFFFF7DCFB0D +:102470006269136823F0020313606269136843F012 +:1024800001031360636900275F6101212046FFF7A4 +:10249000D1FBFFF7F7FD002800F09580E86DFFF70E +:1024A00093FA04F58359BA4609F10809202200215C +:1024B0006846FEF78FFF02A8FFF782FCCDF818A050 +:1024C0006A4609EB07030DF1180E9446BCE80300B9 +:1024D000F44518605960624603F10803F5D1DCF851 +:1024E0000000186020379CF804201A71602FDDD19D +:1024F00095F8C8306FF38203002785F8C8306A4624 +:1025000041462046ADF80070ADF802708DF80470B9 +:10251000FFF75CFD636948BB4FF400421A6008B0E6 +:10252000BDE8F08741F2D00002F078FB814610B19F +:102530005146FFF7E9FCC7F80090B9F1000F8DD1C3 +:102540000020ECE7386803681B6B984701460028B9 +:1025500088D13868FFF734FF3868036832465B6813 +:102560004146984700287FF47DAFE9E761221A6071 +:102570009DF802309DF803201B06120402F470221D +:1025800003F040731343BDF80020C2F30902134364 +:102590009DF804201205022E02F4E0020CBF4FF059 +:1025A00000410021134362690B43D3616369132225 +:1025B0005A616269136823F00103136039462046AB +:1025C000FFF760FD08B96369A6E795F8C93093BBCA +:1025D0006169D1F8002242F00102C1F8002261696C +:1025E000D1F8002222F47C5222F00E02C1F800221F +:1025F0006169D1F8002242F46062C1F80022626988 +:10260000C2F814326269C2F80432626941F6FF719D +:10261000C2F80C126269C2F840326269C2F84432F0 +:1026200063690122C3F81C226269D2F8003223F0E8 +:102630000103C2F8003295F8C83043F0020385F870 +:10264000C8306CE7104A002008B500F051F850EA95 +:102650000103024602D0421E61F10001044B1868DA +:1026600010B10B46FFF744FDBDE8084001F064B827 +:10267000104A002008B50020FFF7E8FDBDE808403B +:1026800001F05AB808B50120FFF7E0FDBDE80840A9 +:1026900001F052B800B59BB0EFF30981682268469B +:1026A000FEF786FEEFF30583014B9B6BFEE700BF51 +:1026B00000ED00E008B5FFF7EDFF000000B59BB0AE +:1026C000EFF3098168226846FEF772FEEFF3058397 +:1026D000014B5B6BFEE700BF00ED00E0FEE7000092 +:1026E0000FB408B5029801F011F9FEE701F038BC0B +:1026F00001F010BC13B56C4684E80600031D94E895 +:10270000030083E80500012002B010BD73B58568A1 +:10271000019155B11B885B0707D4D0E900369B6B4C +:102720009847019AC1B23046A847012002B070BD57 +:10273000F0B5866889B005460C465EB1BDF8383004 +:102740005B070AD4D0E900379B6B98472246C1B299 +:102750003846B047012009B0F0BD00220023CDE982 +:1027600000230023ADF808300A4603AB01F1080648 +:10277000106851681C4603C40832B2422346F7D1A0 +:10278000106820609288A280FFF7B2FF0423ADF8A2 +:1027900008302B68CDE90001DB6B69462846984775 +:1027A000D8E7000030B503680968DD0FB5EBD17FCD +:1027B00023F0604421F060424FEAD1700BD0002B2F +:1027C000B8BFA40C0029B8BF920C944202D034BF09 +:1027D0000120002030BD944205D1C1F38070C3F3C5 +:1027E00080738342F6D194422CBF00200120F1E790 +:1027F0002DE9F041456A15B94162BDE8F0814B68A9 +:1028000023F06047C3F38A464FEAD37EC3F3807850 +:1028100016EA230638BF3E46AC462B465A68BEEB46 +:10282000D27F22F060440AD0002A18DAA40CB44205 +:1028300017D19D420FD10D60DEE71346EEE7A742A8 +:1028400007D102F08044C2F3807242450BD054B1EC +:10285000EFE708D2EDE7CCF800100B60CDE7B4420B +:1028600001D0B442E5D81A689C46002AE5D1196027 +:10287000C3E700002DE9F047089D01F007044FEA87 +:10288000D508224405F0070500EBD1004FF47F493D +:10289000944201D1BDE8F08704F0070705F0070A6C +:1028A00057453E4638BF5646C6F10806111B8E42B4 +:1028B00028BF0E46E10808EBD50E415C13F80EC0A8 +:1028C000B94029FA06F721FA0AF1FFB28CEA0101B0 +:1028D00047FA0AF739408CEA010C03F80EC0344479 +:1028E0003544D5E780EA0120082341F2210201B2F4 +:1028F0004000002980B203F1FF33B8BF504013F00D +:10290000FF03F4D17047000038B50C468D18A5427E +:1029100000D138BD14F8011BFFF7E4FFF7E7000012 +:1029200042684AB1136843604389818901339BB28D +:102930009942438138BF83811046704770B588B093 +:10294000202204460D4668460021FEF743FD20463E +:102950000495FFF7E5FF024658B16B46054608AE01 +:102960001C4603CCB44228606960234605F1080583 +:10297000F6D1104608B070BD082817D909280CD028 +:102980000A280CD00B280CD00C280CD00D280CD009 +:102990000E2814BF4020302070470C2070471020B4 +:1029A000704714207047182070472020704700009F +:1029B000082817D90C280CD910280CD914280CD9A0 +:1029C00018280CD920280CD930288CBF0F200E20B5 +:1029D0007047092070470A2070470B2070470C2071 +:1029E00070470D20704700002DE9F843078C072F32 +:1029F00004461ED9D0E9029800254FF6FF73C5F1B1 +:102A00002006A5F1200029FA05F108FA06F628FAB1 +:102A100000F031430143C9B21846FFF763FF0835A0 +:102A2000402D0346EBD1E1693A46BDE8F843FFF794 +:102A30006BBF4FF6FF70BDE8F883000010B54B6820 +:102A400023B9CA8A63F30902CA8210BD04691A68ED +:102A50001C600361C38A013BC3824A60EFE7000048 +:102A60002DE9F84F1D46CB8A0F46C3F3090105290E +:102A7000814692460B4630D00020AAB207F11A04D4 +:102A80009EB2042E1FFA80F80FD8904503F101037F +:102A900006D3FB8A0A4462F30903FB8201201AE091 +:102AA0001AF80060E6540130EAE79045F1D2A1F14E +:102AB000050B1C237C68BBFBF3F203FB12BB1FFA64 +:102AC0008BF6002C45D14846FFF72AFF044638B95B +:102AD00078606FF00200BDE8F88F4FF00008E6E77D +:102AE000002606607860ADB24FF0000B454510D966 +:102AF0000AEB0803221D13F8011B9155B1B208F12E +:102B000001081B291FFA88F82BD0454506F101065C +:102B1000F1D8FB8AC3F30902154465F30903BCE746 +:102B2000013292B21C462368002BF9D16B1F0B4473 +:102B30001C21B3FBF1F301339BB29A42D3D2BBF118 +:102B4000000FD0D14846FFF7EBFE20B9C4F800B023 +:102B5000BFE70122E7E7C0F800B05E462060044608 +:102B6000C1E74545D5D94846FFF7DAFE08B92060E8 +:102B7000AFE7C0F800B0002620600446B6E70000CA +:102B80002DE9F04F2DED028B1C4683B05B6901925D +:102B900007468846002B00F09A80238C2BB1E2690F +:102BA000002A00F09480072B35D807F10C00FFF7BE +:102BB000B7FE054638B96FF00205284603B0BDECF4 +:102BC000028BBDE8F08F14220021FEF703FC228C5B +:102BD000E16905F10800FEF7EBFB208C013080B2C3 +:102BE000FFF7E6FEFFF7C8FE013880B2208401300F +:102BF00028746369228C1B782A4403F01F0363F056 +:102C00003F0348F000411372384669602946FFF7D8 +:102C1000EFFD0125D1E700F10C034FF0000908EEAC +:102C2000103A4FF0800A4E464D4618EE100AFFF754 +:102C300077FE83460028BED014220021FEF7CAFB8F +:102C4000002E3AD1019BABF8083002220BF1080E9E +:102C50001FFA82FC0CF10100BCF1060F218C80B23E +:102C600001D88E422BD3FFF7A3FEFFF785FE6269E2 +:102C70001278013802F01F028E4208BF4FF0400A5E +:102C800042EA49121BFA80F14AEA020A013048F08E +:102C9000004281F808A08BF81000CBF804205946B8 +:102CA0003846FFF7A5FD238C0135B3422DB289F0DC +:102CB00001094FF0000AB8D17FE70022C6E7E169B9 +:102CC000895D0EF802100136B6B20132C0E76FF02E +:102CD000010572E7F8B515460E463022002104467C +:102CE0001F46FEF777FB069B6360B5F5001F079B49 +:102CF000A76034BF6A094FF6FF72A36297B2E6611C +:102D000004F1100000239A4206D800230360A78232 +:102D1000E3822383E360F8BD06600133304620364A +:102D2000F1E7000003781BB94BB2002BC8BF01705C +:102D30007047000000787047F8B50C46C96907462F +:102D400011B9238C002B37D1257E1F2D34D838782C +:102D500028BB228C072A2CD8268A36F003032BD1D5 +:102D60004FF6FF70FFF7D0FD20F001003102400464 +:102D700041EA0561400C41EA40254FF6FF722346C7 +:102D800029463846FFF7FCFE002807DD6269137804 +:102D90000133DBB21F2B88BF00231370F8BD218ADB +:102DA0002D0645EA012505432046FFF71DFE024694 +:102DB000E5E76FF00300F1E76FF00100EEE70000D8 +:102DC00070B58AB0044616460021282268461D4682 +:102DD000FEF700FBBDF83830ADF810300F9B0593BF +:102DE0009DF840308DF81830119B07936946BDF867 +:102DF0004830ADF820302046CDE90265FFF79CFF52 +:102E00000AB070BD2DE9F041D36905460C4616465F +:102E10000BB9138C5BBB377E1F2F28D895F8008029 +:102E2000B8F1000F26D03046FFF7DEFD33782102DF +:102E300041EAC33141EA0801338A41EA076141EAC4 +:102E400003410246334641F080012846FFF798FED1 +:102E500000280ADD3378012B07D17269137801331A +:102E6000DBB21F2B88BF00231370BDE8F0816FF029 +:102E70000100FAE76FF00300F7E70000F0B58BB050 +:102E800004460D4617460021282268461E46FEF7D6 +:102E9000A1FA9DF84C305A1E534253418DF8003030 +:102EA0009DF84030ADF81030119B05939DF84830E7 +:102EB0008DF81830149B07936A46BDF85430ADF86E +:102EC000203029462046CDE90276FFF79BFF0BB064 +:102ED000F0BD0000406A00B104307047436A1A68D0 +:102EE000426202691A600361C38A013BC382704770 +:102EF0002DE9F041D0F82080194E14461D46414678 +:102F0000002709B9BDE8F081D1E90223A21A65EBD7 +:102F10000303964277EB03031ED2036A8B420DD163 +:102F2000FFF78CFD036A1B68036203690B60C38AA9 +:102F30000161016A013BC3828846E2E7FFF77EFD3B +:102F40000B68C8F8003003690B60C38A0161013B5C +:102F5000C382D8F80010D4E788460968D1E700BFDB +:102F600080841E002DE9F04F8BB00D46DDF85090A7 +:102F700014469B468046002800F01981B9F1000FE5 +:102F800000F01581531E3F2B00F21181012A03D15D +:102F9000BBF1000F40F00B810023CDE90833B8F8F6 +:102FA0001430B5EBC30F4FEAC30703D300200BB0B7 +:102FB000BDE8F08F2B199F42D8F80C303ABF7F1B29 +:102FC000FFB227461BB9D8F81030002B7AD0272D36 +:102FD0004ED8C5F12806B7424FF000032CBFF6B219 +:102FE0003E4600932946D8F8080008AB3246FFF762 +:102FF00041FCA7EB060A35445FFA8AFAB8F81430A8 +:1030000003F10053053BDB000493D8F80C30039325 +:103010002821039B13B1BAF1000F2CD1D8F810006E +:1030200040B1BAF1000F05D0009608AB5246691ABC +:10303000FFF720FC38B2002FB8D066070AD00AABE1 +:1030400003EBD401624211F8083C02F0070213417D +:1030500001F8083C082C3CD9102C40F2B580202CFB +:1030600040F2B780BBF1000F00F09C80082334E0F1 +:10307000BA460026C2E7049BE02B28BFE023069354 +:103080000B44AB42059314D95A1B03980096924502 +:1030900034BF5246D2B2691A08AB04300792FFF728 +:1030A000E9FB079A1644AAEB020A1544F6B25FFA46 +:1030B0008AFA049B069A05999B1A0493039B1B6842 +:1030C0000393A6E70093D8F8080008AB3A462946D0 +:1030D000AEE7BBF1000F13D00123B4EBC30F6CD0EC +:1030E000082C12D89DF82030621E23FA02F2D50770 +:1030F00006D54FF0FF3202FA04F423438DF8203056 +:103100009DF8203089F8003051E7102C12D8BDF816 +:103110002030621E23FA02F2D10706D54FF0FF32AB +:1031200002FA04F42343ADF82030BDF82030A9F8AA +:1031300000303CE7202C0FD80899631E21FA03F3D6 +:10314000DA0705D54FF0FF3202FA04F40C43089475 +:10315000089BC9F800302AE7402C2BD0DDE9086530 +:10316000611EC4F12102A4F1210326FA01F105FA3E +:1031700002F225FA03F311431943CB0712D50122BA +:10318000A4F12003C4F1200102FA03F322FA01F1B1 +:10319000A240524243EA010363EB430332432B4311 +:1031A000CDE90823DDE90823C9E90023FFE66FF034 +:1031B0000100FCE66FF00800F9E6082CA0D9102CFD +:1031C000B3D9202CEED8C3E7BBF1000FADD002235A +:1031D00083E7BBF1000FBBD004237EE730B5012AA3 +:1031E000144638BF0124402C85B028BF4024002558 +:1031F000012ACDE9025518D81B788DF808306307ED +:103200000AD004AB03EBD405624215F8083C02F087 +:103210000702934005F8083C00910346224600212E +:1032200002A8FFF727FB05B030BD082AE4D9102A11 +:1032300003D81B88ADF80830E1E7202A8DBFD3E919 +:1032400000231B680293CDE90223D8E710B5CB68B1 +:103250001BB98B600B618B8210BD04691A681C60FE +:103260000361C38A013BC382CA60F0E703064CBF17 +:10327000C0F3C0300220704708B50246FFF7F6FFE2 +:10328000022806D15306C2F30F2001D100F003003B +:1032900008BDC2F30740FBE72DE9F04F93B0CDE93D +:1032A00003230A6804461046FFF7E0FF022814BF14 +:1032B000C2F306260026002A0D46824680F2F281DD +:1032C00012F0C04940F0EE81097B002900F0EA814C +:1032D000022803D02378B34240F0E781C2F30463AD +:1032E0000693104602F07F030593FFF7C5FF059B89 +:1032F00029444FEA834848EA0A4848EA4668CE78B3 +:1033000000230022CDE90823F309834648EA000898 +:10331000029367D0059B009302466768534608A94D +:103320002046B847002800F0C381276A4FB94146BC +:1033300004F10C00FFF702FB074690B96FF00200A2 +:1033400054E03B6998450DD03F68002FF9D14146C4 +:1033500004F10C00FFF7F2FA07460028EED0236ACA +:103360003B60276297F817C006F01F08CCF3840C67 +:10337000ACEB08001FFA80FE0028B8BF0EF1200059 +:10338000A8EB0C031FFA83FED7E90221B8BF00B2F5 +:10339000002B0793BEBF0EF120031BB2079352EA26 +:1033A000010338D0039BDFF824E39A1A049B4FF003 +:1033B000000C63EB010196457CEB01032BD36B7B87 +:1033C00097F81AE0734519D1029B002B78D0012899 +:1033D00021DC7868F8B9DFF8F0C2944570EB01039E +:1033E00016D337E0276A27B96FF00C0013B0BDE899 +:1033F000F08F3B699845B5D03F68F4E7B2489042FA +:103400007CEB010301D30020F0E7029B002BFAD0F4 +:10341000079B0F2B17DCFA7DB30002F0030203F0C9 +:103420007C031343FB7539462046FFF707FB6B7B94 +:10343000BB76029B3BB9FB7DC3F38402013262F38E +:103440008603FB75D0E76A7BBB7E9A42DBD1029B89 +:10345000002B35D0B309022B32D0039BBB60049BF9 +:10346000FB60142200210DA8FDF7B4FF039B0A9313 +:10347000049B0B932B1D0C932B7BADF83EB0013BB3 +:10348000DBB2ADF83C30069B8DF84230059B8DF8E1 +:10349000433094F82C308DF840A083F001038DF870 +:1034A00044308DF84180A3680AA920469847FB7DE7 +:1034B000C3F38403013303F01F039B02FB82A2E7E3 +:1034C000FB7DC6F34012B2EBD31F40F0F480C3F390 +:1034D0008403434540F0F280029A2B7BB609002A10 +:1034E0004DD0F2075DD4032B40F2EB80039BBB6011 +:1034F000049BFB602B7BAE1D033BDBB2324639469F +:1035000004F10C00FFF7ACFA00280CDA394620462B +:10351000FFF794FAFB7DC3F38403013303F01F0329 +:103520009B02FB820AE7DDE90884AB883B834FF608 +:10353000FF73C9F12000A9F1200228FA09F104FA69 +:1035400000F0014324FA02F211431846C9B2FFF712 +:10355000C9F909F10809B9F1400F0346E9D1B88268 +:103560002A7B033AD2B23146FFF7CEF9FB7DB8820F +:10357000DA43C2F3C01262F3C713FB7543E786B99F +:103580002E1D013BDBB23246394604F10C00FFF739 +:1035900067FA0028BADB2A7BB88A013AD2B23146F0 +:1035A000E2E7F98AC1F30901013B0429DAB25BD8E9 +:1035B000281D002307F11B069A4208D910F801CBF9 +:1035C00006F801C0013101330529DBB2F4D10399BA +:1035D0000A9104990B91934207F11B010C9138BF9A +:1035E000043379680D9134BF55FA83F300230E93A9 +:1035F000FB8AADF83EB0C3F309031A44069B8DF86D +:103600004230059B8DF8433094F82C30ADF83C20C7 +:1036100083F001038DF8443000238DF840A08DF82D +:1036200041807B602A7BB88A013A291DFFF76CF93B +:103630003B8BB882834203D1A3680AA920469847EE +:1036400020460AA9FFF702FEFB7DBA8AC3F3840372 +:10365000013303F01F039B02FB823B8B9A420CBF9A +:1036600000206FF01000C1E67B68002BAFD0052072 +:1036700001E01C3033461E68002EFAD1091A081DDD +:103680002E1D184401EB090CBCF11B0F5FFA89F3E6 +:103690009DD89A429BD916F8013B00F8013B09F1ED +:1036A0000109EFE76FF00900A0E66FF00A009DE660 +:1036B0006FF00B009AE66FF00D0097E66FF00E00CA +:1036C00094E66FF00F0091E640420F0080841E00E8 +:1036D000EFF3098305494A6B22F001024A6368331C +:1036E00083F30988002383F31188704700EF00E01B +:1036F000302080F3118862B60C4B0D4AD96821F452 +:10370000E0610904090C0A43DA60D3F8FC20094996 +:1037100042F08072C3F8FC200A6842F001020A609D +:103720002022DA7783F82200704700BF00ED00E026 +:103730000003FA05001000E010B5302383F3118870 +:103740000E4B5B6813F4006314D0F1EE103AEFF304 +:103750000984683C4FF08073E361094BDB6B23669F +:1037600084F3098800F090F810B1064BA36110BDF6 +:10377000054BFBE783F31188F9E700BF00ED00E09C +:1037800000EF00E0430600084606000800F1604331 +:1037900003F561430901C9B283F80013012200F067 +:1037A0001F039A4043099B0003F1604303F5614303 +:1037B000C3F880211A60704700230375826803698B +:1037C0001B6899689142FBD25A680360426010609E +:1037D0005860704700230375826803691B68996805 +:1037E0009142FBD85A68036042601060586070478D +:1037F00008B50846302383F311880B7D032B05D0D1 +:10380000042B0DD02BB983F3118808BD8B690022DE +:103810001A604FF0FF338361FFF7CEFF0023F2E71A +:10382000D1E9003213605A60F3E70000FFF7C4BF2C +:10383000054BD9680875186802681A605360012240 +:103840000275D860FCF7E8BE204A002030B50C4B6A +:10385000DD684B1C87B004460FD02B46094A6846EA +:1038600000F06CF92046FFF7E3FF009B13B16846B8 +:1038700000F06EF9A86907B030BDFFF7D9FFF9E78E +:10388000204A0020F1370008044B1A68DB68906872 +:103890009B68984294BF002001207047204A002076 +:1038A000084B10B51C68D86822681A605360012262 +:1038B0002275DC60FFF78EFF01462046BDE8104010 +:1038C000FCF7AABE204A0020044B1A68DB68926805 +:1038D0009B689A4201D9FFF7E3BF7047204A002056 +:1038E00038B5074C07490848012300252370656057 +:1038F00000F03AFC0223237085F3118838BD00BF25 +:10390000884C0020404E0008204A002008B572B6BE +:10391000044B186500F0ECFA00F0A0FB024B032208 +:103920001A70FEE7204A0020884C002000F046B9BB +:10393000EFF3118020B9EFF30583302282F3118871 +:103940007047000010B530B9EFF30584C4F30804E4 +:1039500014B180F3118810BDFFF7B6FF84F311880E +:10396000F9E700008B60022308618B8208467047EC +:103970008368A3F1840243F8142C026943F8442CB1 +:10398000426943F8402C094A43F8242CC26843F8A2 +:10399000182C022203F80C2C002203F80B2C044AEA +:1039A00043F8102CA3F12000704700BF3106000837 +:1039B000204A002008B5FFF7DBFFBDE80840FFF70D +:1039C00035BF0000024BDB6898610F20FFF730BF66 +:1039D000204A0020302383F31188FFF7F3BF000053 +:1039E00008B50146302383F311880820FFF72EFF26 +:1039F000002383F3118808BD064BDB6839B14268A8 +:103A000018605A60136043600420FFF71FBF4FF037 +:103A1000FF307047204A00200368984206D01A6899 +:103A20000260506099611846FFF700BF70470000C0 +:103A300010B503689C68A2420CD85C688A600B6071 +:103A40004C602160596099688A1A9A604FF0FF3380 +:103A5000836010BD1B68121BECE700000A2938BF09 +:103A60000A2170B504460D460A26601900F076FB5F +:103A700000F062FB041BA54203D8751C2E460446C9 +:103A8000F3E70A2E04D9BDE87040012000F0ACBB7A +:103A900070BD0000F8B5144B0D46D96103F110015B +:103AA00041600A2A1969826038BF0A2201604860B1 +:103AB0001861A818144600F043FB0A2700F03CFBED +:103AC000431BA342064606D37C1C281900F046FB84 +:103AD00027463546F2E70A2F04D9BDE8F840012011 +:103AE00000F082BBF8BD00BF204A0020F8B50646B2 +:103AF0000D4600F021FB0F4A134653F8107F9F42FA +:103B000006D12A4601463046BDE8F840FFF7C2BF5D +:103B1000D169BB68441A2C1928BF2C46A34202D98C +:103B20002946FFF79BFF224631460348BDE8F8408F +:103B3000FFF77EBF204A0020304A002010B4C0E9C1 +:103B4000032300235DF8044B4361FFF7CFBF000060 +:103B500010B5194C236998420DD0D0E90032816824 +:103B600013605A609A680A449A60002303604FF019 +:103B7000FF33A36110BD2346026843F8102F536042 +:103B80000022026022699A4203D1BDE8104000F091 +:103B9000DFBA936881680B44936000F0CDFA226924 +:103BA000E1699268441AA242E4D91144BDE8104088 +:103BB000091AFFF753BF00BF204A00202DE9F04744 +:103BC000DFF8BC8008F110072C4ED8F8105000F038 +:103BD000B3FAD8F81C40AA68031B9A423ED8144492 +:103BE000D5E900324FF00009C8F81C4013605A6054 +:103BF000C5F80090D8F81030B34201D100F0A8FA0F +:103C000089F31188D5E9033128469847302383F397 +:103C100011886B69002BD8D000F08EFA6A69A0EB8E +:103C200004094A4582460DD2022000F0DDFA002246 +:103C3000D8F81030B34208D151462846BDE8F047C5 +:103C4000FFF728BF121A2244F2E712EB090938BF26 +:103C50004A4629463846FFF7EBFEB5E7D8F810305C +:103C6000B34208D01444211AC8F81C00A960BDE86A +:103C7000F047FFF7F3BEBDE8F08700BF304A0020F1 +:103C8000204A002000207047FEE700007047000037 +:103C90004FF0FF3070470000BFF34F8F024AD368E8 +:103CA000DB03FCD4704700BF003C024008B5094B61 +:103CB0001B7873B9FFF7F0FF074B1A69002ABFBFE3 +:103CC000064A5A6002F188325A601A6822F4806209 +:103CD0001A6008BD904C0020003C0240230167455B +:103CE00008B50B4B1B7893B9FFF7D6FF094B1A6940 +:103CF00042F000421A611A6842F480521A601A684F +:103D000022F480521A601A6842F480621A6008BD78 +:103D1000904C0020003C02400728F0B516D80C4C0F +:103D20000C4923787BB90C4D0E4608234FF00062F6 +:103D300055F8047B46F8042B013B13F0FF033A448B +:103D4000F6D10123237051F82000F0BD0020FCE7DC +:103D5000B44C0020944C00204C4E0008014B53F80A +:103D6000200070474C4E000808207047072810B507 +:103D7000044601D9002010BDFFF7CEFF064B53F8D3 +:103D800024301844C21A0BB90120F4E7126801323A +:103D9000F0D1043BF6E700BF4C4E0008072810B5F1 +:103DA000044621D8FFF778FFFFF780FF0F4AF3237F +:103DB000D360C300DBB243F4007343F0020313612A +:103DC000136943F480331361FFF766FFFFF7A4FF25 +:103DD000074B53F8241000F03DF9FFF781FF204610 +:103DE000BDE81040FFF7C2BF002010BD003C0240FC +:103DF0004C4E0008F8B512F00103144642D1851864 +:103E00002E4A954257D82E4B1B6813F0010352D00F +:103E10002C4DFFF74BFFF323EB60FFF73DFF40F224 +:103E20000127032C15D824F001046618254C401AEC +:103E300040F20117B142236900EB010524D123F0C0 +:103E400001032361FFF74CFF0120F8BD043C04305F +:103E5000E7E78307E7D12B6923F440732B612B69D4 +:103E60003B432B6151F8046B0660BFF34F8FFFF7A4 +:103E700013FF03689E42E9D02B6923F001032B61F5 +:103E8000FFF72EFF0020E0E723F44073236123694E +:103E90003B4323610B882B80BFF34F8FFFF7FCFE62 +:103EA0002D8831F8023BADB2AB42C3D0236923F079 +:103EB00001032361E4E71846C7E700BF00000808D4 +:103EC00000380240003C0240084908B50B7828B190 +:103ED0001BB9FFF7EBFE01230B7008BD002BFCD0D4 +:103EE000BDE808400870FFF7FBBE00BF904C002003 +:103EF0004FF480214FF0005000F0AEB80846114654 +:103F000000F0AEBE012000F0ABBE0000084600F09D +:103F1000C5BE000070B582B0FFF70AFD0E4E054623 +:103F200000F00AF93268904237BF0C4A0B495168D9 +:103F300014682EBFD1E900410131516004190346D4 +:103F400041F10001284601913360FFF7FBFC019924 +:103F5000204602B070BD00BFB84C0020C04C00200D +:103F600070B582B0FFF7E4FC104E054600F0E4F8AF +:103F70003268904237BF0E4A0D49516814682EBF0F +:103F8000D1E9004101315160041941F100010346BA +:103F9000284601913360FFF7D5FC01994FF47A72FE +:103FA00000232046FCF724F902B070BDB84C002075 +:103FB000C04C002010B50244064BD2B2904200D152 +:103FC00010BD441C00B253F8200041F8040BE0B2CD +:103FD000F4E700BF502800400F4B30B51C6F24049D +:103FE00007D41C6F44F400741C671C6F44F4004435 +:103FF0001C670A4C236843F4807323600244084B17 +:10400000D2B2904200D130BD441C00B251F8045BE2 +:1040100043F82050E0B2F4E700380240007000405E +:104020005028004007B5012201A90020FFF7C2FF78 +:10403000019803B05DF804FB13B50446FFF7F2FFE7 +:10404000A04205D0012201A900200194FFF7C4FF7E +:1040500002B010BD704700007047000070470000BC +:10406000074B45F255521A6002225A6040F6FF7221 +:104070009A604CF6CC421A60024B01221A707047CB +:1040800000300040CC4C0020034B1B781BB1034B8D +:104090004AF6AA221A607047CC4C0020003000403B +:1040A000034B1A681AB9034AD2F874281A60704789 +:1040B000C84C002000300240024B4FF08072C3F821 +:1040C000742870470030024008B5FFF7E9FF024B43 +:1040D0001868C0F3407008BDC84C002008B5FFF751 +:1040E000DFFF024B1868C0F3007008BDC84C002009 +:1040F00070470000FEE700000A4B0B480B4A904255 +:104100000BD30B4BDA1C121AC11E22F003028B4296 +:1041100038BF00220021FDF75DB953F8041B40F8B9 +:10412000041BECE708500008C44F0020C44F0020D7 +:10413000C44F002000F0CAB84FF08043586A70475F +:104140004FF08043002258631A610222DA60704700 +:104150004FF080430022DA60704700004FF0804348 +:1041600058637047FEE7000070B51B4B01630025E4 +:10417000044686B0586085620E46FFF7B9FA04F12E +:104180001003C4E904334FF0FF33C4E90635C4E932 +:104190000044A560E562FFF7CFFF2B460246C4E965 +:1041A000082304F134010D4A256580232046FFF7DA +:1041B000D9FB0123E0600A4A0375009272680192FC +:1041C000B268CDE90223074B6846CDE90435FFF715 +:1041D000F1FB06B070BD00BF884C00206C4E00089B +:1041E000714E000865410008024AD36A1843D06244 +:1041F000704700BF204A00204B6843608B68836093 +:10420000CB68C3600B6943614B6903628B6943628E +:104210000B6803607047000008B5234B23481A69F8 +:1042200042F0FF021A611A6922F0FF021A611A694C +:104230001A6B42F0FF021A631A6D42F0FF021A6510 +:104240001B4A1B6D1146FFF7D7FF02F11C0100F559 +:104250008060FFF7D1FF02F1380100F58060FFF7C1 +:10426000CBFF02F1540100F58060FFF7C5FF02F1BA +:10427000700100F58060FFF7BFFF02F18C0100F5CF +:104280008060FFF7B9FF02F1A80100F58060FFF739 +:10429000B3FF02F1C40100F58060FFF7ADFFBDE898 +:1042A000084000F08DB800BF003802400000024016 +:1042B000784E000808B500F019FAFFF711FBBDE8C9 +:1042C0000840FFF7EDBE0000704700000F4B1A6C6E +:1042D00042F001021A641A6E42F001021A660C4A98 +:1042E0001B6E936843F0010393604FF080433122CB +:1042F0009A624FF0FF32DA6200229A615A63DA6002 +:104300005A6001225A611A60704700BF00380240AB +:10431000002004E04FF0804208B51169D3680B40DB +:10432000D9B2C9439B07116107D5302383F31188A4 +:10433000FFF7FCFA002383F3118808BD1E4B1A69AE +:1043400062F0FF021A611A69D2B21A614FF0FF30AF +:104350001A695A69586100215A6959615A691A6A79 +:1043600062F080521A621A6A02F080521A621A6A65 +:104370005A6A58625A6A59625A6A1A6C42F08052F2 +:104380001A641A6E42F080521A661A6E0B4A10684E +:1043900040F480701060186F00F44070B0F5007F3A +:1043A0001EBF4FF4803018671967536823F40073F9 +:1043B000536000F073B900BF003802400070004045 +:1043C0003B4B3C4A1A643C4A4FF4404111601A6826 +:1043D00042F001021A601A689007FCD59A6822F030 +:1043E00003029A60324B9A6812F00C02FBD11968F2 +:1043F00001F0F90119609A601A6842F480321A607B +:104400001A689103FCD55A6F42F001025A67284B93 +:104410005A6F9207FCD5294A5A601A6842F0807296 +:104420001A60254A53685804FCD5214B1A6891013B +:10443000FCD5234AC3F884201A6842F080621A60CF +:104440001A681201FCD51F4A9A600322C3F88C2017 +:104450004FF00062C3F894201B4B1A681B4B9A4222 +:104460001B4B21D11B4A11681B4A91421CD140F2BF +:1044700003121A60164A136803F00F03032BFAD1D4 +:104480000B4B9A6842F002029A609A6802F00C02A2 +:10449000082AFAD15A6C42F480425A645A6E42F4A5 +:1044A00080425A665B6E704740F20372E1E700BFDC +:1044B000003802400004001000700040081940025B +:1044C0001030002400948838002004E0116400209B +:1044D000003C024000ED00E041C20F41074A08B530 +:1044E000536903F00103536123B1054A13680BB10B +:1044F00050689847BDE80840FFF71EB9003C0140EE +:10450000D04C0020074A08B5536903F002035361F9 +:1045100023B1054A93680BB1D0689847BDE80840BD +:10452000FFF70AB9003C0140D04C0020074A08B50B +:10453000536903F00403536123B1054A13690BB1B6 +:1045400050699847BDE80840FFF7F6B8003C0140C5 +:10455000D04C0020074A08B5536903F008035361A3 +:1045600023B1054A93690BB1D0699847BDE808406B +:10457000FFF7E2B8003C0140D04C0020074A08B5E4 +:10458000536903F01003536123B1054A136A0BB159 +:10459000506A9847BDE80840FFF7CEB8003C01409C +:1045A000D04C0020164B10B55C6904F478725A6147 +:1045B000A30604D5134A936A0BB1D06A98476006E4 +:1045C00004D5104A136B0BB1506B9847210604D5E4 +:1045D0000C4A936B0BB1D06B9847E20504D5094A9E +:1045E000136C0BB1506C9847A30504D5054A936C26 +:1045F0000BB1D06C9847BDE81040FFF79DB800BFE5 +:10460000003C0140D04C0020194B10B55C6904F40B +:104610007C425A61620504D5164A136D0BB1506D88 +:104620009847230504D5134A936D0BB1D06D984775 +:10463000E00404D50F4A136E0BB1506E9847A104E5 +:1046400004D50C4A936E0BB1D06E9847620404D522 +:10465000084A136F0BB1506F9847230404D5054ADD +:10466000936F0BB1D06F9847BDE81040FFF764B867 +:10467000003C0140D04C002008B5034800F0E8F8A9 +:10468000BDE80840FFF758B8504D002008B5FFF7C7 +:1046900041FEBDE80840FFF74FB80000062108B50D +:1046A0000846FFF773F806210720FFF76FF8062189 +:1046B0000820FFF76BF806210920FFF767F80621AD +:1046C0000A20FFF763F806211720FFF75FF806219D +:1046D0002820FFF75BF807211C20FFF757F8BDE8FB +:1046E00008400C214720FFF751B8000008B5FFF73C +:1046F00025FE00F07BF800F03DF8FFF7E5FDBDE892 +:104700000840FFF717BD00000268436811430160CD +:1047100003B1184770470000143000F0C5B900001D +:104720004FF0FF33143000F0BFB90000383000F014 +:104730003BBA00004FF0FF33383000F035BA0000CC +:10474000143000F08BB900004FF0FF31143000F04E +:1047500085B90000383000F0E5B900004FF0FF32B5 +:10476000383000F0DFB90000012914BF6FF01300EA +:104770000020704700F058B837B515460E4A026061 +:1047800000224260C0E902220122044602740B4664 +:10479000009000F15C014FF48072143000F034F9A5 +:1047A00000942B464FF4807204F5AE7104F138008A +:1047B00000F0ACF903B030BD584F000838B5C369FC +:1047C00004460D461BB904210844FFF79DFF294606 +:1047D00004F1140000F026F9002806DA201D4FF439 +:1047E0000061BDE83840FFF78FBF38BD0023054AA0 +:1047F00019460133102BC2E9001102F10802F8D169 +:10480000704700BFD04C002002684368114301602C +:1048100003B1184770470000024AD36843F0C00351 +:10482000D36070470014014010B5054C054A0021C3 +:104830002046FFF7A1FF044A044BC4E9972310BDAB +:10484000504D0020194800080014014080F0FA0281 +:104850002DE9F041D0F85C62F7683368DA05044668 +:104860009DB20DD5302383F311884FF4806104305D +:10487000FFF7CAFF6FF480733360002383F311885E +:10488000302383F3118804F1040815F02F033AD183 +:1048900083F31188380615D5290613D5302383F301 +:1048A000118804F1380000F065F900284EDA08217B +:1048B000201DFFF7A9FF4FF67F733B40F3600023F5 +:1048C00083F311887A0616D56B0614D5302383F34B +:1048D0001188D4E913239A420AD1236C43B127F0FB +:1048E00040073F041021201D3F0CFFF78DFFF760AC +:1048F000002383F31188D4F86822D36843B3BDE85A +:10490000F041106918472B0714D015F0080F0CBFA1 +:1049100000214FF48071E80748BF41F02001AA0749 +:1049200048BF41F040016B0748BF41F0800140465D +:10493000FFF76AFFAD06736805D594F86412204648 +:104940001940FFF73BFF3568ADB29EE77060B6E7F0 +:10495000BDE8F081F8B5154682680669AA420B46A3 +:10496000816938BF8568761AB54204460BD218466D +:104970002A46FCF71DFDA3692B44A361A3685B1BBA +:10498000A3602846F8BD0CD918463246FCF710FD46 +:10499000AF1BE1683A463044FCF70AFDE3683B444C +:1049A000EBE718462A46FCF703FDE368E5E700005D +:1049B00083689342F7B51546044638BF8568D0E949 +:1049C0000460361AB5420BD22A46FCF7F1FC636943 +:1049D0002B446361A36828465B1BA36003B0F0BD52 +:1049E0000DD932460191FCF7E3FC0199E068AF1B59 +:1049F0003A463144FCF7DCFCE3683B44E9E72A46ED +:104A0000FCF7D6FCE368E4E710B50A440024C36170 +:104A1000029B8460C0E90000C0E90511C160026129 +:104A2000036210BD08B5D0E90532934201D1826816 +:104A300082B98268013282605A1C42611970D0E9E1 +:104A400004329A4224BFC36843610021FEF7E4FFA9 +:104A5000002008BD4FF0FF30FBE7000070B53023A9 +:104A600004460E4683F31188A568A5B1A368A26920 +:104A7000013BA360531CA36115782269934224BFB4 +:104A8000E368A361E3690BB120469847002383F3F1 +:104A90001188284607E031462046FEF7ADFF002882 +:104AA000E2DA85F3118870BD2DE9F74F04460E4612 +:104AB00017469846D0F81C904FF0300A8AF31188B8 +:104AC0004FF0000B154665B12A4631462046FFF7E8 +:104AD00041FF034660B941462046FEF78DFF00289E +:104AE000F1D0002383F31188781B03B0BDE8F08F69 +:104AF000B9F1000F03D001902046C847019B8BF30A +:104B00001188ED1A1E448AF31188DCE7C0E905110B +:104B1000C160C3611144009B8260C0E90000016173 +:104B200003627047F8B504460D461646302383F3FA +:104B30001188A768A7B1A368013BA36063695A1CE9 +:104B400062611D70D4E904329A4224BFE368636154 +:104B5000E3690BB120469847002080F3118807E0F5 +:104B600031462046FEF748FF0028E2DA87F3118835 +:104B7000F8BD0000D0E905239A4210B501D1826842 +:104B80007AB98268013282605A1C82611C7803699A +:104B90009A4224BFC36883610021FEF73DFF20468F +:104BA00010BD4FF0FF30FBE72DE9F74F04460E46EE +:104BB00017469846D0F81C904FF0300A8AF31188B7 +:104BC0004FF0000B154665B12A4631462046FFF7E7 +:104BD000EFFE034660B941462046FEF70DFF002870 +:104BE000F1D0002383F31188781B03B0BDE8F08F68 +:104BF000B9F1000F03D001902046C847019B8BF309 +:104C00001188ED1A1E448AF31188DCE70B46014631 +:104C1000184600F02DB8000000F040B8012838BF59 +:104C2000012010B50446204600F030F830B900F0FD +:104C300007F808B900F00CF88047F4E710BD000051 +:104C4000024B1868BFF35B8F704700BFBC4F00205A +:104C500008B5062000F084F80120FFF715F80000E1 +:104C6000024B0A4601461868FFF748B91C2300208A +:104C700010B5054C13462CB10A4601460220AFF38D +:104C8000008010BD2046FCE700000000024B0146FA +:104C90001868FFF737B900BF1C230020024B0146FC +:104CA0001868FFF733B900BF1C23002010B5013985 +:104CB0000244904201D1002005E0037811F8014F31 +:104CC000A34201D0181B10BD0130F2E72DE9F041DD +:104CD000A3B1C91A17780144044603F1FF3C8C4282 +:104CE000204601D9002009E00578BD4204F1010405 +:104CF000F5D10CEB0405D618A54201D1BDE8F08131 +:104D000015F8018D16F801EDF045F5D0E7E7000044 +:104D10001F2938B504460D4604D9162303604FF009 +:104D2000FF3038BD426C12B152F821304BB92046E9 +:104D300000F030F82A4601462046BDE8384000F031 +:104D400017B8012B0AD0591C03D116230360012088 +:104D5000E7E7002442F82540284698470020E0E78E +:104D6000024B01461868FFF7D3BF00BF1C23002089 +:104D700038B5074D00230446084611462B60FEF760 +:104D800087FF431C02D12B6803B1236038BD00BFED +:104D9000C04F0020FEF776BF034611F8012B03F841 +:104DA000012B002AF9D170476F72672E617264750A +:104DB00070696C6F742E4269726443414E6479006D +:104DC00040A2E4F1646891060041A3E5F2656992AE +:104DD000070000004261642043414E4966616365FB +:104DE00020696E6465782E0080000000008000005D +:104DF000000080000000000000000000411C0008CE +:104E00002924000889230008511C0008851C00087B +:104E1000811E0008551C0008651C0008591C00086C +:104E2000611C00085D1C0008A91D0008691C000821 +:104E3000F5260008791C00087D1D0008633000007D +:104E40003C4E0008784A0020884C002000400000BA +:104E50000040000000400000004000000000010091 +:104E60000000020000000200000002006D61696E97 +:104E70000069646C650000000004802A00000000E6 +:104E8000AAAAAAAA00004025DFFF00000000000037 +:104E90000080080010000A00000000009AAAAAAAD8 +:104EA00000000000FBFF0000000000008800000080 +:104EB0000000000000000000AAAAAAAA000000004A +:104EC000FFFF0000000000000000000000000000E4 +:104ED00000000000AAAAAAAA00000000FFFF00002C +:104EE00000000000000000000000000000000000C2 +:104EF000AAAAAAAA00000000FFFF0000000000000C +:104F0000000000000000000000000000AAAAAAAAF9 +:104F100000000000FFFF0000000000000000000093 +:104F20000000000000000000AAAAAAAA00000000D9 +:104F3000FFFF000000000000000000000000000073 +:104F4000000000000A000000000000000300000054 +:104F500000000000000000000000000035470008CD +:104F6000214700085D4700084947000855470008E9 +:104F7000414700082D470008194700086947000805 +:104F8000A0B2FF7F01000000140400000000000038 +:104F9000000007000000000040420F00FE2A010050 +:104FA000D2040000202300200000000000000000C8 +:104FB00000000000000000000000000000000000F1 +:104FC00000000000000000000000000000000000E1 +:104FD00000000000000000000000000000000000D1 +:104FE00000000000000000000000000000000000C1 +:104FF00000000000000000000000000000000000B1 +:085000000000000000000000A8 :00000001FF diff --git a/Tools/bootloaders/C-RTK2-HP_bl.bin b/Tools/bootloaders/C-RTK2-HP_bl.bin index 882250633f012a..54d5d3b04c4d42 100755 Binary files a/Tools/bootloaders/C-RTK2-HP_bl.bin and b/Tools/bootloaders/C-RTK2-HP_bl.bin differ diff --git a/Tools/bootloaders/C-RTK2_HP_bl.bin b/Tools/bootloaders/C-RTK2_HP_bl.bin new file mode 100755 index 00000000000000..5b55d1ed6ca7fc Binary files /dev/null and b/Tools/bootloaders/C-RTK2_HP_bl.bin differ diff --git a/Tools/bootloaders/CUAV_GPS_bl.bin b/Tools/bootloaders/CUAV_GPS_bl.bin index d6972c9054f91f..ba018a0af70560 100755 Binary files a/Tools/bootloaders/CUAV_GPS_bl.bin and b/Tools/bootloaders/CUAV_GPS_bl.bin differ diff --git a/Tools/bootloaders/CUAV_GPS_bl.elf b/Tools/bootloaders/CUAV_GPS_bl.elf index 46cab2cc83e876..e07dbb7f30c867 100755 Binary files a/Tools/bootloaders/CUAV_GPS_bl.elf and b/Tools/bootloaders/CUAV_GPS_bl.elf differ diff --git a/Tools/bootloaders/CUAV_GPS_bl.hex b/Tools/bootloaders/CUAV_GPS_bl.hex index 7912e29953412b..3ffd8f8b5699b2 100644 --- a/Tools/bootloaders/CUAV_GPS_bl.hex +++ b/Tools/bootloaders/CUAV_GPS_bl.hex @@ -1,1042 +1,1289 @@ :020000040800F2 -:1000000000070020E5040008BD1500083D150008A4 -:10001000951500083D15000869150008E70400085B -:10002000E7040008E7040008E7040008ED370008CB -:10003000E7040008E7040008E7040008E7040008F4 -:10004000E7040008E7040008E7040008E7040008E4 -:10005000E7040008E7040008193C0008453C0008D4 -:10006000713C00089D3C0008C93C0008E7040008FA -:10007000E7040008E7040008E7040008E7040008B4 -:10008000E7040008E7040008E704000875250008F5 -:10009000E12500083526000889260008F53C0008FF -:1000A000E7040008E7040008E7040008E704000884 -:1000B000693A0008E7040008E7040008E7040008BC -:1000C000E7040008E7040008E7040008E704000864 -:1000D000E70400082D2A0008412A0008E704000868 -:1000E0005D3D0008E7040008E7040008E704000895 -:1000F000E7040008E7040008E7040008E704000834 -:10010000E7040008E7040008E7040008E704000823 -:10011000E7040008E7040008E7040008E704000813 -:10012000E7040008E7040008E7040008E704000803 -:10013000E7040008E7040008E7040008E7040008F3 -:10014000E7040008E7040008E7040008E7040008E3 -:10015000E7040008E7040008E7040008E7040008D3 -:10016000E7040008E7040008E7040008E7040008C3 -:10017000E7040008E7040008E7040008E7040008B3 -:10018000E7040008E7040008E7040008E7040008A3 -:10019000E7040008E7040008E7040008E704000893 -:1001A000E7040008E7040008E7040008E704000883 -:1001B000E7040008E7040008E7040008E704000873 -:1001C000E7040008E7040008E7040008E704000863 -:1001D000E7040008E7040008E7040008E704000853 -:1001E00053B94AB9002908BF00281CBF4FF0FF319E -:1001F0004FF0FF3000F074B9ADF1080C6DE904CE9A -:1002000000F006F8DDF804E0DDE9022304B07047F1 -:100210002DE9F047089D04468E46002B4DD18A42B9 -:10022000944669D9B2FA82F252B101FA02F3C2F1EC -:10023000200120FA01F10CFA02FC41EA030E94407D -:100240004FEA1C48210CBEFBF8F61FFA8CF708FB9E -:1002500016E341EA034306FB07F199420AD91CEB76 -:10026000030306F1FF3080F01F81994240F21C81A8 -:10027000023E63445B1AA4B2B3FBF8F008FB1033F0 -:1002800044EA034400FB07F7A7420AD91CEB040425 -:1002900000F1FF3380F00A81A74240F207816444F5 -:1002A000023840EA0640E41B00261DB1D44000237A -:1002B000C5E900433146BDE8F0878B4209D9002DDE -:1002C00000F0EF800026C5E9000130463146BDE868 -:1002D000F087B3FA83F6002E4AD18B4202D38242D2 -:1002E00000F2F980841A61EB030301209E46002D81 -:1002F000E0D0C5E9004EDDE702B9FFDEB2FA82F2D6 -:10030000002A40F09280A1EB0C014FEA1C471FFA33 -:100310008CFE0126200CB1FBF7F307FB131140EA1A -:1003200001410EFB03F0884208D91CEB010103F1E7 -:10033000FF3802D2884200F2CB804346091AA4B2A9 -:10034000B1FBF7F007FB101144EA01440EFB00FE7D -:10035000A64508D91CEB040400F1FF3102D2A645E2 -:1003600000F2BB800846A4EB0E0440EA03409CE781 -:10037000C6F12007B34022FA07FC4CEA030C20FA2E -:1003800007F401FA06F31C43F9404FEA1C4900FA4E -:1003900006F3B1FBF9F8200C1FFA8CFE09FB1811CB -:1003A00040EA014108FB0EF0884202FA06F20BD93E -:1003B0001CEB010108F1FF3A80F08880884240F28E -:1003C0008580A8F102086144091AA4B2B1FBF9F0D2 -:1003D00009FB101144EA014100FB0EFE8E4508D9CD -:1003E0001CEB010100F1FF346CD28E456AD9023852 -:1003F000614440EA0840A0FB0294A1EB0E01A14237 -:10040000C846A64656D353D05DB1B3EB080261EBA4 -:100410000E0101FA07F722FA06F3F1401F43C5E97E -:10042000007100263146BDE8F087C2F12003D840B4 -:100430000CFA02FC21FA03F3914001434FEA1C47F6 -:100440001FFA8CFEB3FBF7F007FB10360B0C43EAE8 -:10045000064300FB0EF69E4204FA02F408D91CEB98 -:10046000030300F1FF382FD29E422DD90238634496 -:100470009B1B89B2B3FBF7F607FB163341EA034136 -:1004800006FB0EF38B4208D91CEB010106F1FF3885 -:1004900016D28B4214D9023E6144C91A46EA00467C -:1004A00038E72E46284605E70646E3E61846F8E60E -:1004B0004B45A9D2B9EB020864EB0C0E0138A3E757 -:1004C0004646EAE7204694E74046D1E7D0467BE738 -:1004D000023B614432E7304609E76444023842E7B0 -:1004E000704700BF02E000F000F8FEE772B63A483D -:1004F00080F30888394880F3098839484EF6085156 -:10050000CEF20001086040F20000CCF200004EF68E -:100510003471CEF200010860BFF34F8FBFF36F8FCD -:1005200040F20000C0F2F0004EF68851CEF2000119 -:100530000860BFF34F8FBFF36F8F4FF00000E1EE05 -:10054000100A4EF63C71CEF200010860062080F3DE -:100550001488BFF36F8F03F0C9F903F0A5F903F016 -:10056000EFF94FF055301F491B4A91423CBF41F80B -:10057000040BFAE71C49194A91423CBF41F8040BAD -:10058000FAE71A491A4A1B4B9A423EBF51F8040B2C -:1005900042F8040BF8E700201749184A91423CBF83 -:1005A00041F8040BFAE703F083F903F017FA144C4F -:1005B000144DAC4203DA54F8041B8847F9E700F005 -:1005C00041F8114C114DAC4203DA54F8041B884732 -:1005D000F9E703F06BB900000007002000230020BA -:1005E000000000080001002000070020D0400008A3 -:1005F000002300202423002028230020003C00208A -:10060000E0010008E0010008E0010008E001000846 -:100610002DE9F04F2DED108AC1F80CD0C3689D462E -:10062000BDEC108ABDE8F08F002383F311882846C3 -:10063000A047002002F0B0FDFEE702F035FD00DF2C -:10064000FEE700002DE9F04103F06EF8074603F0E5 -:10065000B9F8054600283DD12B4B9F423AD00133D3 -:100660009F423AD0294B27F0FF029A4239D1F8B283 -:1006700000F052FAA84642F2107400F057FC08B19C -:100680000024A04600F04EFA064670B37CBB4646F6 -:1006900035B11F4B9F4203D003F08CF8002426464F -:1006A000002003F04BF81B4B1B691B0722D40EB133 -:1006B00000F032F800F098FC00F07EFE00F080FFC1 -:1006C0000546CCB100F07CFF401BA04214D900F0DD -:1006D00023F8F3E7A8460024CFE704464FF00108CB -:1006E000CBE780464FF47A74C7E70446D0E74FF46F -:1006F0007A74CDE70024DDE700F028FD4FF47A702E -:1007000002F050FDDDE700BF010007B0000008B0B7 -:10071000263A09B0000402401E4B1F4A10B51C4681 -:100720001968013134D004339342F9D162681B4B0C -:100730009A422DD91A4B9B6803F1006303F580336D -:100740009A4225D203F00AF803F01CF8002000F0CA -:100750004DFE144B0220187000F084FE124B1A6CF0 -:1007600000221A64196E1A66196E596C5A64596E11 -:100770005A665B6E72B64FF0E0232021C3F8084D35 -:10078000D4E9003281F311889D4683F3088810472D -:1007900010BD00BF0000010820000108FFFF000895 -:1007A000002300202823002000380240094A136853 -:1007B00049F2690099B21B0C00FB01331360064B30 -:1007C000186844F2506182B2000C01FB020018600C -:1007D00080B27047202300201C23002010B5002188 -:1007E0001022044600F05AFE034B03CB20606160E8 -:1007F0001868A06010BD00BF107AFF1F2DE9F043FC -:10080000224DBBB000F0DCFEAB6840F2ED22C31A13 -:10081000934232D906AFA8602B46282200213846E1 -:1008200001F0DCFB05F10E0000F030FE002604466E -:100830005FFA80F905F10E08F3B2F100994501F174 -:10084000280107D908EB06030822384601F0C6FB49 -:100850000136F1E708230122CDE9023205340C4BC1 -:100860000193A4B230230093CDE9047405A3D3E926 -:100870000023297B074801F0C9F93BB0BDE8F083AC -:10088000AFF3008078F6339F93CACD8D703300208C -:100890007D3300204433002070B50D4614461E46BB -:1008A00001F04AF950B9022E10D1012C0ED112A339 -:1008B000D3E90023C5E90023012007E0282C10D04C -:1008C00005D8012C09D0052C0FD0002070BD302C8C -:1008D000FBD10BA3D3E90023ECE70BA3D3E900235F -:1008E000E8E70BA3D3E90023E4E70BA3D3E9002354 -:1008F000E0E700BFAFF30080401DA12026812A0B56 -:1009000078F6339F93CACD8D9E6AC421818A46EEC4 -:1009100026417272DF25D7B7F017304A39059E5647 -:1009200013B504462346084620220021019001F019 -:1009300055FB22790198032A234628BF032203F896 -:10094000042F2021022201F049FB62790198072A35 -:10095000234628BF072203F8052F2221032201F096 -:100960003DFBA2790198072A234628BF072203F8F6 -:10097000062F2521032201F031FB019804F1080321 -:100980001022282101F02AFB382002B010BD0000FF -:100990002DE9F04FFFB01FAD0CAE40F2751280464E -:1009A0000F4620A80021296000F078FD4822002190 -:1009B000304600F073FD00F003FE554B4FF47A72A1 -:1009C000B0FBF2F0186093E80700012386E8070007 -:1009D0000DF152003382FFF701FF4EF6031333840B -:1009E00006AB18464B4903F063FA162230642946D9 -:1009F000304686F83C20FFF793FF10AB04460146D3 -:100A00000822284601F0EAFA0822A1180DF1410354 -:100A1000284601F0E3FA0DF14203082204F1100127 -:100A2000284601F0DBFA11AB202204F11801284618 -:100A300001F0D4FA12AB402204F13801284601F04B -:100A4000CDFA14AB082204F17801284601F0C6FA69 -:100A50000DF15103082204F18001284601F0BEFA8D -:100A600004F1880A0DF1520904F5847B4B46514686 -:100A7000082228460AF1080A01F0B0FAD34509F124 -:100A80000109F3D119AB08225946284601F0A6FA0C -:100A900004F588744FF0000996F834304B450AD9B4 -:100AA000B36B21464B440822284601F097FA0834DC -:100AB00009F10109F0E74FF0000996F83C304B4589 -:100AC00004EBC90108D9336C08224B44284601F0D5 -:100AD00085FA09F10109F0E700230393BB7E029335 -:100AE000073107F119030193C1F3CF010123CDE9C8 -:100AF00004510093F97E04A3D3E90023404601F09A -:100B000085F87FB0BDE8F08F9E6AC421818A46EEE9 -:100B10002C230020C03E0008014B1870704700BF16 -:100B200038230020F0B5334B1C7B85B034B1324BF9 -:100B30000E221A810024204605B0F0BD2F4A10680D -:100B4000516802AB03C308232D492E480DEB030265 -:100B500003F08CF9054630B9274B2B480A221A813D -:100B600000F0E8FCE6E70169B1F5E02F06D9224B79 -:100B700026480B221A8100F0DDFCDCE7438B40F2B3 -:100B8000E932934207D01C490C20088119462048BD -:100B900000F0D0FCCFE71F4A024402F11003994253 -:100BA00004D2154B1C4810221A81E4E710398E1A22 -:100BB0002046144900F008FD3246074605F11801A9 -:100BC000204600F001FDAB689F4202D1EB689842DD -:100BD0000AD0094B0D221A810090D5E902123B463A -:100BE0000E4800F0A7FCA5E70D4800F0A3FC012487 -:100BF000A1E700BF703300202C230020693F0008CC -:100C0000DCFF060000000108D83E0008E43E0008B2 -:100C1000F63E00080800FFF7143F0008313F0008C7 -:100C20005A3F00082DE9F04FADB006AF80460C46A4 -:100C300000F082FF054600285AD1237E022B1BD1EB -:100C4000E38A012B18D100F0BBFC0646FFF7AEFD8E -:100C500003464FF4C870DFF8D092B3FBF0F206F50C -:100C6000167602FB103316FA83F3C9F80030E37EE0 -:100C700033B9A84B00221A709C37BD46BDE8F08FEF -:100C8000A38AEEB2013BB34205F101050BD93B1D2E -:100C90001E44E90000960023082201F0F8012046D6 -:100CA00001F060F8ECE707F11400FFF797FD32461A -:100CB00007F11401381D03F0C9F80028D9D10F2E0F -:100CC00008D8944B1E70D9F80030A3F51673C9F8F4 -:100CD0000030D1E7FB1CF870014600930722034661 -:100CE000204601F03FF8F978404600F01DFFC3E7C9 -:100CF000E38A282B26D010D8012B1ED0052BBBD180 -:100D0000BFF34F8F8449854BCA6802F4E0621343F6 -:100D1000CB60BFF34F8F00BFFDE7302BACD1637EBC -:100D20007F4D01336A7BDBB29342E94603D1E27E19 -:100D30002B7B9A4265D0CD469EE721464046FFF781 -:100D400027FE99E7A38A013B9BB2C92B94D8744D27 -:100D50002E7B26BB05F10C03009308223346314657 -:100D6000204600F0FFFF731CF2B2D9001E46A38A92 -:100D7000013B9A4205DA0E322A44009200230822EF -:100D8000EEE700230022C5E900230023AB6085F8CD -:100D9000D730C5F8D8302B7B0BB9E37E2B730025F9 -:100DA00007F114093B1D082229464846C7E90155A9 -:100DB000FD6001F013F93B7A05F1010AAB424FEAFD -:100DC000CA0608D9FB6808222B443146484601F080 -:100DD00005F95546EFE7C6F3CF06E17ECDE9049667 -:100DE00000230393A37E02931934282300930194D4 -:100DF00046A3D3E90023404600F008FFFFF7FEFCBE -:100E00003AE74FF0000807F11403A7F81480102206 -:100E1000009341460123204600F0A4FFA68A023E2B -:100E2000B6B2F31C9B109B000733DB08A9EBC3038E -:100E30009D460DF1180A1FFA88F34FEAC801B34224 -:100E400001F110010AD20AEB0803009308220023E3 -:100E5000204600F087FF08F10108ECE795F8D7007D -:100E600000F0CEFAD5F8D83004461BB995F8D70073 -:100E700000F0D6FAD5F8D83033449C4204D295F825 -:100E8000D700013000F0CCFA4FEA960B4FF0000883 -:100E90001FFA88F18B45D5E9003209D90AEB8801A0 -:100EA00003EB8800012200F001FB08F10108EFE7E5 -:100EB000F31842F10002C5E90032D5F8D83095F8B0 -:100EC000D70006EB0308C5F8D88000F099FA8045F2 -:100ED00009D395F8D730D5F8D8000133001B85F831 -:100EE000D730C5F8D800FF2E08D800232B7300F0A8 -:100EF000A9FAFFF717FE08B1FFF70EFC2B68094AA5 -:100F00009B0A013313810023AB6014E72641727200 -:100F1000DF25D7B73D33002000ED00E00400FA05DF -:100F2000703300202C2300204033002030B54FF0D8 -:100F30000054244B22689A4285B007D002F04CFC42 -:100F40000446A8B90024204605B030BD1E4B627D82 -:100F50001A701E48237D03731D49C9220E3000F00C -:100F60008BFA2046E022002100F098FA0124EAE7FB -:100F7000184A194D136C43F000731364AA6D174B94 -:100F80009A42DFD12B6E013B7E2BDBD8144A07CA75 -:100F900001AB83E807001846032100F02BFB6B6DC3 -:100FA00083424FF00003CDD12A6D8A4201BFAB6569 -:100FB000054B2A6E1A7003BF0A4BEA6D1A601C4675 -:100FC000C1E700BF9AAD44C538230020703300202C -:100FD0001600002000380240006600405041A0B0DA -:100FE00058660040182300202DE9FF474B4C022390 -:100FF0006371002302934A4BD3F800C0BCF57A7F9B -:1010000012D3484B484FB7FBFCF69C458CBF0A23D4 -:101010001123581EB6FBF3F503FB1562C1B2002A7B -:101020003ED002280346F4D89DF80B303F49404893 -:101030005A1E9DF80A30013B1B0443EA0253BDF8D7 -:101040000820013A13434B6001F04EFD0023019349 -:10105000384B394900933948394B4FF4805200F0EE -:101060003DFD384B197811B1344800F05DFD00F0BA -:10107000A7FA0546FFF79AFB4FF4C873B0FBF3F2EB -:1010800002FB130305F5167010FA83F02E4B18605F -:1010900002F098FB08B10F23238104B0BDE8F0876C -:1010A0006B1EB3F5806FBFD2C1EBC10E0EF103030F -:1010B0004FEAE309C3F3C703A1EB030809F1010AEF -:1010C0004FF47A705FFA88F609FB00005AFA88F844 -:1010D000B0FBF8F0B0F5617F08D90EF1FF33C3F330 -:1010E000C703C91ACEB2591E0F2914D8721E072A77 -:1010F0008CBF00220122991901FB0551B7FBF1F7C2 -:10110000BC4591D1002A8FD0ADF808508DF80A3037 -:101110008DF80B6088E71346EDE700BF2C23002015 -:10112000182300203F420F0040787D01102300204B -:1011300088340020990800083C2300204433002014 -:10114000250C000838230020403300202DE9F04F03 -:1011500091A7D7E900670FF24829D9E90089874D9F -:1011600093B0DFF844B2864C284600F0B3FD0DF191 -:10117000300A079070B310220021504600F08EF91B -:10118000079B197B4FF0000261F303028DF83020BA -:10119000586899680EAA03C21B680D9A63F31C0273 -:1011A0009DF830300D9243F020038DF8303000234D -:1011B00052461946584601F0A7FC079028B9284620 -:1011C00000F08CFD079B2370CEE72378072B3CD8DB -:1011D0000133237018220021504600F05FF9DFF838 -:1011E000C8B1684C002319465246584601F0B4FC79 -:1011F000014670BB102208A800F050F9636983F41F -:101200008053636100F0DEF90B4612A9024611E932 -:1012100003000DF1240C8CE803009DF83410C1F399 -:10122000030089064CBF0E99BDF838C08DF82C001C -:1012300046BFC1F31C0C4CF00041CCF30A010891ED -:10124000284608A900F012FFCCE7284600F046FD2A -:10125000C0E7284600F070FC0446002848D1DFF8BB -:101260004CB100F0ADF9DBF80030984240D300F00B -:10127000A7F90790FFF79AFA079A8DF820400346DE -:101280004FF4C87002F51672B3FBF0F101FB103396 -:1012900012FA83F3CBF80030DFF814B19BF800109A -:1012A00011B901238DF8203050460791FFF796FAC7 -:1012B0000799C1F11004E4B2062C28BF0624224687 -:1012C00051440DF1210000F0D7F808AB0393182327 -:1012D000029301342C4B0193E4B201230093049454 -:1012E0003B463246284600F029FC00238BF80030AC -:1012F00000F066F9254A264C1368C31AB3F57A7FC5 -:1013000031D3106000F05EF902460B46284600F02B -:10131000EFFC284600F010FC28B3237BDFF894B0E4 -:10132000002B14BF032302238BF8053000F048F98B -:101330004FF47A735146B0FBF3F0CBF800005846F7 -:10134000FFF7EEFA182307300293124B0193C0F314 -:10135000CF0040F25513CDE903A0009342464B461F -:10136000284600F0EBFB237B2BB1FFF747FA237BEA -:10137000002B7FF4F6AE13B0BDE8F08F44330020AD -:1013800055340020000402403C330020503400203B -:101390007033002054340020401DA12026812A0BE8 -:1013A000F1C6A7C1D068080F883400204033002060 -:1013B0003D3300202C23002070B502F055F8094E73 -:1013C000094D3080002428683388834208D902F010 -:1013D00045F82B6804440133B4F5803F2B60F2D309 -:1013E00070BD00BF843400205834002002F000B9E2 -:1013F00000F10060920000F5803002F083B8000038 -:10140000054B1A68054B1B889B1A834202D910446E -:1014100002F024B8002070475834002084340020A3 -:1014200038B5074D04462868204402F01FF828B953 -:1014300028682044BDE8384002F030B838BD00BF0D -:1014400058340020064991F8243033B10023086A4B -:1014500081F824300822FFF7CBBF0120704700BF7E -:101460005C340020022802BF024B4FF080529A6188 -:10147000704700BF0004024010B50023934203D020 -:10148000CC5CC4540133F9E710BD000003460246AA -:10149000D01A12F9011B0029FAD170470244034601 -:1014A000934202D003F8011BFAE770472DE9F84395 -:1014B0001F4D144695F824200746884652BBDFF896 -:1014C00070909CB395F824302BB92022FF21484618 -:1014D0002F62FFF7E3FF95F82400C0F10802A24253 -:1014E00028BF2246D6B24146920005EB8000FFF7A6 -:1014F000C3FF95F82430A41B1E44F6B2082E1744EF -:101500009044E4B285F82460DBD1FFF79BFF00280C -:10151000D7D108E02B6A03EB82038342CFD0FFF7D9 -:1015200091FF0028CBD10020BDE8F8830120FBE724 -:101530005C3400200FB4002004B0704700B59BB0AD -:10154000EFF3098168226846FFF796FFEFF3058302 -:10155000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6ADF -:101560009B6AFEE700ED00E000B59BB0EFF3098158 -:1015700068226846FFF780FFEFF30583044B9A6B00 -:101580009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF9E -:1015900000ED00E000B59BB0EFF3098168226846DA -:1015A000FFF76AFFEFF30583034B5A6B9A6A9A6A57 -:1015B0009A6A9A6A9B6AFEE700ED00E0FEE7000087 -:1015C00002F050B802F028B830B5094D0A449142F3 -:1015D0000DD011F8013B5840082340F30004013BB3 -:1015E0002C4013F0FF0384EA5000F6D1EFE730BD42 -:1015F0002083B8EDF7B54FF0FF33DFF854C0DFF8C4 -:1016000054E000EB81011A4688421CD050F8044B8C -:10161000019401AF042417F8015B82EA05620825F2 -:10162000DB18164605F1FF355241002EBCBF83EA98 -:101630000C0382EA0E0215F0FF05F1D1013C14F013 -:10164000FF04E8D1E0E7D843D14303B0F0BD00BFC9 -:101650009336EAA9EBE1F0422DE9F041C56915B9ED -:10166000C161BDE8F0814B6823F06047C3F38A464F -:101670004FEAD37EC3F3807816EA230638BF3E468E -:10168000AC462B465A68BEEBD27F22F060440AD0AB -:10169000002A18DAA40CB44217D19D420FD10D6074 -:1016A000DEE71346EEE7A74207D102F08044C2F31B -:1016B000807242450BD054B1EFE708D2EDE7CCF889 -:1016C00000100B60CDE7B44201D0B442E5D81A68EF -:1016D0009C46002AE5D11960C3E700002DE9F047D8 -:1016E000089D01F007044FEAD508224405F00705DC -:1016F00000EBD1004FF47F49944201D1BDE8F0875F -:1017000004F0070705F0070A57453E4638BF56461E -:10171000C6F10806111B8E4228BF0E46E10808EBF1 -:10172000D50E415C13F80EC0B94029FA06F721FA2C -:101730000AF1FFB28CEA010147FA0AF739408CEA54 -:10174000010C03F80EC034443544D5E780EA01208B -:10175000082341F2210201B24000002980B203F1C6 -:10176000FF33B8BF504013F0FF03F4D170470000BF -:1017700038B50C468D18A54200D138BD14F8011BB0 -:10178000FFF7E4FFF7E7000002684AB1136803605F -:10179000C388018901339BB29942C38038BF03815A -:1017A0001046704770B588B0202204460D46684642 -:1017B0000021FFF773FE20460495FFF7E5FF024680 -:1017C00058B16B46054608AE1C4603CCB4422860AF -:1017D0006960234605F10805F6D1104608B070BDD2 -:1017E000082817D909280CD00A280CD00B280CD0AF -:1017F0000C280CD00D280CD00E2814BF402030200F -:1018000070470C2070471020704714207047182034 -:101810007047202070470000082817D90C280CD9E1 -:1018200010280CD914280CD918280CD920280CD928 -:1018300030288CBF0F200E207047092070470A20E7 -:1018400070470B2070470C2070470D207047000038 -:1018500010B54B6823B9CA8A63F30902CA8210BD66 -:10186000C4681A681C60C360438A013B43824A60B3 -:10187000EFE700002DE9F84F1D46CB8A0F46C3F372 -:1018800009010629814692460B4630D00020AAB2B3 -:1018900007F119049EB2052E1FFA80F80FD8904563 -:1018A00003F1010306D3FB8A0A4462F30903FB82B6 -:1018B00001201AE01AF80060E6540130EAE790458A -:1018C000F1D2A1F1060B1C237C68BBFBF3F203FBF6 -:1018D00012BB1FFA8BF6002C45D14846FFF754FF88 -:1018E000044638B978606FF00200BDE8F88F4FF019 -:1018F0000008E6E7002606607860ADB24FF0000B06 -:10190000454510D90AEB0803221D13F8011B915518 -:10191000B1B208F101081B291FFA88F82BD0454500 -:1019200006F10106F1D8FB8AC3F30902154465F3F9 -:101930000903BCE7013292B21C462368002BF9D19F -:10194000AB1F0B441C21B3FBF1F301339BB29A4252 -:10195000D3D2BBF1000FD0D14846FFF715FF20B915 -:10196000C4F800B0BFE70122E7E7C0F800B05E4668 -:1019700020600446C1E74545D5D94846FFF704FF36 -:1019800008B92060AFE7C0F800B000262060044628 -:10199000B6E700002DE9F04F2DED028B83B0CDE9C5 -:1019A0000013BDF83C5007469146002A00F0928093 -:1019B0002DB10E9B002B00F08D80072D32D807F142 -:1019C0000C00FFF7E1FE044638B96FF00204204630 -:1019D00003B0BDEC028BBDE8F08F14220021FFF7AD -:1019E0005DFD0E992A4604F10800FFF745FD681CCD -:1019F000C0B2FFF711FFFFF7F3FE207499F8003033 -:101A0000013814FA80F003F01F0363F03F03037200 -:101A1000009B43F00041616038462146FFF71CFE01 -:101A20000124D4E700F10C034FF0000808EE103A4F -:101A30004FF0800A4646444618EE100AFFF7A4FE0F -:101A400083460028C1D014220021FFF727FDC6BB22 -:101A5000019BABF8083002200E9B00F10802991997 -:101A60005BFA82F20130C0B2082801D0AE422AD31C -:101A7000FFF7D2FEFFF7B4FE99F80020009B411E4D -:101A800002F01F0242EA4812AE4208BF4FF0400A7D -:101A90005BFA81F14AEA020A43F0004281F808A0A9 -:101AA0008BF81000CBF8042059463846FFF7D4FDD8 -:101AB0000134AE4224B288F001084FF0000ABBD1D5 -:101AC00085E70020C8E711F801CB02F801CB013609 -:101AD000B6B2C7E76FF0010479E70000F8B5154624 -:101AE0000E462822002104461F46FFF7D7FC069B1E -:101AF0006360B5F5001F079BA76034BF6A094FF606 -:101B0000FF72236204F10C0097B200239A4205D8B9 -:101B10000023036027826382A382F8BD066001333D -:101B200030462036F2E7000003781BB94BB2002B99 -:101B3000C8BF017070470000007870472DE9F74F6B -:101B4000DDF83C90BDF830500D9E9DF83840BDF852 -:101B50004070804692469B46B9F1000F01D1002F9C -:101B600051D11F2C4FD898F80000B0B9072F47D893 -:101B700035F0030347D13A4649464FF6FF70FFF769 -:101B8000F7FD20F001002D02400445EA0464400CFA -:101B900044EA40244FF6FF7321E040EA0520072F76 -:101BA00040EA0464F6D900254FF6FF73C5F1200022 -:101BB000A5F120022AFA05F10BFA00F001432BFAF5 -:101BC00002F211431846C9B2FFF7C0FD0835402D97 -:101BD0000346EBD13A464946FFF7CAFD0346CDE935 -:101BE0000097324621464046FFF7D4FE3378013352 -:101BF000DBB21F2B88BF0023337003B0BDE8F08F2A -:101C00006FF00300F9E76FF00100F6E72DE9F04F00 -:101C100085B09246DDF848800F9D9DF840209DF8E4 -:101C20004490BDF84C7006469B46B8F1000F01D1B8 -:101C3000002F48D11F2A46D83378002B46D00C02FB -:101C400044EA02649DF8381044EAC93444EA014485 -:101C50001C43072F44F0800432D900234FF6FF7253 -:101C6000C3F1200CA3F120002AFA03F10BFA0CFCBB -:101C700041EA0C012BFA00F00143C9B2104603936C -:101C8000FFF764FD039B0833402B0246E8D13A4638 -:101C90004146FFF76DFD0346CDE900872A46214600 -:101CA0003046FFF777FEB9F1010F06D12B780133EB -:101CB000DBB21F2B88BF00232B7005B0BDE8F08F6F -:101CC0004FF6FF73E8E76FF00100F6E76FF00300EF -:101CD000F3E70000C06900B104307047C3691A68B7 -:101CE000C261C2681A60C360438A013B4382704785 -:101CF0002DE9F041D0F81880194E14461D46414692 -:101D0000002709B9BDE8F081D1E90223A21A65EBE9 -:101D10000303964277EB03031ED283698B420DD1F6 -:101D2000FFF796FD83691B688361C3680B60438A74 -:101D3000C1608169013B43828846E2E7FFF788FD85 -:101D40000B68C8F80030C3680B60438AC160013B70 -:101D50004382D8F80010D4E788460968D1E700BF6D -:101D600080841E002DE9F04F8BB00D46DDF85090B9 -:101D700014469B468046002800F01981B9F1000FF7 -:101D800000F01581531E3F2B00F21181012A03D16F -:101D9000BBF1000F40F00B810023CDE90833B8F808 -:101DA0001430B5EBC30F4FEAC30703D300200BB0C9 -:101DB000BDE8F08F2B199F42D8F80C303ABF7F1B3B -:101DC000FFB227461BB9D8F81030002B7AD02F2D40 -:101DD0004ED8C5F13006B7424FF000032CBFF6B223 -:101DE0003E4600932946D8F8080008AB3246FFF774 -:101DF00075FCA7EB060A35445FFA8AFAB8F8143086 -:101E000003F10053063BDB000493D8F80C30039336 -:101E10003021039B13B1BAF1000F2CD1D8F8100078 -:101E200040B1BAF1000F05D0009608AB5246691ACE -:101E3000FFF754FC38B2002FB8D066070AD00AABBF -:101E400003EBD401624211F8083C02F0070213418F -:101E500001F8083C082C3CD9102C40F2B580202C0D -:101E600040F2B780BBF1000F00F09C80082334E003 -:101E7000BA460026C2E7049BE02B28BFE023069366 -:101E80000B44AB42059314D95A1B03980096924514 -:101E900034BF5246D2B2691A08AB04300792FFF73A -:101EA0001DFC079A1644AAEB020A1544F6B25FFA23 -:101EB0008AFA049B069A05999B1A0493039B1B6854 -:101EC0000393A6E70093D8F8080008AB3A462946E2 -:101ED000AEE7BBF1000F13D00123B4EBC30F6CD0FE -:101EE000082C12D89DF82030621E23FA02F2D50782 -:101EF00006D54FF0FF3202FA04F423438DF8203068 -:101F00009DF8203089F8003051E7102C12D8BDF828 -:101F10002030621E23FA02F2D10706D54FF0FF32BD -:101F200002FA04F42343ADF82030BDF82030A9F8BC -:101F300000303CE7202C0FD80899631E21FA03F3E8 -:101F4000DA0705D54FF0FF3202FA04F40C43089487 -:101F5000089BC9F800302AE7402C2BD0DDE9086542 -:101F6000611EC4F12102A4F1210326FA01F105FA50 -:101F700002F225FA03F311431943CB0712D50122CC -:101F8000A4F12003C4F1200102FA03F322FA01F1C3 -:101F9000A240524243EA010363EB430332432B4323 -:101FA000CDE90823DDE90823C9E90023FFE66FF046 -:101FB0000100FCE66FF00800F9E6082CA0D9102C0F -:101FC000B3D9202CEED8C3E7BBF1000FADD002236C -:101FD00083E7BBF1000FBBD004237EE730B5012AB5 -:101FE000144638BF0124402C85B028BF402400256A -:101FF000012ACDE9025518D81B788DF808306307FF -:102000000AD004AB03EBD405624215F8083C02F099 -:102010000702934005F8083C009103462246002140 -:1020200002A8FFF75BFB05B030BD082AE4D9102AEF -:1020300003D81B88ADF80830E1E7202A8DBFD3E92B -:1020400000231B680293CDE90223D8E710B5CB68C3 -:102050001BB98B600B618B8210BDC4681A681C6051 -:10206000C360438A013B4382CA60F0E72DE9F04F29 -:10207000D1F8008093B018F0800FCDE90323C8F3A6 -:10208000C01219BFC8F3C03BC8F306264FF0020BBD -:102090001646B8F1000F04460D4680F2D18118F0C3 -:1020A000C043059340F0CC810B7B002B00F0C8812E -:1020B000BBF1020F03D00178B14240F0C48108F0B7 -:1020C0007F0106916AB3C8F3074A2B44069A93F836 -:1020D0000390760646EA0B4646EA82465FEAD91343 -:1020E00046EA0A06079300F0908000220023CDE91B -:1020F0000A23069B009367685B4652460AA920465E -:10210000B84700287ED0A7699FB9314604F10C007A -:10211000FFF748FB0746E0B96FF0020013B0BDE8D7 -:10212000F08FC8F30F2A18F07F0F08BF0AF0030AD8 -:10213000CBE73B699E420DD03F68002FF9D1314675 -:1021400004F10C00FFF72EFB07460028E4D0A3693A -:102150003B60A761DDE90A2300264FF6FF70C6F158 -:10216000200E22FA06F103FA0EFEA6F1200C23FA45 -:102170000CFC41EA0E0141EA0C01C9B20836099291 -:102180000893FFF7E3FA402EDDE90832E7D1B88281 -:10219000FB7D09F01F06C3F384039B1BD7E90221D3 -:1021A00098B2002BBCBF00F120031BB252EA010021 -:1021B000C8F304680FD00398821A049860EB0101F9 -:1021C000A74890424FF000028A4104D3079A002AA0 -:1021D0005BD0012B23DDFA7D4FEA890302F0030275 -:1021E00003F07C031343FB7539462046FFF730FBB1 -:1021F000079BA3B9FB7DC3F38402013262F386031C -:10220000FB7504E06FF00B0088E7A76917B96FF062 -:102210000C0083E73B699E42BAD03F68F6E719F0AD -:10222000400F32D0039BBB60049BFB601422002153 -:102230000DA8FFF733F9039B0A93049B0B932B1D07 -:102240000C932B7BADF83EA0013BDBB2ADF83C30EC -:10225000069B8DF8433094F824308DF840B083F01D -:1022600001038DF844308DF84160A3688DF84280F9 -:102270000AA920469847FB7DC3F38403013303F08A -:102280001F039B02FB82002048E7FB7DC9F340123D -:10229000B2EBD31F40F0DA80C3F38403B34240F0C3 -:1022A000D88007992B7B4FEA9912002934D0D207A6 -:1022B00041D4032B40F2D080039BBB60049BFB60A6 -:1022C0002B7BAE1D033BDBB23246394604F10C00DA -:1022D000FFF7D0FA00280DDA20463946FFF7B8FAA2 -:1022E000FB7DC3F38403013303F01F039B02FB82D6 -:1022F000032013E7AB883B832A7B033AB88AD2B228 -:102300003146FFF735FAFB7DB882DA43C2F3C012DB -:1023100062F3C713FB75B6E76AB92E1D013BDBB24A -:102320003246394604F10C00FFF7A4FA0028D3DB4B -:102330002A7B013AE2E7F98AC1F30901013B052949 -:10234000DAB259D8281D002307F11A0C9A4208D98D -:1023500010F801EB0CF801E0013101330629DBB282 -:10236000F4D103990A9104990B91934207F11A0150 -:102370000C9138BF043379680D9134BF55FA83F35B -:1023800000230E93FB8AADF83EA0C3F309031A4461 -:10239000069B8DF8433094F82430ADF83C2083F050 -:1023A00001038DF8443000238DF840B08DF8416072 -:1023B0008DF842807B602A7BB88A013A291DFFF79D -:1023C000D7F93B8BB882834203D1A3680AA9204680 -:1023D000984720460AA9FFF739FEFB7DB88AC3F368 -:1023E0008403013303F01F039B02FB823B8B984263 -:1023F00014BF1120002091E67B68002BB1D006208D -:1024000001E01C306346D3F800C0BCF1000FF8D1E6 -:10241000091A081D05F1040C00EB030905989DF845 -:10242000143001EB000EBEF11B0F9AD89A4298D9D6 -:102430001CF8013B09F8013B059B01330593EDE7CF -:102440006FF009006AE66FF00A0067E66FF00D00B2 -:1024500064E66FF00E0061E66FF00F005EE600BF0D -:1024600080841E00404BF0B51C6C404E44F000745C -:102470001C641D6E45F000751D661B6E3C4B9B6A0F -:10248000D3F80052354045F00105C3F80052D3F8A7 -:102490000042344044EA002040F00100C3F800024A -:1024A000002952D00020C3F81C020546C3F80402DC -:1024B000C3F80C02C3F8140203EBC00401301C285B -:1024C000C4F84052C4F84452F6D100254FF0010C34 -:1024D00096781488F70748BFD3F804720CFA04F012 -:1024E00044BF0743C3F80472B70742BFD3F80C7266 -:1024F0000743C3F80C72760742BFD3F81462064351 -:10250000C3F8146203EBC4045668C4F840629668CA -:10251000C4F84462D3F81C4201352043A942C3F8F1 -:102520001C0202F10C02D3D1D3F8002222F00102E6 -:10253000C3F800220C4B1A6C22F000721A641A6E57 -:1025400022F000721A661B6EF0BD0122C3F8401221 -:10255000C3F84412C3F80412C3F81412C3F80C22CF -:10256000C3F81C22E0E700BF003802400000FFFF74 -:1025700088340020184A916A08B58B688B6013F084 -:10258000010104D013F00C0F18BF4FF48031D805AF -:1025900006D513F4406F14BF41F4003141F002013D -:1025A000D80306D513F4402F14BF41F4802141F025 -:1025B0000401D3690BB108489847202383F311889D -:1025C0000648002100F016FE002383F31188BDE8C1 -:1025D000084001F03FB900BF88340020903400204B -:1025E00038B5124CA36ADD68AA0712D05A6922F0E6 -:1025F00002025A61A36913B10121204698472023A2 -:1026000083F311880A48002100F0F4FD002383F3CE -:102610001188EB0606D5A36A1021D960236A0BB195 -:1026200002489847BDE8384001F014B988340020CA -:102630009834002038B5124CA36A1D69AA0712D03D -:102640005A6922F010025A61A36913B1022120468F -:102650009847202383F311880A48002100F0CAFD1F -:10266000002383F31188EB0606D5A36A10211961B4 -:10267000236A0BB102489847BDE8384001F0EAB838 -:10268000883400209834002038B50F4CA36A5D6868 -:102690005D602A070AD5042222701A6822F002021D -:1026A0001A60636A13B10021204698476B0706D56C -:1026B000A36A9969236A13B1034809049847BDE8DE -:1026C000384001F0C7B800BF8834002010B50E4C68 -:1026D000204600F0F7F90D4BA3620B21132000F008 -:1026E000D9F90B21142000F0D5F90B21152000F0A9 -:1026F000D1F90B21162000F0CDF90022BDE81040E1 -:1027000011460E20FFF7AEBE883400200064004062 -:10271000114B984210B5044609D1104B1A6C42F087 -:1027200000721A641A6E42F000721A661B6EA36A77 -:1027300001221A60A36A5A68D20707D562685168F5 -:102740001268D9611A60064A5A6110BD0121082039 -:1027500000F046FCEEE700BF88340020003802405D -:102760005B87010003291AD8DFE801F0020A0F1481 -:10277000836A9B6813F0E05F14BF0120002070475C -:10278000836A9868C0F380607047836A9868C0F372 -:10279000C0607047836A9868C0F30070704700207B -:1027A0007047000010B5032925D8DFE801F00225A5 -:1027B000292D836A9968C1F30161183103EB011374 -:1027C000107884064CBF54689488C0F300114FEA17 -:1027D000410148BF41EAC40100F00F004CBF41F085 -:1027E000040141EA4451586041F001019068D26807 -:1027F0009860DA60196010BD836A03F5C073DFE783 -:10280000836A03F5C873DBE7836A03F5D073D7E700 -:1028100001290AD002290FD081B9836ADA689207A8 -:1028200001D1186903E001207047836AD86810F06D -:10283000030018BF01207047836AF2E70020704749 -:1028400010B539B9836AD96889071BD11B699C0700 -:1028500004D110BD012915D00229FAD1816AD1F81D -:10286000C031D1F8C441D1F8C8011061D1F8CC0110 -:102870005061202008610869800717D1486940F03D -:10288000100012E0816AD1F8B031D1F8B441D1F82A -:10289000B8011061D1F8BC0150612020C860C8683F -:1028A000800703D1486940F002004861C3F340004B -:1028B000C3F38001000140EA4111107920F030009B -:1028C0000143117189064BBF91681189DB085B0DCB -:1028D0004CBF63F31C0163F30A01137948BF916095 -:1028E00064F3030313714FEA14234FEA144458BFEF -:1028F000118113705480ACE7026843681143016092 -:1029000003B1184770470000024AD36843F0C00380 -:10291000D360704700100140024AD36843F0C003FF -:10292000D3607047004400402DE9F041D0F85C626C -:10293000F7683368DA0504469DB20DD5202383F38A -:1029400011884FF400710430FFF7D6FF6FF48073E5 -:102950003360002383F31188202383F3118804F16B -:10296000040815F02F033AD183F31188380615D5E2 -:10297000290613D5202383F3118804F1380000F0D1 -:1029800023FA00284DDA0821201DFFF7B5FF4FF686 -:102990007F733B40F360002383F311887A0616D5DA -:1029A0006B0614D5202383F31188D4E913239A42AC -:1029B0000AD1236C43B127F040073F041021201DAA -:1029C0003F0CFFF799FFF760002383F31188D4F8D9 -:1029D0006422D3683BB3BDE8F041106918472B0768 -:1029E00013D015F0080F0CBF00218021E80748BF65 -:1029F00041F02001AA0748BF41F040016B0748BFE2 -:102A000041F480714046FFF777FFAD06736805D546 -:102A100094F860122046194000F078FA3568ADB29B -:102A20009FE77060B7E7BDE8F081000008B5034894 -:102A3000FFF77AFFBDE8084000F00CBFB434002077 -:102A400008B50348FFF770FFBDE8084000F002BF7B -:102A50001C37002010B5094C094A2046002100F01F -:102A600033FA084BC4F85C32074C084A0021204670 -:102A700000F02AFA064BC4F85C3210BDB4340020D2 -:102A800009290008001001401C37002019290008FE -:102A90000044004000F1604303F561430901C9B2FD -:102AA00083F80013012200F01F039A4043099B00A2 -:102AB00003F1604303F56143C3F880211A60704756 -:102AC000FFF704BE012300F10802C0E902220370EF -:102AD00000F110020023C0E90422C0E90633C0E976 -:102AE000083343607047000010B52023044683F389 -:102AF0001188022303704160FFF70AFE042323704C -:102B0000002383F3118810BD2DE9F0411F460446D0 -:102B10000D461646202383F3118800F10808237818 -:102B2000052B0DD029462046FFF71CFE40B120465C -:102B300032462946FFF736FE002080F3118808E070 -:102B40003946404600F03AFB0028E8D0002383F3E2 -:102B50001188BDE8F08100002DE9F0411F460446D0 -:102B60000D461646202383F3118800F110082378C0 -:102B7000052B0DD029462046FFF74AFE40B12046DE -:102B800032462946FFF75CFE002080F3118808E0FA -:102B90003946404600F012FB0028E8D0002383F3BA -:102BA0001188BDE8F0810000F8B515468268066915 -:102BB000AA420B46816938BF8568761AB542044639 -:102BC0000BD218462A46FEF757FCA3692B44A36193 -:102BD000A3685B1BA3602846F8BD0CD91846324693 -:102BE000FEF74AFCAF1BE1683A463044FEF744FC6E -:102BF000E3683B44EBE718462A46FEF73DFCE368F2 -:102C0000E5E7000083689342F7B51546044638BFF0 -:102C10008568D0E90460361AB5420BD22A46FEF721 -:102C20002BFC63692B446361A36828465B1BA3608C -:102C300003B0F0BD0DD932460191FEF71DFC01999C -:102C4000E068AF1B3A463144FEF716FCE3683B44AC -:102C5000E9E72A46FEF710FCE368E4E710B50A440A -:102C60000024C361029B8460C0E90000C0E9051133 -:102C7000C1600261036210BD08B5D0E9053293421C -:102C800001D1826882B98268013282605A1C426135 -:102C90001970D0E904329A4224BFC368436100210D -:102CA00000F09CFA002008BD4FF0FF30FBE7000069 -:102CB00070B5202304460E4683F31188A568A5B19C -:102CC000A368A269013BA360531CA3611578226924 -:102CD000934224BFE368A361E3690BB120469847A0 -:102CE000002383F31188284607E03146204600F090 -:102CF00065FA0028E2DA85F3118870BD2DE9F74FF7 -:102D000004460E4617469846D0F81C904FF0200A0D -:102D10008AF311884FF0000B154665B12A463146FB -:102D20002046FFF741FF034660B94146204600F0C8 -:102D300045FA0028F1D0002383F31188781B03B0F3 -:102D4000BDE8F08FB9F1000F03D001902046C847CD -:102D5000019B8BF31188ED1A1E448AF31188DCE77E -:102D6000C0E90511C160C3611144009B8260C0E9E4 -:102D70000000016103627047F8B504460D4616462F -:102D8000202383F31188A768A7B1A368013BA36040 -:102D900063695A1C62611D70D4E904329A4224BFEF -:102DA000E3686361E3690BB120469847002080F334 -:102DB000118807E03146204600F000FA0028E2DAE8 -:102DC00087F31188F8BD0000D0E905239A4210B5B9 -:102DD00001D182687AB98268013282605A1C8261AC -:102DE0001C7803699A4224BFC3688361002100F004 -:102DF000F5F9204610BD4FF0FF30FBE72DE9F74F06 -:102E000004460E4617469846D0F81C904FF0200A0C -:102E10008AF311884FF0000B154665B12A463146FA -:102E20002046FFF7EFFE034660B94146204600F01A -:102E3000C5F90028F1D0002383F31188781B03B073 -:102E4000BDE8F08FB9F1000F03D001902046C847CC -:102E5000019B8BF31188ED1A1E448AF31188DCE77D -:102E6000026843681143016003B1184770470000CE -:102E70001430FFF743BF00004FF0FF331430FFF76B -:102E80003DBF00003830FFF7B9BF00004FF0FF33FF -:102E90003830FFF7B3BF00001430FFF709BF000060 -:102EA0004FF0FF311430FFF703BF00003830FFF759 -:102EB00063BF00004FF0FF323830FFF75DBF000006 -:102EC00000207047FFF7C6BD37B515460E4A0260B1 -:102ED00000224260C0E902220122044602740B462D -:102EE000009000F15C014FF480721430FFF7B6FEE1 -:102EF00000942B464FF4807204F5AE7104F1380053 -:102F0000FFF72EFF03B030BD743F000838B5C3692A -:102F100004460D461BB904210844FFF7A1FF2946CA -:102F200004F11400FFF7A8FE002806DA201D4FF474 -:102F30008061BDE83840FFF793BF38BD024B0022E7 -:102F4000C3E900339A60704784390020002303747A -:102F50008268054B1B6899689142FBD25A680360EE -:102F600042601060586070478439002008B5202303 -:102F700083F31188037C032B05D0042B0DD02BB9D0 -:102F800083F3118808BD436900221A604FF0FF33B4 -:102F90004361FFF7DBFF0023F2E7D0E90032136063 -:102FA0005A60F3E7002303748268054B1B68996835 -:102FB0009142FBD85A6803604260106058607047C5 -:102FC00084390020054B19690874186802681A6072 -:102FD0005360186101230374FDF71ABB8439002084 -:102FE00030B54B1C0B4D87B0044610D02B690A4AF4 -:102FF00001A800F01BF92046FFF7E4FF049B13B182 -:1030000001A800F04FF92B69586907B030BDFFF7F0 -:10301000D9FFF8E7843900206D2F000838B50C4D32 -:1030200041612B6981689A689142044603D8BDE8E2 -:103030003840FFF78BBF1846FFF7B4FF01232C6120 -:10304000014623742046BDE83840FDF7E1BA00BFD1 -:1030500084390020044B1A681B6990689B68984269 -:1030600094BF0020012070478439002010B5084C1F -:10307000236820691A6822605460012223611A744F -:10308000FFF790FF01462069BDE81040FDF7C0BA88 -:103090008439002008B5FFF7DDFF18B1BDE808400E -:1030A000FFF7E4BF08BD0000FFF7E0BFFEE7000048 -:1030B00010B50C4CFFF742FF00F0AAF80A49802235 -:1030C000204600F031F8012344F8180C037400F096 -:1030D0009DFB002383F3118862B60448BDE81040CD -:1030E00000F042B8AC3900209C3F0008AC3F00081B -:1030F00000F012B9EFF3118020B9EFF3058320221D -:1031000082F311887047000010B530B9EFF30584E1 -:10311000C4F3080414B180F3118810BDFFF7BAFF9F -:1031200084F31188F9E7000082600222028270476E -:103130008368A3F17C0243F80C2C026943F83C2C11 -:10314000426943F8382C074A43F81C2CC26843F8FC -:10315000102C022203F8082C002203F8072CA3F1FC -:10316000180070472906000810B5202383F3118842 -:10317000FFF7DEFF00210446FFF750FF002383F333 -:103180001188204610BD0000024B1B6958610F20BA -:10319000FFF718BF84390020202383F31188FFF73D -:1031A000F3BF000008B50146202383F311880820EF -:1031B000FFF716FF002383F3118808BD49B1064BC2 -:1031C00042681B6918605A60136043600420FFF76F -:1031D00007BF4FF0FF3070478439002003689842E2 -:1031E00006D01A680260506059611846FFF7AEBEFB -:1031F0007047000038B504460D462068844200D16F -:1032000038BD036823605C604561FFF79FFEF4E70B -:10321000054B03F11402C3E905224FF0FF310022F0 -:10322000C3E90712704700BF8439002070B51C4EF7 -:10323000C0E9032305460C4600F06EFB334653F805 -:10324000142F9A420DD13062C5E901242A600A2C5C -:103250002CBF00190A30C6E90555BDE8704000F0E2 -:1032600049BB316A431AE31838BF1C469368A3422E -:1032700002D9081900F04CFB73699A6894420CD883 -:103280005A68AC602B606A6015609A685D60121BBA -:103290009A604FF0FF33F36170BD1B68A41AECE72E -:1032A0008439002038B51B4C636998420DD0D0E9B1 -:1032B000003213605A6000228168C2609A680A4432 -:1032C0009A604FF0FF33E36138BD2246036842F84D -:1032D000143F002193425A60C16003D1BDE83840D9 -:1032E00000F010BB9A688168256A0A449A6000F071 -:1032F00013FB63699A68411B8A42E5D9AB181D1A12 -:10330000092D206A98BF01F10A02BDE83840104437 -:1033100000F0FEBA843900202DE9F041184C002756 -:1033200004F11406656900F0F7FA236AAA68C11A65 -:103330008A4215D813442362D5E9003213605A60DB -:103340006369D5F80C80EF60B34201D100F0DAFA7E -:1033500087F311882869C047202383F31188E1E7A8 -:103360006169B14209D013441B1ABDE8F0410A2B30 -:103370002CBFC0180A3000F0CBBABDE8F08100BF06 -:103380008439002000207047FEE7000070470000ED -:103390004FF0FF3070470000BFF34F8F024AD368F1 -:1033A000DB03FCD4704700BF003C024008B5094B6A -:1033B0001B7873B9FFF7F0FF074B1A69002ABFBFEC -:1033C000064A5A6002F188325A601A6822F4806212 -:1033D0001A6008BD403B0020003C024023016745C5 -:1033E00008B50B4B1B7893B9FFF7D6FF094B1A6949 -:1033F00042F000421A611A6842F480521A601A6858 -:1034000022F480521A601A6842F480621A6008BD81 -:10341000403B0020003C02400728F0B516D80C4C79 -:103420000C4923787BB90C4D0E4608234FF00062FF -:1034300055F8047B46F8042B013B13F0FF033A4494 -:10344000F6D10123237051F82000F0BD0020FCE7E5 -:10345000643B0020443B0020C43F0008014B53F86C -:1034600020007047C43F000808207047072810B5A7 -:10347000044601D9002010BDFFF7CEFF064B53F8DC -:1034800024301844C21A0BB90120F4E71268013243 -:10349000F0D1043BF6E700BFC43F0008072838B569 -:1034A000044628D8FFF726FEFFF776FFFFF77EFFDA -:1034B000124AF323D360E300DBB243F4007343F01A -:1034C00002031361136943F48033136105462046F8 -:1034D000FFF762FFFFF7A0FF094B53F8241000F03D -:1034E0003BF92846FFF77CFFFFF70EFE2046BDE8BC -:1034F0003840FFF7BBBF002038BD00BF003C024092 -:10350000C43F000812F001032DE9F04105460E46C4 -:1035100014464BD18118334A914261D8324B1B6813 -:1035200013F001035CD0314FFFF7E4FDFFF73EFFDE -:10353000F323FB60FFF730FF314640F20128032CF4 -:1035400018D824F00104294E0C446D1A40F20118D9 -:10355000A142336905EB01072AD123F0010333614E -:10356000FFF73EFFFFF7D0FD0120BDE8F081043CEE -:103570000435E4E7AB07E4D13B6923F440733B61D6 -:103580003B6943EA08033B6151F8046B2E60BFF3CB -:103590004F8FFFF701FF2B689E42E8D03B6923F075 -:1035A00001033B61FFF71CFFFFF7AEFD0020DCE7E6 -:1035B00023F440733361336943EA080333610B88B2 -:1035C0003B80BFF34F8FFFF7E7FE3F8831F8023BA8 -:1035D000BFB2BB42BCD0336923F001033361E1E7E2 -:1035E0001846C2E70000080800380240003C0240CC -:1035F000084908B50B7828B11BB9FFF7D7FE01239E -:103600000B7008BD002BFCD0BDE808400870FFF728 -:10361000E7BE00BF403B002070B582B0FFF76AFDF7 -:103620000E4E054600F078F93268904237BF0C4ADA -:103630000B49516814682EBFD1E900410131516036 -:103640000419034641F10001284601913360FFF758 -:103650005BFD0199204602B070BD00BF683B0020B1 -:10366000703B002070B582B0FFF744FD104E054658 -:1036700000F052F93268904237BF0E4A0D49516846 -:1036800014682EBFD1E9004101315160041941F1A4 -:1036900000010346284601913360FFF735FD01998B -:1036A0004FF47A7200232046FCF79AFD02B070BDF9 -:1036B000683B0020703B002010B50244064BD2B29C -:1036C000904200D110BD441C00B253F8200041F8D4 -:1036D000040BE0B2F4E700BF502800400F4B30B5B8 -:1036E0001C6F240407D41C6F44F400741C671C6F07 -:1036F00044F400441C670A4C236843F4807323603D -:103700000244084BD2B2904200D130BD441C00B2FA -:1037100051F8045B43F82050E0B2F4E7003802406F -:10372000007000405028004007B5012201A9002088 -:10373000FFF7C2FF019803B05DF804FB13B5044620 -:10374000FFF7F2FFA04205D0012201A90020019459 -:10375000FFF7C4FF02B010BD70470000074B45F2F1 -:1037600055521A6002225A6040F6FF729A604CF677 -:10377000CC421A60024B01221A70704700300040A0 -:103780007C3B0020034B1B781BB1034B4AF6AA225B -:103790001A6070477C3B002000300040034B1A68E1 -:1037A0001AB9034AD2F874281A607047783B00208F -:1037B00000300240024B4FF08072C3F8742870470B -:1037C0000030024008B5FFF7E9FF024B1868C0F36C -:1037D000407008BD783B002008B5FFF7DFFF024BC3 -:1037E0001868C0F3007008BD783B0020EFF3098330 -:1037F00005494A6B22F001024A63683383F3098862 -:10380000002383F31188704700EF00E0202080F34D -:10381000118862B60C4B0D4AD96821F4E0610904A5 -:10382000090C0A43DA60D3F8FC20094942F080729F -:10383000C3F8FC200A6842F001020A601022DA771D -:1038400083F82200704700BF00ED00E00003FA0596 -:10385000001000E010B5202383F311880E4B5B6845 -:1038600013F4006314D0F1EE103AEFF30984683CCE -:103870004FF08073E361094BDB6B236684F30988A7 -:10388000FFF7E8FB10B1064BA36110BD054BFBE74A -:1038900083F31188F9E700BF00ED00E000EF00E0DE -:1038A0003B0600083E06000870470000FEE70000E7 -:1038B0000A4B0B480B4A90420BD30B4BDA1C121AE3 -:1038C000C11E22F003028B4238BF00220021FDF707 -:1038D000E5BD53F8041B40F8041BECE7F440000876 -:1038E000003C0020003C0020003C0020704700000D -:1038F00000F080B84FF08043002258631A61022222 -:10390000DA6070474FF080430022DA6070470000B1 -:103910004FF08043586370474FF08043586A7047B8 -:103920004B6843608B688360CB68C3600B694361FD -:103930004B6903628B6943620B6803607047000048 -:1039400008B5234B23481A6942F0FF021A611A692D -:1039500022F0FF021A611A691A6B42F0FF021A6321 -:103960001A6D42F0FF021A651B4A1B6D1146FFF7E4 -:10397000D7FF02F11C0100F58060FFF7D1FF02F1D3 -:10398000380100F58060FFF7CBFF02F1540100F52C -:103990008060FFF7C5FF02F1700100F58060FFF75E -:1039A000BFFF02F18C0100F58060FFF7B9FF02F163 -:1039B000A80100F58060FFF7B3FF02F1C40100F534 -:1039C0008060FFF7ADFFBDE8084000F097B800BF8A -:1039D0000038024000000240E43F000808B500F053 -:1039E00017FAFFF765FBBDE80840FFF7D7BE0000F8 -:1039F00070470000104B1A6C42F001021A641A6EF4 -:103A000042F001021A660D4A1B6E936843F00103EF -:103A100093604FF0804331229A624FF0FF32DA62B6 -:103A200000229A615A63DA605A6001225A610821C1 -:103A30001A601C20FFF72EB800380240002004E076 -:103A40004FF0804208B51169D3680B40D9B2C94321 -:103A50009B07116107D5202383F31188FFF748FBEB -:103A6000002383F3118808BD08B5FFF7E9FFBDE81F -:103A70000840FFF7EFBE00001E4B1A6962F0FF021C -:103A80001A611A69D2B21A614FF0FF301A695A6985 -:103A9000586100215A6959615A691A6A62F0805264 -:103AA0001A621A6A02F080521A621A6A5A6A5862D4 -:103AB0005A6A59625A6A1A6C42F080521A641A6E33 -:103AC00042F080521A661A6E0B4A106840F48070F9 -:103AD0001060186F00F44070B0F5007F1EBF4FF407 -:103AE000803018671967536823F40073536000F03F -:103AF0006FB900BF00380240007000403B4B3C4AA9 -:103B00001A643C4A4FF4404111601A6842F00102C5 -:103B10001A601A689007FCD59A6822F003029A602E -:103B2000324B9A6812F00C02FBD1196801F0F901CE -:103B300019609A601A6842F480321A601A68910318 -:103B4000FCD55A6F42F001025A67284B5A6F920710 -:103B5000FCD5294A5A601A6842F080721A60254AD8 -:103B600053685804FCD5214B1A689101FCD5234AAF -:103B7000C3F884201A6842F080621A601A68120141 -:103B8000FCD51F4A9A600322C3F88C204FF00062D4 -:103B9000C3F894201B4B1A681B4B9A421B4B21D134 -:103BA0001B4A11681B4A91421CD140F203121A6051 -:103BB000164A136803F00F03032BFAD10B4B9A68D4 -:103BC00042F002029A609A6802F00C02082AFAD1C6 -:103BD0005A6C42F480425A645A6E42F480425A66E9 -:103BE0005B6E704740F20372E1E700BF00380240AD -:103BF000000400100070004008194002103000243A -:103C000000948838002004E011640020003C024049 -:103C100000ED00E041C20F41084A08B55169136840 -:103C20000B4003F00103536123B1054A13680BB144 -:103C300050689847BDE80840FFF70CBE003C0140C3 -:103C4000803B0020084A08B5516913680B4003F017 -:103C50000203536123B1054A93680BB1D0689847BA -:103C6000BDE80840FFF7F6BD003C0140803B002066 -:103C7000084A08B5516913680B4003F00403536107 -:103C800023B1054A13690BB150699847BDE8084054 -:103C9000FFF7E0BD003C0140803B0020084A08B52A -:103CA000516913680B4003F00803536123B1054ABF -:103CB00093690BB1D0699847BDE80840FFF7CABDCA -:103CC000003C0140803B0020084A08B55169136858 -:103CD0000B4003F01003536123B1054A136A0BB183 -:103CE000506A9847BDE80840FFF7B4BD003C01406A -:103CF000803B0020174B10B55A691C68144004F42F -:103D000078725A61A30604D5134A936A0BB1D06A3C -:103D10009847600604D5104A136B0BB1506B984757 -:103D2000210604D50C4A936B0BB1D06B9847E20582 -:103D300004D5094A136C0BB1506C9847A30504D500 -:103D4000054A936C0BB1D06C9847BDE81040FFF763 -:103D500081BD00BF003C0140803B00201A4B10B5E4 -:103D60005A691C68144004F47C425A61620504D507 -:103D7000164A136D0BB1506D9847230504D5134AAD -:103D8000936D0BB1D06D9847E00404D50F4A136EC4 -:103D90000BB1506E9847A10404D50C4A936E0BB139 -:103DA000D06E9847620404D5084A136F0BB1506F68 -:103DB0009847230404D5054A936F0BB1D06F9847F9 -:103DC000BDE81040FFF746BD003C0140803B0020AD -:103DD000062108B50846FEF75DFE06210720FEF71E -:103DE00059FE06210820FEF755FE06210920FEF7A0 -:103DF00051FE06210A20FEF74DFE06211720FEF790 -:103E000049FEBDE8084006212820FEF743BE000019 -:103E100008B5FFF731FE00F00BF8FEF751FEFFF793 -:103E200051F8FFF7E5FDBDE80840FFF761BD000070 -:103E30000023054A19460133102BC2E9001102F193 -:103E40000802F8D1704700BF803B002010B501394F -:103E50000244904201D1002005E0037811F8014F9F -:103E6000A34201D0181B10BD0130F2E72DE9F0414B -:103E7000A3B1C91A17780144044603F1FF3C8C42F0 -:103E8000204601D9002009E00578BD4204F1010473 -:103E9000F5D10CEB0405D618A54201D1BDE8F0819F -:103EA00015F8018D16F801EDF045F5D0E7E70000B3 -:103EB000034611F8012B03F8012B002AF9D17047B2 -:103EC0006F72672E6172647570696C6F742E6375A2 -:103ED00061765F67707300004E6F206170702073B1 -:103EE00069670A00426164206677206C656E6774BA -:103EF000682025750A0042616420626F6172645F08 -:103F000069642025752073686F756C642062652074 -:103F100025750A00426164206677206465736372C8 -:103F20006970746F72206C656E6774682025750AFD -:103F30000042616420617070204352432030782534 -:103F40003038783A30782530387820307825303855 -:103F5000783A3078253038780A00476F6F642066E9 -:103F600069726D776172650A0040A2E4F16468913C -:103F700006000000000000008D2E0008792E0008C9 -:103F8000B52E0008A12E0008AD2E0008992E0008BD -:103F9000852E0008712E0008C12E00086D61696E23 -:103FA0000000000069646C6500000000A43F000888 -:103FB000C8390020403B002001000000AD3000085F -:103FC0000000000000400000004000000040000031 -:103FD000004000000000010000000200000002009C -:103FE00000000200A001102800000000AAAAAAAA4E -:103FF00050011024FFFF00000077000000000000C7 -:1040000000A40A0100000000AAA6AAAA805000008D -:10401000DFEF0000000000778800000000000000D3 -:1040200000000000AAAAAAAA00000000FFFF0000EA -:104030000000000000000000000000000000000080 -:10404000AAAAAAAA00000000FFFF000000000000CA -:10405000000000000000000000000000AAAAAAAAB8 -:1040600000000000FFFF0000000000000000000052 -:104070000000000000000000AAAAAAAA0000000098 -:10408000FFFF000000000000000000000000000032 -:1040900000000000AAAAAAAA00000000FFFF00007A -:1040A0000000000000000000000000000000000010 -:1040B0000A000000000000000300000000000000F3 -:1040C000000000004CC1FF7F010000000000000064 -:1040D000E9030000000000000000070000000000ED -:1040E000640000000000000040420F00FE2A0100B2 -:0440F000D2040000F6 +:1000000000070020F5040008F1260008A9260008D2 +:10001000D1260008A9260008C9260008F704000810 +:10002000F7040008F7040008F7040008E5360008A4 +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008F144000819450008F7 +:10006000414500086945000891450008F70400086B +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F70400085D260008DC +:100090008926000899260008F7040008B9450008D9 +:1000A000F7040008F7040008F7040008F704000844 +:1000B000B5460008F7040008F7040008F704000834 +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F70400088D460008A1460008F704000850 +:1000E0001D460008F7040008F7040008F70400089C +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008F7040008A3 +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E000CD12000800000000000000000000000028 +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600003F0D0FD03F062FE4FF055301F491B4AE7 +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE703F0AEFD54 +:1005B00003F08AFE144C154DAC4203DA54F8041BC8 +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E703F096BD0007002094 +:1005E000002300200000000808ED00E000010020CA +:1005F00000070020F04F0008002300208023002087 +:100600008023002030520020E0010008E4010008AF +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002003F0D4F953 +:10064000FEE703F037F900DFFEE70000F8B500F041 +:100650004FFE03F0F1FC074603F040FD054600287D +:100660003FD12C4B9F423CD001339F423CD02A4B80 +:1006700027F0FF029A423AD1F8B200F045FC2E462C +:1006800042F2107400F046FC08B10024264601F046 +:100690001DF980B3032000F045F80024264635B14B +:1006A0001E4B9F4203D003F011FD0024264600207C +:1006B00003F0CCFC1A4B1B691B0722D40EB100F0CF +:1006C00047F800F093FC00F015FE02F019F805461B +:1006D000CCB102F015F8401BA04214D900F038F854 +:1006E000F3E72E460024CDE704460126CAE7064676 +:1006F0004FF47A74C6E7002CD1D04FF47A740126F7 +:10070000CDE70024DDE700F0B9FC4FF47A7003F088 +:1007100071F9DDE7010007B0000008B0263A09B022 +:1007200000040240084B187003280CD8DFE800F0E2 +:1007300008050208022000F03BBE022000F02EBE99 +:10074000024B00225A60704780230020842300203F +:1007500010B501F0BBF830B1204B03221A70204BCA +:1007600000225A6010BD1F4B1F4A1C4619680131F8 +:10077000F8D004339342F9D162681C4B9A42F1D904 +:100780001B4B9B6803F1006303F580339A42E9D267 +:1007900003F070FC03F082FC002000F0C5FD022095 +:1007A000FFF7C0FF134B1A6C00221A64196E1A6609 +:1007B000196E596C5A64596E5A665B6E72B64FF078 +:1007C000E0233021C3F8084DD4E9003281F31188C9 +:1007D0009D4683F308881047C4E700BF80230020AC +:1007E000842300200000010820000108FFFF00080A +:1007F0000023002000380240094A136849F26900CA +:1008000099B21B0C00FB01331360064B186844F2CD +:10081000506182B2000C01FB0200186080B2704788 +:10082000182300201423002010B5002110220446B4 +:1008300000F0DAFD034B03CB206061601868A06014 +:1008400010BD00BF107AFF1F2DE9F041ADF54E7DC0 +:100850000DF134086CAC40F2751207460D460EA837 +:100860000021C8F8001000F0BFFD4FF4C472002151 +:10087000204600F0B9FD01F043FF274B4FF47A7298 +:10088000B0FBF2F0186093E80700022384E8070049 +:100890000DF5E9702382FFF7C7FF4EF603131F49DA +:1008A000238407A804F0AAFA162384F832310DF243 +:1008B000E32207AB0DF12C0C1E4603CE66451060FB +:1008C0005160334602F10802F6D130681060B388F7 +:1008D000938041460122204600F0D2FD002303937D +:1008E000AB7E029305F11903019380B20123CDE998 +:1008F00004800093E97E06A3D3E90023384602F082 +:10090000C7FA0DF54E7DBDE8F08100BFAFF3008062 +:100910009E6AC421818A46EE8C2300200C4E00087A +:100920002DE9F0412C4C237ADAB080460D465BBBB2 +:1009300027A9284600F0B4FE0746002842D19DF8BA +:100940009D60C82E3ED801464FF4A662204600F0B6 +:100950004BFD4FF48073C4F8F8314FF40073C4F8C2 +:100960000C334FF44073C4F8203432460DF19E012D +:1009700004F1090000F026FD26449DF89C307772B2 +:1009800023720BB9EB7E23728122002106AC27A8CB +:1009900000F02AFD0122214627A800F0BDFE002319 +:1009A0000393AB7E029305F1190380B201932823D0 +:1009B000CDE904400093E97E05A3D3E90023404636 +:1009C00002F066FA5AB0BDE8F08100BFAFF30080D4 +:1009D00026417272DF25D7B7A8440020F0B5254E16 +:1009E0004FF48A7505FB0065F1B096F8D83085F8AC +:1009F000DC300024D822214685F8E8403AA800F0EF +:100A0000F3FC06F1090000F0E7FCD5F8E4308DF8BE +:100A1000F000C2B206AF06F109010DF1F100CDE917 +:100A20003A3400F0CFFC394601223AA800F0A0FE8B +:100A300080B2CDE9047008230127CDE9023706F121 +:100A4000D803019330230093317A0B4807A3D3E9ED +:100A5000002302F01DFAA04206DD01F051FEC5F8A8 +:100A6000E000384671B0F0BD2046FBE778F6339FD2 +:100A700093CACD8DA8440020A43300202DE9F04175 +:100A80001D4D1E4E1E4F86B0284602F02DFA03461D +:100A900058B30024CDE90344ADF81440027B8DF82F +:100AA000142099684068029403AA03C21B68DFF807 +:100AB000548043F00043029301F024FE821941F177 +:100AC0000003009402A9384601F0E6F8A04205DDD3 +:100AD000284602F00DFA88F80040D5E798F8003073 +:100AE000072B05D8013388F8003006B0BDE8F08147 +:100AF000014802F0FDF9F8E7A433002040420F005E +:100B0000D8330020DD49002070B50D4614461E463E +:100B100002F01AF950B9022E10D1012C0ED112A3F5 +:100B2000D3E90023C5E90023012007E0282C10D0D9 +:100B300005D8012C09D0052C0FD0002070BD302C19 +:100B4000FBD10BA3D3E90023ECE70BA3D3E90023EC +:100B5000E8E70BA3D3E90023E4E70BA3D3E90023E1 +:100B6000E0E700BFAFF30080401DA12026812A0BE3 +:100B700078F6339F93CACD8D9E6AC421818A46EE52 +:100B800026417272DF25D7B7F017304A39059E56D5 +:100B900038B505460E4C0021013500F0E7FBA4F8FE +:100BA0002C55B4F82C0500F0C9FB78B1B4F82C052D +:100BB00000F0D4FB014648B9B4F82C0500F0D6FB90 +:100BC000B4F82C350133A4F82C35EAE738BD00BF62 +:100BD000A844002010B50A4B0A4A1A6003F5805356 +:100BE00093F860203AB9DC6D2CB1204600F0ECFEA1 +:100BF000204604F043F8BDE81040034800F0E4BE8E +:100C0000D8330020604E0008204400202DE9F04F2A +:100C10008FB000AF05460C4602F096F8002849D187 +:100C2000237E022B1BD1E38A012B18D101F068FD32 +:100C30000646FFF7E1FD03464FF4C870DFF8C482B3 +:100C4000B3FBF0F206F5167602FB103316FA83F3C7 +:100C5000C8F80030E37E33B9A34B00221A703C374A +:100C6000BD46BDE8F08F07F12401204600F0D6FC18 +:100C70000028F4D107F11400FFF7D6FD97F82640BD +:100C800007F11401224607F1270004F041F800287B +:100C9000E2D10F2C08D8944B1C70D8F80030A3F583 +:100CA0001673C8F80030DAE797F82410284602F0E7 +:100CB00043F8D4E7E38A282B2BD010D8012B23D07C +:100CC000052BCCD1BFF34F8F8849894BCA6802F4FA +:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 +:100CE000BDD1844EE17E327A9142B8D1607E3146E8 +:100CF000002291F8DC50854200F0A5800132042AE0 +:100D000001F58A71F5D1AAE721462846FFF79CFD37 +:100D1000A5E721462846FFF703FEA0E7B2F8EC500E +:100D20007B6005F103094FEA99094FEA8902D11D59 +:100D3000C908A8EBC1039D46EB460021584600F0C8 +:100D400053FB04F1EE012A463144584600F03AFBC9 +:100D50007B6813B9012000F0E7FA96F8D20000F0A2 +:100D6000EDFA044630B9307200F008FB204600F07E +:100D7000DBFAB1E0D6F8D4203AB996F8D200B6F84A +:100D80002C25824201D8FFF703FFD6F8D4202A444D +:100D9000944208D296F8D200B6F82C25013082424F +:100DA00001D8FFF7F5FE70685FFA89F2594600F046 +:100DB00023FB08B9C54679E0726896F8D2002A4448 +:100DC0007260D6F8D42005EB0209C6F8D49000F082 +:100DD000B5FA814509D396F8D220D6F8D40001326D +:100DE000001B86F8D220C6F8D400FF2D0FD80024AF +:100DF000347200F0C3FA204600F096FA00F066FD67 +:100E00003D4B188108B9FFF7A3FCC54627E7BB682F +:100E100096F8D9000AFB0362FB68D2F8E41082F866 +:100E2000E83001F58061C2F8E030C2F8E410FFF765 +:100E3000D5FDFFF723FE96F8D920013202F0030218 +:100E400086F8D920B6E74FF48A7A0AFB02F505F155 +:100E5000EA013144204600F0B7FCF86000287FF436 +:100E6000FEAE3544012285F8E82001F049FCD5F8B2 +:100E7000E020D6ED007ADFED216A801A192838BF0C +:100E8000192040F6B832904228BF1046B8EE677A73 +:100E900007EE900AF8EEE77A67EEA67ADFED186AB9 +:100EA000E7EE267AFCEEE77AC6ED007A96F8D930BE +:100EB000BB60BA6873680AFB02F4321992F8E81052 +:100EC00059B1D2F8E4108B42E8463FF427AF002135 +:100ED00082F8E810C2F8E010C5467368064A9B0A1B +:100EE00001331381BBE600BF9D33002000ED00E01D +:100EF0000400FA05A84400208C230020CDCCCC3D72 +:100F00006666663FA0330020014B1870704700BF33 +:100F10009823002030B54FF000542B4B22689A42A2 +:100F200085B007D003F0E4F8044620BB0024204637 +:100F300005B030BD254B627D25481A70237D0372B4 +:100F40004FF48073C0F8F8314FF40073C0F80C33DD +:100F500000254FF44073C0F820341E49C0F8E45017 +:100F6000C922093000F02EFA2046E022294600F07E +:100F70003BFA0124DBE7184A184D136C43F0007369 +:100F80001364AA6D164B9A42D0D12B6E013B7E2B77 +:100F9000CCD8144A07CA01AB83E8070018460321DE +:100FA00000F062FC6B6D83424FF00003BED12A6DEE +:100FB0008A4201BFAB65054B2A6E1A7003BF0A4B0C +:100FC000EA6D1A601C46B2E79AAD44C5982300202A +:100FD000A8440020160000200038024000660040AF +:100FE0005041A0B0586600401023002037B51A4D7C +:100FF00000F06CFC02236B71184B288119681848AB +:10100000012201F01BFA00230193164B16490093AD +:101010001648174B4FF4805201F066FE154B1978B5 +:1010200011B1124801F088FE01F06AFB0446FFF797 +:10103000E3FB4FF4C873B0FBF3F202FB130304F5B8 +:10104000167010FA83F00C4B186003F047F808B1E3 +:101050000F232B8103B030BD8C23002010230020F0 +:10106000D8330020090B00089C230020A433002063 +:101070000D0C000898230020A03300202DE9F04F2C +:101080002DED028B0FF23829D9E90089834C93B0FA +:101090000BAE9FED7E8BFFF7F1FC814FDFF828A2AE +:1010A00000230A93ADF834300B9373604FF0000BBC +:1010B0005B468DED008B01250DF11D0207A9384619 +:1010C0008DF81C508DF81DB001F068F99DF81C30AA +:1010D000002B40F0A580204601F036FE0646002891 +:1010E00045D1704F01F00CFB3B6898423FD301F0B3 +:1010F00007FB8246FFF780FB4FF4C873B0FBF3F2A7 +:1011000002FB13030AF5167010FA83F03860664F7D +:1011100097F800B0CBF1100ABBF1000F14BF3346B3 +:101120002B465FFA8AFA0EA88DF82830FFF77CFB71 +:10113000BAF1060F28BF4FF0060A0EAB03EB0B0106 +:1011400052460DF1290000F03DF90AAB0393182334 +:1011500002930AF10102554BD2B2CDE90053049239 +:1011600020464CA3D3E9002301F034FE3E7001F089 +:10117000C7FA4F4A4F4D1368C31AB3F57A7F2ED37F +:10118000106001F0BFFA02460B46204601F0BAFE9D +:10119000204601F0D9FD10B32B7A474E002B14BF27 +:1011A00003230223737101F0ABFA0EAF4FF47A738D +:1011B0000122B0FBF3F039463060304600F006FA09 +:1011C000182302933D4B019380B240F25513CDE9B1 +:1011D0000370009342464B46204601F0FBFD2B7AFC +:1011E00093B101F08DFA002607464FF48A7A95F8FC +:1011F000D900304400F003000AFB005393F8E820C4 +:1012000092B30136042EF2D1C82002F0F3FB2B7A00 +:10121000002B7FF43DAF13B0BDEC028BBDE8F08F27 +:10122000DAF8143083F48053CAF814305946102287 +:101230000EA800F0D9F80DF11E0308AA0AA9384635 +:1012400000F028FE96E803000FAB83E803009DF84A +:1012500034308DF844300A9B0E930EA9DDE9082343 +:10126000204602F023F821E7D3F8E02042B12B68B2 +:10127000FA2B38BFFA23BA1A0533B2EB430FC0D3A7 +:10128000FFF7ACFB0028BCD1BEE700BF00000000A8 +:1012900000000000401DA12026812A0BA43300205D +:1012A000D8330020A03300209D3300209C33002041 +:1012B000D8490020A84400208C230020DC490020CD +:1012C000F1C6A7C1D068080F0004024008B5054860 +:1012D00000F07AFEBDE80840034A0449002003F00C +:1012E000C7BC00BFD8330020184A0020D50B000827 +:1012F0007047000070B502F041FD094E094D308085 +:10130000002428683388834208D902F031FD2B6815 +:1013100004440133B4F5803F2B60F2D370BD00BFAD +:101320000C4A0020E049002002F0D8BD00F1006026 +:10133000920000F5803002F067BD0000054B1A688E +:10134000054B1B889B1A834202D9104402F010BD42 +:1013500000207047E04900200C4A0020024B1B6827 +:10136000184402F00DBD00BFE0490020024B1B688D +:10137000184402F01DBD00BFE0490020064991F865 +:10138000243033B10023086A81F824300822FFF7A3 +:10139000CDBF0120704700BFE4490020022802BFF2 +:1013A000024B4FF480529A61704700BF0004024024 +:1013B000022802BF024B4FF080529A61704700BF73 +:1013C0000004024010B50023934203D0CC5CC45407 +:1013D0000133F9E710BD000003460246D01A12F9A6 +:1013E000011B0029FAD1704702440346934202D000 +:1013F00003F8011BFAE770472DE9F8431F4D144627 +:1014000095F824200746884652BBDFF870909CB3BD +:1014100095F824302BB92022FF2148462F62FFF790 +:10142000E3FF95F82400C0F10802A24228BF22463B +:10143000D6B24146920005EB8000FFF7C3FF95F856 +:101440002430A41B1E44F6B2082E17449044E4B284 +:1014500085F82460DBD1FFF791FF0028D7D108E0A1 +:101460002B6A03EB82038342CFD0FFF787FF00286C +:10147000CBD10020BDE8F8830120FBE7E449002040 +:101480002DE9F0470D46044600219046284640F2DB +:101490007912FFF7A9FF234620220021284601F0F8 +:1014A000A7FE231D02222021284601F0A1FE631D74 +:1014B00003222221284601F09BFEA31D03222521A1 +:1014C000284601F095FE04F1080310222821284641 +:1014D00001F08EFE04F1100308223821284601F0A5 +:1014E00087FE04F1110308224021284601F080FE06 +:1014F00004F1120308224821284601F079FE04F184 +:10150000140320225021284601F072FE04F1180332 +:1015100040227021284601F06BFE04F120030822CE +:10152000B021284601F064FE04F121030822B8210D +:10153000284601F05DFE04F12207C0263B463146F5 +:1015400008222846083601F053FEB6F5A07F07F1C1 +:101550000107F3D104F1320308223146284601F095 +:1015600047FE002704F1330A94F832304FEAC709E6 +:101570009F4209F5A47615D3B8F1000F08D1314682 +:1015800004F599730722284601F032FE09F24F163E +:10159000274694F832213B1B93420CD3F01DC00820 +:1015A000BDE8F0870AEB070308223146284601F020 +:1015B0001FFE0137D8E707F23313314608222846C9 +:1015C00001F016FE08360137E3E7000013B50446C4 +:1015D0000846002101602346C0F803102022019034 +:1015E00001F006FE0198231D0222202101F000FED9 +:1015F0000198631D0322222101F0FAFD0198A31D29 +:101600000322252101F0F4FD019804F108031022C2 +:10161000282101F0EDFD072002B010BDF7B5002331 +:10162000047F00910E4607221946054601F0A4FCEE +:10163000731C0093012200230721284601F09CFC23 +:10164000C4B9B31C0093052223460821284601F0A3 +:1016500093FC0D243746B278BB1B934211D32B7FEA +:10166000A88A0734E408BBB9844294BF0020012053 +:1016700003B0F0BDAB8ADB00083BDB08B370082485 +:10168000E8E7FB1C0093214600230822284601F0CE +:1016900073FC08340137DEE7201A18BF0120E7E7A2 +:1016A000F7B50023047F00910E460822194605462F +:1016B00001F062FC731CC4B9082200931146234652 +:1016C000284601F059FC1024012372785F1C013B6D +:1016D000934211D32B7FA88A0734E408BBB9844214 +:1016E00094BF0020012003B0F0BDAB8ADB00083BB3 +:1016F000DB0873700824E7E7F31900932146002301 +:101700000822284601F038FC08343B46DDE7201A61 +:1017100018BF0120E7E70000F8B50E46054614465D +:10172000002181223046FFF75FFE2B460822002170 +:10173000304601F05DFD7CB96B1C07220821304664 +:1017400001F056FD0F2401236A785F1C013B934290 +:1017500004D3E01DC008F8BD0824F4E7EB192146C6 +:101760000822304601F044FD08343B46ECE7000017 +:10177000F8B50E46054614460021CE223046FFF746 +:1017800033FE2B4628220021304601F031FD7CB982 +:1017900005F1080308222821304601F029FD3024F4 +:1017A0002F462A7A7B1B934204D3E01DC008F8BD64 +:1017B0002824F5E707F1090321460822304601F005 +:1017C00017FD08340137ECE7F7B5047F00910E46AA +:1017D000012310220021054601F0CEFBC4B9B31C41 +:1017E0000093092223461021284601F0C5FB192445 +:1017F00037467288BB1B9A4211D82B7FA88A0734C0 +:10180000E408BBB9844294BF0020012003B0F0BDBE +:10181000AB8ADB00103BDB0873801024E8E73B1D3C +:101820000093214600230822284601F0A5FB083436 +:101830000137DEE7201A18BF0120E7E730B5094D70 +:101840000A4491420DD011F8013B5840082340F35F +:101850000004013B2C4013F0FF0384EA5000F6D152 +:10186000EFE730BD2083B8EDF7B54FF0FF33DFF879 +:1018700054C0DFF854E000EB81011A4688421CD0C6 +:1018800050F8044B019401AF042417F8015B82EA7D +:1018900005620825DB18164605F1FF355241002E7A +:1018A000BCBF83EA0C0382EA0E0215F0FF05F1D1FA +:1018B000013C14F0FF04E8D1E0E7D843D14303B082 +:1018C000F0BD00BF9336EAA9EBE1F042F7B5384A24 +:1018D000106851686B4603C36A4636493648082388 +:1018E00003F026FA0446002833D10A25334A10684B +:1018F00051686B4603C36A4631492F48082303F0F9 +:1019000017FA0446002849D00369B3F5E02F45D8FB +:10191000B0F8661040F2E93291423FD1294A0244C0 +:1019200002F15C018B4239D35C3B234900209E1AB3 +:10193000FFF784FF3246074604F164010020FFF7F9 +:101940007DFFA3689F4229D1E368984208BF002524 +:1019500024E00369B3F5E02F27D8418B40F2E93248 +:10196000914220D1174A024402F110018B4218D350 +:10197000103B114900209D1AFFF760FF2A460646DA +:1019800004F118010020FFF759FFA3689E4202D11D +:10199000E368984201D00D25A8E70025284603B04A +:1019A000F0BD1025A2E70C25A0E70B259EE700BFA0 +:1019B000244E0008DCFF0600000001082D4E000840 +:1019C00090FF06000800FFF710B5037C044613B92A +:1019D000006803F095F9204610BD00000023BFF316 +:1019E0005B8FC360BFF35B8FBFF35B8F8360BFF31D +:1019F0005B8F7047BFF35B8F0068BFF35B8F7047EF +:101A000070B505460C30FFF7F5FF05F108060446F2 +:101A10003046FFF7EFFFA04206D930466D68FFF76A +:101A2000E9FF2544281A70BD3046FFF7E3FF201A6E +:101A3000F9E7000070B50546406898B105F1080067 +:101A4000FFF7D8FF05F10C0604463046FFF7D2FF3A +:101A50008442304694BF6D680025FFF7CBFF013C00 +:101A60002C44201A70BD000038B50C460546FFF71F +:101A7000C7FFA04210D305F10800FFF7BBFF0444E5 +:101A80006868B4FBF0F100FB1144BFF35B8F0120E9 +:101A9000AC60BFF35B8F38BD0020FCE72DE9F0415F +:101AA000144607460D46FFF7C5FF844228BF04468B +:101AB000D4B1B84658F80C6B4046FFF79BFF304452 +:101AC000286040467E68FFF795FF331A9C4203D892 +:101AD0006C600120BDE8F0816B60A41B3B68AB60CB +:101AE0002044E8600220F5E72046F3E738B50C46CD +:101AF0000546FFF79FFFA04210D305F10C00FFF74A +:101B000079FF04446868B4FBF0F100FB1144BFF3B3 +:101B10005B8F0120EC60BFF35B8F38BD0020FCE7DA +:101B20002DE9FF41884669460746FFF7B7FF6C4637 +:101B300006B204EBC6060025B44209D062682068EC +:101B400008EB0501FFF73EFC636808341D44F3E72A +:101B500029463846FFF7CAFF284604B0BDE8F081A1 +:101B6000F8B505460C300F46FFF744FF05F10806AF +:101B700004463046FFF73EFFA042304688BF6C68FF +:101B8000FFF738FF201A386020B130462C68FFF785 +:101B900031FF2044F8BD000073B5144606460D46DB +:101BA000FFF72EFF844228BF04460190DCB101A953 +:101BB0003046FFF7D5FF019B33B93268C5E90233E0 +:101BC000C5E9002401200CE09C4238BF0194286044 +:101BD000019868608442F5D93368AB60241AEC60E0 +:101BE000022002B070BD2046FBE700002DE9FF4156 +:101BF0000F466946FFF7D0FF6C4600B204EBC00504 +:101C00000026AC4209D0D4F8048054F8081BB81957 +:101C10004246FFF7D7FB4644F3E7304604B0BDE841 +:101C2000F081000038B50546FFF7E0FF04460146A5 +:101C30002846FFF719FF204638BD0000302383F304 +:101C4000118862B670470000002383F3118862B6E2 +:101C50007047000010B4026854681A4623465DF8C5 +:101C6000044B184701207047002070470020704740 +:101C700070470000002070470E20704700F580502C +:101C800090F8C800C0F340007047000000F5805095 +:101C900090F9C90070470000F7B50C68BDF82070D6 +:101CA00014F000541E466FD10B7B082B6CD8FFF745 +:101CB000C5FF4569AB685B010CD4AB681B0108D458 +:101CC000AC6814F080545DD1FFF7BEFF204603B02E +:101CD000F0BD01240B6804F1180C002BB8BFDB0029 +:101CE0004FEA0C1CB4BF43F004035B0545F80C300D +:101CF0000B680FFA84FC13F0804F18BF05EB0C1E25 +:101D000005EB0C1C1EBFDEF8803143F00203CEF859 +:101D100080310B7BCCF8843105EB04158B68C5F85A +:101D20008C314B68C5F88831DCF8803143F0010311 +:101D3000CCF8803100EB441541F268031D4403EBFD +:101D400044130344C5E9002608330D4601F10C0C89 +:101D500055F804EB43F804EB6545F9D184342D883C +:101D60001D8000EB441407F00303257925F00B05D3 +:101D70002B432371FFF768FF0097334600F0E2FC26 +:101D80000120A4E70224A5E74FF0FF309FE7000001 +:101D900013B500F580540191E06DFFF74BFE1F284D +:101DA0000AD90199E06D2022FFF7BAFEA0F12003C5 +:101DB0005842584102B010BD0020FBE708B500F5BD +:101DC0008050FFF73BFFC06DFFF708FEBDE80840FD +:101DD000FFF73ABF00220260828142608260704752 +:101DE00010B500220023C0E900230023044603812C +:101DF0000C30FFF7EFFF204610BD0000F0B50546A0 +:101E000000F580500C4690F8C83013F0040FC3F36F +:101E1000800108BF114661F3820304F1840680F853 +:101E2000C83005EB461389B01B79D8072ED57AB395 +:101E300019072DD46846FFF7D3FF05EB441303F5CC +:101E4000835303F1180703AA10331868596814461E +:101E500003C40833BB422246F7D1186820609B8830 +:101E6000A380DDE90E23CDE900230123ADF808307E +:101E70002B686946DB6B2846984705EB46152B799E +:101E80001A075CBF43F008032B7101E0002AF4D16C +:101E900009B0F0BD2DE9F047074688B007F580543A +:101EA00068469A468846FFF7C9FE9146FFF798FFB5 +:101EB000E06DFFF7A5FD1F2829D9E06D20226946B6 +:101EC000FFF7B0FE202822D103AD444605AB2E46D5 +:101ED00003CE9E4220606160354604F10804F6D1CD +:101EE00030682060B388A380DDE90023C9E90023BE +:101EF000BDF80830AAF80030FFF7A6FE4A46534660 +:101F00004146384608B0BDE8F04700F009BCFFF78D +:101F10009BFE002008B0BDE8F08700002DE9F84FD7 +:101F20000023C0E90133254B044640F8183B0F4617 +:101F3000FFF750FF04F12800FFF752FF04F14808B3 +:101F400004F582554646083530462036FFF748FFEF +:101F5000AE42F9D104F580554FF480534FF000099B +:101F6000C5E91339C5F848800123EE6504F58758A3 +:101F700004F58456C5F8549085F8583085F86030DB +:101F8000083608F108084FF0000A4FF0000B46E948 +:101F900008ABA6F11800FFF71DFF203646F8289C75 +:101FA0004645F4D185F8C97017B1054800F0A2FB89 +:101FB000044B63612046BDE8F88F00BF604E000807 +:101FC000384E00080064004010B5044B19780446F0 +:101FD0004A1C1A70FFF7A2FF204610BD144A0020C9 +:101FE0002DE9F047002950D0294B2A4FB7FBF1F5D6 +:101FF00099428CBF0A231123581EB5FBF3FC03FB47 +:102000001C53C4B22BB102280346F5D80020BDE80A +:10201000F0870CF1FF36B6F5806FF7D2C4EBC40E33 +:102020000EF103034FEAE309C3F3C703A4EB03086C +:1020300009F1010A4FF47A755FFA88F009FB05553A +:102040005AFA88F8B5FBF8F5B5F5617FC1BF0EF116 +:10205000FF33C3F3C703E01AC0B25C1C50FA84F428 +:102060000CFB04F4B7FBF4F4A142CFD1013BDBB28B +:102070000F2BCBD80138C0B20728C7D80021107168 +:1020800016809170D3700120C1E70846BFE700BFFA +:102090003F420F0040787D0170B505460E464FF473 +:1020A0007A746B695B6803F00103B34207D04FF4A5 +:1020B0007A7001F09FFC013CF3D1204670BD0120F5 +:1020C000FCE7000030B54269936913F0700F16D039 +:1020D00000230B4C936103F1840200EB421211794F +:1020E0004D0709D5890707D5416954F823508D60FC +:1020F000117941F0040111710133032BEBD130BD93 +:102100004C4E000873B51D46436916469A68D207BF +:10211000044609D59A6801219960C2F34002CDE9CD +:1021200000650021FFF76AFE63699A68D1050BD547 +:102130009A684FF480719960C2F34022CDE900653E +:1021400001212046FFF75AFE63699A68D2030BD536 +:102150009A684FF480319960C2F34042CDE900653E +:1021600002212046FFF74AFE204602B0BDE870403B +:10217000FFF7A8BFF8B50446466900296CD106F1FF +:102180000C07386880076AD006EB01153868D5F867 +:10219000B00110F0040FD5F8B0011ABFC00840F02C +:1021A0000040400DA061D5F8B0C11CF0020F1CBF6B +:1021B00040F08040A061D5F8B40106EB011100F0B9 +:1021C0000F0084F82400D1F8B8012077D1F8B801C5 +:1021D000000A6077D1F8B801000CA077D1F8B801F7 +:1021E000000EE077D1F8BC0184F82000D1F8BC01E2 +:1021F000000A84F82100D1F8BC01000C84F8220008 +:10220000D1F8BC11090E84F823103821396004F18B +:10221000340004F1180104F1240551F8046B40F86E +:10222000046BA942F9D109880180C4E90A23214637 +:102230000023238651F8283B2046DB6B984704F5A2 +:102240008052204692F8C83043F0040382F8C83028 +:10225000BDE8F840FFF736BF06F1100791E7F8BD7B +:1022600010B5044600F04EFA02460B4652EA03014E +:1022700002D0013A63F100030449086820B1214605 +:10228000BDE81040FFF776BF10BD00BF104A002028 +:10229000F8B500F583511E46FFF7D0FCDFF844C0C7 +:1022A0000831002404F1840500EB45152B795F0704 +:1022B0000ED4DB060CD5D1E900739742B34107D2A7 +:1022C00043695CF824709F602B7943F004032B7101 +:1022D0000134032C01F12001E4D1BDE8F840FFF7FF +:1022E000B3BC00BF4C4E000808B5FFF7A7FCFFF7D2 +:1022F000E9FEBDE80840FFF7A7BC0000F8B5436958 +:102300000546986800F0E050B0F1E05F0F461FD03E +:10231000E8B1FFF793FC05F583541034002606F16D +:10232000840305EB43131B791A0706D50136032EE8 +:1023300004F12004F3D1012007E05B07F6D4214625 +:10234000384600F039FA0028F0D1FFF77DFCF8BDDF +:102350000120FCE700F5805008B5FFF76FFCC06D69 +:10236000FFF74EFBFFF770FC43090CBF0120002074 +:1023700008BD0000F8B51D46002313700F46064641 +:102380001446FFF7E7FF80F00100387025B12946B9 +:102390003046FFF7B3FF2070F8BD00002DE9B841CB +:1023A0000C4615461F46804600F0ACF90B462178D6 +:1023B000024609B9287850B14046FFF769FFFFF798 +:1023C00093FF3B462A462146FFF7D4FF0120BDE894 +:1023D000B881000010B5FFF731FC174B1A6C42F0C2 +:1023E00000721A641A6A42F000721A621A6A00F5E0 +:1023F000805422F000721A62FFF726FC94F8C8306D +:10240000DB0718D4B9B103211320FFF717FC01F043 +:10241000C7F90321142001F0C3F90321152001F0AD +:10242000BFF994F8C83043F0010384F8C830BDE820 +:102430001040FFF709BC10BD003802402DE9F047FD +:1024400000F5805588B095F8C930012B04468846C0 +:1024500016467FD8804F57F823200AB947F8230043 +:10246000D7F800A0C4F80C802674BAF1000F63D02E +:1024700095F8C930012B6FD001212046FFF7AAFF44 +:10248000FFF7DCFB6269136823F0020313606269E3 +:10249000136843F001031360636900275F61012142 +:1024A0002046FFF7D1FBFFF7F7FD002800F09580ED +:1024B000E86DFFF793FA04F58359BA4609F1080964 +:1024C000202200216846FEF78FFF02A8FFF782FC5A +:1024D000CDF818A06A4609EB07030DF1180E9446D3 +:1024E000BCE80300F44518605960624603F1080334 +:1024F000F5D1DCF80000186020379CF804201A7130 +:10250000602FDDD195F8C8306FF38203002785F87E +:10251000C8306A4641462046ADF80070ADF80270FA +:102520008DF80470FFF75CFD636948BB4FF400420F +:102530001A6008B0BDE8F08741F2D00002F0A0FBBD +:10254000814610B15146FFF7E9FCC7F80090B9F198 +:10255000000F8DD10020ECE7386803681B6B9847AB +:102560000146002888D13868FFF734FF38680368CF +:1025700032465B684146984700287FF47DAFE9E723 +:1025800061221A609DF802309DF803201B06120498 +:1025900002F4702203F040731343BDF80020C2F32D +:1025A000090213439DF804201205022E02F4E002F2 +:1025B0000CBF4FF000410021134362690B43D3610C +:1025C000636913225A616269136823F0010313607F +:1025D00039462046FFF760FD08B96369A6E795F81C +:1025E000C93093BB6169D1F8002242F00102C1F801 +:1025F00000226169D1F8002222F47C5222F00E02FE +:10260000C1F800226169D1F8002242F46062C1F889 +:1026100000226269C2F814326269C2F80432626947 +:1026200041F6FF71C2F80C126269C2F84032626969 +:10263000C2F8443263690122C3F81C226269D2F8ED +:10264000003223F00103C2F8003295F8C83043F09D +:10265000020385F8C8306CE7104A002008B500F086 +:1026600051F850EA0103024602D0421E61F1000116 +:10267000044B186810B10B46FFF744FDBDE8084055 +:1026800001F064B8104A002008B50020FFF7E8FD0B +:10269000BDE8084001F05AB808B50120FFF7E0FD99 +:1026A000BDE8084001F052B800B59BB0EFF30981D6 +:1026B00068226846FEF786FEEFF30583014B9B6BAD +:1026C000FEE700BF00ED00E008B5FFF7EDFF0000FA +:1026D00000B59BB0EFF3098168226846FEF772FEF1 +:1026E000EFF30583014B5B6BFEE700BF00ED00E0FD +:1026F000FEE700000FB408B5029801F011F9FEE7FB +:1027000001F038BC01F010BC13B56C4684E806003B +:10271000031D94E8030083E80500012002B010BD0A +:1027200073B58568019155B11B885B0707D4D0E963 +:1027300000369B6B9847019AC1B23046A8470120EA +:1027400002B070BDF0B5866889B005460C465EB132 +:10275000BDF838305B070AD4D0E900379B6B984747 +:102760002246C1B23846B047012009B0F0BD002270 +:102770000023CDE900230023ADF808300A4603AB5F +:1027800001F10806106851681C4603C40832B242C1 +:102790002346F7D1106820609288A280FFF7B2FF2D +:1027A0000423ADF808302B68CDE90001DB6B6946E6 +:1027B00028469847D8E7000030B503680968DD0F60 +:1027C000B5EBD17F23F0604421F060424FEAD17035 +:1027D0000BD0002BB8BFA40C0029B8BF920C9442B8 +:1027E00002D034BF0120002030BD944205D1C1F396 +:1027F0008070C3F380738342F6D194422CBF0020D3 +:102800000120F1E72DE9F041456A15B94162BDE8C3 +:10281000F0814B6823F06047C3F38A464FEAD37ECA +:10282000C3F3807816EA230638BF3E46AC462B46F3 +:102830005A68BEEBD27F22F060440AD0002A18DA30 +:10284000A40CB44217D19D420FD10D60DEE71346B0 +:10285000EEE7A74207D102F08044C2F380724245FE +:102860000BD054B1EFE708D2EDE7CCF800100B60C5 +:10287000CDE7B44201D0B442E5D81A689C46002A9C +:10288000E5D11960C3E700002DE9F047089D01F08C +:1028900007044FEAD508224405F0070500EBD100F4 +:1028A0004FF47F49944201D1BDE8F08704F0070757 +:1028B00005F0070A57453E4638BF5646C6F108069A +:1028C000111B8E4228BF0E46E10808EBD50E415C75 +:1028D00013F80EC0B94029FA06F721FA0AF1FFB23F +:1028E0008CEA010147FA0AF739408CEA010C03F837 +:1028F0000EC034443544D5E780EA0120082341F274 +:10290000210201B24000002980B203F1FF33B8BFB9 +:10291000504013F0FF03F4D17047000038B50C4667 +:102920008D18A54200D138BD14F8011BFFF7E4FF54 +:10293000F7E7000042684AB1136843604389818920 +:1029400001339BB29942438138BF8381104670475F +:1029500070B588B0202204460D4668460021FEF777 +:1029600043FD20460495FFF7E5FF024658B16B464C +:10297000054608AE1C4603CCB44228606960234675 +:1029800005F10805F6D1104608B070BD082817D922 +:1029900009280CD00A280CD00B280CD00C280CD0FD +:1029A0000D280CD00E2814BF4020302070470C207A +:1029B000704710207047142070471820704720205F +:1029C00070470000082817D90C280CD910280CD9FA +:1029D00014280CD918280CD920280CD930288CBFE1 +:1029E0000F200E207047092070470A2070470B20E7 +:1029F00070470C2070470D20704700002DE9F84308 +:102A0000078C072F04461ED9D0E9029800254FF6FF +:102A1000FF73C5F12006A5F1200029FA05F108FA97 +:102A200006F628FA00F031430143C9B21846FFF711 +:102A300063FF0835402D0346EBD1E1693A46BDE816 +:102A4000F843FFF76BBF4FF6FF70BDE8F883000057 +:102A500010B54B6823B9CA8A63F30902CA8210BD54 +:102A600004691A681C600361C38A013BC3824A601F +:102A7000EFE700002DE9F84F1D46CB8A0F46C3F360 +:102A800009010529814692460B4630D00020AAB2A2 +:102A900007F11A049EB2042E1FFA80F80FD8904551 +:102AA00003F1010306D3FB8A0A4462F30903FB82A4 +:102AB00001201AE01AF80060E6540130EAE7904578 +:102AC000F1D2A1F1050B1C237C68BBFBF3F203FBE5 +:102AD00012BB1FFA8BF6002C45D14846FFF72AFFA0 +:102AE000044638B978606FF00200BDE8F88F4FF007 +:102AF0000008E6E7002606607860ADB24FF0000BF4 +:102B0000454510D90AEB0803221D13F8011B915506 +:102B1000B1B208F101081B291FFA88F82BD04545EE +:102B200006F10106F1D8FB8AC3F30902154465F3E7 +:102B30000903BCE7013292B21C462368002BF9D18D +:102B40006B1F0B441C21B3FBF1F301339BB29A4280 +:102B5000D3D2BBF1000FD0D14846FFF7EBFE20B92E +:102B6000C4F800B0BFE70122E7E7C0F800B05E4656 +:102B700020600446C1E74545D5D94846FFF7DAFE4F +:102B800008B92060AFE7C0F800B000262060044616 +:102B9000B6E700002DE9F04F2DED028B1C4683B007 +:102BA0005B69019207468846002B00F09A80238CCF +:102BB0002BB1E269002A00F09480072B35D807F189 +:102BC0000C00FFF7B7FE054638B96FF0020528463E +:102BD00003B0BDEC028BBDE8F08F14220021FEF79C +:102BE00003FC228CE16905F10800FEF7EBFB208C69 +:102BF000013080B2FFF7E6FEFFF7C8FE013880B271 +:102C00002084013028746369228C1B782A4403F0E5 +:102C10001F0363F03F0348F00041137238466960B8 +:102C20002946FFF7EFFD0125D1E700F10C034FF036 +:102C3000000908EE103A4FF0800A4E464D4618EE55 +:102C4000100AFFF777FE83460028BED01422002129 +:102C5000FEF7CAFB002E3AD1019BABF808300222E6 +:102C60000BF1080E1FFA82FC0CF10100BCF1060FFB +:102C7000218C80B201D88E422BD3FFF7A3FEFFF741 +:102C800085FE62691278013802F01F028E4208BF89 +:102C90004FF0400A42EA49121BFA80F14AEA020A5E +:102CA000013048F0004281F808A08BF81000CBF802 +:102CB000042059463846FFF7A5FD238C0135B34261 +:102CC0002DB289F001094FF0000AB8D17FE7002248 +:102CD000C6E7E169895D0EF802100136B6B201322D +:102CE000C0E76FF0010572E7F8B515460E463022D1 +:102CF000002104461F46FEF777FB069B6360B5F58F +:102D0000001F079BA76034BF6A094FF6FF72A362DA +:102D100097B2E66104F1100000239A4206D800231E +:102D20000360A782E3822383E360F8BD066001337A +:102D300030462036F1E7000003781BB94BB2002B78 +:102D4000C8BF01707047000000787047F8B50C46A6 +:102D5000C969074611B9238C002B37D1257E1F2D59 +:102D600034D8387828BB228C072A2CD8268A36F00B +:102D700003032BD14FF6FF70FFF7D0FD20F00100C9 +:102D80003102400441EA0561400C41EA40254FF61A +:102D9000FF72234629463846FFF7FCFE002807DD70 +:102DA000626913780133DBB21F2B88BF00231370D5 +:102DB000F8BD218A2D0645EA012505432046FFF787 +:102DC0001DFE0246E5E76FF00300F1E76FF001003A +:102DD000EEE7000070B58AB00446164600212822AE +:102DE00068461D46FEF700FBBDF83830ADF81030E0 +:102DF0000F9B05939DF840308DF81830119B079379 +:102E00006946BDF84830ADF820302046CDE902656E +:102E1000FFF79CFF0AB070BD2DE9F041D36905466C +:102E20000C4616460BB9138C5BBB377E1F2F28D878 +:102E300095F80080B8F1000F26D03046FFF7DEFD90 +:102E40003378210241EAC33141EA0801338A41EA79 +:102E5000076141EA03410246334641F080012846BA +:102E6000FFF798FE00280ADD3378012B07D172693D +:102E700013780133DBB21F2B88BF00231370BDE82A +:102E8000F0816FF00100FAE76FF00300F7E7000050 +:102E9000F0B58BB004460D4617460021282268463F +:102EA0001E46FEF7A1FA9DF84C305A1E534253417C +:102EB0008DF800309DF84030ADF81030119B05932F +:102EC0009DF848308DF81830149B07936A46BDF87A +:102ED0005430ADF8203029462046CDE90276FFF780 +:102EE0009BFF0BB0F0BD0000406A00B1043070479A +:102EF000436A1A68426202691A600361C38A013B2D +:102F0000C38270472DE9F041D0F82080194E144655 +:102F10001D464146002709B9BDE8F081D1E90223E9 +:102F2000A21A65EB0303964277EB03031ED2036AF2 +:102F30008B420DD1FFF78CFD036A1B6803620369A6 +:102F40000B60C38A0161016A013BC3828846E2E7E4 +:102F5000FFF77EFD0B68C8F8003003690B60C38A79 +:102F60000161013BC382D8F80010D4E788460968A4 +:102F7000D1E700BF80841E002DE9F04F8BB00D46D5 +:102F8000DDF8509014469B468046002800F01981D9 +:102F9000B9F1000F00F01581531E3F2B00F2118193 +:102FA000012A03D1BBF1000F40F00B810023CDE9D2 +:102FB0000833B8F81430B5EBC30F4FEAC30703D397 +:102FC00000200BB0BDE8F08F2B199F42D8F80C30D1 +:102FD0003ABF7F1BFFB227461BB9D8F81030002B31 +:102FE0007AD0272D4ED8C5F12806B7424FF00003FE +:102FF0002CBFF6B23E4600932946D8F8080008AB2D +:103000003246FFF741FCA7EB060A35445FFA8AFA1D +:10301000B8F8143003F10053053BDB000493D8F8F3 +:103020000C3003932821039B13B1BAF1000F2CD16C +:10303000D8F8100040B1BAF1000F05D0009608ABE7 +:103040005246691AFFF720FC38B2002FB8D0660745 +:103050000AD00AAB03EBD401624211F8083C02F03B +:103060000702134101F8083C082C3CD9102C40F20F +:10307000B580202C40F2B780BBF1000F00F09C809F +:10308000082334E0BA460026C2E7049BE02B28BFA1 +:10309000E02306930B44AB42059314D95A1B0398C3 +:1030A0000096924534BF5246D2B2691A08AB04303A +:1030B0000792FFF7E9FB079A1644AAEB020A1544A8 +:1030C000F6B25FFA8AFA049B069A05999B1A049352 +:1030D000039B1B680393A6E70093D8F8080008AB8E +:1030E0003A462946AEE7BBF1000F13D00123B4EBFB +:1030F000C30F6CD0082C12D89DF82030621E23FA22 +:1031000002F2D50706D54FF0FF3202FA04F423434A +:103110008DF820309DF8203089F8003051E7102CD0 +:1031200012D8BDF82030621E23FA02F2D10706D56C +:103130004FF0FF3202FA04F42343ADF82030BDF81B +:103140002030A9F800303CE7202C0FD80899631EE6 +:1031500021FA03F3DA0705D54FF0FF3202FA04F43F +:103160000C430894089BC9F800302AE7402C2BD068 +:10317000DDE90865611EC4F12102A4F1210326FAEC +:1031800001F105FA02F225FA03F311431943CB07C3 +:1031900012D50122A4F12003C4F1200102FA03F3A5 +:1031A00022FA01F1A240524243EA010363EB4303D6 +:1031B00032432B43CDE90823DDE90823C9E9002385 +:1031C000FFE66FF00100FCE66FF00800F9E6082C5E +:1031D000A0D9102CB3D9202CEED8C3E7BBF1000F37 +:1031E000ADD0022383E7BBF1000FBBD004237EE701 +:1031F00030B5012A144638BF0124402C85B028BFC1 +:1032000040240025012ACDE9025518D81B788DF8F5 +:10321000083063070AD004AB03EBD405624215F80B +:10322000083C02F00702934005F8083C0091034671 +:103230002246002102A8FFF727FB05B030BD082A6F +:10324000E4D9102A03D81B88ADF80830E1E7202A1A +:103250008DBFD3E900231B680293CDE90223D8E791 +:1032600010B5CB681BB98B600B618B8210BD0469F4 +:103270001A681C600361C38A013BC382CA60F0E71D +:1032800003064CBFC0F3C0300220704708B50246A9 +:10329000FFF7F6FF022806D15306C2F30F2001D133 +:1032A00000F0030008BDC2F30740FBE72DE9F04F33 +:1032B00093B0CDE903230A6804461046FFF7E0FF08 +:1032C000022814BFC2F306260026002A0D468246B5 +:1032D00080F2F28112F0C04940F0EE81097B0029B2 +:1032E00000F0EA81022803D02378B34240F0E7815E +:1032F000C2F304630693104602F07F030593FFF7C1 +:10330000C5FF059B29444FEA834848EA0A4848EA32 +:103310004668CE7800230022CDE90823F3098346CE +:1033200048EA0008029367D0059B0093024667684D +:10333000534608A92046B847002800F0C381276AF1 +:103340004FB9414604F10C00FFF702FB074690B964 +:103350006FF0020054E03B6998450DD03F68002FA4 +:10336000F9D1414604F10C00FFF7F2FA07460028B4 +:10337000EED0236A3B60276297F817C006F01F085B +:10338000CCF3840CACEB08001FFA80FE0028B8BF19 +:103390000EF12000A8EB0C031FFA83FED7E90221EF +:1033A000B8BF00B2002B0793BEBF0EF120031BB2C3 +:1033B000079352EA010338D0039BDFF824E39A1AFB +:1033C000049B4FF0000C63EB010196457CEB01037D +:1033D0002BD36B7B97F81AE0734519D1029B002B16 +:1033E00078D0012821DC7868F8B9DFF8F0C294457C +:1033F00070EB010316D337E0276A27B96FF00C0092 +:1034000013B0BDE8F08F3B699845B5D03F68F4E74D +:10341000B24890427CEB010301D30020F0E7029B0D +:10342000002BFAD0079B0F2B17DCFA7DB30002F0BC +:10343000030203F07C031343FB7539462046FFF774 +:1034400007FB6B7BBB76029B3BB9FB7DC3F384021E +:10345000013262F38603FB75D0E76A7BBB7E9A423A +:10346000DBD1029B002B35D0B309022B32D0039B5A +:10347000BB60049BFB60142200210DA8FDF7B4FF84 +:10348000039B0A93049B0B932B1D0C932B7BADF892 +:103490003EB0013BDBB2ADF83C30069B8DF84230CC +:1034A000059B8DF8433094F82C308DF840A083F0C4 +:1034B00001038DF844308DF84180A3680AA92046A5 +:1034C0009847FB7DC3F38403013303F01F039B0282 +:1034D000FB82A2E7FB7DC6F34012B2EBD31F40F0A4 +:1034E000F480C3F38403434540F0F280029A2B7BBF +:1034F000B609002A4DD0F2075DD4032B40F2EB80D1 +:10350000039BBB60049BFB602B7BAE1D033BDBB2CC +:103510003246394604F10C00FFF7ACFA00280CDA09 +:1035200039462046FFF794FAFB7DC3F38403013349 +:1035300003F01F039B02FB820AE7DDE90884AB88E6 +:103540003B834FF6FF73C9F12000A9F1200228FA4E +:1035500009F104FA00F0014324FA02F2114318467B +:10356000C9B2FFF7C9F909F10809B9F1400F0346DB +:10357000E9D1B8822A7B033AD2B23146FFF7CEF9BD +:10358000FB7DB882DA43C2F3C01262F3C713FB7546 +:1035900043E786B92E1D013BDBB23246394604F1C2 +:1035A0000C00FFF767FA0028BADB2A7BB88A013AD9 +:1035B000D2B23146E2E7F98AC1F30901013B04299D +:1035C000DAB25BD8281D002307F11B069A4208D9FE +:1035D00010F801CB06F801C0013101330529DBB237 +:1035E000F4D103990A9104990B91934207F11B01BD +:1035F0000C9138BF043379680D9134BF55FA83F3C9 +:1036000000230E93FB8AADF83EB0C3F309031A44BE +:10361000069B8DF84230059B8DF8433094F82C3092 +:10362000ADF83C2083F001038DF8443000238DF881 +:1036300040A08DF841807B602A7BB88A013A291D21 +:10364000FFF76CF93B8BB882834203D1A3680AA9C8 +:103650002046984720460AA9FFF702FEFB7DBA8A5A +:10366000C3F38403013303F01F039B02FB823B8BF4 +:103670009A420CBF00206FF01000C1E67B68002B5F +:10368000AFD0052001E01C3033461E68002EFAD171 +:10369000091A081D2E1D184401EB090CBCF11B0F63 +:1036A0005FFA89F39DD89A429BD916F8013B00F83E +:1036B000013B09F10109EFE76FF00900A0E66FF0A7 +:1036C0000A009DE66FF00B009AE66FF00D0097E69A +:1036D0006FF00E0094E66FF00F0091E640420F008D +:1036E00080841E00EFF3098305494A6B22F0010232 +:1036F0004A63683383F30988002383F31188704792 +:1037000000EF00E0302080F3118862B60C4B0D4AC8 +:10371000D96821F4E0610904090C0A43DA60D3F89E +:10372000FC20094942F08072C3F8FC200A6842F08C +:1037300001020A602022DA7783F82200704700BF76 +:1037400000ED00E00003FA05001000E010B53023A2 +:1037500083F311880E4B5B6813F4006314D0F1EE11 +:10376000103AEFF30984683C4FF08073E361094B32 +:10377000DB6B236684F3098800F090F810B1064BE8 +:10378000A36110BD054BFBE783F31188F9E700BF88 +:1037900000ED00E000EF00E04306000846060008E8 +:1037A00000F1604303F561430901C9B283F80013D6 +:1037B000012200F01F039A4043099B0003F160437C +:1037C00003F56143C3F880211A6070470023037535 +:1037D000826803691B6899689142FBD25A6803604A +:1037E0004260106058607047002303758268036967 +:1037F0001B6899689142FBD85A6803604260106068 +:103800005860704708B50846302383F311880B7D54 +:10381000032B05D0042B0DD02BB983F3118808BDE1 +:103820008B6900221A604FF0FF338361FFF7CEFFF0 +:103830000023F2E7D1E9003213605A60F3E7000099 +:10384000FFF7C4BF054BD9680875186802681A608D +:10385000536001220275D860FCF7DEBE204A0020CA +:1038600030B50C4BDD684B1C87B004460FD02B469F +:10387000094A684600F06CF92046FFF7E3FF009B19 +:1038800013B1684600F06EF9A86907B030BDFFF7C4 +:10389000D9FFF9E7204A002005380008044B1A68D0 +:1038A000DB6890689B68984294BF002001207047B5 +:1038B000204A0020084B10B51C68D86822681A609E +:1038C000536001222275DC60FFF78EFF014620461F +:1038D000BDE81040FCF7A0BE204A0020044B1A6847 +:1038E000DB6892689B689A4201D9FFF7E3BF704793 +:1038F000204A002038B5074C074908480123002515 +:103900002370656000F03AFC0223237085F3118870 +:1039100038BD00BF884C0020A44E0008204A00207B +:1039200008B572B6044B186500F0ECFA00F0A0FB85 +:10393000024B03221A70FEE7204A0020884C002028 +:1039400000F046B9EFF3118020B9EFF30583302280 +:1039500082F311887047000010B530B9EFF3058489 +:10396000C4F3080414B180F3118810BDFFF7B6FF4B +:1039700084F31188F9E700008B60022308618B82D1 +:10398000084670478368A3F1840243F8142C026947 +:1039900043F8442C426943F8402C094A43F8242C4C +:1039A000C26843F8182C022203F80C2C002203F8FA +:1039B0000B2C044A43F8102CA3F12000704700BFE1 +:1039C00031060008204A002008B5FFF7DBFFBDE8FC +:1039D0000840FFF735BF0000024BDB6898610F20FD +:1039E000FFF730BF204A0020302383F31188FFF710 +:1039F000F3BF000008B50146302383F31188082087 +:103A0000FFF72EFF002383F3118808BD064BDB6808 +:103A100039B1426818605A60136043600420FFF7B0 +:103A20001FBF4FF0FF307047204A002003689842C4 +:103A300006D01A680260506099611846FFF700BF0F +:103A40007047000010B503689C68A2420CD85C68FF +:103A50008A600B604C602160596099688A1A9A608C +:103A60004FF0FF33836010BD1B68121BECE70000B2 +:103A70000A2938BF0A2170B504460D460A26601986 +:103A800000F076FB00F062FB041BA54203D8751C16 +:103A90002E460446F3E70A2E04D9BDE87040012003 +:103AA00000F0ACBB70BD0000F8B5144B0D46D961F9 +:103AB00003F1100141600A2A1969826038BF0A22A5 +:103AC000016048601861A818144600F043FB0A27FB +:103AD00000F03CFB431BA342064606D37C1C28197E +:103AE00000F046FB27463546F2E70A2F04D9BDE829 +:103AF000F840012000F082BBF8BD00BF204A002042 +:103B0000F8B506460D4600F021FB0F4A134653F860 +:103B1000107F9F4206D12A4601463046BDE8F84054 +:103B2000FFF7C2BFD169BB68441A2C1928BF2C46C5 +:103B3000A34202D92946FFF79BFF2246314603489C +:103B4000BDE8F840FFF77EBF204A0020304A002041 +:103B500010B4C0E9032300235DF8044B4361FFF771 +:103B6000CFBF000010B5194C236998420DD0D0E9A1 +:103B70000032816813605A609A680A449A60002390 +:103B800003604FF0FF33A36110BD2346026843F882 +:103B9000102F53600022026022699A4203D1BDE8CF +:103BA000104000F0DFBA936881680B44936000F026 +:103BB000CDFA2269E1699268441AA242E4D911441B +:103BC000BDE81040091AFFF753BF00BF204A00208C +:103BD0002DE9F047DFF8BC8008F110072C4ED8F82B +:103BE000105000F0B3FAD8F81C40AA68031B9A42A0 +:103BF0003ED81444D5E900324FF00009C8F81C4003 +:103C000013605A60C5F80090D8F81030B34201D163 +:103C100000F0A8FA89F31188D5E9033128469847BE +:103C2000302383F311886B69002BD8D000F08EFA13 +:103C30006A69A0EB04094A4582460DD2022000F0D1 +:103C4000DDFA0022D8F81030B34208D15146284698 +:103C5000BDE8F047FFF728BF121A2244F2E712EB43 +:103C6000090938BF4A4629463846FFF7EBFEB5E753 +:103C7000D8F81030B34208D01444211AC8F81C00F8 +:103C8000A960BDE8F047FFF7F3BEBDE8F08700BFCD +:103C9000304A0020204A002000207047FEE7000044 +:103CA000704700004FF0FF3070470000BFF34F8FA8 +:103CB000024AD368DB03FCD4704700BF003C0240DB +:103CC00008B5094B1B7873B9FFF7F0FF074B1A696A +:103CD000002ABFBF064A5A6002F188325A601A6849 +:103CE00022F480621A6008BD904C0020003C024023 +:103CF0002301674508B50B4B1B7893B9FFF7D6FF37 +:103D0000094B1A6942F000421A611A6842F4805263 +:103D10001A601A6822F480521A601A6842F48062AB +:103D20001A6008BD904C0020003C02400728F0B506 +:103D300016D80C4C0C4923787BB90C4D0E46082341 +:103D40004FF0006255F8047B46F8042B013B13F05A +:103D5000FF033A44F6D10123237051F82000F0BD4F +:103D60000020FCE7B44C0020944C0020B04E00082A +:103D7000014B53F820007047B04E000808207047F0 +:103D8000072810B5044601D9002010BDFFF7CEFF6B +:103D9000064B53F824301844C21A0BB90120F4E73B +:103DA00012680132F0D1043BF6E700BFB04E0008C4 +:103DB000072810B5044621D8FFF778FFFFF780FFEA +:103DC0000F4AF323D360C300DBB243F4007343F024 +:103DD00002031361136943F480331361FFF766FF35 +:103DE000FFF7A4FF074B53F8241000F03DF9FFF74D +:103DF00081FF2046BDE81040FFF7C2BF002010BD84 +:103E0000003C0240B04E0008F8B512F00103144621 +:103E100042D185182E4A954257D82E4B1B6813F075 +:103E2000010352D02C4DFFF74BFFF323EB60FFF75C +:103E30003DFF40F20127032C15D824F00104661839 +:103E4000254C401A40F20117B142236900EB0105ED +:103E500024D123F001032361FFF74CFF0120F8BDBB +:103E6000043C0430E7E78307E7D12B6923F4407370 +:103E70002B612B693B432B6151F8046B0660BFF348 +:103E80004F8FFFF713FF03689E42E9D02B6923F0A1 +:103E900001032B61FFF72EFF0020E0E723F44073BE +:103EA000236123693B4323610B882B80BFF34F8F32 +:103EB000FFF7FCFE2D8831F8023BADB2AB42C3D018 +:103EC000236923F001032361E4E71846C7E700BF35 +:103ED0000000080800380240003C0240084908B5CC +:103EE0000B7828B11BB9FFF7EBFE01230B7008BD5F +:103EF000002BFCD0BDE808400870FFF7FBBE00BFF8 +:103F0000904C00204FF480214FF0005000F0AEB8EC +:103F10000846114600F0D6BE012000F0D3BE0000D6 +:103F2000084600F0EDBE000070B582B0FFF70AFD54 +:103F30000E4E054600F00AF93268904237BF0C4A2F +:103F40000B49516814682EBFD1E90041013151601D +:103F50000419034641F10001284601913360FFF73F +:103F6000FBFC0199204602B070BD00BFB84C002098 +:103F7000C04C002070B582B0FFF7E4FC104E05463F +:103F800000F0E4F83268904237BF0E4A0D4951689C +:103F900014682EBFD1E9004101315160041941F18B +:103FA00000010346284601913360FFF7D5FC0199D3 +:103FB0004FF47A7200232046FCF71AF902B070BD64 +:103FC000B84C0020C04C002010B50244064BD2B2C1 +:103FD000904200D110BD441C00B253F8200041F8BB +:103FE000040BE0B2F4E700BF502800400F4B30B59F +:103FF0001C6F240407D41C6F44F400741C671C6FEE +:1040000044F400441C670A4C236843F48073236023 +:104010000244084BD2B2904200D130BD441C00B2E1 +:1040200051F8045B43F82050E0B2F4E70038024056 +:10403000007000405028004007B5012201A900206F +:10404000FFF7C2FF019803B05DF804FB13B5044607 +:10405000FFF7F2FFA04205D0012201A90020019440 +:10406000FFF7C4FF02B010BD7047000070470000AA +:1040700070470000074B45F255521A6002225A6001 +:1040800040F6FF729A604CF6CC421A60024B012255 +:104090001A70704700300040CC4C0020034B1B7856 +:1040A0001BB1034B4AF6AA221A607047CC4C002081 +:1040B00000300040034B1A681AB9034AD2F874283A +:1040C0001A607047C84C002000300240024B4FF08D +:1040D0008072C3F8742870470030024008B5FFF7BB +:1040E000E9FF024B1868C0F3407008BDC84C0020BF +:1040F00008B5FFF7DFFF024B1868C0F3007008BD7A +:10410000C84C002070470000FEE700000A4B0B4837 +:104110000B4A90420BD30B4BDA1C121AC11E22F031 +:1041200003028B4238BF00220021FDF75DB953F82E +:10413000041B40F8041BECE77050000830520020CC +:10414000305200203052002000F0CAB84FF08043B7 +:10415000586A70474FF08043002258631A61022268 +:10416000DA6070474FF080430022DA607047000049 +:104170004FF0804358637047FEE7000070B51B4B5B +:1041800001630025044686B0586085620E46FFF73D +:10419000B9FA04F11003C4E904334FF0FF33C4E962 +:1041A0000635C4E90044A560E562FFF7CFFF2B4662 +:1041B0000246C4E9082304F134010D4A2565802331 +:1041C0002046FFF7D9FB0123E0600A4A03750092FD +:1041D00072680192B268CDE90223074B6846CDE9C7 +:1041E0000435FFF7F1FB06B070BD00BF884C00201E +:1041F000D04E0008D54E000879410008024AD36A23 +:104200001843D062704700BF204A00204B684360CB +:104210008B688360CB68C3600B6943614B69036241 +:104220008B6943620B6803607047000008B5234B3D +:1042300023481A6942F0FF021A611A6922F0FF024C +:104240001A611A691A6B42F0FF021A631A6D42F082 +:10425000FF021A651B4A1B6D1146FFF7D7FF02F1DB +:104260001C0100F58060FFF7D1FF02F1380100F575 +:104270008060FFF7CBFF02F1540100F58060FFF78B +:10428000C5FF02F1700100F58060FFF7BFFF02F18A +:104290008C0100F58060FFF7B9FF02F1A80100F57D +:1042A0008060FFF7B3FF02F1C40100F58060FFF703 +:1042B000ADFFBDE8084000F08DB800BF00380240F7 +:1042C00000000240DC4E000808B500F027FAFFF7B6 +:1042D00011FBBDE80840FFF7EDBE0000704700008D +:1042E0000F4B1A6C42F001021A641A6E42F001027E +:1042F0001A660C4A1B6E936843F0010393604FF0FB +:10430000804331229A624FF0FF32DA6200229A61D2 +:104310005A63DA605A6001225A611A60704700BF1E +:1043200000380240002004E04FF0804208B51169D7 +:10433000D3680B40D9B2C9439B07116107D530231D +:1043400083F31188FFF7FCFA002383F3118808BD7B +:104350001E4B1A6962F0FF021A611A69D2B21A6121 +:104360004FF0FF301A695A69586100215A69596142 +:104370005A691A6A62F080521A621A6A02F080520E +:104380001A621A6A5A6A58625A6A59625A6A1A6CE6 +:1043900042F080521A641A6E42F080521A661A6E07 +:1043A0000B4A106840F480701060186F00F4407081 +:1043B000B0F5007F1EBF4FF480301867196753684F +:1043C00023F40073536000F07DB900BF0038024051 +:1043D000007000403B4B3C4A1A643C4A4FF4404159 +:1043E00011601A6842F001021A601A689007FCD541 +:1043F0009A6822F003029A60324B9A6812F00C021B +:10440000FBD1196801F0F90119609A601A6842F449 +:1044100080321A601A689103FCD55A6F42F001028B +:104420005A67284B5A6F9207FCD5294A5A601A6876 +:1044300042F080721A60254A53685804FCD5214B1B +:104440001A689101FCD5234AC3F884201A6842F007 +:1044500080621A601A681201FCD51F4A9A60032212 +:10446000C3F88C204FF00062C3F894201B4B1A68ED +:104470001B4B9A421B4B21D11B4A11681B4A91428C +:104480001CD140F203121A60164A136803F00F039E +:10449000032BFAD10B4B9A6842F002029A609A6899 +:1044A00002F00C02082AFAD15A6C42F480425A6493 +:1044B0005A6E42F480425A665B6E704740F2037255 +:1044C000E1E700BF00380240000400100070004027 +:1044D000081940021030002400948838002004E0BD +:1044E00011640020003C024000ED00E041C20F4199 +:1044F000074A08B5536903F00103536123B1054A24 +:1045000013680BB150689847BDE80840FFF71EB923 +:10451000003C0140D04C0020074A08B5536903F025 +:104520000203536123B1054A93680BB1D0689847E1 +:10453000BDE80840FFF70AB9003C0140D04C00201C +:10454000074A08B5536903F00403536123B1054AD0 +:1045500013690BB150699847BDE80840FFF7F6B8FA +:10456000003C0140D04C0020074A08B5536903F0D5 +:104570000803536123B1054A93690BB1D069984789 +:10458000BDE80840FFF7E2B8003C0140D04C0020F5 +:10459000074A08B5536903F01003536123B1054A74 +:1045A000136A0BB1506A9847BDE80840FFF7CEB8D0 +:1045B000003C0140D04C0020164B10B55C6904F45F +:1045C00078725A61A30604D5134A936A0BB1D06A74 +:1045D0009847600604D5104A136B0BB1506B98478F +:1045E000210604D50C4A936B0BB1D06B9847E205BA +:1045F00004D5094A136C0BB1506C9847A30504D538 +:10460000054A936C0BB1D06C9847BDE81040FFF79A +:104610009DB800BF003C0140D04C0020194B10B5A4 +:104620005C6904F47C425A61620504D5164A136D34 +:104630000BB1506D9847230504D5134A936D0BB108 +:10464000D06D9847E00404D50F4A136E0BB1506E3D +:104650009847A10404D50C4A936E0BB1D06E9847CD +:10466000620404D5084A136F0BB1506F98472304B6 +:1046700004D5054A936F0BB1D06F9847BDE8104041 +:10468000FFF764B8003C0140D04C002008B5034857 +:1046900000F010F9BDE80840FFF758B8504D002071 +:1046A00008B5034800F006F9BDE80840FFF74EB82A +:1046B000BC4F002008B5FFF737FEBDE80840FFF704 +:1046C00045B80000062108B50846FFF769F806213D +:1046D0000720FFF765F806210820FFF761F806219B +:1046E0000920FFF75DF806210A20FFF759F8062197 +:1046F0001720FFF755F806212820FFF751F807216A +:104700001C20FFF74DF80C212520FFF749F8BDE8E4 +:1047100008400C212620FFF743B8000008B5FFF73A +:1047200017FE00F07BF800F03DF8FFF7D7FDBDE87D +:104730000840FFF709BD00000268436811430160AB +:1047400003B1184770470000143000F0DFB90000D3 +:104750004FF0FF33143000F0D9B90000383000F0CA +:1047600055BA00004FF0FF33383000F04FBA000068 +:10477000143000F0A5B900004FF0FF31143000F004 +:104780009FB90000383000F0FFB900004FF0FF3251 +:10479000383000F0F9B90000012914BF6FF01300A0 +:1047A0000020704700F060B837B515460E4A026029 +:1047B00000224260C0E902220122044602740B4634 +:1047C000009000F15C014FF48072143000F04EF95B +:1047D00000942B464FF4807204F5AE7104F138005A +:1047E00000F0C6F903B030BDBC4F000838B5C3694E +:1047F00004460D461BB904210844FFF79DFF2946D6 +:1048000004F1140000F040F9002806DA201D4FF4EE +:104810000061BDE83840FFF78FBF38BD0023054A6F +:1048200019460133102BC2E9001102F10802F8D138 +:10483000704700BFD04C00200268436811430160FC +:1048400003B1184770470000024AD36843F0C00321 +:10485000D360704700100140024AD36843F0C003A0 +:10486000D36070470044004010B50A4C0A4A204605 +:104870000021FFF799FF094B094AC4E99723094C26 +:10488000094A00212046FFF78FFF0849084BC4E979 +:10489000971310BD504D00204948000880F0FA02DF +:1048A00000100140BC4F002059480008004400405F +:1048B00040787D012DE9F041D0F85C62F7683368FB +:1048C000DA0504469DB20DD5302383F311884FF4E9 +:1048D00080610430FFF7B0FF6FF480733360002312 +:1048E00083F31188302383F3118804F1040815F051 +:1048F0002F033AD183F31188380615D5290613D52D +:10490000302383F3118804F1380000F065F90028A2 +:104910004EDA0821201DFFF78FFF4FF67F733B40D3 +:10492000F360002383F311887A0616D56B0614D53D +:10493000302383F31188D4E913239A420AD1236CDC +:1049400043B127F040073F041021201D3F0CFFF723 +:1049500073FFF760002383F31188D4F86822D368CB +:1049600043B3BDE8F041106918472B0714D015F088 +:10497000080F0CBF00214FF48071E80748BF41F0D9 +:104980002001AA0748BF41F040016B0748BF41F032 +:1049900080014046FFF750FFAD06736805D594F8D7 +:1049A000641220461940FFF721FF3568ADB29EE73B +:1049B0007060B6E7BDE8F081F8B515468268066913 +:1049C000AA420B46816938BF8568761AB54204460B +:1049D0000BD218462A46FCF7F5FCA3692B44A361C9 +:1049E000A3685B1BA3602846F8BD0CD91846324665 +:1049F000FCF7E8FCAF1BE1683A463044FCF7E2FC08 +:104A0000E3683B44EBE718462A46FCF7DBFCE36827 +:104A1000E5E7000083689342F7B51546044638BFC2 +:104A20008568D0E90460361AB5420BD22A46FCF7F5 +:104A3000C9FC63692B446361A36828465B1BA360C0 +:104A400003B0F0BD0DD932460191FCF7BBFC0199D2 +:104A5000E068AF1B3A463144FCF7B4FCE3683B44E2 +:104A6000E9E72A46FCF7AEFCE368E4E710B50A4440 +:104A70000024C361029B8460C0E90000C0E9051105 +:104A8000C1600261036210BD08B5D0E905329342EE +:104A900001D1826882B98268013282605A1C426107 +:104AA0001970D0E904329A4224BFC36843610021DF +:104AB000FEF7BCFF002008BD4FF0FF30FBE7000011 +:104AC00070B5302304460E4683F31188A568A5B15E +:104AD000A368A269013BA360531CA36115782269F6 +:104AE000934224BFE368A361E3690BB12046984772 +:104AF000002383F31188284607E031462046FEF75D +:104B000085FF0028E2DA85F3118870BD2DE9F74FA3 +:104B100004460E4617469846D0F81C904FF0300ACF +:104B20008AF311884FF0000B154665B12A463146CD +:104B30002046FFF741FF034660B941462046FEF795 +:104B400065FF0028F1D0002383F31188781B03B0A0 +:104B5000BDE8F08FB9F1000F03D001902046C8479F +:104B6000019B8BF31188ED1A1E448AF31188DCE750 +:104B7000C0E90511C160C3611144009B8260C0E9B6 +:104B80000000016103627047F8B504460D46164601 +:104B9000302383F31188A768A7B1A368013BA36002 +:104BA00063695A1C62611D70D4E904329A4224BFC1 +:104BB000E3686361E3690BB120469847002080F306 +:104BC000118807E031462046FEF720FF0028E2DA90 +:104BD00087F31188F8BD0000D0E905239A4210B58B +:104BE00001D182687AB98268013282605A1C82617E +:104BF0001C7803699A4224BFC36883610021FEF7D1 +:104C000015FF204610BD4FF0FF30FBE72DE9F74FB1 +:104C100004460E4617469846D0F81C904FF0300ACE +:104C20008AF311884FF0000B154665B12A463146CC +:104C30002046FFF7EFFE034660B941462046FEF7E7 +:104C4000E5FE0028F1D0002383F31188781B03B020 +:104C5000BDE8F08FB9F1000F03D001902046C8479E +:104C6000019B8BF31188ED1A1E448AF31188DCE74F +:104C70000B460146184600F02DB8000000F040B881 +:104C8000012838BF012010B50446204600F030F856 +:104C900030B900F007F808B900F00CF88047F4E7E5 +:104CA00010BD0000024B1868BFF35B8F704700BF58 +:104CB0002852002008B5062000F084F80120FEF7F5 +:104CC000EDFF0000024B0A4601461868FFF720B9C5 +:104CD0001C23002010B5054C13462CB10A46014692 +:104CE0000220AFF3008010BD2046FCE7000000006A +:104CF000024B01461868FFF70FB900BF1C230020C4 +:104D0000024B01461868FFF70BB900BF1C230020B7 +:104D100010B501390244904201D1002005E003782A +:104D200011F8014FA34201D0181B10BD0130F2E76A +:104D30002DE9F041A3B1C91A17780144044603F1E3 +:104D4000FF3C8C42204601D9002009E00578BD4295 +:104D500004F10104F5D10CEB0405D618A54201D1EC +:104D6000BDE8F08115F8018D16F801EDF045F5D09C +:104D7000E7E700001F2938B504460D4604D916237D +:104D800003604FF0FF3038BD426C12B152F8213051 +:104D90004BB9204600F030F82A4601462046BDE8CF +:104DA000384000F017B8012B0AD0591C03D1162344 +:104DB00003600120E7E7002442F825402846984791 +:104DC0000020E0E7024B01461868FFF7D3BF00BFA1 +:104DD0001C23002038B5074D002304460846114621 +:104DE0002B60FEF75FFF431C02D12B6803B12360E9 +:104DF00038BD00BF2C520020FEF74EBF034611F80D +:104E0000012B03F8012B002AF9D170476F72672E2E +:104E10006172647570696C6F742E435541565F47BB +:104E20005053000040A2E4F1646891060041A3E5FC +:104E3000F2656992070000004261642043414E49D7 +:104E40006661636520696E6465782E0080000000ED +:104E50000080000000008000000000000000000052 +:104E6000551C00083D2400089D230008651C00080F +:104E7000991C0008951E0008691C0008791C000890 +:104E80006D1C0008751C0008711C0008BD1D000881 +:104E90007D1C0008092700088D1C0008911D0008D2 +:104EA00063300000A04E0008784A0020884C0020A3 +:104EB00000400000004000000040000000400000F2 +:104EC00000000100000002000000020000000200DB +:104ED0006D61696E0069646C65000000A0011028B6 +:104EE00000000000AAAAAAAA50011024FFFF000097 +:104EF000007700000000000000A40A01000000008C +:104F0000AAA6AAAA80500000DFEF000000000077E8 +:104F1000880000000000000000000000AAAAAAAA61 +:104F200000000000FFFF0000000000000000000083 +:104F30000000000000000000AAAAAAAA00000000C9 +:104F4000FFFF000000000000000000000000000063 +:104F500000000000AAAAAAAA00000000FFFF0000AB +:104F60000000000000000000000000000000000041 +:104F7000AAAAAAAA00000000FFFF0000000000008B +:104F8000000000000000000000000000AAAAAAAA79 +:104F900000000000FFFF0000000000000000000013 +:104FA00000000000000000000A00000000000000F7 +:104FB00003000000000000000000000000000000EE +:104FC00065470008514700088D47000879470008E9 +:104FD00085470008714700085D47000849470008F9 +:104FE000994700083CB2FF7F01000000000000006C +:104FF000E9030000000000000000070000000000BE +:1050000040420F00FE2A0100D204000020230020AD +:105010000000000000000000000000000000000090 +:105020000000000000000000000000000000000080 +:105030000000000000000000000000000000000070 +:105040000000000000000000000000000000000060 +:105050000000000000000000000000000000000050 +:105060000000000000000000000000000000000040 :00000001FF diff --git a/Tools/bootloaders/CarbonixF405_bl.bin b/Tools/bootloaders/CarbonixF405_bl.bin new file mode 100755 index 00000000000000..bbf4a40fcc0d73 Binary files /dev/null and b/Tools/bootloaders/CarbonixF405_bl.bin differ diff --git a/Tools/bootloaders/CarbonixL496_bl.bin b/Tools/bootloaders/CarbonixL496_bl.bin new file mode 100755 index 00000000000000..47736493150d3c Binary files /dev/null and b/Tools/bootloaders/CarbonixL496_bl.bin differ diff --git a/Tools/bootloaders/CubeOrange-bdshot_bl.hex b/Tools/bootloaders/CubeOrange-bdshot_bl.hex old mode 100755 new mode 100644 diff --git a/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin b/Tools/bootloaders/CubeOrange-periph-heavy_bl.bin index b8e0bb3b3d5b64..c912c780818ced 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 ddae0f5234808c..6b527aec21bde3 100644 --- a/Tools/bootloaders/CubeOrange-periph-heavy_bl.hex +++ b/Tools/bootloaders/CubeOrange-periph-heavy_bl.hex @@ -1,1927 +1,2014 @@ :020000040800F2 -:1000000000060020B5050008ED3100086D3100083C -:10001000C53100086D31000899310008B7050008A6 -:10002000B7050008B7050008B705000841400008FB -:10003000B7050008B7050008B7050008B7050008B0 -:10004000B7050008B7050008B7050008B7050008A0 -:10005000B7050008B7050008C16E0008ED6E00087E -:10006000196F0008456F0008716F0008B705000898 -:10007000B7050008B7050008B7050008B705000870 -:10008000B7050008B7050008B7050008B52D00083A -:10009000DD2D0008C92D0008F12D00089D6F000816 -:1000A000B7050008B7050008B7050008B705000840 -:1000B000B7050008B7050008B7050008B705000830 -:1000C000B7050008B7050008B7050008B705000820 -:1000D000B7050008B7050008B7050008B705000810 -:1000E00001700008B7050008B7050008B70500084B -:1000F000B7050008B7050008B7050008B7050008F0 -:10010000B7050008B705000889700008B7050008A2 -:10011000B7050008B7050008B7050008B7050008CF -:10012000B7050008B7050008B7050008B7050008BF -:10013000B7050008B7050008B7050008B7050008AF -:10014000B7050008B7050008B7050008B70500089F -:10015000B7050008B7050008B7050008B70500088F -:10016000B7050008B7050008B7050008B70500087F -:10017000B7050008E9650008B7050008B7050008DD -:10018000B7050008B705000875700008B705000836 -:10019000B7050008B7050008B7050008B70500084F -:1001A000B7050008B7050008B7050008B70500083F -:1001B000B7050008B7050008B7050008B70500082F -:1001C000B7050008B7050008B7050008B70500081F -:1001D000B7050008D5650008B7050008B705000891 -:1001E000B7050008B7050008B7050008B7050008FF -:1001F000B7050008B7050008B7050008B7050008EF -:10020000B7050008B7050008B7050008B7050008DE -:10021000B7050008B7050008B7050008B7050008CE -:10022000B7050008B7050008B7050008B7050008BE -:10023000B7050008B7050008B7050008B7050008AE -:10024000B7050008B7050008B7050008B70500089E -:10025000B7050008B7050008B7050008B70500088E -:10026000B7050008B7050008B7050008B70500087E -:10027000B7050008B7050008B7050008B70500086E -:10028000B7050008B7050008B7050008B70500085E -:10029000B7050008B7050008B7050008B70500084E -:1002A000391A0008000000000000000000000000F3 -:1002B00053B94AB9002908BF00281CBF4FF0FF31CD -:1002C0004FF0FF3000F074B9ADF1080C6DE904CEC9 -:1002D00000F006F8DDF804E0DDE9022304B0704721 -:1002E0002DE9F047089D04468E46002B4DD18A42E9 -:1002F000944669D9B2FA82F252B101FA02F3C2F11C -:10030000200120FA01F10CFA02FC41EA030E9440AC -:100310004FEA1C48210CBEFBF8F61FFA8CF708FBCD -:1003200016E341EA034306FB07F199420AD91CEBA5 -:10033000030306F1FF3080F01F81994240F21C81D7 -:10034000023E63445B1AA4B2B3FBF8F008FB10331F -:1003500044EA034400FB07F7A7420AD91CEB040454 -:1003600000F1FF3380F00A81A74240F20781644424 -:10037000023840EA0640E41B00261DB1D4400023A9 -:10038000C5E900433146BDE8F0878B4209D9002D0D -:1003900000F0EF800026C5E9000130463146BDE897 -:1003A000F087B3FA83F6002E4AD18B4202D3824201 -:1003B00000F2F980841A61EB030301209E46002DB0 -:1003C000E0D0C5E9004EDDE702B9FFDEB2FA82F205 -:1003D000002A40F09280A1EB0C014FEA1C471FFA63 -:1003E0008CFE0126200CB1FBF7F307FB131140EA4A -:1003F00001410EFB03F0884208D91CEB010103F117 -:10040000FF3802D2884200F2CB804346091AA4B2D8 -:10041000B1FBF7F007FB101144EA01440EFB00FEAC -:10042000A64508D91CEB040400F1FF3102D2A64511 -:1004300000F2BB800846A4EB0E0440EA03409CE7B0 -:10044000C6F12007B34022FA07FC4CEA030C20FA5D -:1004500007F401FA06F31C43F9404FEA1C4900FA7D -:1004600006F3B1FBF9F8200C1FFA8CFE09FB1811FA -:1004700040EA014108FB0EF0884202FA06F20BD96D -:100480001CEB010108F1FF3A80F08880884240F2BD -:100490008580A8F102086144091AA4B2B1FBF9F001 -:1004A00009FB101144EA014100FB0EFE8E4508D9FC -:1004B0001CEB010100F1FF346CD28E456AD9023881 -:1004C000614440EA0840A0FB0294A1EB0E01A14266 -:1004D000C846A64656D353D05DB1B3EB080261EBD4 -:1004E0000E0101FA07F722FA06F3F1401F43C5E9AE -:1004F000007100263146BDE8F087C2F12003D840E4 -:100500000CFA02FC21FA03F3914001434FEA1C4725 -:100510001FFA8CFEB3FBF7F007FB10360B0C43EA17 -:10052000064300FB0EF69E4204FA02F408D91CEBC7 -:10053000030300F1FF382FD29E422DD902386344C5 -:100540009B1B89B2B3FBF7F607FB163341EA034165 -:1005500006FB0EF38B4208D91CEB010106F1FF38B4 -:1005600016D28B4214D9023E6144C91A46EA0046AB -:1005700038E72E46284605E70646E3E61846F8E63D -:100580004B45A9D2B9EB020864EB0C0E0138A3E786 -:100590004646EAE7204694E74046D1E7D0467BE767 -:1005A000023B614432E7304609E76444023842E7DF -:1005B000704700BF02E000F000F8FEE772B63A486C -:1005C00080F30888394880F3098839484EF6085185 -:1005D000CEF20001086040F20000CCF200004EF6BE -:1005E0003471CEF200010860BFF34F8FBFF36F8FFD -:1005F00040F20000C0F2F0004EF68851CEF2000149 -:100600000860BFF34F8FBFF36F8F4FF00000E1EE34 -:10061000100A4EF63C71CEF200010860062080F30D -:100620001488BFF36F8F05F0E7FA05F089FA06F03A -:100630000DFA4FF055301F491B4A91423CBF41F81B -:10064000040BFAE71C49194A91423CBF41F8040BDC -:10065000FAE71A491A4A1B4B9A423EBF51F8040B5B -:1006600042F8040BF8E700201749184A91423CBFB2 -:1006700041F8040BFAE705F0A1FA06F05FFA144C12 -:10068000144DAC4203DA54F8041B8847F9E700F034 -:1006900041F8114C114DAC4203DA54F8041B884761 -:1006A000F9E705F089BA00000006002000220020CA -:1006B00000000008000000200006002088770008E5 -:1006C00000220020C8220020C82200202082002012 -:1006D000A0020008A4020008A4020008A402000866 -:1006E0002DE9F04F2DED108AC1F80CD0D0F80CD0C8 -:1006F000BDEC108ABDE8F08F002383F311882846F3 -:10070000A047002004F066FDFEE704F0D5FC00DF02 -:10071000FEE70000F8B501F0CFFA30B1264B002219 -:100720000E211A725A729972DA7205F08DF9074623 -:1007300005F0FCF90546A0BB204B9F4231D00133A8 -:100740009F4231D027F0FF021D4B9A422FD12E46F7 -:1007500042F21074F8B200F09FFD00F0A7FF08B15C -:100760000024264600F09EFD08B90646044635B131 -:10077000144B9F4203D0002405F0D0F926460020F8 -:1007800005F06CF90EB100F065F801F019FB00F00E -:10079000B1FF01F0D7F9204600F012F900F05AF845 -:1007A000F9E72E460024D8E704460126D5E7064699 -:1007B00041F28834D1E700BF00220020010007B0D9 -:1007C000000008B0263A09B008B501F087F9A0F199 -:1007D00020035842584108BD07B541F212030221D7 -:1007E00001A8ADF8043001F097F903B05DF804FBFF -:1007F000202310B583F311881248C3680BB104F0AD -:100800006FFD0023104A4FF47A710E4804F02CFD5E -:10081000002383F311880D4C236813B12368013B37 -:100820002360636813B16368013B6360084B1B7806 -:1008300033B9636823B9022001F044FA32236360BC -:1008400010BD00BFC8220020F1070008E4230020EB -:10085000DC220020F8B5534B534A1C46196801317D -:1008600000F09F8004339342F8D162684F4B9A4264 -:1008700040F297804E4B9B6803F1006303F5003311 -:100880009A4280F08E8005F01DF905F02FF90020C6 -:1008900001F072F90220474B187001F011FA464B33 -:1008A0000021D3F8E820C3F8E810D3F81021C3F8EA -:1008B0001011D3F81021D3F8EC20C3F8EC10D3F8C2 -:1008C0001421C3F81411D3F81421D3F8F020C3F87D -:1008D000F010D3F81821C3F81811D3F81821D3F861 -:1008E000802042F00062C3F88020D3F8802022F0FC -:1008F0000062C3F88020D3F88020D3F8802042F033 -:100900000072C3F88020D3F8802022F00072C3F870 -:100910008020D3F8803072B64FF0E023C3F8084D42 -:10092000D4E90004BFF34F8FBFF36F8F234AC2F89F -:100930008410BFF34F8F536923F480335361BFF3A7 -:100940004F8FD2F8803043F6E076C3F3C905C3F386 -:100950004E335B0103EA060C29464CEA81770139E4 -:10096000C2F87472F9D2203B13F1200FF2D1BFF319 -:100970004F8FBFF36F8FBFF34F8FBFF36F8F5369ED -:1009800023F4003353610023C2F85032BFF34F8F7A -:10099000BFF36F8F202383F31188854680F3088887 -:1009A0002047F8BD0000020820000208FFFF0108F0 -:1009B00000220020DC2200200044025800ED00E06C -:1009C0002DE9F04F93B0AC4B2022FF2100900AA8F4 -:1009D0009D6801F09FF9A94A1378A3B90121A8489D -:1009E0001170C360202383F31188C3680BB104F036 -:1009F00077FC0023A34A4FF47A71A14804F034FC39 -:100A0000002383F31188009B9F4A03B113600023E6 -:100A10009E49009C98469B461E469A460B70536022 -:100A2000012001F04DF924B1974B1B68002B00F019 -:100A30001C82002001F052F80390039B002B01DA86 -:100A400000F0A8FE039B002BEDDB012001F036F93E -:100A5000039B213B162BE3D801A252F823F000BFE1 -:100A6000BD0A0008E50A0008790B0008210A000801 -:100A7000210A0008210A00080D0C0008DF0D0008FB -:100A8000F90C00085B0D0008830D0008A90D000893 -:100A9000210A0008BB0D0008210A00082D0E0008DD -:100AA0005D0B0008210A0008710E0008C90A000841 -:100AB0005D0B0008210A00085B0D00080220FFF70B -:100AC00083FE002840F0FB81009B022105A8B8F1BD -:100AD000000F08BF1C4641F21233ADF8143001F08C -:100AE0001BF89DE74FF47A7000F0F8FF071EEBDB70 -:100AF0000220FFF769FE0028E6D0013F052F00F233 -:100B0000E081DFE807F0030A0D1013360523042106 -:100B100005A8059301F000F817E004215648F9E70D -:100B200004215B48F6E704215A48F3E74FF01C091B -:100B3000484609F1040901F021F80421059005A8AF -:100B400000F0EAFFB9F12C0FF2D101204FF0000ABA -:100B500000FA07F747EA0B0B5FFA8BFB01F026F967 -:100B600026B10BF00B030B2B08BF0024FFF734FE5C -:100B700056E704214848CDE7002EA5D00BF00B0323 -:100B80000B2BA1D10220FFF71FFE074600289BD0A8 -:100B900001203E4E00F0F0FF4FF0000802203070C0 -:100BA00001F08EF85FFA88F9484600F0F5FF044638 -:100BB00090B1484608F1010800F0FEFF0028F1D18D -:100BC000B846044641F21213022105A83E46ADF88C -:100BD000143000F0A1FF23E70123254602203370E3 -:100BE00001F06CF8244B9B68AB4207D9284600F013 -:100BF000C5FF013040F068810435F3E70025234B41 -:100C0000B8463E461D70204B5D60A7E7002E3FF4BE -:100C10005BAF0BF00B030B2B7FF456AF02201B4B8B -:100C2000187001F04DF8322000F058FFB0F10009C3 -:100C3000FFF64AAF19F003077FF446AF0E4A09EBFF -:100C40000503926893423FF63FAFB9F5807F3FF7C7 -:100C50003BAF124BB945019322DD4FF47A7000F09F -:100C60003DFF0390039A002AFFF62EAF039A013747 -:100C7000019B03F8012BEDE700220020E023002078 -:100C8000C8220020F1070008E4230020DC22002015 -:100C900004220020082200200C220020E022002054 -:100CA000C820FFF791FD074600283FF40DAF1F2D28 -:100CB00011D8C5F120020AAB25F0030084494A454A -:100CC000184428BF4A46019200F0FEFF019AFF2116 -:100CD0007F4801F01FF84FEAA903C9F387027C4956 -:100CE0002846019301F01EF8064600283FF46AAF3B -:100CF000019B05EB830531E70220FFF765FD002826 -:100D00003FF4E2AE00F074FF00283FF4DDAE0027B0 -:100D1000B946704B9B68BB4218D91F2F11D80A9B4C -:100D200001330ED027F0030312AA134453F8203CDA -:100D300005934846042205A9043702F065FA814666 -:100D4000E7E7384600F01AFF0590F2E7CDF8149077 -:100D5000042105A800F0E0FE00E70023642104A8B8 -:100D6000049300F0CFFE00287FF4AEAE0220FFF720 -:100D70002BFD00283FF4A8AE049800F02FFF05904B -:100D8000E6E70023642104A8049300F0BBFE0028DA -:100D90007FF49AAE0220FFF717FD00283FF494AECF -:100DA000049800F01DFFEAE70220FFF70DFD002880 -:100DB0003FF48AAE00F02CFFE1E70220FFF704FDCC -:100DC00000283FF481AE05A9142000F027FF074654 -:100DD0000421049004A800F09FFE3946B9E73220B0 -:100DE00000F07CFE071EFFF66FAEBB077FF46CAE13 -:100DF000384A07EB0A03926893423FF665AE022039 -:100E0000FFF7E2FC00283FF45FAE27F003075744EA -:100E1000BA453FF4A3AE50460AF1040A00F0AEFE14 -:100E20000421059005A800F077FEF1E74FF47A70F1 -:100E3000FFF7CAFC00283FF447AE00F0D9FE0028B7 -:100E400044D00A9B01330BD008220AA9002000F0ED -:100E500069FF00283AD02022FF210AA800F05AFF9B -:100E6000FFF7BAFC1C4804F0BBF913B0BDE8F08FE3 -:100E7000002E3FF429AE0BF00B030B2B7FF424AEB6 -:100E80000023642105A8059300F03CFE07460028D6 -:100E90007FF41AAE0220FFF797FC814600283FF44A -:100EA00013AEFFF799FC41F2883004F099F90598E8 -:100EB00000F0C0FF4E463C4600F078FFB0E5064625 -:100EC0004CE64FF0000AFFE5B8467BE6374679E688 -:100ED000E022002000220020A0860100094A49F2F9 -:100EE0006900136899B21B0C00FB013344F2506196 -:100EF0001360054B186882B2000C01FB02001860F9 -:100F000080B27047142200201022002000211022FD -:100F100010B5044600F0FEFE034B03CB2060616079 -:100F20001868A06010BD00BF00E8F11F2DE9F04374 -:100F3000224DBBB002F062F940F2ED22AB68C31A59 -:100F4000934232D906AF2B4628220021A8603846AA -:100F500002F032FE05F10E0000F0D4FE0026044639 -:100F60005FFA80F905F10E08F3B2F100994501F13D -:100F7000280107D908EB060308223846013602F09B -:100F80001BFEF1E7082301220534297B0C48A4B29B -:100F9000CDE902320B4B01933023CDE90474009369 -:100FA00004A3D3E9002302F01FFC3BB0BDE8F083AB -:100FB000AFF3008078F6339F93CACD8D905D00200B -:100FC000043400209D5D002070B50D4614461E4679 -:100FD00002F0A0FB50B9022E10D1012C0ED112A3A9 -:100FE000D3E900230120C5E9002307E0282C10D015 -:100FF00005D8012C09D0052C0FD0002070BD302C55 -:10100000FBD10BA3D3E90023ECE70BA3D3E9002327 -:10101000E8E70BA3D3E90023E4E70BA3D3E900231C -:10102000E0E700BFAFF30080401DA12026812A0B1E -:1010300078F6339F93CACD8D9E6AC421818A46EE8D -:1010400026417272DF25D7B7F017304A39059E5610 -:1010500013B504460846202200212346019002F0E1 -:10106000ABFD227923460198032A4FF0200128BFC7 -:10107000032203F8042F022202F09EFD6279234628 -:101080000198072A4FF0220128BF072203F8052FF5 -:10109000032202F091FDA27923460198072A4FF01E -:1010A000250128BF072203F8062F032202F084FD42 -:1010B000019804F108031022282102F07DFD382058 -:1010C00002B010BD2DE9F04FADF5017D0F460021B6 -:1010D00040F275120EAE804622A8219100F01AFE51 -:1010E00048220021304600F015FE21AD02F086F8BE -:1010F0004FF47A72554B0DF15A09B0FBF2F01860BB -:1011000093E80700012386E807000DF15A003382B7 -:10111000FFF7FCFE47F605034D49338406AB18463E -:1011200006F0A2F81F2229463064304686F83C209B -:10113000FFF78EFF12AB044601460822284602F054 -:101140003BFD08220DF149032846A11804F1880A45 -:1011500002F032FD0DF14A03082204F11001284685 -:1011600004F5847B02F028FD13AB202204F1180162 -:10117000284602F021FD14AB402204F13801284634 -:1011800002F01AFD16AB082204F17801284602F09D -:1011900013FD0DF15903082204F18001284602F0E5 -:1011A0000BFD51460AF1080A4B460822284609F170 -:1011B000010902F001FDD345F3D104F588744FF025 -:1011C00000091BAB08225946284602F0F5FC96F8A8 -:1011D00034304B450AD9B36B2146082228464B448C -:1011E000083409F1010902F0E7FCF0E74FF00009CB -:1011F00096F83C3004EBC9014B4508D9336C082202 -:1012000028464B4409F1010902F0D6FCF0E700231F -:10121000073140460393C1F3CF01BB7E029307F130 -:10122000190301930123CDE904510093F97E05A32D -:10123000D3E9002302F0D8FA0DF5017DBDE8F08F67 -:10124000AFF300809E6AC421818A46EEEC23002021 -:1012500098720008F8B50E4C02260E4FA4F5805384 -:1012600043F8307C237E3BB965692DB1284601F0F7 -:1012700041FE284605F062FF2046A4F5A55401F082 -:1012800039FE012EA4F1100400D1F8BD0126E5E7D6 -:1012900010590020C8730008014B1870704700BF38 -:1012A000F8230020334BF0B51C7B85B034B1324BB2 -:1012B0000E221A810024204605B0F0BD2F4A02AB51 -:1012C0001068516803C308232D492E480DEB030213 -:1012D00005F05CFF054630B9274B0A222A481A81DF -:1012E00001F090FDE6E70169B1F5F01F06D9224B48 -:1012F0000B2226481A8101F085FDDCE7438BB3F50C -:10130000AF6F09D01C4A0C21214811814FF4AF6204 -:10131000194601F077FDCEE71E4A024402F11003A0 -:10132000994204D2144B10221B481A81E3E710396A -:1013300020468E1A134901F067FF05F11801074690 -:101340003246204601F060FFAB689F4202D1EB6855 -:1013500098420AD0084B0D221A813B4600900F4854 -:10136000D5E9021201F04EFDA4E70D48012401F079 -:1013700049FDA0E7905D0020EC23002049730008A0 -:10138000DCFF1D0000000208B8720008C4720008EB -:10139000D67200080800FEF7F47200081173000806 -:1013A0003A7300082DE9F04FADB080460C4606AF09 -:1013B00002F0B0F90546002859D1237E022B1BD13B -:1013C000E38A012B18D101F019FF0646FFF786FDCD -:1013D00003464FF4C87006F51676DFF8CC92B3FBDF -:1013E000F0F202FB103316FA83F3C9F80030E37E03 -:1013F00033B9A84B00221A709C37BD46BDE8F08F68 -:10140000A38AEEB20135013BB3420BD93B1DE90083 -:10141000082220461E4401F0F8010023009602F045 -:101420008FFAEDE707F11400FFF770FD324607F180 -:101430001401381D05F09AFE0028DAD10F2E08D8C5 -:10144000944B1E70D9F80030A3F51673C9F800301C -:10145000D2E7FB1CF87001460722009303462046A2 -:1014600002F06EFAF978404602F04CF9C4E7E38ADC -:10147000282B26D010D8012B1ED0052BBCD1BFF3B2 -:101480004F8F8549854BCA6802F4E0621343CB60F5 -:10149000BFF34F8F00BFFDE7302BADD1637EE94630 -:1014A0007F4D01336A7BDBB2934203D1E27E2B7B1B -:1014B0009A4265D0CD469FE721464046FFF702FE9F -:1014C0009AE7A38A013B9BB2C92B95D8744D2E7B1A -:1014D00026BB05F10C030822314600933346204613 -:1014E00002F02EFA731CF2B2D9001E46A38A013B09 -:1014F0009A4205DA0E3200232A4400920822EEE7CF -:1015000000230022C5E900230023AB6085F8D73013 -:10151000C5F8D8302B7B0BB9E37E2B73002507F180 -:1015200014093B1D082229464846FD60C7E90155BC -:1015300002F042FB3B7A05F1010AAB424FEACA06D0 -:1015400008D9FB680822314648462B44554602F02C -:1015500033FBEFE7C6F3CF060023E17E1934039394 -:101560004046CDE9049663780194029328230093C2 -:1015700046A3D3E9002302F037F9FFF7D7FC3BE796 -:101580004FF0000807F1140310222046A7F814803A -:1015900041460093012302F0D3F9A68A023EB6B277 -:1015A000F31C9B109B000733DB08A9EBC3039D468C -:1015B0000DF1180A1FFA88F34FEAC801B34201F18E -:1015C00010010AD20AEB08030822204608F101089C -:1015D0000093002302F0B4F9ECE795F8D70000F08F -:1015E000DBFAD5F8D83004461BB995F8D70000F0DF -:1015F000E3FAD5F8D83033449C4204D295F8D700AA -:10160000013000F0D9FA4FEA960B4FF000081FFAAC -:1016100088F18B45D5E9003209D90AEB880101220E -:1016200003EB880008F1010800F07CFBEFE7F318FA -:1016300095F8D70042F10002C5E90032D5F8D8305C -:1016400006EB0308C5F8D88000F0A6FA804509D358 -:1016500095F8D730D5F8D8000133001B85F8D7307E -:10166000C5F8D800FF2E08D800232B7300F0C0FA6D -:10167000FFF718FE08B1FFF7EDF82B68094A9B0A3F -:10168000013313810023AB6014E700BF264172725F -:10169000DF25D7B7FD33002000ED00E00400FA0598 -:1016A000905D0020EC2300200034002010B54FF0A6 -:1016B00040540C4B22689A4212D1627D0A4B0B486F -:1016C0001A70C922237D0E30094900F8023C00F04F -:1016D000FBFAE0220021204600F01CFB012010BD97 -:1016E0000020FCE79AAD44C5F8230020905D00205F -:1016F0001600003037B502231D4C1E4D0122204636 -:101700001D496B71236804F580545B689847D4F8D1 -:10171000B034012218495B6804F5966098470023AD -:1017200016494FF480520193154B16480093164BFF -:1017300001F0C2FF154B197811B1124801F0E2FF18 -:1017400001F05CFD0446FFF7C9FB4FF4C873B0FB22 -:10175000F3F202FB130304F5167010FA83F00C4B3E -:10176000186004F0E3F908B10F232B8103B030BDFA -:1017700030340020EC23002040420F00FC230020E6 -:10178000C90F000804340020A5130008F823002026 -:10179000003400202DE9F04F9C4D2DED028B93B0CD -:1017A000DFF890A29A4F284602F082F803460028FC -:1017B0003DD00024974E0E94A046ADF84440A1467B -:1017C000CDE90F44027B8DF844200FAA9968406848 -:1017D00003C21B6843F000430E93336804F22C5499 -:1017E000D3F810B001F00CFD10EB0A02CDF8009018 -:1017F000304606F5A55641F100030EA9D84740F63C -:1018000058230028C8BF48F0010810369C42E4D194 -:10181000B8F1000F05D0284602F04EF887F8009086 -:10182000C1E73B78072B00F2E08001333B700023D7 -:101830000DF12C084FF0010A0A93ADF834300B93E8 -:10184000C8F804309FED6B8B0026724C3746236836 -:101850004FF0000B0DF11D0207A920468DF81CA0CA -:101860008DF81DB08DED008BD3F808905B46C8470E -:101870009DF81C90B9F1000F1ED0102259460EA8F9 -:1018800000F048FA236808AA0AA95F6920460DF10A -:101890001E03B8470FAB4F4698E8030083E80300E8 -:1018A0009DF834300EA928468DF844300A9B0E93DB -:1018B000DDE9082302F0C8F906F22C5640F6582359 -:1018C00004F5A5549E4204F11004C0D1002FBBD1F1 -:1018D000284601F01FFF002840D14F4E01F08EFC3A -:1018E000336898423AD301F089FC0446FFF7F6FAD0 -:1018F0004FF4C87304F516748DF82870B0FBF3F23A -:1019000002FB130314FA83F33360444E377817B99C -:1019100001238DF82830C7F110040EA8FFF7F6FA5E -:101920000EABE4B20DF12900D919062C28BF06240C -:101930002246013400F0C8F90AABE4B2284603930A -:10194000182304940293364B0193012300932BA395 -:10195000D3E9002301F0E0FE0023337001F04EFCD8 -:10196000304A314C1368C31AB3F57A7F30D3106014 -:1019700001F046FC02460B46284601F0A7FF284628 -:1019800001F0C8FE20B3237B0EAF284E002B14BFFE -:1019900003230223737101F031FC4FF47A7339464B -:1019A000B0FBF3F030603046FFF752FB18230730EE -:1019B00002931F4BC0F3CF00019340F25513CDE9C2 -:1019C0000370009328460FA3D3E9002301F0A4FE7F -:1019D000237B2BB1FFF7AAFA237B002B7FF4E0AE29 -:1019E00013B0BDEC028BBDE8F08F284601F064FF18 -:1019F0001DE700BF0000000000000000401DA12006 -:101A000026812A0BF1C6A7C1D068080F0434002034 -:101A1000755E00203034002000340020FD330020AB -:101A2000FC330020705E0020905D0020EC2300203D -:101A3000745E002040420F0008B5064800F014FD17 -:101A4000054800F011FD054A05490020BDE80840A1 -:101A500005F06EBB30340020E0480020D05E00204E -:101A600055120008F7B50C46184E4FF47A7105462A -:101A700002FB01F396F90020501C0BD114482946B3 -:101A800001930268176A2246B8478442019B03D13A -:101A9000002310E0002AF1D096F90020511C01D05B -:101AA000012A0DD10B4829460268166A2246B04722 -:101AB000844205D10123084A0120137003B0F0BD10 -:101AC0004FF4FA7003F08CFB0020F7E71822002097 -:101AD000F8640020D45E0020BC5E0020002307B51F -:101AE000024601210DF107008DF80730FFF7BAFF1C -:101AF00020B19DF8070003B05DF804FB4FF0FF3004 -:101B0000F9E700000A46042108B5FFF7ABFF80F0B3 -:101B10000100C0B2404208BD074B0A4630B41978F4 -:101B2000064B53F82140014623682046DD69044BEB -:101B3000AC4630BC604700BFBC5E0020707300083C -:101B4000A086010070B50A4E00240A4D03F0F6FD90 -:101B5000308028683388834208D903F0EBFD2B6876 -:101B600004440133B4F5003F2B60F2D370BD00BFD5 -:101B7000BE5E0020785E002003F0BEBE00F1006073 -:101B800000F500300068704700F10060920000F539 -:101B9000003003F035BE0000054B1A68054B1B886A -:101BA0009B1A834202D9104403F0C4BD0020704741 -:101BB000785E0020BE5E002038B5074D04462868D8 -:101BC000204403F0BDFD28B928682044BDE8384012 -:101BD00003F0C8BD38BD00BF785E0020002070470C -:101BE00000F1FF5000F58F10D0F80008704700009A -:101BF000064991F8243033B100230822086A81F89D -:101C00002430FFF7C1BF0120704700BF7C5E002079 -:101C1000014B1868704700BF0010005C244BF0B502 -:101C20001A680446234BC2F30B06120C1F8858682F -:101C3000BE4293F9085028D09F89BE4206D10120A8 -:101C40000C2505FB0033586893F9085041F2010355 -:101C50009A421CD041F203039A421AD042F2010385 -:101C60009A4218D042F203039A4208BF5625621ED8 -:101C70000B46441E0A4493420FD214F9016F581CBC -:101C80006EB1034600F8016CF5E70020D8E75A254D -:101C9000EDE75925EBE75825E9E7184605E02C2440 -:101CA00082421C7001D9981C5D70401AF0BD00BFC3 -:101CB0000010005C1C2200200020704770470000CC -:101CC0007047000070470000002310B5934203D016 -:101CD000CC5CC4540133F9E710BD0000013810B5E5 -:101CE00010F9013F3BB191F900409C4203D11AB178 -:101CF0000131013AF4E71AB191F90020981A10BDA8 -:101D00001046FCE703460246D01A12F9011B0029CF -:101D1000FAD1704702440346934202D003F8011BF4 -:101D2000FAE770472DE9F8431F4D144607468846E9 -:101D300095F8242052BBDFF870909CB395F82430BE -:101D40002BB92022FF2148462F62FFF7E3FF95F8C9 -:101D500024004146C0F1080205EB8000A24228BFE2 -:101D60002246D6B29200FFF7AFFF95F82430A41BAD -:101D700017441E449044E4B2F6B2082E85F824605D -:101D8000DBD1FFF735FF0028D7D108E02B6A03EB42 -:101D900082038342CFD0FFF72BFF0028CBD1002056 -:101DA000BDE8F8830120FBE77C5E0020024B1A7837 -:101DB000024B1A70704700BFBC5E00201822002042 -:101DC00038B5164C164D204602F000FD2946204637 -:101DD00002F028FD2D681348D5F89020D2F8043879 -:101DE00043F00203C2F8043803F0FAF90E4928461A -:101DF00002F026FED5F890200C48D2F804380C49A1 -:101E0000A04223F00203C2F804384FF4E1330B6020 -:101E100003D0BDE8384002F037BC38BDF86400207C -:101E20001075000840420F0018750008D45E0020AD -:101E3000A45E002038B50B4B04461A780A4B53F8C1 -:101E400022500A4B9D420CD0094B00211822184603 -:101E5000FFF760FF046001462846BDE8384002F005 -:101E600013BC38BDBC5E002070730008F86400200D -:101E7000A45E0020202383F3118862B6704700001F -:101E8000002383F3118862B6704700000120704779 -:101E9000704700007047000010B4134602681468D1 -:101EA0000022A4465DF8044B6047000000F5805016 -:101EB00090F859047047000000F5805090F85204E3 -:101EC0007047000000F5805090F9580470470000FA -:101ED0004E20704700F5805208B5FFF7CBFFD2F8CF -:101EE0009834D2F894041844D2F890341844D2F8B4 -:101EF00078341844D2F888341844D2F8843418441A -:101F0000FFF7BEFF08BD00002DE9F74F0C4600F5B6 -:101F100080511F46054691F852349046BDF83090E6 -:101F20009BB1D1F874340133C1F8743423689A003A -:101F300006D4237B082B0BD9627B0AB10F2B07D960 -:101F4000D1F878340133C1F878344FF0FF300FE026 -:101F5000FFF790FFEB6AD3F8C42012F4001A0AD0FE -:101F6000D1F87C3400200133C1F87C34FFF788FFBE -:101F700003B0BDE8F08F22684FF0480BD3F8C4607F -:101F8000002A6B6AC6F30446B4BF42F08042920452 -:101F90001BFB063BCBF8002023685B004FEA06637F -:101FA00044BF42F00052CBF80020227B43EA0243B8 -:101FB0007201CBF80430607B18B343F44013CBF8C4 -:101FC0000430D1F8A4340133C1F8A434AB1803F5BC -:101FD0008353197B41F020011973207B019200F09B -:101FE0006DFF0330019A80105FFA8AF30AF1010A4B -:101FF00083420DDA04EB83010BEB8303496899609C -:10200000F2E7AB1803F58353197B60F34511E3E75F -:102010000121EB6A04F10C00B140C3F8D010AB18F9 -:10202000214603F58253C3E9048705EB461303F504 -:102030008253183351F804CB814243F804CBF9D1D1 -:1020400009882A442846198041F26803D65002F5CF -:10205000805209F0030392F86C1043F0100321F052 -:102060001F010B43214682F86C304246FFF708FF00 -:102070003B46CDF8309003B0BDE8F04F00F0E4BE31 -:102080002DE9F04700F58056044696F85254002D8D -:1020900040F00181037C032B40F092802B462846C0 -:1020A0002F465FFA83FC944510DA01EBCC0E51F811 -:1020B0003CC0BCF1000F04DBDEF804C0BCF1000F33 -:1020C00002DB01370133ECE70130FBE7FFF7D2FE1B -:1020D000E36AF0B9D3F8800040F00200C3F8800052 -:1020E0004E23E06A002F6ED1D0F8803043F0010318 -:1020F000C0F88030694B6A4A1B6803F1805303F5CE -:102100002C539B009342A36240F2AF80654801F0DC -:102110006FF84D2842D8DFF884814FEA004EDFF88F -:102120008891D8F800C04EEA8C0EC3F884E00CF118 -:10213000805303F52C539B00636100EB0C03D4F830 -:102140002CC0C8F80030C0F14E03DCF8800040F02D -:102150003000CCF880004FF0000CD4F81480E64634 -:102160005FFA8CF08242BCDD01EBC00A51F830000E -:10217000002810DBDAF804A0BAF1000F0BDA09EA44 -:1021800000400AF07F0A40EA0A0040F0084048F8A0 -:102190002E000EF1010E0CF1010CE1E79A6922F01C -:1021A00001029A6101F02AF80646E36A9B69D907A1 -:1021B00004D501F023F8831BFA2BF6D9FFF760FE54 -:1021C0002846BDE8F087B7EB530F3DD2DFF8CCE0EF -:1021D0004FEA074CDEF800304CEA830CC0F888C0A8 -:1021E00003F1805003EB4703002700F52C50CEF895 -:1021F0000030BC468000A061E06AD0F8803043F037 -:102200000C03C0F88030D4F818E0FBB29A427FF794 -:1022100071AF51F8330001EBC3080028D8F804303F -:1022200001DB002B0EDB20F0604023F0604340F028 -:10223000005043F000434EF83C000EEBCC000CF194 -:10224000010C43600137E0E7836923F001038361F8 -:1022500000F0D4FF0646E36A9B69DA07AED500F0CA -:10226000CDFF831BFA2BF6D9A8E7E26A936923F026 -:102270000103936100F0C2FF0746E36A9B69DB0735 -:1022800005D500F0BBFFC31BFA2BF6D996E7012555 -:1022900086F8525492E7002592E700BFCC5E0020FA -:1022A000FCB50040787300080000FF0713B500F587 -:1022B00080540191606C00F053FE1F280AD920223F -:1022C0000199606C00F0C2FEA0F120035842584111 -:1022D00002B010BD0020FBE700F5805008B5FFF705 -:1022E000C9FD406C00F010FEBDE80840FFF7C8BD16 -:1022F00000220260828142608260704700220023D7 -:1023000010B5C0E90023002304460C3020F8043C3B -:10231000FFF7EEFF204610BD2DE9F047074688B0D5 -:102320009A46884607F5805468469146FFF7A2FD15 -:10233000FFF7E4FF606C00F0F9FD1F282DD9202283 -:102340006946606C00F006FF202826D194F85234CC -:102350001BB303AD444605AB2E46083403CE9E4264 -:1023600044F8080C44F8041C3546F5D13068414661 -:1023700020603846B388A380DDE90023C9E9002343 -:10238000BDF808304A46AAF80030FFF779FD5346F9 -:1023900008B0BDE8F04700F045BD0020FFF770FD34 -:1023A00008B0BDE8F08700002DE9F84F002306468D -:1023B00000F58154054688461034C0E90133274BA7 -:1023C00046F8303B374638462037FFF797FFA7429D -:1023D000F9D105F580544FF4805305F5A3594FF01A -:1023E000000A26630026676405F5835709F1100982 -:1023F0004FF0000B1037E663C4E90D36012384F873 -:10240000403084F84830A7F11800203747E910AB76 -:10241000FFF76EFF47F8286C4F45F4D1B8F1010F74 -:1024200084F85884A4F85A64A4F85C64A4F85E6440 -:1024300084F86064A4F86264A4F86464A4F8666430 -:1024400084F8686402D9064800F0D2FE054B28469D -:1024500053F82830EB62BDE8F88F00BFC87300085E -:102460009C730008B8730008044B10B51978044633 -:102470004A1C1A70FFF798FF204610BDC95E002065 -:102480002DE9F04700295FD0304F3148B7FBF1F517 -:1024900081428CBF0A201120431EB5FBF0FC00FBDB -:1024A0001C50DCB220B1022B1846F5D8002037E0D2 -:1024B0000CF1FF35B5F5806F32D2C4EBC4094FF48F -:1024C0007A7009F103034FEAE308C3F3C70308F185 -:1024D000010AA4EB030E08FB00085FFA8EF65AFA15 -:1024E0008EFEB8FBFEFEBEF5617F1BDC1FFA8EF48C -:1024F000581C56FA80F00CFB00FCB7FBFCFC614555 -:10250000D4D1013BDBB20F2BD0D8711E0020C9B251 -:10251000072905D8107101201480558053719171DD -:10252000BDE8F08709F1FF334FEAE30EC3F3C703B9 -:102530000EF10108E41A0EFB0000E6B258FA84F42A -:10254000B0FBF4F4A4B2D3E70846E9E700B4C4044E -:102550003F420F0038B540F27772C36A154CC3F89A -:10256000BC200722C36AC3F8C8202268C16A93004E -:1025700043F4C023C1F8A03002F1805302F16C0192 -:10258000C56A03F52C53EA3289009B00226041F0B2 -:10259000E061094AC361C5F8C01003F5D87103F5BD -:1025A0006A7341629342836202D9044800F020FEBC -:1025B00038BD00BFCC5E0020FCB500407873000839 -:1025C0002DE9F04F00F58055994689B0044695F8FD -:1025D00058348A469046022B04D90027384609B061 -:1025E000BDE8F08F9E4A52F8231009B942F8230043 -:1025F0009C49C4F80CA00B7884F81090C3B9FFF77D -:1026000039FC994BD3F8EC2042F48072C3F8EC20EB -:10261000D3F8942042F48072C3F89420D3F8942025 -:1026200022F48072C3F8942001230B70FFF728FC7A -:1026300095F851346BB9FFF71DFC8C4A95F8583466 -:10264000D35CEBB1012B24D0012385F85134FFF783 -:1026500017FCFFF70FFCE26A936923F01003936104 -:1026600000F0CCFD0746E36A9E6916F0080617D015 -:1026700000F0C4FDC31BFA2BF5D9FFF701FCACE752 -:102680000221132001F04EFE0221152001F04AFE26 -:10269000DAE70221142001F045FE02211620F5E7B9 -:1026A0009A6942F001029A6100F0A8FD0746E36AC8 -:1026B0009A69D00705D400F0A1FDC31BFA2BF6D907 -:1026C000DBE79A69002704F5825B42F002020BF116 -:1026D000100B9A61E36A5F65FFF7D2FB686C00F04C -:1026E00013FC202200216846FFF714FB02A8FFF725 -:1026F000FFFD6A460BEB06030DF1180E0697944694 -:102700000833BCE80300F44543F8080C43F8041C04 -:102710006246F4D1DCF8000020361860B6F5806F10 -:102720009CF804201A71DCD1002304F5A252514612 -:1027300020461A3285F8503485F85334FFF7A0FE4E -:10274000074690B9E26A936923F00103936100F0B0 -:1027500055FD0546E36A9B69D9077FF53EAF00F05A -:102760004DFD431BFA2BF5D937E795F85F6495F8D3 -:102770005E243602C5F86CA4E36A46EA426695F820 -:1027800060241643B5F85C2446EA0246DE61B8F1DF -:10279000000F29D004F5A352414620460232FFF72C -:1027A0006FFE90B9E26A936923F00103936100F030 -:1027B00025FD0546E36A9B69DA077FF50EAF00F059 -:1027C0001DFD431BFA2BF5D907E795F8683495F8FA -:1027D00067141B01C5F87084E26A43EA0123B5F867 -:1027E000641443EA0143D360E36A00262046C3F839 -:1027F000BC60FFF7AFFE85F859646FF04042E36AB2 -:10280000B9F1030F1A651A4AE36A5A654FF00222BA -:10281000E36A9A654FF0FF32E36AC3F8E0204FF0B5 -:102820000302E36ADA65E26A936943F440739361F1 -:102830003FF4D4AEE26A936923F00103936100F0A0 -:10284000DDFC0646E36A9B69DB0705D500F0D6FC94 -:10285000831BFA2BF6D9C0E6012385F85234BDE676 -:10286000C05E0020C85E002000440258B07300081B -:10287000550200022DE9F04F054689B09046994671 -:10288000002741F2680A00F58056EB6AD3F8D83089 -:10289000FB40D8074AD505EB47124FEA471B524485 -:1028A0001379190742D4D6F880340133C6F880343E -:1028B00013799A0605EB0B0248BFD6F8A8345244A8 -:1028C00044BF0133C6F8A834137943F008031371E9 -:1028D000DB0723D596F8533403B305F582546846D5 -:1028E000FFF70CFD03AB18345C4404F1080C2068BE -:1028F000083454F8041C1A46644503C21346F6D142 -:102900002068694610602846A2889A800123ADF8A5 -:1029100008302B68CDE900891B6C9847D6F85434F1 -:1029200023B1D6F89C340133C6F89C340137202FEC -:10293000ABD109B0BDE8F08F2DE9F04F0F468DB057 -:10294000044600F05DFC82468946002F5BD1E36AB5 -:10295000D3F8A02012F4FE0F03D100200DB0BDE883 -:10296000F08FD3F8A420920141BF04F58051D1F833 -:1029700094240132C1F89424D3F8A4205606ECD054 -:10298000D3F8A450E669C5F305254823E8464FF07F -:10299000000B03FB05664046FFF7AAFC32685100B6 -:1029A0004ABF22F06043C2F38A4343F000439200DF -:1029B00048BF43F080430093736813F400131BBFB8 -:1029C000012304F580528DF80D308DF80D301EBFB7 -:1029D000D2F8AC340133C2F8AC34F38803F00F03FF -:1029E0008DF80C309DF80C0000F068FA5FFA8BF35C -:1029F000984225D9F2180CA90BF1010B127A0B445D -:102A000003F82C2CEEE7012FA7D1E36AD3F8B0200E -:102A100012F4FE0FA1D0D3F8B420950141BF04F504 -:102A20008051D1F894240132C1F89424D3F8B42011 -:102A3000500692D0D3F8B450266AC5F30525A4E712 -:102A4000EFB9E36AC3F8A85004A807ADFFF756FC36 -:102A500098E80F0007C52B800023204604A9ADF895 -:102A60001830236804F580541B6CCDE904A99847FD -:102A700058B1D4F88C340133C4F88C346EE7012F8C -:102A8000E2D1E36AC3F8B850DEE7D4F8903401200D -:102A90000133C4F8903461E7F8B505460F4600F5F8 -:102AA0008054012639462846FFF746FF10B184F8C6 -:102AB0005364F7E7D4F8543423B1D4F89C34013389 -:102AC000C4F89C34F8BD0000C36AF0B51A6C12F467 -:102AD0007F0F2BD01B6C00F5805441F268054FF03E -:102AE000010CC4F8A0340023471900EB43125E0127 -:102AF0002A44117911F0020F15D0490713D4B9599E -:102B0000C66A0CFA01F1D6F8CCE011EA0E0F0AD031 -:102B1000C6F8D410117941F004011171D4F8882459 -:102B20000132C4F888240133202BDED1F0BD00002F -:102B30002B4B70B51E561B5C012B30D8294D2A4AF1 -:102B400055F8233052F8264013B349B3236D9A0544 -:102B500010D54FF40073236500F052FB50EA0102D8 -:102B60000B4602D0013861F10003024655F82600F9 -:102B7000FFF780FE236D9B012CD54FF0007255F8B6 -:102B80002630226503F58053012283F8592421E081 -:102B900001232365102323654FF48053236570BD03 -:102BA000236DDA0702D4236D5B0706D505230021C8 -:102BB00055F826002365FFF76FFF236DD80602D472 -:102BC000236D590606D55023012155F826002365AB -:102BD000FFF762FF55F82600BDE87040FFF774BFAD -:102BE000B4730008C05E0020B873000808B5FFF792 -:102BF00041F9FFF769FFBDE80840FFF741B9000060 -:102C0000C36AD3F8C00010F07C5005D0D3F8C400DC -:102C100080F40010C0F340507047000000F5805071 -:102C200008B5FFF727F9406C00F080F9FFF728F9A5 -:102C300043090CBF0120002008BD000000F58053AF -:102C400093F8592462B1C16A8A6922F001028A614B -:102C5000D3F898240132C3F89824002283F8592429 -:102C6000704700002DE9F74300F582519846002592 -:102C7000FFF700F9103141F2680E4FF0010900F53D -:102C8000805C00EB4514744423795E071CD4DB069A -:102C90001AD58E69C36A09FA06F6D3F8CC703E429B -:102CA00012D04F6801970F689742019F77EB080792 -:102CB0000AD2C3F8D460237943F004032371DCF80B -:102CC00084340133CCF8843401352031202DD8D11F -:102CD00003B0BDE8F043FFF7D3B80000F8B51E46D7 -:102CE00000230F46054613701446FFF797FF80F048 -:102CF000010038701EB12846FFF782FF2070F8BD32 -:102D00002DE9F04F994685B00B780E468046174660 -:102D100001931378DDE90EBA029300F071FA33786B -:102D200004460D4613B93B78002B41D022462B4672 -:102D30004046FFF797FFFFF759FFFFF77FFF4B462E -:102D40003A463146FFF7CAFF33782BB1019B1BB1DE -:102D5000012005B0BDE8F08F3B7813B1029B002B3A -:102D6000F6D108F5805303935C4575EB0A031FD237 -:102D7000039BD3F85404D8B1BBEB04020368D968B1 -:102D80006AEB050388474B463A4631464046FFF713 -:102D9000A5FF337813B1019B002BD9D13B7813B138 -:102DA000029B002BD4D100F02BFA04460D46DBE742 -:102DB0000020CEE7002108B50846FFF7B9FEBDE8C0 -:102DC000084001F075B9000008B501210020FFF7A7 -:102DD000AFFEBDE8084001F06BB9000008B5002166 -:102DE0000120FFF7A5FEBDE8084001F061B9000031 -:102DF000012108B50846FFF79BFEBDE8084001F039 -:102E000057B900000FB4002004B0704713B56C46EA -:102E1000031D84E8060094E8030083E80500012010 -:102E200002B010BD73B58568019155B11B885B0771 -:102E300007D4D0E90036DB6B9847019AC1B230461F -:102E4000A847012002B070BDF0B5866889B005467C -:102E50000C465EB1BDF838305B070AD4D0E90037C4 -:102E6000DB6B98472246C1B23846B047012009B013 -:102E7000F0BD0022002301F10806CDE90023002364 -:102E80000A46ADF8083003AB1068083252F8041C4B -:102E90001C46B24203C42346F6D1106820609288D3 -:102EA000A28000F0AFF90423ADF808302B68CDE91B -:102EB00000011B6C694628469847D7E7082817D9B0 -:102EC00009280CD00A280CD00B280CD00C280CD0C8 -:102ED0000D280CD00E2814BF4020302070470C2045 -:102EE000704710207047142070471820704720202A -:102EF0007047000010B5037C044613B9006804F065 -:102F00002DF9204610BD00000023BFF35B8FC36086 -:102F1000BFF35B8FBFF35B8F8360BFF35B8F704743 -:102F2000BFF35B8F0068BFF35B8F704770B50546DA -:102F30000C30FFF7F5FF044605F108063046FFF7B1 -:102F4000EFFFA04206D96D683046FFF7E9FF254440 -:102F5000281A70BD3046FFF7E3FF201AF9E700009A -:102F600070B505464068A0B105F10C0605F10800F2 -:102F7000FFF7D6FF04463046FFF7D2FF844204F144 -:102F8000FF34304694BF6D680025FFF7C9FF2C441D -:102F9000201A70BD38B50C460546FFF7C7FFA042A2 -:102FA00010D305F10800FFF7BBFF04446868BFF3C6 -:102FB0005B8FB4FBF0F100FB11440120AC60BFF368 -:102FC0005B8F38BD0020FCE72DE9F0411446074631 -:102FD0000D46FFF7C5FF844228BF0446D4B1B8466A -:102FE00058F80C6B4046FFF79BFF30442860404682 -:102FF0007E68FFF795FF331A9C4203D801206C606E -:10300000BDE8F081A41B6B603B682044AB60E860C6 -:103010000220F5E72046F3E738B50C460546FFF7F2 -:103020009FFFA04210D305F10C00FFF779FF044485 -:103030006868BFF35B8FB4FBF0F100FB1144012023 -:10304000EC60BFF35B8F38BD0020FCE72DE9FF414A -:103050008846694607466C46FFF7B6FF002506B26C -:1030600004EBC606B4420AD0626808EB050120688A -:103070000834FEF729FE54F8043C1D44F2E72946C3 -:103080003846FFF7C9FF284604B0BDE8F0810000CC -:10309000F8B505460C300F46FFF742FF05F108066C -:1030A00004463046FFF73CFFA042304688BF6C68BC -:1030B000FFF736FF201A386020B12C683046FFF742 -:1030C0002FFF2044F8BD000073B5144606460D4698 -:1030D000FFF72CFF8442019028BF0446DCB101A910 -:1030E0003046FFF7D5FF019B33B93268C5E902339B -:1030F000C5E9002401200CE09C42286038BF0194FF -:10310000019884426860F5D93368241A0220AB60C4 -:10311000EC6002B070BD2046FBE700002DE9FF41E6 -:103120000F4669466C46FFF7CFFF00B2002604EB5E -:10313000C005AC4209D0D4F80480B81954F8081B73 -:1031400042464644FEF7C0FDF3E7304604B0BDE812 -:10315000F081000038B50546FFF7E0FF0446014660 -:103160002846FFF717FF204638BD000000B59BB08A -:10317000EFF3098168226846FEF7A6FDEFF30583A9 -:10318000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A93 -:103190009B6AFEE700ED00E000B59BB0EFF309810C -:1031A00068226846FEF790FDEFF30583044B9A6BA7 -:1031B0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF52 -:1031C00000ED00E000B59BB0EFF30981682268468E -:1031D000FEF77AFDEFF30583034B5A6B9A6A9A6AFE -:1031E0009A6A9A6A9B6AFEE700ED00E0FEE700003B -:1031F0000FB408B5029801F083FFFEE702F0C4BBEC -:1032000002F09CBB02F09ABB30B50A44084D9142D3 -:103210000DD011F8013B5840082340F30004013B56 -:103220002C4013F0FF0384EA5000F6D1EFE730BDE5 -:103230002083B8ED2DE9F041C56915B9C161BDE83C -:10324000F0814B68AC4623F06047C3F38A464FEAEF -:10325000D37EC3F3807816EA230638BF3E462B465A -:103260005A68BEEBD27F22F060440AD0002A18DAF6 -:10327000A40CB44217D19D420FD10D60DEE7134676 -:10328000EEE7A74207D102F08044C2F380724245C4 -:103290000BD054B1EFE708D2EDE7CCF800100B608B -:1032A000CDE7B44201D0B442E5D81A689C46002A62 -:1032B000E5D11960C3E700002DE9F047089D01F052 -:1032C000070400EBD1004FF47F494FEAD5082244B0 -:1032D00005F00705944201D1BDE8F08704F0070727 -:1032E00005F0070A111B08EBD50E57453E4613F8AB -:1032F0000EC038BF5646C6F108068E4228BF0E469D -:10330000E108415C34443544B94029FA06F721FA12 -:103310000AF1FFB28CEA010147FA0AF739408CEA58 -:10332000010C03F80EC0D5E780EA0120082341F222 -:10333000210201B2013B4000002980B2B8BF5040D9 -:1033400013F0FF03F5D1704738B50C468D18A54230 -:1033500000D138BD14F8011BFFF7E6FFF7E70000C6 -:1033600002684AB1136801890360C38801339BB2C4 -:103370009942C38038BF03811046704770B588B04A -:10338000044620220D4668460021FEF7C3FC204675 -:103390000495FFF7E5FF024660B16B46054608AEAF -:1033A0001C46083503CCB44245F8080C45F8041C0B -:1033B0002346F5D1104608B070BD0000082817D983 -:1033C00009280CD00A280CD00B280CD00C280CD0C3 -:1033D0000D280CD00E2814BF4020302070470C2040 -:1033E0007047102070471420704718207047202025 -:1033F00070470000082817D90C280CD910280CD9C0 -:1034000014280CD918280CD920280CD930288CBFA6 -:103410000F200E207047092070470A2070470B20AC -:1034200070470C2070470D207047000010B54B68A6 -:1034300023B9CA8A63F30902CA8210BDC4681A6834 -:103440001C60C360438A013B43824A60EFE700008F -:103450002DE9F84F1D46CB8A0F468146C3F309017B -:10346000924606290B4630D00020AAB207F1190473 -:103470009EB21FFA80F8052E0FD8904503F1010384 -:1034800006D30A44FB8A62F309030120FB821AE097 -:103490001AF800600130E654EAE79045F1D2A1F154 -:1034A000060B1C237C68BBFBF3F203FB12BB1FFA69 -:1034B0008BF6002C45D14846FFF752FF044638B939 -:1034C00078606FF00200BDE8F88F4FF00008E6E783 -:1034D000002606607860ADB24FF0000B454510D96C -:1034E0000AEB0803221D13F8011B08F1010891558E -:1034F000B1B21FFA88F81B292BD0454506F1010609 -:10350000F1D8FB8AC3F30902154465F30903BCE74C -:1035100001321C4692B22368002BF9D1AB1F0B4439 -:103520001C21B3FBF1F301339BB29A42D3D2BBF11E -:10353000000FD0D14846FFF713FF20B9C4F800B000 -:10354000BFE70122E7E7C0F800B05E46206004460E -:10355000C1E74545D5D94846FFF702FF08B92060C5 -:10356000AFE7C0F800B0002620600446B6E70000D0 -:103570002DE9F04F2DED028B83B007469146BDF843 -:103580003C50CDE90013002A00F092802DB10E9B33 -:10359000002B00F08D80072D32D807F10C00FFF7CB -:1035A000DFFE044638B96FF00204204603B0BDECDC -:1035B000028BBDE8F08F14220021FEF7ABFB2A46F8 -:1035C0000E9904F10800FEF77FFB681CC0B2FFF7FC -:1035D00011FFFFF7F3FE207499F80030013803F073 -:1035E0001F0314FA80F063F03F0303723846009B18 -:1035F00043F0004161602146FFF71CFE0124D4E73F -:103600004FF0000800F10C034FF0800A4646444694 -:1036100008EE103A18EE100AFFF7A2FE83460028C3 -:10362000C1D014220021FEF775FBC6BB019B02200E -:10363000ABF808300E9B00F1080299195BFA82F290 -:103640000130C0B2082801D0AE422AD3FFF7D2FE23 -:10365000AE4208BF4FF0400AFFF7B0FE99F80020D5 -:10366000411E009B02F01F0201345BFA81F142EA25 -:10367000481288F0010824B24AEA020A43F00042E4 -:1036800081F808A059468BF810003846CBF8042082 -:103690004FF0000AFFF7CEFDAE42BBD185E7002018 -:1036A000C8E711F801CB013602F801CBB6B2C7E783 -:1036B0006FF0010479E70000F8B515460E462822A0 -:1036C000002104461F46FEF725FB069BB5F5001FAB -:1036D000A760636004F10C00079B34BF6A094FF6D2 -:1036E000FF722362002397B29A4205D80023036039 -:1036F00027826382A382F8BD0660013330462036FC -:10370000F2E7000003781BB94BB2002BC8BF017071 -:1037100070470000007870472DE9F74FDDF83C90C6 -:10372000804692469B46BDF830500D9E9DF838402D -:10373000BDF84070B9F1000F01D1002F51D11F2CFD -:103740004FD898F80000B0B9072F47D835F00303D9 -:1037500047D13A4649464FF6FF702D02FFF7F4FD78 -:1037600020F0010045EA04644004400C44EA40248F -:103770004FF6FF7321E040EA0520072F40EA04647A -:10378000F6D900254FF6FF73C5F12000A5F1200200 -:103790002AFA05F108350BFA00F02BFA02F2014380 -:1037A00018461143C9B2FFF7BFFD402D0346EBD1C8 -:1037B0003A464946FFF7C8FD034632462146404691 -:1037C000CDE90097FFF7D4FE33780133DBB21F2B2E -:1037D00088BF0023337003B0BDE8F08F6FF00300A3 -:1037E000F9E76FF00100F6E72DE9F04F85B092465A -:1037F00006469B46DDF848800F9D9DF840209DF8C9 -:103800004490BDF84C70B8F1000F01D1002F49D1A0 -:103810001F2A47D83378002B47D00C029DF8381068 -:10382000072F44EA026444EAC93444EA014444EA02 -:10383000030444F0800432D900234FF6FF72C3F131 -:10384000200CA3F120002AFA03F103930BFA0CFCDD -:103850002BFA00F041EA0C0101431046C9B2FFF710 -:1038600063FD039B02460833402BE8D13A464146AC -:10387000FFF76AFD03462A4621463046CDE9008718 -:10388000FFF776FEB9F1010F06D12B780133DBB2D9 -:103890001F2B88BF00232B7005B0BDE8F08F4FF6BB -:1038A000FF73E8E76FF00100F6E76FF00300F3E75E -:1038B000C06900B104307047C3691A68C261C26848 -:1038C0001A60C360438A013B438270472DE9F0418F -:1038D000D0F8188014461D46184E4146002709B9F5 -:1038E000BDE8F081D1E90223A21A65EB03039642F9 -:1038F00077EB03031ED283698B420DD1FFF796FD50 -:1039000083691B688361C3680B60438AC160013BA4 -:10391000816943828846E2E7FFF788FD0B68C8F8B3 -:103920000030C3680B60438AC160013B4382D8F812 -:103930000010D4E788460968D1E700BF80841E00E4 -:103940002DE9F04F8BB00D4614469B46DDF85090A4 -:103950008046002800F01881B9F1000F00F01481B2 -:10396000531E3F2B00F21081012A03D1BBF1000F3F -:1039700040F00A810023CDE90833B8F81430B5EBE4 -:10398000C30F4FEAC30703D300200BB0BDE8F08F8D -:103990002B199F42D8F80C3036BF7F1B2746FFB249 -:1039A0001BB9D8F81030002B7AD02F2D4DD8C5F187 -:1039B000300600232946B742009308ABD8F8080028 -:1039C0002CBFF6B23E46A7EB060A354432465FFAF4 -:1039D0008AFAFFF771FCB8F81430302103F1005374 -:1039E000063BDB000493D8F80C300393039B13B120 -:1039F000BAF1000F2CD1D8F8100040B1BAF1000F85 -:103A000005D008AB5246691A0096FFF755FC38B24C -:103A1000002FB9D066070AD00AAB624203EBD4018B -:103A200002F0070211F8083C134101F8083C082C89 -:103A30003DD9102C40F2B580202C40F2B780BBF16C -:103A4000000F00F09C80082335E0BA460026C2E74C -:103A5000049BE02B28BFE02306930B44AB42059365 -:103A600015D95A1B0398691A0096924508AB00F1C4 -:103A7000040034BF5246D2B20792FFF71DFC079AEA -:103A80001644AAEB020A1544F6B25FFA8AFA049BBE -:103A9000069A05999B1A0493039B1B680393A5E759 -:103AA00000933A4608AB2946D8F80800ADE7BBF1C9 -:103AB000000F13D00123B4EBC30F6BD0082C12D826 -:103AC0009DF82030621E23FA02F2D50706D54FF08A -:103AD000FF3202FA04F423438DF820309DF82030A1 -:103AE00089F8003051E7102C12D8BDF82030621E42 -:103AF00023FA02F2D10706D54FF0FF3202FA04F49E -:103B00002343ADF82030BDF82030A9F800303CE761 -:103B1000202C0FD80899631E21FA03F3DA0705D584 -:103B20004FF0FF3202FA04F40C430894089BC9F8E2 -:103B300000302AE7402C2AD0611EC4F12102A4F1F2 -:103B40002103DDE9086526FA01F105FA02F225FAFA -:103B500003F311431943CB0711D50122A4F120032C -:103B6000C4F1200102FA03F322FA01F1A2400B434F -:103B7000524263EB430332432B43CDE90823DDE993 -:103B80000823C9E9002300E76FF00100FDE66FF0AC -:103B90000800FAE6082CA1D9102CB4D9202CEED8B4 -:103BA000C4E7BBF1000FAED0022384E7BBF1000FE6 -:103BB000BCD004237FE70000012A30B5144638BF8B -:103BC000012485B00025402C28BF4024012ACDE9DE -:103BD000025518D81B788DF8083063070AD004AB5B -:103BE000624203EBD40502F0070215F8083C93404B -:103BF00005F8083C034600912246002102A8FFF781 -:103C00005BFB05B030BD082AE4D9102A03D81B8815 -:103C1000ADF80830E1E7202A95BF1B68D3E90023FF -:103C20000293CDE90223D8E710B5CB681BB98B60AE -:103C30000B618B8210BDC4681A681C60C360438A24 -:103C4000013B4382CA60F0E72DE9F04FD1F80080D4 -:103C500093B004460D4618F0800FCDE90323C8F356 -:103C6000C01219BFC8F3C03BC8F306264FF0020BC1 -:103C70001646B8F1000F80F2D18118F0C0430593C9 -:103C800040F0CC810B7B002B00F0C881BBF1020F10 -:103C900003D00178B14240F0C48108F07F01069161 -:103CA0006AB3C8F3074A2B447606069A46EA0B46DF -:103CB00093F8039046EA82465FEAD91346EA0A0679 -:103CC000079300F090800022002367680AA920462D -:103CD000CDE90A23069B524600935B46B84700286D -:103CE0007ED0A7699FB9314604F10C00FFF746FB6F -:103CF0000746E0B96FF0020013B0BDE8F08FC8F3DB -:103D00000F2A18F07F0F08BF0AF0030ACBE73B69C0 -:103D10009E420DD03F68002FF9D1314604F10C00CE -:103D2000FFF72CFB07460028E4D0A3693B60A7619E -:103D300000264FF6FF70DDE90A23C6F1200E22FAB5 -:103D400006F1A6F1200C083603FA0EFE099223FABA -:103D50000CFC089341EA0E0141EA0C01C9B2FFF7DD -:103D6000E3FA402EDDE90832E7D1B882FB7D09F0A5 -:103D70001F06C8F30468C3F384039B1B98B2002B8F -:103D8000D7E90221BCBF00F120031BB252EA0100B7 -:103D90000FD00398821A049860EB0101A748904263 -:103DA0004FF000028A4104D3079A002A5BD0012B0E -:103DB00023DDFA7D4FEA89033946204602F00302EB -:103DC00003F07C031343FB75FFF730FB079BA3B99C -:103DD000FB7DC3F38402013262F38603FB7504E0CA -:103DE0006FF00B0088E7A76917B96FF00C0083E745 -:103DF0003B699E42BAD03F68F6E719F0400F32D0D7 -:103E0000039B142200210DA8BB60049BFB60FDF7FF -:103E100081FF039B0AA920460A93049BADF83EA0AC -:103E20000B932B1D8DF840B00C932B7B8DF84160CC -:103E3000013B8DF84280DBB2ADF83C30069B8DF83B -:103E4000433094F8243083F001038DF84430A368A4 -:103E50009847FB7DC3F38403013303F01F039B02E8 -:103E6000FB82002048E7FB7DC9F34012B2EBD31F71 -:103E700040F0DA80C3F38403B34240F0D88007995E -:103E80004FEA99122B7B002934D0D20741D4032B5F -:103E900040F2D080039BAE1D394604F10C00BB609C -:103EA0003246049BFB602B7B033BDBB2FFF7D0FA6F -:103EB00000280DDA20463946FFF7B8FAFB7D0320CB -:103EC000C3F38403013303F01F039B02FB8213E758 -:103ED000AB883B832A7B033AD2B2B88A3146FFF7DC -:103EE00033FAFB7DB882DA43C2F3C01262F3C71320 -:103EF000FB75B6E76AB92E1D013B394604F10C008B -:103F0000DBB23246FFF7A4FA0028D3DB2A7B013A62 -:103F1000E2E7F98A013BC1F30901DAB2052959D870 -:103F2000281D002307F11A0C9A4208D910F801EB5A -:103F300001330CF801E00131DBB20629F4D1039919 -:103F400093420A9138BF043304992CBF002355FAD9 -:103F500083F30B9107F11A010C9179680E930D917F -:103F6000291DFB8AADF83EA0C3F309038DF840B0CC -:103F70008DF841601A44069B8DF842808DF84330DD -:103F800094F82430ADF83C2083F001038DF84430E0 -:103F90000023B88A7B602A7B013AFFF7D5F93B8B77 -:103FA000B882834203D1A3680AA9204698472046D5 -:103FB0000AA9FFF739FEFB7DB88AC3F384030133F6 -:103FC00003F01F039B02FB823B8B984214BF11201E -:103FD000002091E67B68002BB1D0062001E01C3068 -:103FE0006346D3F800C0BCF1000FF8D1091A05F1FF -:103FF000040C081D00EB030905989DF8143001EB33 -:10400000000EBEF11B0F9AD89A4298D91CF8013BBA -:1040100009F8013B059B01330593EDE76FF00900BB -:104020006AE66FF00A0067E66FF00D0064E66FF075 -:104030000E0061E66FF00F005EE600BF80841E0098 -:10404000EFF30983054968334A6B22F001024A63A2 -:1040500083F30988002383F31188704700EF00E0A1 -:10406000202080F3118862B60D4B0E4AD96821F4E6 -:10407000E0610904090C0A430B49DA60D3F8FC201B -:1040800042F08072C3F8FC20084AC2F8B01F1168E1 -:1040900041F0010111601022DA7783F822007047A5 -:1040A00000ED00E00003FA0555CEACC5001000E0BD -:1040B000202310B583F311880E4B5B6813F4006363 -:1040C00014D0F1EE103AEFF309844FF08073683C9E -:1040D000E361094BDB6B236684F3098800F0C2FFC0 -:1040E00010B1064BA36110BD054BFBE783F31188AC -:1040F000F9E700BF00ED00E000EF00E00B0700086B -:104100000E070008026843681143016003B11847B5 -:1041100070470000024A136843F0C0031360704701 -:104120000078004013B50E4C204600F0A1FA04F1CF -:10413000140000234FF400720A49009400F062F961 -:10414000094B4FF40072094904F13800009400F063 -:10415000DBF9074A074BC4E9172302B010BD00BFC3 -:10416000D45E0020405F002015410008406100201F -:104170000078004000E1F505037C30B5244C0029AF -:1041800018BF0C46012B11D1224B98420ED1224B65 -:10419000D3F8E82042F08042C3F8E820D3F8102199 -:1041A00042F08042C3F81021D3F810312268036E28 -:1041B000C16D03EB52038466B3FBF2F3626815042E -:1041C00042BF23F0070503F0070343EA4503CB6032 -:1041D000A36843F040034B60E36843F001038B6046 -:1041E00042F4967343F001030B604FF0FF330B6210 -:1041F000510505D512F0102205D0B2F1805F04D030 -:1042000080F8643030BD7F23FAE73F23F8E700BF32 -:104210000C740008D45E0020004402582DE9F047D9 -:10422000C66D05463768F4692107346219D014F069 -:10423000080118BF8021E20748BF41F02001A30711 -:104240004FF0200348BF41F04001600748BF41F4F0 -:10425000807183F31188281DFFF754FF002383F337 -:104260001188E2050AD5202383F311884FF40071E9 -:10427000281DFFF747FF002383F311884FF0200923 -:104280004FF0000A14F0200838D13B0616D54FF045 -:10429000200905F1380A200610D589F31188504607 -:1042A00000F066F9002836DA0821281DFFF72AFFFA -:1042B00027F080033360002383F31188790614D537 -:1042C000620612D5202383F31188D5E913239A427D -:1042D00008D12B6C33B127F040071021281DFFF7C0 -:1042E00011FF3760002383F31188E30618D5AA6E07 -:1042F0001369ABB15069BDE8F047184789F31188DD -:10430000736A284695F86410194000F0CBF98AF3D7 -:104310001188F469B6E7B06288F31188F469BAE7E6 -:10432000BDE8F087090100F16043012203F5614314 -:10433000C9B283F8001300F01F039A4043099B00A1 -:1043400003F1604303F56143C3F880211A607047AD -:10435000F8B51546826804460B46AA4200D2856825 -:10436000A1692669761AB5420BD218462A46FDF78E -:10437000ABFCA3692B44A3612846A3685B1BA36025 -:10438000F8BD0CD9AF1B18463246FDF79DFC3A46E6 -:10439000E1683044FDF798FCE3683B44EBE71846DE -:1043A0002A46FDF791FCE368E5E700008368934245 -:1043B000F7B50446154600D28568D4E90460361A7C -:1043C000B5420BD22A46FDF77FFC63692B4463613B -:1043D0002846A3685B1BA36003B0F0BD0DD932462D -:1043E000AF1B0191FDF770FC01993A46E06831443A -:1043F000FDF76AFCE3683B44E9E72A46FDF764FC05 -:10440000E368E4E710B50A440024C361029B8460BA -:10441000C16002610362C0E90000C0E9051110BD7E -:1044200008B5D0E90532934201D1826882B9826829 -:10443000013282605A1C426119700021D0E90432B5 -:104440009A4224BFC368436100F0E6FE002008BD25 -:104450004FF0FF30FBE7000070B5202304460E4606 -:1044600083F31188A568A5B1A368A269013BA36085 -:10447000531CA36115782269934224BFE368A361AA -:10448000E3690BB120469847002383F3118828463F -:1044900007E03146204600F0AFFE0028E2DA85F35F -:1044A000118870BD2DE9F74F04460E461746984611 -:1044B000D0F81C904FF0200A8AF311884FF0000BBF -:1044C000154665B12A4631462046FFF741FF0346AF -:1044D00060B94146204600F08FFE0028F1D000234D -:1044E00083F31188781B03B0BDE8F08FB9F1000F9A -:1044F00003D001902046C847019B8BF31188ED1A29 -:104500001E448AF31188DCE7C160C361009B8260AE -:104510000362C0E905111144C0E900000161704760 -:10452000F8B504460D461646202383F31188A76884 -:10453000A7B1A368013BA36063695A1C62611D7047 -:10454000D4E904329A4224BFE3686361E3690BB1A2 -:1045500020469847002080F3118807E03146204626 -:1045600000F04AFE0028E2DA87F31188F8BD000067 -:10457000D0E9052310B59A4201D182687AB98268E0 -:104580000021013282605A1C82611C7803699A42C0 -:1045900024BFC368836100F03FFE204610BD4FF08A -:1045A000FF30FBE72DE9F74F04460E4617469846C5 -:1045B000D0F81C904FF0200A8AF311884FF0000BBE -:1045C000154665B12A4631462046FFF7EFFE034601 -:1045D00060B94146204600F00FFE0028F1D00023CC -:1045E00083F31188781B03B0BDE8F08FB9F1000F99 -:1045F00003D001902046C847019B8BF31188ED1A28 -:104600001E448AF31188DCE70268436811430160A5 -:1046100003B11847704700001430FFF743BF000094 -:104620004FF0FF331430FFF73DBF00003830FFF785 -:10463000B9BF00004FF0FF333830FFF7B3BF0000C1 -:104640001430FFF709BF00004FF0FF311430FFF7BF -:1046500003BF00003830FFF763BF00004FF0FF32A8 -:104660003830FFF75DBF000000207047FFF75ABDEC -:10467000044B036000234360C0E902330123037449 -:10468000704700BF2474000810B52023044683F34C -:104690001188FFF771FD02232374002383F311882F -:1046A00010BD000038B5C36904460D461BB904218E -:1046B0000844FFF7A9FF294604F11400FFF7B0FEF4 -:1046C000002806DA201D4FF48061BDE83840FFF76E -:1046D0009BBF38BD026843681143016003B11847AE -:1046E0007047000013B5406B00F58054D4F8A4382F -:1046F0001A681178042914D1017C022911D1197981 -:10470000012312898B4013420BD101A94C3002F0D6 -:104710009DF8D4F8A4480246019B2179206800F056 -:10472000DFF902B010BD0000143002F01FB8000025 -:104730004FF0FF33143002F019B800004C3002F093 -:10474000F1B800004FF0FF334C3002F0EBB800003E -:10475000143001F0EDBF00004FF0FF31143001F0D4 -:10476000E7BF00004C3002F0BDB800004FF0FF3250 -:104770004C3002F0B7B800000020704710B500F5CB -:104780008054D4F8A4381A681178042917D1017C10 -:10479000022914D15979012352898B4013420ED139 -:1047A000143001F07FFF024648B1D4F8A4484FF41A -:1047B000407361792068BDE8104000F07FB910BDFA -:1047C000406BFFF7DBBF0000704700007FB5124B66 -:1047D00001250426044603600023057400F18402C9 -:1047E00043602946C0E902330C4B02901430019318 -:1047F0004FF44073009601F031FF094B04F69442E8 -:10480000294604F14C000294CDE900634FF4407353 -:1048100001F0F8FF04B070BD4C740008C1470008F7 -:10482000E54600080A68202383F311880B790B33CF -:1048300042F823004B79133342F823008B7913B1EC -:104840000B3342F8230000F58053C3F8A418022369 -:104850000374002383F311887047000038B5037F89 -:10486000044613B190F85430ABB90125201D022144 -:10487000FFF730FF04F114006FF00101257700F01D -:10488000D7FC04F14C0084F854506FF00101BDE8EE -:10489000384000F0CDBC38BD10B5012104460430CD -:1048A000FFF718FF0023237784F8543010BD000071 -:1048B00038B504460025143001F0E8FE04F14C0040 -:1048C000257701F0B7FF201D84F854500121FFF730 -:1048D00001FF2046BDE83840FFF750BF90F8803018 -:1048E00003F06003202B06D190F881200023212AB9 -:1048F00003D81F2A06D800207047222AFBD1C0E91E -:104900001D3303E0034A426707228267C367012021 -:10491000704700BF3422002037B500F58055D5F828 -:10492000A4381A68117804291AD1017C022917D1F8 -:104930001979012312898B40134211D100F14C04E3 -:10494000204602F037F858B101A9204601F07EFF59 -:10495000D5F8A4480246019B2179206800F0C0F8F0 -:1049600003B030BD01F10B03F0B550F8236085B002 -:1049700004460D46FEB1202383F3118804EB85071E -:10498000301D0821FFF7A6FEFB6806F14C005B69AD -:104990001B681BB1019001F067FF019803A901F0AA -:1049A00055FF024648B1039B2946204600F098F87F -:1049B000002383F3118805B0F0BDFB685A691268C3 -:1049C000002AF5D01B8A013B1340F1D104F180028B -:1049D000EAE70000133138B550F82140ECB120234C -:1049E00083F3118804F58053D3F8A428136852790F -:1049F00003EB8203DB689B695D6845B104216018A5 -:104A0000FFF768FE294604F1140001F055FE204628 -:104A1000FFF7B4FE002383F3118838BD7047000010 -:104A200001F05EB901234022002110B5044600F8D0 -:104A3000303BFDF76FF90023C4E9013310BD0000DE -:104A400010B52023044683F31188242241600021FD -:104A50000C30FDF75FF9204601F064F90223237062 -:104A6000002383F3118810BD70B500EB8103054668 -:104A700050690E461446DA6018B110220021FDF785 -:104A800049F9A06918B110220021FDF743F9314618 -:104A90002846BDE8704001F057BA00008368202224 -:104AA000002103F0011310B5044683601030FDF7B8 -:104AB00031F92046BDE8104001F0D2BAF0B401252A -:104AC00000EB810447898D40E4683D43A46945813A -:104AD00023600023A2606360F0BC01F0EFBA000025 -:104AE000F0B4012500EB810407898D40E4683D4363 -:104AF0006469058123600023A2606360F0BC01F05B -:104B000065BB000070B50223002504462422037013 -:104B10002946C0F888500C3040F8045CFDF7FAF8DC -:104B2000204684F8705001F0A3F963681B6823B134 -:104B300029462046BDE87040184770BD037880F8CC -:104B40008C300523037043681B6810B504460BB115 -:104B5000042198470023A36010BD000090F88C202A -:104B6000436802701B680BB10521184770470000AD -:104B700070B590F87030044613B1002380F870309F -:104B800004F18002204601F08FFA63689B68B3B994 -:104B900094F8803013F0600535D00021204601F0F4 -:104BA00039FD0021204601F029FD63681B6813B11F -:104BB000062120469847062384F8703070BD2046B1 -:104BC00098470028E4D0B4F88630A26F9A4288BF94 -:104BD000A36794F98030A56F002B4FF0200380F27B -:104BE0000381002D00F0F280092284F8702083F305 -:104BF000118800212046D4E91D23FFF771FF00230F -:104C000083F31188DAE794F8812003F07F0343EA05 -:104C1000022340F20232934200F0C58021D8B3F55E -:104C2000807F48D00DD8012B3FD0022B00F093801D -:104C3000002BB2D104F1880262670222A267E36707 -:104C4000C1E7B3F5817F00F09B80B3F5407FA4D12D -:104C500094F88230012BA0D1B4F8883043F00203DD -:104C600032E0B3F5006F4DD017D8B3F5A06F31D057 -:104C7000A3F5C063012B90D86368204694F8822086 -:104C80005E6894F88310B4F88430B047002884D06C -:104C9000436863670368A3671AE0B3F5106F36D003 -:104CA00040F6024293427FF478AF5C4B6367022385 -:104CB000A3670023C3E794F88230012B7FF46DAF24 -:104CC000B4F8883023F00203A4F88830C4E91D55F5 -:104CD000E56778E7B4F88030B3F5A06F0ED194F8AB -:104CE0008230204684F88A3001F020F963681B681E -:104CF00013B1012120469847032323700023C4E900 -:104D00001D339CE704F18B0363670123C3E723781A -:104D1000042B10D1202383F311882046FFF7BEFE19 -:104D200085F311880321636884F88B5021701B6818 -:104D30000BB12046984794F88230002BDED084F8DF -:104D40008B300423237063681B68002BD6D00221AC -:104D500020469847D2E794F8843020461D0603F099 -:104D60000F010AD501F092F9012804D002287FF43E -:104D700014AF2B4B9AE72B4B98E701F079F9F3E747 -:104D800094F88230002B7FF408AF94F8843013F04D -:104D90000F01B3D01A06204602D501F053FCADE74F -:104DA00001F044FCAAE794F88230002B7FF4F5AEC2 -:104DB00094F8843013F00F01A0D01B06204602D5D2 -:104DC00001F028FC9AE701F019FC97E7142284F817 -:104DD000702083F311882B462A4629462046FFF788 -:104DE0006DFE85F31188E9E65DB1152284F8702027 -:104DF00083F3118800212046D4E91D23FFF75EFECE -:104E0000FDE60B2284F8702083F311882B462A4696 -:104E100029462046FFF764FEE3E700BF7C740008E4 -:104E2000747400087874000838B590F8703004463F -:104E3000002B3ED0063BDAB20F2A34D80F2B32D8E3 -:104E4000DFE803F03731310822323131313131318D -:104E500031313737856FB0F886309D4214D2C36840 -:104E60001B8AB5FBF3F203FB12556DB9202383F3C4 -:104E700011882B462A462946FFF732FE85F3118812 -:104E80000A2384F870300EE0142384F87030202355 -:104E900083F31188002320461A461946FFF70EFEB9 -:104EA000002383F3118838BDC36F03B198470023F3 -:104EB000E7E70021204601F0ADFB0021204601F08C -:104EC0009DFB63681B6813B10621204698470623A3 -:104ED000D7E7000010B590F870300446142B29D0A5 -:104EE00017D8062B05D001D81BB110BD093B022BEA -:104EF000FBD80021204601F08DFB0021204601F067 -:104F00007DFB63681B6813B1062120469847062382 -:104F100019E0152BE9D10B2380F87030202383F39F -:104F2000118800231A461946FFF7DAFD002383F3A0 -:104F30001188DAE7C3689B695B68002BD5D1C36F22 -:104F400003B19847002384F87030CEE7024B00226B -:104F5000C3E900339A6070474063002000238268F1 -:104F60000374054B1B6899689142FBD25A68036031 -:104F700042601060586070474063002008B52023ED -:104F800083F31188037C032B05D0042B0DD02BB9A0 -:104F900083F3118808BD436900221A604FF0FF3384 -:104FA0004361FFF7DBFF0023F2E7D0E90032136033 -:104FB0005A60F3E7002382680374054B1B68996805 -:104FC0009142FBD85A680360426010605860704795 -:104FD00040630020054B1969087418680268536023 -:104FE0001A60186101230374FBF77ABB4063002049 -:104FF0004B1C30B5044687B00A4D10D02B6901A870 -:10500000094A00F031F92046FFF7E4FF049B13B191 -:1050100001A800F065F92B69586907B030BDFFF7AA -:10502000D9FFF8E7406300207D4F000838B50C4DEC -:10503000044641612B6981689A68914203D8BDE8B2 -:105040003840FFF78BBF1846FFF7B4FF01232C61F0 -:10505000014623742046BDE83840FBF741BB00BF42 -:1050600040630020044B1A681B6990689B68984253 -:1050700094BF0020012070474063002010B5084C09 -:10508000236820691A6854602260012223611A741F -:10509000FFF790FF01462069BDE81040FBF720BBF9 -:1050A0004063002008B5FFF7DDFF18B1BDE80840F8 -:1050B000FFF7E4BF08BD0000FFF7E0BFFEE7000018 -:1050C00010B50C4CFFF742FF00F0C0F880220A49EF -:1050D000204600F047F8012344F8180C0374FEF74B -:1050E000BFFF002383F3118862B60448BDE8104077 -:1050F00000F058B8686300208074000890740008BD -:1051000008B572B6034B586200F00AFC00F0D8FCF8 -:10511000FEE700BF4063002000F01CB9EFF31180F0 -:1051200020B9EFF30583202282F311887047000035 -:1051300010B530B9EFF30584C4F3080414B180F35B -:10514000118810BDFFF7AEFF84F31188F9E7000066 -:10515000034A516853685B1A9842FBD8704700BFF6 -:10516000001000E082600222028270478368A3F18F -:105170007C0243F80C2C026943F83C2C426943F84A -:10518000382C074A43F81C2CC268A3F1180043F8D6 -:10519000102C022203F8082C002203F8072C704779 -:1051A000F906000810B5202383F31188FFF7DEFF0E -:1051B00000210446FFF73AFF002383F311882046BD -:1051C00010BD0000024B1B6958610F20FFF702BFA2 -:1051D00040630020202383F31188FFF7F3BF000012 -:1051E00008B50146202383F311880820FFF700FF4C -:1051F000002383F3118808BD49B1064B42681B693F -:1052000018605A60136043600420FFF7F1BE4FF04E -:10521000FF307047406300200368984206D01A6848 -:105220000260506018465961FFF798BE7047000051 -:1052300038B504460D462068844200D138BD036865 -:1052400023605C604561FFF789FEF4E7054B4FF092 -:10525000FF3103F11402C3E905220022C3E907125A -:10526000704700BF4063002070B51C4E05460C46D9 -:10527000C0E9032301F0D4FB334653F8142F9A42BC -:105280000DD130620A2C2CBF00190A302A60C5E902 -:105290000124C6E90555BDE8704001F0ABBB316A99 -:1052A000431AE31838BF1C469368A34202D9081971 -:1052B00001F0B0FB73699A6894420CD85A68AC60EC -:1052C0002B606A6015609A685D60121B9A604FF0EF -:1052D000FF33F36170BDA41A1B68ECE74063002044 -:1052E00038B51B4C636998420DD08168D0E9003213 -:1052F00013605A600022C2609A680A449A604FF0B4 -:10530000FF33E36138BD03682246002142F8143FB1 -:1053100093425A60C16003D1BDE8384001F074BBCC -:105320009A688168256A0A449A6001F079FB63698A -:10533000411B9A688A42E5D9AB181D1A206A092DCB -:1053400098BF01F10A02BDE83840104401F062BB89 -:10535000406300202DE9F041184C002704F11406A9 -:10536000656901F05DFB236AAA68C11A8A4215D8F3 -:105370001344D5F80C802362D5E9003213605A60DB -:105380006369EF60B34201D101F03EFB87F31188FE -:105390002869C047202383F31188E1E76169B1429E -:1053A00009D013441B1ABDE8F0410A2B2CBFC018CA -:1053B0000A3001F02FBBBDE8F08100BF4063002040 -:1053C00000207047FEE70000704700004FF0FF30FC -:1053D0007047000002290CD0032904D00129074896 -:1053E00018BF00207047032A05D8054800EBC2000B -:1053F0007047044870470020704700BF747500086C -:10540000442200202875000870B59AB00546084669 -:10541000144601A900F0C2F801A8FCF773FC431C74 -:105420000022C6B25B001046C5E900342370032396 -:10543000023404F8013C01ABD1B202348E4201D8EF -:105440001AB070BD13F8011B013204F8010C04F806 -:10545000021CF1E708B5202383F311880348FFF706 -:105460005BFA002383F3118808BD00BFF8640020B5 -:1054700090F8803003F01F02012A07D190F88120B4 -:105480000B2A03D10023C0E91D3315E003F06003AC -:10549000202B08D1B0F884302BB990F88120212A34 -:1054A00003D81F2A04D8FFF719BA222AEBD0FAE74B -:1054B000034A426707228267C3670120704700BF23 -:1054C0003B22002007B5052917D8DFE801F019169F -:1054D00003191920202383F31188104A0121019018 -:1054E000FFF7C2FA019802210D4AFFF7BDFA0D48F5 -:1054F000FFF7DEF9002383F3118803B05DF804FBA6 -:10550000202383F311880748FFF7A8F9F2E7202347 -:1055100083F311880348FFF7BFF9EBE7C87400086D -:10552000EC740008F864002038B50C4D0C4C2A4689 -:105530000C4904F10800FFF767FF05F1CA0204F106 -:1055400010000949FFF760FF05F5CA7204F1180061 -:105550000649BDE83840FFF757BF00BFD07D0020A7 -:1055600044220020A8740008B2740008BD7400082A -:1055700070B5044608460D46FCF7C4FBC6B220468B -:10558000013403780BB9184670BD32462946FCF742 -:10559000A5FB0028F3D10120F6E700002DE9F04734 -:1055A00005460C46FCF7AEFB2C49C6B22846FFF771 -:1055B000DFFF08B11036F6B229492846FFF7D8FFB9 -:1055C00008B11036F6B2632E0BD8DFF89080DFF802 -:1055D0009090244FDFF898A02E7846B92670BDE849 -:1055E000F08729462046BDE8F04701F03DBE252E54 -:1055F00030D1072241462846FCF770FB80B91A4B90 -:10560000224603F1140153F8040B8B4242F8040BB9 -:10561000F9D1198807359B78173411809370DBE72F -:10562000082249462846FCF759FB98B9A21C0F4BA3 -:10563000197802320909C95D02F8041C13F8011B2C -:1056400001F00F015345C95D02F8031CF0D1183475 -:105650000835C1E7013504F8016BBDE79475000812 -:10566000BD740008B47500089C75000800E8F11FBF -:105670000CE8F11FBFF34F8F044B1A695107FCD19F -:10568000D3F810215207F8D1704700BF0020005214 -:1056900008B50D4B1B78ABB9FFF7ECFF0B4BDA6885 -:1056A000D10704D50A4A5A6002F188325A60D3F809 -:1056B0000C21D20706D5064AC3F8042102F188322C -:1056C000C3F8042108BD00BF2E8000200020005236 -:1056D0002301674508B5114B1B78F3B9104B1A69C4 -:1056E000510703D5DA6842F04002DA60D3F810219E -:1056F000520705D5D3F80C2142F04002C3F80C2123 -:10570000FFF7B8FF064BDA6842F00102DA60D3F81F -:105710000C2142F00102C3F80C2108BD2E800020AC -:10572000002000520F289ABF00F58060400400203E -:10573000704700004FF400307047000010207047A1 -:105740000F2808B50BD8FFF7EDFF00F5003302680E -:10575000013204D104308342F9D1012008BD002078 -:10576000FCE700000F2870B5054645D8FFF7D6FCCA -:10577000224CFFF77FFF0646FFF78AFF4FF0FF330B -:10578000072D6361C4F8143120D82361FFF772FF3D -:105790002B0243F02403E360E36843F08003E360FB -:1057A00023695A07FCD42846FFF764FF4FF4003101 -:1057B000FFF7B8FF00F060F93046FFF78BFFFFF707 -:1057C000B7FC2846BDE87040FFF7BABFC4F81031F7 -:1057D000FFF750FFA5F108031B0243F02403C4F8B0 -:1057E0000C31D4F80C3143F08003C4F80C31D4F8F8 -:1057F00010315B07FBD4D6E7002070BD00200052BB -:105800002DE9F84F40EA020305460C461746D80634 -:1058100002D00020BDE8F88F27F01F07DFF8D4B0D2 -:10582000FFF736FF2744BC4203D10120FFF752FFA8 -:10583000F0E720222946204601F098FC10B92035D7 -:105840002034F0E72B4605F120021E68711CE0D1E0 -:1058500004339A42F9D1FFF761FC05F17843234AFA -:10586000B3F5801F224B28BF9A4603F1040338BFCB -:105870009046A2F1080228BF9846A3F108033ABF58 -:105880009146DA469946FFF7F5FEC8F80060A5EBA9 -:10589000040CD9F8002004F11C0142F00202C9F8FE -:1058A0000020221FDAF8006016F00506FAD152F83F -:1058B000043F8A424CF80230F4D1BFF34F8FFFF718 -:1058C000D9FE4FF0FF32C8F80020D9F8002022F0AE -:1058D0000202C9F80020FFF72BFC202221462846AF -:1058E00001F044FC0028AAD030469FE71420005263 -:1058F000102100521020005210B5084C237828B116 -:105900001BB9FFF7C5FE0123237010BD002BFCD08F -:105910002070BDE81040FFF7DDBE00BF2E800020E4 -:1059200038B5054D00240334696855F80C0B00F0B8 -:10593000B5F8122CF7D138BDC875000870B5104EF7 -:1059400082B0FFF7EBFB054601F06AF832680346C8 -:105950009042336037BF0B4A0A495168146836BF1A -:105960000131D1E9004151600419284641F100019B -:105970000191FFF7DDFB2046019902B070BD00BF29 -:10598000308000203880002070B5124E82B0FFF7C2 -:10599000C5FB054601F044F8326803469042336087 -:1059A00037BF0D4A0C495168146836BF0131D1E93F -:1059B000004151600419284641F100010191FFF7AF -:1059C000B7FB4FF47A72002320460199FAF770FC76 -:1059D00002B070BD30800020388000200244074BA8 -:1059E000D2B210B5904200D110BD441C00B253F8A1 -:1059F000200041F8040BE0B2F4E700BF504000582B -:105A00000E4B30B51C6F240405D41C6F1C671C6F33 -:105A100044F400441C670A4C02442368D2B243F4A5 -:105A200080732360074B904200D130BD441C51F875 -:105A3000045B00B243F82050E0B2F4E7004402589F -:105A4000004802585040005807B5012201A9002023 -:105A5000FFF7C4FF019803B05DF804FB13B50446DB -:105A6000FFF7F2FFA04205D0012201A90020019416 -:105A7000FFF7C6FF02B010BD0144BFF34F8F064BC6 -:105A8000884204D3BFF34F8FBFF36F8F7047C3F8C3 -:105A90005C022030F4E700BF00ED00E00144BFF3FA -:105AA0004F8F064B884204D3BFF34F8FBFF36F8FE6 -:105AB0007047C3F870022030F4E700BF00ED00E04B -:105AC00070470000074B45F255521A6002225A6097 -:105AD00040F6FF729A604CF6CC421A600122024BEB -:105AE0001A7070470048005844800020034B1B7810 -:105AF0001BB1034B4AF6AA221A607047448000206B -:105B000000480058034B1A681AB9034AD2F8D02447 -:105B10001A6070474080002000400258024B4FF44A -:105B20008032C3F8D02470470040025808B5FFF710 -:105B3000E9FF024B1868C0F3806008BD4080002078 -:105B400070B5BFF34F8FBFF36F8F1A4A0021C2F8B1 -:105B50005012BFF34F8FBFF36F8F536943F400337D -:105B60005361BFF34F8FBFF36F8FC2F88410BFF341 -:105B70004F8FD2F8803043F6E074C3F3C900C3F30B -:105B80004E335B0103EA0406014646EA817501399A -:105B9000C2F86052F9D2203B13F1200FF2D1BFF3CB -:105BA0004F8F536943F480335361BFF34F8FBFF37B -:105BB0006F8F70BD00ED00E0FEE700000A4B0B4860 -:105BC0000B4A90420BD30B4BC11EDA1C121A22F067 -:105BD00003028B4238BF00220021FCF79BB853F828 -:105BE000041B40F8041BECE75078000820820020DA -:105BF00020820020208200207047000070B5D0E98C -:105C0000244300224FF0FF359E6804EB42135101FC -:105C1000D3F80009002805DAD3F8000940F08040E5 -:105C2000C3F80009D3F8000B002805DAD3F8000BFD -:105C300040F08040C3F8000B013263189642C3F86D -:105C40000859C3F8085BE0D24FF00113C4F81C38C0 -:105C500070BD000000EB8103D3F80CC02DE9F043C8 -:105C6000DCF814204E1CD0F89050D2F800E005EB80 -:105C7000063605EB4118506870450AD30122D5F865 -:105C8000343802FA01F123EA0101C5F83418BDE8FD -:105C9000F083AEEB0003BCF81040A34228BF2346BC -:105CA000D8F81849A4B2B3EB840FF0D89468A4F1E3 -:105CB000040959F8047F3760A4EB09071F44042F37 -:105CC000F7D81C44034494605360D4E7890141F041 -:105CD0002001016103699B06FCD41220FFF738BA4A -:105CE00010B50A4C2046FEF79DFE094BC4F89030D3 -:105CF000084BC4F89430084C2046FEF793FE074B3F -:105D0000C4F89030064BC4F8943010BD4880002091 -:105D10000000084034760008E480002000000440C1 -:105D20004076000870B503780546012B5DD1494BDC -:105D3000D0F89040984259D1474B0E216520D3F8B6 -:105D4000D82042F00062C3F8D820D3F8002142F0F6 -:105D50000062C3F80021D3F80021D3F8802042F07C -:105D60000062C3F88020D3F8802022F00062C3F8DC -:105D70008020D3F88030FEF7D5FA384BE360384BFB -:105D8000C4F800380023D5F89060C4F8003EC02362 -:105D900023604FF40413A3633369002BFCDA01235F -:105DA0000C203361FFF7D4F93369DB07FCD41220F0 -:105DB000FFF7CEF93369002BFCDA00262846A660EF -:105DC000FFF71CFF6B68C4F81068DB68C4F8146840 -:105DD000C4F81C68002B3AD1224BA3614FF0FF336B -:105DE0006361A36843F00103A36070BD1E4B98423A -:105DF000C8D1194B0E214D20D3F8D82042F00072A3 -:105E0000C3F8D820D3F8002142F00072C3F8002173 -:105E1000D3F80021D3F8802042F00072C3F880202C -:105E2000D3F8802022F00072C3F88020D3F88020BD -:105E3000D3F8D82022F08062C3F8D820D3F800210C -:105E400022F08062C3F80021D3F8003193E7074BBA -:105E5000C3E700BF488000200044025840140040BF -:105E600003002002003C30C0E4800020083C30C029 -:105E7000F8B5D0F89040054600214FF00066204666 -:105E8000FFF724FFD5F8941000234FF001128F681C -:105E90004FF0FF30C4F83438C4F81C2804EB431228 -:105EA00001339F42C2F80069C2F8006BC2F80809CA -:105EB000C2F8080BF2D20B68D5F89020C5F89830DC -:105EC000636210231361166916F01006FBD11220CD -:105ED000FFF73EF9D4F8003823F4FE63C4F8003825 -:105EE000A36943F4402343F01003A3610923C4F8DA -:105EF0001038C4F814380B4BEB604FF0C043C4F8B3 -:105F0000103B094BC4F8003BC4F81069C4F80039D1 -:105F1000D5F8983003F1100243F48013C5F89820A7 -:105F2000A362F8BD1076000840800010D0F89020E1 -:105F300090F88A10D2F8003823F4FE6343EA011384 -:105F4000C2F80038704700002DE9F84300EB8103E8 -:105F5000D0F890500C468046DA680FFA81F9480173 -:105F6000166806F00306731E022B05EB41134FF073 -:105F7000000194BFB604384EC3F8101B4FF0010166 -:105F800004F1100398BF06F1805601FA03F39169FA -:105F900098BF06F5004600293AD0578A04F1580107 -:105FA000374349016F50D5F81C180B430021C5F841 -:105FB0001C382B180127C3F81019A7405369611E1C -:105FC0009BB3138A928B9B08012A88BF5343D8F84E -:105FD0009820981842EA034301F140022146C8F88C -:105FE0009800284605EB82025360FFF76FFE08EB2E -:105FF0008900C3681B8A43EA845348341E43640102 -:106000002E51D5F81C381F43C5F81C78BDE8F8831D -:1060100005EB4917D7F8001B21F40041C7F8001B16 -:10602000D5F81C1821EA0303C0E704F13F030B4A2B -:106030002846214605EB83035A60FFF747FE05EB30 -:106040004910D0F8003923F40043C0F80039D5F8DE -:106050001C3823EA0707D7E700800010000400027D -:10606000D0F894201268C0F89820FFF7C7BD000050 -:106070005831D0F8903049015B5813F4004004D0F7 -:1060800013F4001F0CBF0220012070474831D0F8E4 -:10609000903049015B5813F4004004D013F4001F02 -:1060A0000CBF02200120704700EB8101CB68196A08 -:1060B0000B6813604B6853607047000000EB81036E -:1060C00030B5DD68AA691368D36019B9402B84BF65 -:1060D000402313606B8A1468D0F890201C4402EBB4 -:1060E0004110013C09B2B4FBF3F46343033323F0E2 -:1060F000030343EAC44343F0C043C0F8103B2B689A -:1061000003F00303012B0ED1D2F8083802EB411043 -:1061100013F4807FD0F8003B14BF43F0805343F06A -:106120000053C0F8003B02EB4112D2F8003B43F0B1 -:106130000443C2F8003B30BD2DE9F041D0F8906037 -:1061400005460C4606EB4113D3F8087B3A07C3F823 -:10615000087B08D5D6F814381B0704D500EB81035B -:10616000DB685B689847FA071FD5D6F81438DB0759 -:106170001BD505EB8403D968CCB98B69488A5A686A -:10618000B2FBF0F600FB16228AB91868DA68904272 -:106190000DD2121AC3E90024202383F3118821466B -:1061A0002846FFF78BFF84F31188BDE8F0810123B7 -:1061B00003FA04F26B8923EA02036B81CB68002B9C -:1061C000F3D021462846BDE8F041184700EB810393 -:1061D0004A0170B5DD68D0F890306C692668E660D9 -:1061E00056BB1A444FF40020C2F810092A6802F086 -:1061F0000302012A0AB20ED1D3F8080803EB4214B5 -:1062000010F4807FD4F8000914BF40F0805040F0B3 -:106210000050C4F8000903EB4212D2F8000940F024 -:106220000440C2F800090122D3F8340802FA01F14F -:106230000143C3F8341870BD19B9402E84BF402003 -:10624000206020681A442E8A8419013CB4FBF6F4BD -:1062500040EAC44040F00050C6E700002DE9F0419C -:10626000D0F8906004460D4606EB4113D3F8087948 -:10627000C3F80879FB071CD5D6F81038DA0718D50B -:1062800000EB8103D3F80CC0DCF81430D3F800E045 -:10629000DA6896451BD2A2EB0E024FF000081A6096 -:1062A000C3F80480202383F31188FFF78FFF88F35E -:1062B00011883B0618D50123D6F83428AB40134289 -:1062C00012D029462046BDE8F041FFF7C3BC0123A8 -:1062D00003FA01F2038923EA02030381DCF80830A0 -:1062E000002BE6D09847E4E7BDE8F0812DE9F84FB0 -:1062F000D0F8905004466E69AB691E4016F4805881 -:106300006E6103D0BDE8F84FFEF7FCBB002E12DA39 -:10631000D5F8003E9F0705D0D5F8003E23F00303D3 -:10632000C5F8003ED5F80438204623F00103C5F82F -:106330000438FEF713FC300505D52046FFF75EFC58 -:106340002046FEF7FBFBB1040CD5D5F8083813F056 -:10635000060FEB6823F470530CBF43F4105343F45F -:10636000A053EB60320704D56368DB680BB12046AD -:106370009847F30200F1BA80B70226D5D4F890907E -:1063800000274FF0010A09EB4712D2F8003B03F453 -:106390004023B3F5802F11D1D2F8003B002B0DDA4A -:1063A00062890AFA07F322EA0303638104EB870395 -:1063B000DB68DB6813B13946204698470137D4F8CB -:1063C0009430FFB29B689F42DDD9F00619D5D4F80E -:1063D0009000026AC2F30A1702F00F0302F4F012EF -:1063E000B2F5802F00F0CC80B2F5402F09D104EB3C -:1063F0008303002200F58050DB681B6A974240F05F -:10640000B2803003D5F8185835D5E90303D50021FB -:106410002046FFF791FEAA0303D501212046FFF78E -:106420008BFE6B0303D502212046FFF785FE2F0369 -:1064300003D503212046FFF77FFEE80203D50421A0 -:106440002046FFF779FEA90203D505212046FFF774 -:1064500073FE6A0203D506212046FFF76DFE2B026C -:1064600003D507212046FFF767FEEF0103D508217A -:106470002046FFF761FE700340F1A980E90703D5CC -:1064800000212046FFF7EAFEAA0703D50121204696 -:10649000FFF7E4FE6B0703D502212046FFF7DEFE7F -:1064A0002F0703D503212046FFF7D8FEEE0603D5BC -:1064B00004212046FFF7D2FEA80603D50521204679 -:1064C000FFF7CCFE690603D506212046FFF7C6FE7E -:1064D0002A0603D507212046FFF7C0FEEB0576D537 -:1064E00020460821BDE8F84FFFF7B8BED4F89090D9 -:1064F00000274FF0010AD4F894305FFA87FB9B68BD -:106500009B453FF639AF09EB4B13D3F8002902F452 -:106510004022B2F5802F24D1D3F80029002A20DAB6 -:10652000D3F8002942F09042C3F80029D3F800299B -:10653000002AFBDB5946D4F89000FFF7C7FB2289FD -:106540000AFA0BF322EA0303238104EB8B03DB68D3 -:106550009B6813B159462046984759462046FFF795 -:1065600079FB0137C7E7910701D1D0F80080072AEE -:1065700002F101029CBF03F8018B4FEA18283DE7A6 -:1065800004EB830300F58050DA68D2F818C0DCF819 -:106590000820DCE9001CA1EB0C0C00218F4208D183 -:1065A000DB689B699A683A449A605A683A445A6030 -:1065B00027E711F0030F01D1D0F800808C4501F1DD -:1065C000010184BF02F8018B4FEA1828E6E7BDE815 -:1065D000F88F000008B50348FFF788FEBDE80840C3 -:1065E000FDF766BD4880002008B50348FFF77EFE32 -:1065F000BDE80840FDF75CBDE4800020D0F8903095 -:1066000003EB4111D1F8003B43F40013C1F8003B08 -:1066100070470000D0F8903003EB4111D1F80039F9 -:1066200043F40013C1F8003970470000D0F89030EF -:1066300003EB4111D1F8003B23F40013C1F8003BF8 -:1066400070470000D0F8903003EB4111D1F80039C9 -:1066500023F40013C1F800397047000030B504334B -:10666000039C0172002104FB0325C160C0E90653AD -:10667000049B0363059BC0E90000C0E90422C0E954 -:106680000842C0E90A11436330BD00000022416A9C -:10669000C260C0E90411C0E90A226FF00101FEF7EF -:1066A000C7BD0000D0E90432934201D1C2680AB9E3 -:1066B000181D704700207047036919600021C268E7 -:1066C0000132C260C269134482699342036124BFEC -:1066D000436A0361FEF7A0BD38B504460D46E36882 -:1066E0003BB162690020131D1268A3621344E36288 -:1066F00007E0237A33B929462046FEF77DFD0028BE -:10670000EDDA38BD6FF00100FBE70000C368C26935 -:10671000013BC3604369134482699342436124BFD0 -:10672000436A436100238362036B03B118477047D8 -:1067300070B52023044683F31188866A3EB9FFF7BB -:10674000CBFF054618B186F31188284670BDA36AB1 -:10675000E26A13F8015B9342A36202D32046FFF77B -:10676000D5FF002383F31188EFE700002DE9F84FF0 -:1067700004460E46174698464FF0200989F31188C3 -:106780000025AA46D4F828B0BBF1000F09D1414634 -:106790002046FFF7A1FF20B18BF311882846BDE802 -:1067A000F88FD4E90A12A7EB050B521A934528BFBC -:1067B0009346BBF1400F1BD9334601F1400251F81B -:1067C000040B914243F8040BF9D1A36A40364035DB -:1067D0004033A362D4E90A239A4202D32046FFF74A -:1067E00095FF8AF31188BD42D8D289F31188C9E791 -:1067F00030465A46FBF768FAA36A5E445D445B4440 -:10680000A362E7E710B5029C0433017204FB032185 -:10681000C460C0E906130023C0E90A33039B036385 -:10682000049BC0E90000C0E90422C0E908424363B8 -:1068300010BD0000026A6FF00101C260426AC0E947 -:1068400004220022C0E90A22FEF7F2BCD0E90423A8 -:106850009A4201D1C26822B9184650F8043B0B6035 -:106860007047002070470000C3680021C2690133EF -:10687000C3604369134482699342436124BF436AFE -:106880004361FEF7C9BC000038B504460D46E36815 -:106890003BB1236900201A1DA262E2691344E3623E -:1068A00007E0237A33B929462046FEF7A5FC0028E5 -:1068B000EDDA38BD6FF00100FBE7000003691960F5 -:1068C000C268013AC260C26913448269934203619B -:1068D00024BF436A036100238362036B03B118473B -:1068E0007047000070B520230D460446114683F31F -:1068F0001188866A2EB9FFF7C7FF10B186F3118899 -:1069000070BDA36A1D70A36AE26A01339342A36259 -:1069100004D3E16920460439FFF7D0FF002080F35B -:106920001188EDE72DE9F84F04460D46904699464B -:106930004FF0200A8AF311880026B346A76A4FB9A0 -:1069400049462046FFF7A0FF20B187F31188304663 -:10695000BDE8F88FD4E90A073A1AA8EB0607974270 -:1069600028BF1746402F1BD905F1400355F8042BCB -:106970009D4240F8042BF9D1A36A40364033A3620C -:10698000D4E90A239A4204D3E16920460439FFF787 -:1069900095FF8BF311884645D9D28AF31188CDE74C -:1069A00029463A46FBF790F9A36A3D443E443B44EE -:1069B000A362E5E7D0E904239A4217D1C3689BB1EB -:1069C000836A8BB1043B9B1A0ED01360C368013BF2 -:1069D000C360C3691A4483699A42026124BF436A4F -:1069E0000361002383620123184670470023FBE7FD -:1069F00000F0CEB8034B002258631A610222DA601D -:106A0000704700BF000C0040014B0022DA60704765 -:106A1000000C0040014B5863704700BF000C004061 -:106A2000014B586A704700BF000C00404B68436040 -:106A30008B688360CB68C3600B6943614B690362F9 -:106A40008B6943620B6803607047000008B5364BE2 -:106A500040F2FF713548D3F888200A43C3F88820F4 -:106A6000D3F8882022F4FF6222F00702C3F88820BE -:106A7000D3F88820D3F8E0200A43C3F8E020D3F805 -:106A800008210A43C3F80821294AD3F808311146DE -:106A9000FFF7CCFF00F5806002F11C01FFF7C6FF95 -:106AA00000F5806002F13801FFF7C0FF00F580605B -:106AB00002F15401FFF7BAFF00F5806002F17001A6 -:106AC000FFF7B4FF00F5806002F18C01FFF7AEFF25 -:106AD00000F5806002F1A801FFF7A8FF00F58060D3 -:106AE00002F1C401FFF7A2FF00F5806002F1E001AE -:106AF000FFF79CFF00F5806002F1FC01FFF796FFB5 -:106B000002F58C7100F58060FFF790FF00F0F4F85B -:106B1000084B0522C3F898204FF06052C3F89C2020 -:106B2000054AC3F8A02008BD0044025800000258DE -:106B30004C76000800ED00E01F00080308B500F0E7 -:106B4000D7FAFEF7BDFA0F4BD3F8DC2042F0400233 -:106B5000C3F8DC20D3F8042122F04002C3F804215A -:106B6000D3F80431084B1A6842F008021A601A6818 -:106B700042F004021A60FEF7C5FFBDE80840FEF7C8 -:106B8000D3BC00BF00440258001802487047000000 -:106B9000114BD3F8E82042F00802C3F8E820D3F8FC -:106BA000102142F00802C3F810210C4AD3F810312A -:106BB000D36B43F00803D363C722094B9A624FF0AB -:106BC000FF32DA6200229A615A63DA605A60012267 -:106BD0005A611A60704700BF004402580010005C00 -:106BE000000C0040094A08B51169D3680B40D9B2BE -:106BF0009B076FEA0101116107D5202383F31188F8 -:106C0000FEF78AFA002383F3118808BD000C0040C8 -:106C1000384B4FF0FF31D3F88020C3F88010D3F801 -:106C200080200022C3F88020D3F88000D3F88400AD -:106C3000C3F88410D3F88400C3F88420D3F8840008 -:106C4000D86F40F0FF4040F4FF0040F43F5040F068 -:106C50003F00D867D86F20F0FF4020F4FF0020F4F9 -:106C60003F5020F03F00D867D86FD3F888006FEA14 -:106C700040506FEA5050C3F88800D3F88800C0F342 -:106C80000A00C3F88800D3F88800D3F89000C3F84E -:106C90009010D3F89000C3F89020D3F89000D3F868 -:106CA0009400C3F89410D3F89400C3F89420D3F858 -:106CB0009400D3F89800C3F89810D3F89800C3F85C -:106CC0009820D3F89800D3F88C00C3F88C10D3F830 -:106CD0008C00C3F88C20D3F88C00D3F89C00C3F848 -:106CE0009C10D3F89C10C3F89C20D3F89C3000F083 -:106CF000D3B900BF00440258614B0122C3F80821F8 -:106D0000604BD3F8F42042F00202C3F8F420D3F829 -:106D10001C2142F00202C3F81C210222D3F81C31CC -:106D2000594BDA605A689104FCD5584A1A6001221E -:106D30009A60574ADA6000221A614FF440429A6121 -:106D4000514B9A699204FCD51A6842F480721A6019 -:106D50004C4B1A6F12F4407F04D04FF480321A6704 -:106D600000221A671A6842F001021A60454B1A683D -:106D70005007FCD500221A611A6912F03802FBD1C3 -:106D8000012119604FF0804159605A67414ADA6227 -:106D9000414A1A611A6842F480321A60394B1A6803 -:106DA0009103FCD51A6842F480521A601A68920462 -:106DB000FCD53A4A3A499A6200225A631963394922 -:106DC000DA6399635A64384A1A64384ADA621A688C -:106DD00042F0A8521A602B4B1A6802F02852B2F106 -:106DE000285FF9D148229A614FF48862DA61402223 -:106DF0001A622F4ADA644FF080521A652D4A5A659A -:106E00002D4A9A6532232D4A1360136803F00F034D -:106E1000022BFAD11B4B1A6942F003021A611A695C -:106E200002F03802182AFAD1D3F8DC2042F00052DE -:106E3000C3F8DC20D3F8042142F00052C3F8042147 -:106E4000D3F80421D3F8DC2042F08042C3F8DC20E0 -:106E5000D3F8042142F08042C3F80421D3F804217E -:106E6000D3F8DC2042F00042C3F8DC20D3F8042140 -:106E700042F00042C3F80421D3F80431704700BF48 -:106E800000800051004402580048025800C000F041 -:106E9000020000010000FF0100889008322060001D -:106EA000630209011D02040047040508FD0BFF01F0 -:106EB000200000200010E00000010100002000522E -:106EC0004FF0B04208B5D2F8883003F00103C2F8A1 -:106ED000883023B1044A13680BB150689847BDE865 -:106EE0000840FDF7E5B800BF988100204FF0B042A0 -:106EF00008B5D2F8883003F00203C2F8883023B115 -:106F0000044A93680BB1D0689847BDE80840FDF784 -:106F1000CFB800BF988100204FF0B04208B5D2F83A -:106F2000883003F00403C2F8883023B1044A13699F -:106F30000BB150699847BDE80840FDF7B9B800BFEC -:106F4000988100204FF0B04208B5D2F8883003F0A5 -:106F50000803C2F8883023B1044A93690BB1D069A1 -:106F60009847BDE80840FDF7A3B800BF988100200E -:106F70004FF0B04208B5D2F8883003F01003C2F8E1 -:106F8000883023B1044A136A0BB1506A9847BDE8B0 -:106F90000840FDF78DB800BF988100204FF0B04346 -:106FA00010B5D3F8884004F47872C3F88820A3069B -:106FB00004D5124A936A0BB1D06A9847600604D58B -:106FC0000E4A136B0BB1506B9847210604D50B4A40 -:106FD000936B0BB1D06B9847E20504D5074A136C4D -:106FE0000BB1506C9847A30504D5044A936C0BB1C0 -:106FF000D06C9847BDE81040FDF75AB89881002042 -:107000004FF0B04310B5D3F8884004F47C42C3F885 -:107010008820620504D5164A136D0BB1506D984750 -:10702000230504D5124A936D0BB1D06D9847E00447 -:1070300004D50F4A136E0BB1506E9847A10404D5C6 -:107040000B4A936E0BB1D06E9847620404D5084A80 -:10705000136F0BB1506F9847230404D5044A936F04 -:107060000BB1D06F9847BDE81040FDF721B800BFC5 -:107070009881002008B50348FDF7D0F8BDE8084026 -:10708000FDF716B8D45E002008B5FFF7ABFDBDE8EC -:107090000840FDF70DB80000062108B50846FDF7C9 -:1070A00041F906210720FDF73DF906210820FDF7EB -:1070B00039F906210920FDF735F906210A20FDF7E7 -:1070C00031F906211720FDF72DF906212820FDF7BB -:1070D00029F909217A20FDF725F907213220FDF74A -:1070E00021F90C215220BDE80840FDF71BB9000032 -:1070F00008B5FFF78DFD00F00DF8FDF7B7FAFDF7C5 -:107100008FFCFDF761FBFFF741FDBDE80840FFF78D -:107110006FBC00000023054A19460133102BC2E959 -:10712000001102F10802F8D1704700BF98810020D9 -:107130000B460146184600F003B8000000F00EB8F8 -:1071400010B5054C13462CB10A4601460220AFF398 -:10715000008010BD2046FCE700000000024B014605 -:10716000186800F035B800BF6422002010B501395E -:107170000244904201D1002005E0037811F8014F4C -:10718000A34201D0181B10BD0130F2E72DE9F041F8 -:10719000A3B1C91A17780144044603F1FF3C8C429D -:1071A000204601D9002009E00578BD4204F1010420 -:1071B000F5D10CEB0405D618A54201D1BDE8F0814C -:1071C00015F8018D16F801EDF045F5D0E7E7000060 -:1071D00037B5002944D051F8043C0190002BA1F1AF -:1071E0000404B8BFE41800F047F81E4A0198136879 -:1071F00033B96360146003B0BDE8304000F042B8BA -:10720000A34208D9256861198B4201BF19685B68E0 -:1072100049192160EDE71A465B680BB1A342FAD920 -:1072200011685518A5420BD1246821445418A34273 -:107230001160E0D11C685B68536021441160DAE79B -:1072400002D90C230360D6E7256861198B4204BF7D -:1072500019685B68636004BF491921605460CAE71C -:1072600003B030BD18820020034611F8012B03F84B -:10727000012B002AF9D17047014800F009B800BF7E -:107280001C820020014800F005B800BF1C820020CD -:1072900070470000704700006F72672E617264755E -:1072A00070696C6F742E437562654F72616E6765AD -:1072B0002D706572697068004E6F20617070207368 -:1072C00069670A00426164206677206C656E6774A6 -:1072D000682025750A0042616420626F6172645FF4 -:1072E00069642025752073686F756C642062652061 -:1072F00025750A00426164206677206465736372B5 -:107300006970746F72206C656E6774682025750AE9 -:107310000042616420617070204352432030782520 -:107320003038783A30782530387820307825303841 -:10733000783A3078253038780A00476F6F642066D5 -:1073400069726D776172650A0040A2E4F164689128 -:107350000600000053544D333248373F3F3F00533F -:10736000544D3332483734332F3735330000000063 -:10737000F8640020D45E002043414E4644496661D3 -:1073800063653A204D6573736167652052414D20F6 -:107390004F766572666C6F77210000004261642051 -:1073A00043414E496661636520696E6465782E00CD -:1073B000000100000001FF0000A0004000A4004008 -:1073C0000000000000000000C1250008991E000810 -:1073D000012D00088D1E0008091F00081923000850 -:1073E00081200008D11E0008D51E0008911E00084B -:1073F000AD1E0008951E0008D9220008B91E00081D -:107400000D2E0008C51E0008AD22000800960000E1 -:10741000000000000000000000000000000000006C -:10742000000000000000000035460008214600086A -:107430005D460008494600085546000841460008D8 -:107440002D460008194600086946000800000000A3 -:1074500045470008314700086D47000859470008B4 -:1074600065470008514700083D47000829470008C4 -:107470007947000800000000010000000000000043 -:107480006D61696E0000000069646C6500000000B9 -:107490008874000880630020F86400200100000068 -:1074A000BD500008000000004172647550696C6FA7 -:1074B000740025424F415244252D424C002553452E -:1074C0005249414C2500000002000000000000006D -:1074D00065490008D549000840004000A07D002013 -:1074E000B07D00200200000000000000030000004A -:1074F000000000001D4A000800000000100000000D -:10750000C07D00200000000001000000000000001D -:107510004880002001010200C5540008D55300082E -:1075200071540008555400084300000030750008ED -:1075300009024300020100C03209040000010202F6 -:1075400001000524001001052401000104240202A9 -:107550000524060001070582030800FF0904010055 -:10756000020A000000070501024000000705810231 -:1075700040000000120000007C750008120110019C -:1075800002000040091241570002010203010000FD -:107590000403090425424F415244250043756265A6 -:1075A0004F72616E67652D7065726970682D6865D0 -:1075B00061767900303132333435363738394142EB -:1075C0004344454600000000000000200000020087 -:1075D0000200000000010030000000000000000078 -:1075E0000000002400000800040000000004000067 -:1075F00000FC0000020000000000043000800000D9 -:107600000000000000000038000001000100000040 -:1076100000000000714B0008294E0008D54E0008FC -:107620004000400080810020808100200100000097 -:107630009081002080000000400100000800000050 -:107640000001000000040000080000000000802A83 -:1076500000000000AAAAAAAA00000024FFFF000060 -:107660000000000000A00A0000210002000000004D -:10767000AAAAAAAA00000000FFFF0000000000095B -:10768000000009001400005400000000AAAAAAAAE1 -:1076900014000054FFFF0000000000000000000084 -:1076A0000A40100000000000AAAA8AAA00401000A8 -:1076B000FFFF0000990000000000000000810200B0 -:1076C00000000000AAAAAAAA00410100FFFF0000D2 -:1076D0000000007007000000000000000000000033 -:1076E000AAAAAAAA00000000FFFF000000000000F4 -:1076F000000000000000000000000000AAAAAAAAE2 -:1077000000000000FFFF000000000000000000007B -:107710000000000000000000AAAAAAAA00000000C1 -:10772000FFFF00000000000000000000000000005B -:1077300000000000AAAAAAAA00000000FFFF0000A3 -:107740000000000000000000000000000000000039 -:10775000AAAAAAAA00000000FFFF00000000000083 -:10776000000000000000000000000000AAAAAAAA71 -:1077700000000000FFFF000000000000000000000B -:10778000608BFF7F01000000780500000000000012 -:1077900000001E0000000000FE2A0100D2040000CC -:1077A000FF00000000000000547300083F000000CC -:1077B000500400005F7300083F00000000960000C6 -:1077C000000008009600000000080000040000000F -:1077D000907500080000000000000000000000009C -:1077E00000000000000000000000000068220020EF -:1077F0000000000000000000000000000000000089 -:107800000000000000000000000000000000000078 -:107810000000000000000000000000000000000068 -:107820000000000000000000000000000000000058 -:107830000000000000000000000000000000000048 -:107840000000000000000000000000000000000038 +:1000000000060020F50500086135000819350008D4 +:10001000413500081935000839350008F705000892 +:10002000F7050008F7050008F70500084545000832 +:10003000F7050008F7050008F7050008F7050008B0 +:10004000F7050008F7050008F7050008F7050008A0 +:10005000F7050008F70500086975000895750008A0 +:10006000C1750008ED75000819760008F70500084D +:10007000F7050008F7050008F7050008F705000870 +:10008000F7050008F7050008F7050008C93400085F +:10009000F1340008DD340008053500084576000815 +:1000A000F7050008F7050008F7050008F705000840 +:1000B000F7050008F7050008F7050008F705000830 +:1000C000F7050008F7050008F7050008F705000820 +:1000D000F7050008F7050008F7050008F705000810 +:1000E000A9760008F7050008F7050008F7050008DD +:1000F000F7050008F7050008F7050008F7050008F0 +:10010000F7050008F705000831770008F705000833 +:10011000F7050008F7050008F7050008F7050008CF +:10012000F7050008F7050008F7050008F7050008BF +:10013000F7050008F7050008F7050008F7050008AF +:10014000F7050008F7050008F7050008F70500089F +:10015000F7050008F7050008F7050008F70500088F +:10016000F7050008F7050008F7050008F70500087F +:10017000F7050008F16B0008F7050008F70500080F +:10018000F7050008F70500081D770008F7050008C7 +:10019000F7050008F7050008F7050008F70500084F +:1001A000F7050008F7050008F7050008F70500083F +:1001B000F7050008F7050008F7050008F70500082F +:1001C000F7050008F7050008F7050008F70500081F +:1001D000F7050008DD6B0008F7050008F7050008C3 +:1001E000F7050008F7050008F7050008F7050008FF +:1001F000F7050008F7050008F7050008F7050008EF +:10020000F7050008F7050008F7050008F7050008DE +:10021000F7050008F7050008F7050008F7050008CE +:10022000F7050008F7050008F7050008F7050008BE +:10023000F7050008F7050008F7050008F7050008AE +:10024000F7050008F7050008F7050008F70500089E +:10025000F7050008F7050008F7050008F70500088E +:10026000F7050008F7050008F7050008F70500087E +:10027000F7050008F7050008F7050008F70500086E +:10028000F7050008F7050008F7050008F70500085E +:10029000F7050008F7050008F7050008F70500084E +:1002A000F7050008F7050008F7050008F70500083E +:1002B000F7050008F7050008F7050008F70500082E +:1002C000F7050008F7050008F7050008F70500081E +:1002D000F7050008F7050008F7050008F70500080E +:1002E000111A0008000000000000000000000000DB +: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 +:1006600005F032FD06F040FD4FF055301F491B4AA2 +:1006700091423CBF41F8040BFAE71D49184A9142E8 +:100680003CBF41F8040BFAE71A491B4A1B4B9A423C +:100690003EBF51F8040B42F8040BF8E7002018495C +:1006A000184A91423CBF41F8040BFAE705F04AFDB5 +:1006B00006F09EFD144C154DAC4203DA54F8041BB1 +:1006C0008847F9E700F042F8114C124DAC4203DACA +:1006D00054F8041B8847F9E705F032BD00060020F6 +:1006E000002200200000000808ED00E000000020CB +:1006F00000060020E87C000800220020D022002014 +:10070000D022002030870020E0020008E402000828 +:10071000E4020008E40200082DE9F04F2DED108AF4 +:10072000C1F80CD0D0F80CD0BDEC108ABDE8F08F29 +:10073000002383F311882846A047002004F0AAFF75 +:10074000FEE704F003FF00DFFEE70000F8B501F06C +:1007500075F905F03DFC074605F0ACFC0546B8BB55 +:10076000204B9F4234D001339F4234D027F0FF0208 +:100770001D4B9A4232D12E4642F21074F8B200F06C +:1007800093FF00F097FF08B10024264601F04CFDCE +:1007900020B10024032000F07BF8264635B1134B2E +:1007A0009F4203D0002405F07DFC2646002005F082 +:1007B00019FC0EB100F082F801F0E2FA00F0AEFF91 +:1007C00001F0B8F9204600F029F900F077F8F9E7D0 +:1007D0002E460024D5E704460126D2E7064641F21C +:1007E0008834CEE7010007B0000008B0263A09B00F +:1007F00008B501F06BF9A0F120035842584108BD3B +:1008000007B541F21203022101A8ADF8043001F04E +:100810007BF903B05DF804FB38B5302383F311880E +:10082000174803680BB105F001F80023154A4FF48F +:100830007A71134804F0F0FF002383F31188124CFF +:10084000236813B12368013B2360636813B16368B5 +:10085000013B63600D4D2B7833B963687BB902208F +:1008600001F010FA322363602B78032B07D1636801 +:100870002BB9022001F006FA4FF47A73636038BD99 +:10088000D022002019080008F0230020E8220020D0 +:10089000084B187003280CD8DFE800F008050208A0 +:1008A000022001F0EDB9022001F0E8B9024B00226C +:1008B0005A607047E8220020F0230020F8B501F0CC +:1008C000B3FC30B14D4B03221A7000224C4B5A60DE +:1008D000F8BD4C4B4C4A1C4619680131F8D0043322 +:1008E0009342F9D16268494B9A42F1D9484B9B68CF +:1008F00003F1006303F500339A42E9D205F0A6FB49 +:1009000005F0B8FB002001F02FF90220FFF7C0FF2F +:10091000404B0021D3F8E820C3F8E810D3F81021A9 +:10092000C3F81011D3F81021D3F8EC20C3F8EC1061 +:10093000D3F81421C3F81411D3F81421D3F8F020FC +:10094000C3F8F010D3F81821C3F81811D3F8182100 +:10095000D3F8802042F00072C3F88020D3F88020C2 +:1009600022F00072C3F88020D3F8803072B64FF0C6 +:10097000E023C3F8084DD4E90004BFF34F8FBFF361 +:100980006F8F254AC2F88410BFF34F8F536923F449 +:1009900080335361BFF34F8FD2F8803043F6E07657 +:1009A000C3F3C905C3F34E335B0103EA060C2946C2 +:1009B0004CEA81770139C2F87472F9D2203B13F105 +:1009C000200FF2D1BFF34F8FBFF36F8FBFF34F8F65 +:1009D000BFF36F8F536923F4003353610023C2F8D0 +:1009E0005032BFF34F8FBFF36F8F302383F31188E3 +:1009F000854680F3088820476AE700BFE822002088 +:100A0000F02300200000020820000208FFFF010878 +:100A1000002200200044025800ED00E02DE9F04FD4 +:100A200093B0B74B2022FF2100900AA89D6801F0E7 +:100A300051F9B44A1378A3B90121B3481170036086 +:100A4000302383F3118803680BB104F0EFFE002319 +:100A5000AE4A4FF47A71AC4804F0DEFE002383F313 +:100A60001188009B13B1AA4B009A1A60A94A137807 +:100A7000032B03D000231370A54A53604FF0000AE4 +:100A8000009CD3465646D146012001F0F9F824B126 +:100A90009F4B1B68002B00F02C82002001F016F801 +:100AA0000390039B002B01DA00F08CFE039B002BCC +:100AB000EDDB012001F0E2F8039B213B1F2BE3D883 +:100AC00001A252F823F000BF490B0008710B000887 +:100AD000050C0008890A0008890A0008890A00082C +:100AE000970C0008670E0008810D0008E30D000850 +:100AF0000B0E0008310E0008890A0008430E00089A +:100B0000890A0008B50E0008E90B0008890A0008E8 +:100B1000F90E0008550B0008E90B0008890A0008C7 +:100B2000E30D0008890A0008890A0008890A0008FC +:100B3000890A0008890A0008890A0008890A000849 +:100B4000890A0008050C00080220FFF751FE002862 +:100B500040F0F981009B022105A8BAF1000F08BFFF +:100B60001C4641F21233ADF8143000F0CDFF8BE794 +:100B70004FF47A7000F0AAFF071EEBDB0220FFF7AC +:100B800037FE0028E6D0013F052F00F2DE81DFE8C6 +:100B900007F0030A0D1013360523042105A8059359 +:100BA00000F0B2FF17E004215548F9E704215A4844 +:100BB000F6E704215948F3E74FF01C08404608F1D6 +:100BC000040800F0D3FF0421059005A800F09CFF65 +:100BD000B8F12C0FF2D101204FF0000900FA07F70D +:100BE00047EA0B0B5FFA8BFB01F0C0F826B10BF064 +:100BF0000B030B2B08BF0024FFF702FE44E7042180 +:100C00004748CDE7002EA5D00BF00B030B2BA1D14D +:100C10000220FFF7EDFD074600289BD001200026AB +:100C200000F0A2FF0220FFF733FE1FFA86F84046CD +:100C300000F0AAFF0446B0B1039940460136A1F185 +:100C400040025142514100F0B7FF0028EDD1BA46B1 +:100C5000044641F21213022105A83E46ADF81430B5 +:100C600000F052FF10E725460120FFF711FE244B4C +:100C70009B68AB4207D9284600F078FF013040F06E +:100C800067810435F3E70025224BBA463E461D70C6 +:100C90001F4B5D60A8E7002E3FF45CAF0BF00B0329 +:100CA0000B2B7FF457AF0220FFF7F2FD322000F04C +:100CB0000DFFB0F10008FFF64DAF18F003077FF409 +:100CC00049AF0F4A08EB0503926893423FF642AFE3 +:100CD000B8F5807F3FF73EAF124BB845019323DD57 +:100CE0004FF47A7000F0F2FE0390039A002AFFF6A8 +:100CF00031AF039A0137019B03F8012BEDE700BFE9 +:100D000000220020EC230020D02200201908000837 +:100D1000F0230020E82200200422002008220020E6 +:100D20000C220020EC220020C820FFF761FD0746BE +:100D300000283FF40FAF1F2D11D8C5F120020AABD8 +:100D400025F0030084494245184428BF42460192D9 +:100D500000F09AFF019AFF217F4800F0BBFF4FEAA5 +:100D6000A803C8F387027C492846019300F0BAFF24 +:100D7000064600283FF46DAF019B05EB830533E782 +:100D80000220FFF735FD00283FF4E4AE00F026FF17 +:100D900000283FF4DFAE0027B846704B9B68BB428B +:100DA00018D91F2F11D80A9B01330ED027F0030347 +:100DB00012AA134453F8203C05934046042205A987 +:100DC000043701F01BFA8046E7E7384600F0CEFE14 +:100DD0000590F2E7CDF81480042105A800F094FEF8 +:100DE00002E70023642104A8049300F083FE002896 +:100DF0007FF4B0AE0220FFF7FBFC00283FF4AAAE60 +:100E0000049800F0E1FE0590E6E70023642104A8C1 +:100E1000049300F06FFE00287FF49CAE0220FFF7E1 +:100E2000E7FC00283FF496AE049800F0CFFEEAE716 +:100E30000220FFF7DDFC00283FF48CAE00F0DEFE60 +:100E4000E1E70220FFF7D4FC00283FF483AE05A9B8 +:100E5000142000F0D9FE07460421049004A800F0F5 +:100E600053FE3946B9E7322000F030FE071EFFF688 +:100E700071AEBB077FF46EAE384A07EB0903926888 +:100E800093423FF667AE0220FFF7B2FC00283FF422 +:100E900061AE27F003074F44B9453FF4A5AE48467D +:100EA00009F1040900F062FE0421059005A800F094 +:100EB0002BFEF1E74FF47A70FFF79AFC00283FF41D +:100EC00049AE00F08BFE002844D00A9B01330BD0C2 +:100ED00008220AA9002000F005FF00283AD02022AD +:100EE000FF210AA800F0F6FEFFF78AFC1C4804F078 +:100EF000D7FB13B0BDE8F08F002E3FF42BAE0BF004 +:100F00000B030B2B7FF426AE0023642105A8059369 +:100F100000F0F0FD074600287FF41CAE0220FFF72A +:100F200067FC804600283FF415AEFFF769FC41F2EC +:100F3000883004F0B5FB059800F062FF46463C4659 +:100F400000F014FFA0E506464EE64FF0000901E66A +:100F5000BA467EE637467CE6EC22002000220020DE +:100F6000A0860100094A49F26900136899B21B0C76 +:100F700000FB013344F250611360054B186882B2E4 +:100F8000000C01FB0200186080B2704714220020A0 +:100F9000102200200021102210B5044600F09AFE15 +:100FA000034B03CB206061601868A06010BD00BFD8 +:100FB00000E8F11F2DE9F041ADF5527D0D4600210D +:100FC00040F2751270AC074612A8119100F082FE33 +:100FD0004FF4C4720021204600F07CFE0DF144085D +:100FE00002F0C6FA4FF47A72264BB0FBF2F01860AA +:100FF00093E80700022384E807000DF5F1702382CF +:10100000FFF7C8FF47F605031F4907A8238406F02A +:1010100033FC25230DF2F3220DF13C0C84F8323120 +:1010200007AB1E46083203CE664542F8080C42F86C +:10103000041C3346F5D130684146106020463379B0 +:101040001371012200F0FEFE002380B2E97E0393BB +:10105000AB7E029305F1190301930123009307A3CB +:10106000D3E90023CDE90480384602F03FFE0DF5B8 +:10107000527DBDE8F08100BFAFF300809E6AC421BD +:10108000818A46EEF8230020887800082DE9F04197 +:101090002C4CDAB080460D46237A5BBB27A9284644 +:1010A00000F0DEFF0746002842D19DF89D60C82E63 +:1010B0003ED801464FF4A662204600F00BFE4FF4E6 +:1010C000807332460DF19E01C4F8F8314FF400737D +:1010D00004F109002644C4F80C334FF44073C4F8FB +:1010E000203400F0D1FD9DF89C30777223720BB94B +:1010F000EB7E237206AC8122002127A800F0EAFDD6 +:101100000122214627A800F0E7FF002380B2E97EF4 +:101110000393AB7E029305F1190301932823CDE9D4 +:1011200004400093404605A3D3E9002302F0DEFD0E +:101130005AB0BDE8F08100BFAFF300802641727263 +:10114000DF25D7B7A05D0020F0B5254E4FF48A7596 +:10115000F1B0002405FB006596F8D830D82221466E +:1011600085F8DC303AA885F8E84006AF00F0B2FD1B +:1011700006F1090000F0A6FDD5F8E430C2B206F190 +:1011800009018DF8F0000DF1F100CDE93A3400F0DD +:101190007BFD394601223AA800F0CAFF082380B23D +:1011A000317ACDE9047001270E48CDE9023706F106 +:1011B000D80301933023009307A3D3E9002302F05F +:1011C00095FDA04206DD02F0D3F9C5F8E0003846EF +:1011D00071B0F0BD2046FBE778F6339F93CACD8D02 +:1011E000A05D0020103400202DE9F04F274F87B07C +:1011F000DFF8A480264E384602F0A4FD03460028FE +:101200003CD00024234DADF81440A1460294A246E0 +:10121000CDE90344027B8DF8142003AA9968406845 +:1012200003C21B6843F0004302932B6804F22C5462 +:10123000D3F810B002F09EF910EB0802CDF800A030 +:10124000284605F5A55541F1000302A9D84740F607 +:1012500058230028C8BF49F0010910359C42E4D149 +:10126000B9F1000F05D0384602F070FD86F800A0F5 +:10127000C1E73378072B04D80133337007B0BDE8DA +:10128000F08F024802F062FDF8E700BF1034002042 +:10129000D56200204034002040420F0070B50D465A +:1012A00014461E4602F07EFC50B9022E10D1012CCD +:1012B0000ED112A3D3E900230120C5E9002307E0E2 +:1012C000282C10D005D8012C09D0052C0FD00020D7 +:1012D00070BD302CFBD10BA3D3E90023ECE70BA3AB +:1012E000D3E90023E8E70BA3D3E90023E4E70BA34A +:1012F000D3E90023E0E700BFAFF30080401DA12049 +:1013000026812A0B78F6339F93CACD8D9E6AC4211D +:10131000818A46EE26417272DF25D7B7F017304A30 +:1013200039059E5638B505460E4C0021013500F0B2 +:1013300043FCA4F82C55B4F82C0500F025FC78B13A +:10134000B4F82C0500F030FC014648B9B4F82C057F +:1013500000F032FCB4F82C350133A4F82C35EAE760 +:1013600038BD00BFA05D0020F8B50E4C02260E4F20 +:10137000A4F5805343F8307C237E3BB965692DB1D9 +:10138000284600F0CBFF284606F02CFA2046A4F5AC +:10139000A55400F0C3FF012EA4F1100400D1F8BD44 +:1013A0000126E5E720590020507900082DE9F04F8B +:1013B0008FB005460C4600AF02F0F4FB002849D17F +:1013C000237E022B1BD1E38A012B18D102F0D0F827 +:1013D0000646FFF7C7FD03464FF4C87006F51676BC +:1013E000DFF8C082B3FBF0F202FB103316FA83F38E +:1013F000C8F80030E37E33B9A34B00221A703C37A3 +:10140000BD46BDE8F08F07F12401204600F0E6FD5F +:101410000028F4D107F11400FFF7BCFD97F826402F +:1014200007F1140107F12700224606F0F3F900281E +:10143000E2D10F2C08D8944B1C70D8F80030A3F5DB +:101440001673C8F80030DAE797F82410284602F03F +:10145000A1FBD4E7E38A282B2BD010D8012B23D073 +:10146000052BCCD1BFF34F8F8849894BCA6802F452 +:10147000E0621343CB60BFF34F8F00BFFDE7302B1B +:10148000BDD1844EE17E327A9142B8D1607E314640 +:10149000002291F8DC50854200F0A580013201F570 +:1014A0008A71042AF5D1AAE721462846FFF782FD72 +:1014B000A5E721462846FFF7E9FDA0E7B2F8EC5082 +:1014C0007B6005F103094FEA99094FEA8902D11DB2 +:1014D000C908A8EBC10300219D46EB46584600F021 +:1014E000F9FB04F1EE012A465846314400F0CCFBEA +:1014F0007B6813B9012000F037FB96F8D20000F0AA +:1015000043FB044630B9307200F068FB204600F01F +:101510002BFBB1E0D6F8D4203AB996F8D200B6F851 +:101520002C25824201D8FFF7FDFED6F8D4202A44AC +:10153000944208D296F8D200B6F82C2501308242A7 +:1015400001D8FFF7EFFE5FFA89F25946706800F0A4 +:10155000C9FB08B9C54679E0726896F8D2002A44FA +:101560007260D6F8D42005EB0209C6F8D49000F0DA +:101570000BFB814509D396F8D220D6F8D40001326E +:10158000001B86F8D220C6F8D400FF2D0FD8002407 +:10159000347200F023FB204600F0E6FA00F044FE2F +:1015A0003D4B188108B9FFF789F9C54627E7BB68A5 +:1015B00096F8D9000AFB0362FB68D2F8E41082F8BF +:1015C000E83001F58061C2F8E030C2F8E410FFF7BE +:1015D000BBFDFFF709FE96F8D920013202F00302A5 +:1015E00086F8D920B6E74FF48A7A20460AFB02F53E +:1015F00005F1EA01314400F0C7FDF86000287FF4EE +:10160000FEAE0122354485F8E82001F0B1FFD5F89F +:10161000E020D6ED007A801A40F6B832B8EE677A4C +:10162000DFED1E6A192838BF1920904228BF1046E6 +:1016300007EE900AF8EEE77A67EEA67ADFED186A11 +:10164000E7EE267AFCEEE77AC6ED007A96F8D93016 +:10165000BB60BA6873680AFB02F4321992F8E810AA +:1016600059B1D2F8E410E8468B423FF427AF00218D +:1016700082F8E810C2F8E010C5467368064A9B0A73 +:1016800001331381BBE600BF0934002000ED00E008 +:101690000400FA05A05D0020F8230020CDCCCC3D4D +:1016A0006666663F0C340020014B1870704700BF1F +:1016B0000424002038B54FF04054144B22689A425D +:1016C00021D1627D0025124B12481A70C922237D58 +:1016D0000930114900F8013C4FF48073C0F8DB5029 +:1016E000C0F8EF314FF40073C0F803334FF4407388 +:1016F000C0F8173400F0C8FAE0222946204600F06E +:10170000E9FA012038BD0020FCE700BF9AAD44C5CE +:1017100004240020A05D00201600003037B500F042 +:1017200083FD1F4C1F4D022301221F496B7123684B +:101730002881204604F580545B6898470122D4F83C +:10174000B03404F5966018495B6898470023174940 +:101750004FF480520193164B16480093164B02F03B +:10176000F1F9164B197811B1124802F013FA01F091 +:10177000FFFE0446FFF7F6FB4FF4C873B0FBF3F22D +:1017800002FB130304F5167010FA83F00C4B18607B +:1017900004F090FC08B10F232B8103B030BD00BFD3 +:1017A00040340020F823002040420F00082400208D +:1017B0009D12000810340020AD13000804240020FE +:1017C0000C3400202DE9F04F00252DED028B93B055 +:1017D0000DF12C084FF0010ADFF814B2FFF704FDF9 +:1017E0000A95ADF834500B95C8F804509FED798BED +:1017F00000267E4C374623680DF11D0207A92046BE +:101800008DF81CA08DF81D508DED008BD3F808903D +:101810000023C8479DF81C90B9F1000F1ED010227C +:1018200000210EA800F056FA236808AA0AA95F69E9 +:1018300020460DF11E03B8470FAB4F4698E8030052 +:1018400083E803009DF834300EA958468DF84430E3 +:101850000A9B0E93DDE9082302F056FC06F22C5693 +:1018600040F6582304F5A5549E4204F11004C2D159 +:10187000002FBDD15E4802F095F900283FD15D4EA2 +:1018800001F076FE3368984239D301F071FE0446C8 +:10189000FFF768FB4FF4C8738DF82870B0FBF3F2C4 +:1018A00002FB130304F5167010FA83F03060524EF9 +:1018B000377817B901238DF82830C7F110040EA826 +:1018C000FFF768FB0EABE4B20DF12900D919062C25 +:1018D00028BF06242246013400F0D6F90AABE4B250 +:1018E00043480393182304940293444B0193012328 +:1018F00000933AA3D3E9002302F09AF9357001F07E +:1019000037FE3F4A3F4C1368C31AB3F57A7F2FD393 +:10191000106001F02FFE02460B46354802F020FA17 +:10192000334802F03FF918B3237A0EAF364E002B3E +:1019300014BF03230223737101F01AFE4FF47A736C +:1019400001223946B0FBF3F03060304600F01EFB58 +:10195000182380B202932D4B019340F25513CDE929 +:101960000370009322481FA3D3E9002302F060F91B +:10197000237A93B101F0FCFD002607464FF48A78E4 +:1019800094F8D900304400F0030008FB004393F8BA +:10199000E82072B10136042EF2D1C82003F080FE97 +:1019A000237A002B7FF414AF13B0BDEC028BBDE89B +:1019B000F08FD3F8E02042B12368BA1AFA2B38BF6F +:1019C000FA230533B2EB430FE4D3FFF7BDFB002846 +:1019D000E0D1E2E70000000000000000401DA1206F +:1019E00026812A0BF1C6A7C1D068080F4034002019 +:1019F000103400200C34002009340020083400206A +:101A0000D0620020A05D0020F8230020D4620020D6 +:101A100008B5064801F0B6F8054801F0B3F8054AE4 +:101A200005490020BDE8084005F0D6BE403400203E +:101A3000F048002030630020691300087047000060 +:101A40002DE9F84F4FF47A7306460D46002402FB49 +:101A500003F7DFF85080DFF8509098F900305FFA14 +:101A600084FA5A1C01D0A34212D159F824002A4604 +:101A700031460368D3F820B03B46D847854207D1AA +:101A8000074B012083F800A0BDE8F88F0124E4E7AC +:101A9000002CFBD04FF4FA7003F002FE0020F3E7B5 +:101AA0001C630020182200201C22002070B5044670 +:101AB0004FF47A76412C254628BF412506FB05F0D8 +:101AC00003F0EEFD641BF5D170BD0000002307B5E7 +:101AD000024601210DF107008DF80730FFF7B0FF36 +:101AE00020B19DF8070003B05DF804FB4FF0FF3014 +:101AF000F9E700000A46042108B5FFF7A1FF80F0CE +:101B00000100C0B2404208BD074B0A4630B4197804 +:101B1000064B53F82140014623682046DD69044BFB +:101B2000AC4630BC604700BF1C6300201C22002074 +:101B3000A086010070B50A4E00240A4D04F0CEF8CC +:101B4000308028683388834208D904F0C3F82B68B2 +:101B500004440133B4F5003F2B60F2D370BD00BFE5 +:101B60001E630020D862002004F086B900F10060F6 +:101B700000F500300068704700F10060920000F549 +:101B8000003004F007B90000054B1A68054B1B88AC +:101B90009B1A834202D9104404F09CB8002070477D +:101BA000D86200201E630020024B1B68184404F01A +:101BB00097B800BFD8620020024B1B68184404F09D +:101BC000A1B800BFD86200200020704700F1FF508C +:101BD00000F58F10D0F8000870470000064991F812 +:101BE000243033B100230822086A81F82430FFF73B +:101BF000C3BF0120704700BFDC620020014B1868A2 +:101C0000704700BF0010005C194B013803220844E4 +:101C100070B51D68174BC5F30B042D0C1E88A6422A +:101C20000BD15C680A46013C824213460FD214F97C +:101C3000016F4EB102F8016BF6E7013A03F10803B8 +:101C4000ECD181420B4602D22C2203F8012B042452 +:101C5000094A1688AE4204D1984284BF967803F8A8 +:101C6000016B013C02F10402F3D1581A70BD00BFB0 +:101C70000010005C24220020DC780008704700007F +:101C80007047000070470000002310B5934203D056 +:101C9000CC5CC4540133F9E710BD0000013810B525 +:101CA00010F9013F3BB191F900409C4203D11AB1B8 +:101CB0000131013AF4E71AB191F90020981A10BDE8 +:101CC0001046FCE703460246D01A12F9011B002910 +:101CD000FAD1704702440346934202D003F8011B35 +:101CE000FAE770472DE9F8431F4D1446074688462A +:101CF00095F8242052BBDFF870909CB395F82430FF +:101D00002BB92022FF2148462F62FFF7E3FF95F809 +:101D100024004146C0F1080205EB8000A24228BF22 +:101D20002246D6B29200FFF7AFFF95F82430A41BED +:101D300017441E449044E4B2F6B2082E85F824609D +:101D4000DBD1FFF74BFF0028D7D108E02B6A03EB6C +:101D500082038342CFD0FFF741FF0028CBD1002080 +:101D6000BDE8F8830120FBE7DC620020024B1A7813 +:101D7000024B1A70704700BF1C630020182200201D +:101D800038B51A4C1A4D204602F0A8FF29462046C5 +:101D900002F0D0FF2D684FF47A70D5F89020D2F879 +:101DA000043843F00203C2F80438FFF77FFE1149FC +:101DB000284603F0CDF8D5F890200F4DD2F804381E +:101DC000286823F002030D49A042C2F804384FF4FA +:101DD000E1330B6001D002F0DFFE6868A04204D05E +:101DE0000649BDE8384002F0D7BE38BD106A002071 +:101DF0007C7A0008847A00081C22002004630020FA +:101E00000C4B70B50C4D04461E780C4B55F8262033 +:101E10009A420DD00A4B002118221846FFF75AFFAC +:101E20000460014655F82600BDE8704002F0B4BEDB +:101E300070BD00BF1C6300201C220020106A00201F +:101E4000046300202DE9F0470D460446002190462A +:101E5000284640F27912FFF73DFF23462022002159 +:101E6000284604F1220702F0F1F8231D0222202166 +:101E70002846C02602F0EAF8631D032222212846E4 +:101E800002F0E4F8A31D03222521284602F0DEF823 +:101E900004F1080310222821284602F0D7F804F1A3 +:101EA000100308223821284602F0D0F804F111036B +:101EB00008224021284602F0C9F804F11203082242 +:101EC0004821284602F0C2F804F1140320225021D0 +:101ED000284602F0BBF804F118034022702128467E +:101EE00002F0B4F804F120030822B021284602F0E1 +:101EF000ADF804F121030822B821284602F0A6F823 +:101F0000314608363B4608222846013702F09EF843 +:101F1000B6F5A07FF4D1002704F1330A04F13203AF +:101F200008223146284602F091F894F832304FEA00 +:101F3000C7099F4209F5A47615D3B8F1000F08D15F +:101F4000314609F24F1604F599730722284602F02C +:101F50007DF827463B1B94F8322193420CD3F01DA9 +:101F6000C008BDE8F0870AEB07030822314628467F +:101F7000013702F06BF8D8E707F233133146082235 +:101F800028460836013702F061F8E3E713B5044646 +:101F9000084600212022234601900160C0F803106A +:101FA00002F054F8231D01980222202102F04EF87D +:101FB000631D01980322222102F048F8A31D019815 +:101FC0000322252102F042F8019804F108031022AF +:101FD000282102F03BF8072002B010BD0023F7B51E +:101FE0000E46047F072200911946054601F0F2FED5 +:101FF000731C0122072100932846002301F0EAFE0A +:10200000C4B9B31C052208212846009323460D2499 +:1020100001F0E0FE3746BB1BB278934211D3073480 +:102020002B7FA88AE408BBB9844294BF002001201A +:1020300003B0F0BDAB8A0824DB00083BDB08B370BB +:10204000E8E7FB1C214608222846009300230834B9 +:10205000013701F0BFFEDEE7201A18BF0120E7E7D5 +:102060000023F7B50E46047F082200911946054665 +:1020700001F0B0FE731CC4B908220093234610245B +:102080001146284601F0A6FE01235F1C7278013B31 +:10209000934211D307342B7FA88AE408BBB984424A +:1020A00094BF0020012003B0F0BDAB8A0824DB0000 +:1020B000083BDB087370E7E7F3192146082228463E +:1020C0000093002301F086FE08343B46DDE7201A2A +:1020D00018BF0120E7E70000F8B50E460546144694 +:1020E000002181223046FFF7F5FD2B460822002112 +:1020F000304601F0ABFF7CB90F246B1C072208218E +:10210000304601F0A3FF01235F1C6A78013B934234 +:1021100004D3E01DC008F8BD0824F4E7EB192146FC +:102120000822304601F092FF08343B46ECE70000FD +:10213000F8B50E46054614460021CE223046FFF77C +:10214000C9FD2B4628220021304601F07FFF7CB9D3 +:10215000302405F1080308222821304601F076FFDB +:102160002F467B1B2A7A934204D3E01DC008F8BD9A +:102170002824F5E707F109032146082230460834F0 +:10218000013701F063FFECE7F7B5047F0E460091DD +:10219000012310220021054601F01CFEC4B9B31C26 +:1021A00009221021284600932346192401F012FE2B +:1021B00037467288BB1B9A4211D807342B7FA88AF6 +:1021C000E408BBB9844294BF0020012003B0F0BDF5 +:1021D000AB8A1024DB00103BDB087380E8E73B1D73 +:1021E000214608222846009300230834013701F0D5 +:1021F000F1FDDEE7201A18BF0120E7E730B50A44F9 +:10220000084D91420DD011F8013B5840082340F38E +:102210000004013B2C4013F0FF0384EA5000F6D188 +:10222000EFE730BD2083B8EDF7B5364A6B4610684E +:1022300051686A4603C308233349344805F0FAFA63 +:10224000044690BB0A25324A6B46106851686A46BC +:1022500003C308232F492D4805F0ECFA0446002853 +:1022600047D00369B3F5F01F43D8B0F86620B2F544 +:10227000AF6F3ED1284A024402F15C018B4238D351 +:102280005C3B224900209E1AFFF7B8FF04F164016D +:10229000074632460020FFF7B1FFA3689F4228D1CE +:1022A000E368984208BF002523E00369B3F5F01FF7 +:1022B00026D8428BB2F5AF6F20D1174A024402F103 +:1022C00010018B4218D3103B104900209D1AFFF7D4 +:1022D00095FF04F1180106462A460020FFF78EFFFD +:1022E000A3689E4202D1E368984201D00D25AAE777 +:1022F0000025284603B0F0BD1025A4E70C25A2E771 +:102300000B25A0E7EC780008DCFF1D0000000208A8 +:10231000F578000890FF1D000800FEF710B5037C5B +:10232000044613B9006805F06DFA204610BD0000A0 +:102330000023BFF35B8FC360BFF35B8FBFF35B8F83 +:102340008360BFF35B8F7047BFF35B8F0068BFF3A1 +:102350005B8F704770B505460C30FFF7F5FF0446FC +:1023600005F108063046FFF7EFFFA04206D96D6879 +:102370003046FFF7E9FF2544281A70BD3046FFF7C5 +:10238000E3FF201AF9E7000070B505464068A0B1E8 +:1023900005F10C0605F10800FFF7D6FF04463046AC +:1023A000FFF7D2FF844204F1FF34304694BF6D68DA +:1023B0000025FFF7C9FF2C44201A70BD38B50C4624 +:1023C0000546FFF7C7FFA04210D305F10800FFF74D +:1023D000BBFF04446868BFF35B8FB4FBF0F100FB04 +:1023E00011440120AC60BFF35B8F38BD0020FCE7D7 +:1023F0002DE9F041144607460D46FFF7C5FF84421C +:1024000028BF0446D4B1B84658F80C6B4046FFF7D5 +:102410009BFF3044286040467E68FFF795FF331AE3 +:102420009C4203D801206C60BDE8F081A41B6B6066 +:102430003B682044AB60E8600220F5E72046F3E704 +:1024400038B50C460546FFF79FFFA04210D305F1B3 +:102450000C00FFF779FF04446868BFF35B8FB4FB9F +:10246000F0F100FB11440120EC60BFF35B8F38BD3D +:102470000020FCE72DE9FF418846694607466C4687 +:10248000FFF7B6FF002506B204EBC606B4420AD039 +:10249000626808EB050120680834FFF7F5FB54F883 +:1024A000043C1D44F2E729463846FFF7C9FF284699 +:1024B00004B0BDE8F0810000F8B505460C300F46C9 +:1024C000FFF742FF05F1080604463046FFF73CFFE0 +:1024D000A042304688BF6C68FFF736FF201A38608C +:1024E00020B12C683046FFF72FFF2044F8BD0000D4 +:1024F00073B5144606460D46FFF72CFF8442019043 +:1025000028BF0446DCB101A93046FFF7D5FF019B87 +:1025100033B93268C5E90233C5E9002401200CE073 +:102520009C42286038BF0194019884426860F5D9C4 +:102530003368241A0220AB60EC6002B070BD204604 +:10254000FBE700002DE9FF410F4669466C46FFF7A7 +:10255000CFFF00B2002604EBC005AC4209D0D4F88E +:102560000480B81954F8081B42464644FFF78CFB18 +:10257000F3E7304604B0BDE8F081000038B5054609 +:10258000FFF7E0FF044601462846FFF717FF204605 +:1025900038BD0000302383F3118862B67047000015 +:1025A000002383F3118862B6704700000120704752 +:1025B0007047000010B41346026814680022A44655 +:1025C0005DF8044B6047000000F5805090F8590416 +:1025D0007047000000F5805090F8520470470000EA +:1025E00000F5805090F95804704700004E20704765 +:1025F00000F5805208B5FFF7CDFFD2F89834D2F835 +:1026000094041844D2F890341844D2F8783418441A +:10261000D2F888341844D2F884341844FFF7C0FF45 +:1026200008BD00002DE9F04F0C4600F5805185B043 +:102630001F4691F8523405469046BDF838909BB13C +:10264000D1F874340133C1F8743423689A0006D485 +:10265000237B082B0BD9627B0AB10F2B07D9D1F84A +:1026600078340133C1F878344FF0FF300FE0FFF7D2 +:1026700091FFEB6AD3F8C42012F4001A0AD0D1F803 +:102680007C3400200133C1F87C34FFF789FF05B0AA +:10269000BDE8F08F22684FF0480BD3F8C460002AE1 +:1026A0006B6AC6F30446B4BF42F0804292041BFB3F +:1026B000063BCBF8002023685B004FEA066344BF6B +:1026C00042F00052CBF80020227B43EA0243720121 +:1026D000CBF80430607B18B343F44013CBF80430DC +:1026E000D1F8A4340133C1F8A434AB1803F58353F3 +:1026F000197B41F020011973207B039200F094FFB5 +:102700000330039A80105FFA8AF30AF1010A8342C8 +:102710000DDA04EB83010BEB830349689960F2E760 +:10272000AB1803F58353197B60F34511E3E70121EF +:10273000EB6A04F10C00B140C3F8D010AB1821468D +:1027400003F58253C3E9048705EB461303F582536F +:10275000183351F804CB814243F804CBF9D10988EE +:102760002A442846198041F26803D65002F5805267 +:1027700009F0030392F86C1043F0100321F01F01DD +:102780000B43214682F86C304246FFF709FF3B4677 +:10279000CDF8009000F00EFF012078E72DE9F0471A +:1027A00000F58056044696F85254002D40F0018101 +:1027B000037C032B40F092802B4628462F465FFA7D +:1027C00083FC944510DA01EBCC0E51F83CC0BCF10F +:1027D000000F04DBDEF804C0BCF1000F02DB0137A0 +:1027E0000133ECE70130FBE7FFF7D4FEE36AF0B911 +:1027F000D3F8800040F00200C3F880004E23E06A66 +:10280000002F6ED1D0F8803043F00103C0F8803043 +:10281000694B6A4A1B6803F1805303F52C539B00F4 +:102820009342A36240F2AF80654800F09BFE4D28C2 +:1028300042D8DFF884814FEA004EDFF88891D8F85B +:1028400000C04EEA8C0EC3F884E00CF1805303F50F +:102850002C539B00636100EB0C03D4F82CC0C8F828 +:102860000030C0F14E03DCF8800040F03000CCF8BE +:1028700080004FF0000CD4F81480E6465FFA8CF02C +:102880008242BCDD01EBC00A51F83000002810DBA9 +:10289000DAF804A0BAF1000F0BDA09EA00400AF0F6 +:1028A0007F0A40EA0A0040F0084048F82E000EF186 +:1028B000010E0CF1010CE1E79A6922F001029A6124 +:1028C00000F056FE0646E36A9B69D90704D500F07E +:1028D0004FFE831BFA2BF6D9FFF762FE2846BDE8B0 +:1028E000F087B7EB530F3DD2DFF8CCE04FEA074C4F +:1028F000DEF800304CEA830CC0F888C003F1805049 +:1029000003EB4703002700F52C50CEF80030BC46FF +:102910008000A061E06AD0F8803043F00C03C0F87A +:102920008030D4F818E0FBB29A427FF771AF51F8CB +:10293000330001EBC3080028D8F8043001DB002B7A +:102940000EDB20F0604023F0604340F0005043F085 +:1029500000434EF83C000EEBCC000CF1010C436040 +:102960000137E0E7836923F00103836100F000FE93 +:102970000646E36A9B69DA07AED500F0F9FD831BD2 +:10298000FA2BF6D9A8E7E26A936923F00103936171 +:1029900000F0EEFD0746E36A9B69DB0705D500F012 +:1029A000E7FDC31BFA2BF6D996E7012586F85254AA +:1029B00092E7002592E700BF2C630020FCB50040A1 +:1029C000007900080000FF0713B500F5805401915D +:1029D000606CFFF7D9FC1F280AD920220199606C8E +:1029E000FFF748FDA0F120035842584102B010BD46 +:1029F0000020FBE700F5805008B5FFF7CBFD406CE9 +:102A0000FFF796FCBDE80840FFF7CABD0022026050 +:102A100082814260826070470022002310B5C0E9C5 +:102A20000023002304460C3020F8043CFFF7EEFF9F +:102A3000204610BD2DE9F047074688B09A468846E3 +:102A400007F5805468469146FFF7A4FDFFF7E4FFC1 +:102A5000606CFFF77FFC1F282DD920226946606C2F +:102A6000FFF78CFD202826D194F852341BB303AD18 +:102A7000444605AB2E46083403CE9E4244F8080C6B +:102A800044F8041C3546F5D130684146206038468C +:102A9000B388A380DDE90023C9E90023BDF808302D +:102AA0004A46AAF80030FFF77BFD534608B0BDE860 +:102AB000F04700F06DBD0020FFF772FD08B0BDE8E3 +:102AC000F08700002DE9F84F0023064600F58154F9 +:102AD000054688461034C0E90133274B46F8303BA1 +:102AE000374638462037FFF797FFA742F9D105F55B +:102AF00080544FF4805305F5A3594FF0000A266324 +:102B00000026676405F5835709F110094FF0000BA3 +:102B10001037E663C4E90D36012384F8403084F8A9 +:102B20004830A7F11800203747E910ABFFF76EFFD8 +:102B300047F8286C4F45F4D1B8F1010F84F8588458 +:102B4000A4F85A64A4F85C64A4F85E6484F8606431 +:102B5000A4F86264A4F86464A4F8666484F8686401 +:102B600002D9064800F0FEFC054B284653F82830F1 +:102B7000EB62BDE8F88F00BF5079000824790008A7 +:102B800040790008044B10B5197804464A1C1A70A5 +:102B9000FFF798FF204610BD296300202DE9F0477C +:102BA00000295FD0304F3148B7FBF1F581428CBF2F +:102BB0000A201120431EB5FBF0FC00FB1C50DCB2C8 +:102BC00020B1022B1846F5D8002037E00CF1FF3574 +:102BD000B5F5806F32D2C4EBC4094FF47A7009F1B5 +:102BE00003034FEAE308C3F3C70308F1010AA4EBA8 +:102BF000030E08FB00085FFA8EF65AFA8EFEB8FB49 +:102C0000FEFEBEF5617F1BDC1FFA8EF4581C56FADF +:102C100080F00CFB00FCB7FBFCFC6145D4D1013B10 +:102C2000DBB20F2BD0D8711E0020C9B2072905D8FE +:102C3000107101201480558053719171BDE8F087A7 +:102C400009F1FF334FEAE30EC3F3C7030EF10108A6 +:102C5000E41A0EFB0000E6B258FA84F4B0FBF4F478 +:102C6000A4B2D3E70846E9E700B4C4043F420F002A +:102C700038B540F27772C36A154CC3F8BC200722FE +:102C8000C36AC3F8C8202268C16A930043F4C02312 +:102C9000C1F8A03002F1805302F16C01C56A03F55E +:102CA0002C53EA3289009B00226041F0E061094A1E +:102CB000C361C5F8C01003F5D87103F56A734162AA +:102CC0009342836202D9044800F04CFC38BD00BF37 +:102CD0002C630020FCB50040007900082DE9F04F7E +:102CE00000F58055994689B0044695F858348A46CF +:102CF0009046022B04D90027384609B0BDE8F08F72 +:102D00009B4A52F8231009B942F823009949C4F8A4 +:102D10000CA00B7884F81090C3B9FFF73BFC964BDE +:102D2000D3F8EC2042F48072C3F8EC20D3F894205E +:102D300042F48072C3F89420D3F8942022F4807275 +:102D4000C3F8942001230B70FFF72AFC95F8513447 +:102D50006BB9FFF71FFC894A95F85834D35CEBB187 +:102D6000012B24D0012385F85134FFF719FCFFF71C +:102D700011FCE26A936923F01003936100F0F8FB01 +:102D80000746E36A9E6916F0080617D000F0F0FBCC +:102D9000C31BFA2BF5D9FFF703FCACE70321132083 +:102DA00001F044FD0321152001F040FDDAE7032185 +:102DB000142001F03BFD03211620F5E79A6942F04B +:102DC00001029A6100F0D4FB0746E36A9A69D007D2 +:102DD00005D400F0CDFBC31BFA2BF6D9DBE79A69CB +:102DE000002704F5825B42F002020BF1100B9A619E +:102DF000E36A5F65FFF7D4FB686CFFF799FA20225E +:102E000000216846FEF766FF02A8FFF7FFFD6A464D +:102E10000BEB06030DF1180E069794460833BCE839 +:102E20000300F44543F8080C43F8041C6246F4D14F +:102E3000DCF8000020361860B6F5806F9CF804209E +:102E40001A71DCD1002304F5A252514620461A32F1 +:102E500085F8503485F85334FFF7A0FE074690B943 +:102E6000E26A936923F00103936100F081FB054658 +:102E7000E36A9B69D9077FF53EAF00F079FB431BFE +:102E8000FA2BF5D937E795F85F6495F85E2436029A +:102E9000C5F86CA4E36A46EA426695F860241643D6 +:102EA000B5F85C2446EA0246DE61B8F1000F29D08D +:102EB00004F5A352414620460232FFF76FFE90B957 +:102EC000E26A936923F00103936100F051FB054628 +:102ED000E36A9B69DA077FF50EAF00F049FB431BFD +:102EE000FA2BF5D907E795F8683495F867141B01B4 +:102EF000C5F87084E26A43EA0123B5F8641443EA32 +:102F00000143D360E36A00262046C3F8BC60FFF7A4 +:102F1000AFFE85F859646FF04042E36A1A65184ABB +:102F2000E36A5A654FF00222E36A9A654FF0FF3276 +:102F3000E36AC3F8E0200322E36A9145DA653FF4CF +:102F4000DBAEE26A936923F00103936100F010FBAA +:102F50000646E36A9B69DB0705D500F009FB831B86 +:102F6000FA2BF6D9C7E6012385F85234C4E600BF30 +:102F700020630020286300200044025838790008AC +:102F8000550200022DE9F04F054689B0904699465A +:102F9000002741F2680A00F58056EB6AD3F8D83072 +:102FA000FB40D8074AD505EB47124FEA471B52446E +:102FB0001379190742D4D6F880340133C6F8803427 +:102FC00013799A0605EB0B0248BFD6F8A834524491 +:102FD00044BF0133C6F8A834137943F008031371D2 +:102FE000DB0723D596F8533403B305F582546846BE +:102FF000FFF712FD03AB18345C4404F1080C2068A1 +:10300000083454F8041C1A46644503C21346F6D12A +:103010002068694610602846A2889A800123ADF88E +:1030200008302B68CDE90089DB6B9847D6F854341B +:1030300023B1D6F89C340133C6F89C340137202FD5 +:10304000ABD109B0BDE8F08F2DE9F04F0F468DB040 +:10305000044600F08FFA82468946002F5BD1E36A6E +:10306000D3F8A02012F4FE0F03D100200DB0BDE86C +:10307000F08FD3F8A420920141BF04F58051D1F81C +:1030800094240132C1F89424D3F8A4205606ECD03D +:10309000D3F8A450E669C5F305254823E8464FF068 +:1030A000000B03FB05664046FFF7B0FC3268510099 +:1030B0004ABF22F06043C2F38A4343F000439200C8 +:1030C00048BF43F080430093736813F400131BBFA1 +:1030D000012304F580528DF80D308DF80D301EBFA0 +:1030E000D2F8AC340133C2F8AC34F38803F00F03E8 +:1030F0008DF80C309DF80C0000F096FA5FFA8BF317 +:10310000984225D9F2180CA90BF1010B127A0B4445 +:1031100003F82C2CEEE7012FA7D1E36AD3F8B020F7 +:1031200012F4FE0FA1D0D3F8B420950141BF04F5ED +:103130008051D1F894240132C1F89424D3F8B420FA +:10314000500692D0D3F8B450266AC5F30525A4E7FB +:10315000EFB9E36AC3F8A85004A807ADFFF75CFC19 +:1031600098E80F0007C52B800023204604A9ADF87E +:103170001830236804F58054DB6BCDE904A9984727 +:1031800058B1D4F88C340133C4F88C346EE7012F75 +:10319000E2D1E36AC3F8B850DEE7D4F890340120F6 +:1031A0000133C4F8903461E7F8B505460F4600F5E1 +:1031B0008054012639462846FFF746FF10B184F8AF +:1031C0005364F7E7D4F8543423B1D4F89C34013372 +:1031D000C4F89C34F8BD0000C36AF0B51A6C12F450 +:1031E0007F0F2BD01B6C00F5805441F268054FF027 +:1031F000010CC4F8A0340023471900EB43125E0110 +:103200002A44117911F0020F15D0490713D4B95986 +:10321000C66A0CFA01F1D6F8CCE011EA0E0F0AD01A +:10322000C6F8D410117941F004011171D4F8882442 +:103230000132C4F888240133202BDED1F0BD000018 +:103240002B4B70B51E561B5C012B30D8294D2A4ADA +:1032500055F8233052F8264013B349B3236D9A052D +:1032600010D54FF40073236500F084F950EA010291 +:103270000B4602D0013861F10003024655F82600E2 +:10328000FFF780FE236D9B012CD54FF0007255F89F +:103290002630226503F58053012283F8592421E06A +:1032A00001232365102323654FF48053236570BDEC +:1032B000236DDA0702D4236D5B0706D505230021B1 +:1032C00055F826002365FFF76FFF236DD80602D45B +:1032D000236D590606D55023012155F82600236594 +:1032E000FFF762FF55F82600BDE87040FFF774BF96 +:1032F0003C790008206300204079000808B5FFF7FA +:1033000049F9FFF769FFBDE80840FFF749B9000038 +:10331000C36AD3F8C00010F07C5005D0D3F8C400C5 +:1033200080F40010C0F340507047000000F580505A +:1033300008B5FFF72FF9406CFFF70CF8FFF730F9ED +:1033400043090CBF0120002008BD000000F5805398 +:1033500093F8592462B1C16A8A6922F001028A6134 +:10336000D3F898240132C3F89824002283F8592412 +:10337000704700002DE9F74300F58251984600257B +:10338000FFF708F9103141F2680E4FF0010900F51E +:10339000805C00EB4514744423795E071CD4DB0683 +:1033A0001AD58E69C36A09FA06F6D3F8CC703E4284 +:1033B00012D04F6801970F689742019F77EB08077B +:1033C0000AD2C3F8D460237943F004032371DCF8F4 +:1033D00084340133CCF8843401352031202DD8D108 +:1033E00003B0BDE8F043FFF7DBB80000F8B51E46B8 +:1033F00000230F46054613701446FFF797FF80F031 +:10340000010038701EB12846FFF782FF2070F8BD1A +:103410002DE9F04F85B099460D468046164691F845 +:1034200000B0DDE90EA302931378019300F0A2F837 +:103430002B7804460F4613B93378002B42D022462E +:103440003B464046FFF796FFFFF758FFFFF77EFF2A +:103450004B4632462946FFF7C9FF2B7833B1BBF103 +:10346000000F03D0012005B0BDE8F08F337813B111 +:10347000019B002BF6D108F5805303935445029B22 +:1034800077EB03031ED2039BD3F85404D0B1036837 +:10349000AAEB0401DB6889B298474B4632462946BD +:1034A0004046FFF7A3FF2B7813B1BBF1000FD9D132 +:1034B000337813B1019B002BD4D100F05BF80446A4 +:1034C0000F46DBE70020CEE7002108B50846FFF7EE +:1034D000B7FEBDE8084001F06DB8000008B5012155 +:1034E0000020FFF7ADFEBDE8084001F063B8000022 +:1034F00008B500210120FFF7A3FEBDE8084001F058 +:1035000059B80000012108B50846FFF799FEBDE84B +:10351000084001F04FB8000000B59BB0EFF30981FF +:1035200068226846FEF7B0FBEFF30583014B9B6B07 +:10353000FEE700BF00ED00E008B5FFF7EDFF00007B +:1035400000B59BB0EFF3098168226846FEF79CFB4B +:10355000EFF30583014B5B6BFEE700BF00ED00E07E +:10356000FEE700000FB408B5029802F025F8FEE768 +:1035700002F0CEBC02F0A6BC13B56C46031D84E875 +:10358000060094E8030083E80500012002B010BDA6 +:1035900073B58568019155B11B885B0707D4D0E9E5 +:1035A00000369B6B9847019AC1B23046A84701206C +:1035B00002B070BDF0B5866889B005460C465EB1B4 +:1035C000BDF838305B070AD4D0E900379B6B9847C9 +:1035D0002246C1B23846B047012009B0F0BD0022F2 +:1035E000002301F10806CDE9002300230A46ADF8C7 +:1035F000083003AB1068083252F8041C1C46B24273 +:1036000003C42346F6D1106820609288A280FFF799 +:10361000B1FF0423ADF808302B68CDE90001DB6B66 +:10362000694628469847D7E7082817D909280CD0B3 +:103630000A280CD00B280CD00C280CD00D280CD04C +:103640000E2814BF4020302070470C2070471020F7 +:1036500070471420704718207047202070470000E2 +:103660002DE9F041456A15B94162BDE8F0814B682A +:10367000AC4623F06047C3F38A464FEAD37EC3F3D8 +:10368000807816EA230638BF3E462B465A68BEEBC2 +:10369000D27F22F060440AD0002A18DAA40CB44287 +:1036A00017D19D420FD10D60DEE71346EEE7A7422A +:1036B00007D102F08044C2F3807242450BD054B16E +:1036C000EFE708D2EDE7CCF800100B60CDE7B4428D +:1036D00001D0B442E5D81A689C46002AE5D11960A9 +:1036E000C3E700002DE9F047089D01F0070400EB57 +:1036F000D1004FF47F494FEAD508224405F0070571 +:10370000944201D1BDE8F08704F0070705F0070AED +:10371000111B08EBD50E57453E4613F80EC038BFB7 +:103720005646C6F108068E4228BF0E46E108415CA7 +:1037300034443544B94029FA06F721FA0AF1FFB2B8 +:103740008CEA010147FA0AF739408CEA010C03F8C8 +:103750000EC0D5E780EA0120082341F2210201B220 +:10376000013B4000002980B2B8BF504013F0FF0376 +:10377000F5D1704738B50C468D18A54200D138BD3B +:1037800014F8011BFFF7E6FFF7E7000042684AB1B3 +:10379000136881894360438901339BB29942438115 +:1037A00038BF83811046704770B588B00446202228 +:1037B0000D4668460021FEF78DFA20460495FFF776 +:1037C000E5FF024660B16B46054608AE1C4608356B +:1037D00003CCB44245F8080C45F8041C2346F5D147 +:1037E000104608B070BD0000082817D909280CD071 +:1037F0000A280CD00B280CD00C280CD00D280CD08B +:103800000E2814BF4020302070470C207047102035 +:103810007047142070471820704720207047000020 +:10382000082817D90C280CD910280CD914280CD921 +:1038300018280CD920280CD930288CBF0F200E2036 +:103840007047092070470A2070470B2070470C20F2 +:1038500070470D20704700002DE9F843078C04469F +:10386000072F1ED900254FF6FF73D0E90298C5F146 +:103870002006A5F1200029FA05F1083508FA06F618 +:1038800028FA00F0314301431846C9B2FFF762FF3E +:10389000402D0346EBD13A46E169BDE8F843FFF716 +:1038A00069BF4FF6FF70BDE8F883000010B54B68A4 +:1038B00023B9CA8A63F30902CA8210BD04691A686F +:1038C0001C600361C38A013BC3824A60EFE70000CA +:1038D0002DE9F84F1D46CB8A0F468146C3F30901F7 +:1038E000924605290B4630D00020AAB207F11A04EF +:1038F0009EB21FFA80F8042E0FD8904503F1010301 +:1039000006D30A44FB8A62F309030120FB821AE012 +:103910001AF800600130E654EAE79045F1D2A1F1CF +:10392000050B1C237C68BBFBF3F203FB12BB1FFAE5 +:103930008BF6002C45D14846FFF728FF044638B9DE +:1039400078606FF00200BDE8F88F4FF00008E6E7FE +:10395000002606607860ADB24FF0000B454510D9E7 +:103960000AEB0803221D13F8011B08F10108915509 +:10397000B1B21FFA88F81B292BD0454506F1010684 +:10398000F1D8FB8AC3F30902154465F30903BCE7C8 +:1039900001321C4692B22368002BF9D16B1F0B44F5 +:1039A0001C21B3FBF1F301339BB29A42D3D2BBF19A +:1039B000000FD0D14846FFF7E9FE20B9C4F800B0A7 +:1039C000BFE70122E7E7C0F800B05E46206004468A +:1039D000C1E74545D5D94846FFF7D8FE08B920606C +:1039E000AFE7C0F800B0002620600446B6E700004C +:1039F0002DE9F04F1C46074688462DED028B83B01B +:103A00005B690192002B00F09A80238C2BB1E26954 +:103A1000002A00F09480072B35D807F10C00FFF73F +:103A2000B5FE054638B96FF00205284603B0BDEC77 +:103A3000028BBDE8F08F14220021FEF74BF9228C97 +:103A4000E16905F10800FEF71FF9208C48F00041FC +:103A5000013080B2FFF7E4FEFFF7C6FE013880B206 +:103A600020840130287438466369228C1B782A44EC +:103A700003F01F0363F03F03137269602946FFF7E9 +:103A8000EFFD0125D1E74FF0000900F10C034FF0E5 +:103A9000800A4E464D4608EE103A18EE100AFFF71F +:103AA00075FE83460028BED014220021FEF712F9CD +:103AB000002E3AD1019B0222ABF808300BF1080E20 +:103AC0001FFA82FC218C0CF10100BCF1060F80B2C0 +:103AD00001D88E422BD3FFF7A3FE8E4208BF4FF0D2 +:103AE000400AFFF781FE62690138013512781BFA3E +:103AF00080F1013002F01F022DB242EA491289F032 +:103B000001094AEA020A48F0004281F808A0594631 +:103B10008BF810003846CBF804204FF0000AFFF76E +:103B20009FFD238CB342B8D17FE70022C6E7E1694D +:103B3000895D01360EF80210B6B20132C0E76FF0AF +:103B4000010572E7F8B515460E46302200210446FD +:103B50001F46FEF7BFF8069BB5F5001FA760636020 +:103B600004F11000079B34BF6A094FF6FF72E6614B +:103B7000A362002397B29A4206D800230360A7826B +:103B8000E3822383E360F8BD0660013330462036CC +:103B9000F1E7000003781BB94BB2002BC8BF0170DE +:103BA0007047000000787047F8B50C46C9690746B1 +:103BB00011B9238C002B37D1257E1F2D34D83878AE +:103BC00028BB228C072A2CD8268A36F003032BD157 +:103BD0004FF6FF70FFF7CEFD20F0010031024FF6E7 +:103BE000FF72400441EA0561400C41EA402523464A +:103BF00029463846FFF7FCFE002807DD6269137886 +:103C00000133DBB21F2B88BF00231370F8BD218A5C +:103C10002D0645EA012505432046FFF71DFE024615 +:103C2000E5E76FF00300F1E76FF00100EEE7000059 +:103C300070B58AB0044616460021282268461D4603 +:103C4000FEF748F8BDF8383069462046ADF8103028 +:103C50000F9B05939DF840308DF81830119B07930A +:103C6000BDF84830CDE90265ADF82030FFF79CFF84 +:103C70000AB070BD2DE9F041D36905460C461646E1 +:103C80000BB9138C5BBB377E1F2F28D895F80080AB +:103C9000B8F1000F26D03046FFF7DEFD3378210261 +:103CA0000246284641EAC331338A41EA080141EA23 +:103CB000076141EA0341334641F08001FFF798FE76 +:103CC00000280ADD3378012B07D17269137801339C +:103CD000DBB21F2B88BF00231370BDE8F0816FF0AB +:103CE0000100FAE76FF00300F7E70000F0B58BB0D2 +:103CF00004460D4617460021282268461E46FDF759 +:103D0000E9FF9DF84C30294620465A1E5342534144 +:103D10006A468DF800309DF84030ADF81030119BA8 +:103D200005939DF848308DF81830149B0793BDF823 +:103D30005430CDE90276ADF82030FFF79BFF0BB091 +:103D4000F0BD0000406A00B104307047436A1A6851 +:103D5000426202691A600361C38A013BC3827047F1 +:103D60002DE9F041D0F8208014461D46184E4146FA +:103D7000002709B9BDE8F081D1E90223A21A65EB59 +:103D80000303964277EB03031ED2036A8B420DD1E5 +:103D9000FFF78CFD036A1B68036203690B60C38A2B +:103DA0000161013B016AC3828846E2E7FFF77EFDBD +:103DB0000B68C8F8003003690B60C38A0161013BDE +:103DC000C382D8F80010D4E788460968D1E700BF5D +:103DD00080841E002DE9F04F8BB00D4614469B46A3 +:103DE000DDF850908046002800F01881B9F1000FEE +:103DF00000F01481531E3F2B00F21081012A03D1E1 +:103E0000BBF1000F40F00A810023CDE90833B8F878 +:103E10001430B5EBC30F4FEAC30703D300200BB038 +:103E2000BDE8F08F2B199F42D8F80C3036BF7F1BAE +:103E30002746FFB21BB9D8F81030002B7AD0272DB7 +:103E40004DD8C5F1280600232946B742009308AB98 +:103E5000D8F808002CBFF6B23E46A7EB060A354458 +:103E600032465FFA8AFAFFF73DFCB8F81430282191 +:103E700003F10053053BDB000493D8F80C300393A7 +:103E8000039B13B1BAF1000F2CD1D8F8100040B148 +:103E9000BAF1000F05D008AB5246691A0096FFF739 +:103EA00021FC38B2002FB9D066070AD00AAB6242B3 +:103EB00003EBD40102F0070211F8083C134101F8AA +:103EC000083C082C3DD9102C40F2B580202C40F243 +:103ED000B780BBF1000F00F09C80082335E0BA46A4 +:103EE0000026C2E7049BE02B28BFE02306930B4487 +:103EF000AB42059315D95A1B0398691A009692454F +:103F000008AB00F1040034BF5246D2B20792FFF76B +:103F1000E9FB079A1644AAEB020A1544F6B25FFAC7 +:103F20008AFA049B069A05999B1A0493039B1B68C3 +:103F30000393A5E700933A4608AB2946D8F8080052 +:103F4000ADE7BBF1000F13D00123B4EBC30F6BD06F +:103F5000082C12D89DF82030621E23FA02F2D507F1 +:103F600006D54FF0FF3202FA04F423438DF82030D7 +:103F70009DF8203089F8003051E7102C12D8BDF898 +:103F80002030621E23FA02F2D10706D54FF0FF322D +:103F900002FA04F42343ADF82030BDF82030A9F82C +:103FA00000303CE7202C0FD80899631E21FA03F358 +:103FB000DA0705D54FF0FF3202FA04F40C430894F7 +:103FC000089BC9F800302AE7402C2AD0611EC4F1B2 +:103FD0002102A4F12103DDE9086526FA01F105FAC1 +:103FE00002F225FA03F311431943CB0711D501223D +:103FF000A4F12003C4F1200102FA03F322FA01F133 +:10400000A2400B43524263EB430332432B43CDE9BF +:104010000823DDE90823C9E9002300E76FF0010068 +:10402000FDE66FF00800FAE6082CA1D9102CB4D9EF +:10403000202CEED8C4E7BBF1000FAED0022384E7FA +:10404000BBF1000FBCD004237FE70000012A30B58C +:10405000144638BF012485B00025402C28BF4024D9 +:10406000012ACDE9025518D81B788DF8083063076E +:104070000AD004AB624203EBD40502F0070215F844 +:10408000083C934005F8083C034600912246002175 +:1040900002A8FFF727FB05B030BD082AE4D9102A93 +:1040A00003D81B88ADF80830E1E7202A95BF1B68CC +:1040B000D3E900230293CDE90223D8E710B5CB68FA +:1040C0001BB98B600B618B8210BD04691A681C6080 +:1040D0000361C38A013BC382CA60F0E703064CBF99 +:1040E000C0F3C0300220704708B50246FFF7F6FF64 +:1040F000022806D15306C2F30F2001D100F00300BD +:1041000008BDC2F30740FBE72DE9F04F93B004462A +:104110000D46CDE903230A681046FFF7DFFF0228AA +:10412000824614BFC2F306260026002A80F2F381DD +:1041300012F0C04940F0EF81097B002900F0EB81CB +:10414000022803D02378B34240F0E881C2F304632D +:1041500010462944069302F07F030593FFF7C4FF3E +:10416000059B002283464FEA8348002348EA0A4819 +:1041700048EA4668CE78CDE90823F30948EA000802 +:10418000029368D0059B024608A920460093534637 +:104190006768B847002800F0C481276A4FB94146D4 +:1041A00004F10C00FFF700FB074690B96FF0020026 +:1041B00055E03B6998450DD03F68002FF9D1414645 +:1041C00004F10C00FFF7F0FA07460028EED0236A4E +:1041D0003B60276297F817C006F01F08CCF3840CE9 +:1041E000ACEB0800A8EB0C031FFA80FE0028B8BF58 +:1041F0000EF120001FFA83FEB8BF00B2002B079318 +:10420000B8BF0EF12003D7E90221BCBF1BB2079350 +:1042100052EA010338D0039B4FF0000CDFF820E393 +:104220009A1A049B63EB010196457CEB01032BD3A7 +:104230006B7B97F81AE0734519D1029B002B78D05D +:10424000012821DC7868F8B9DFF8F0C2944570EBFA +:10425000010316D337E0276A27B96FF00C0013B0BB +:10426000BDE8F08F3B699845B4D03F68F4E7B348A8 +:1042700090427CEB010301D30020F0E7029B002B6E +:10428000FAD0079B0F2B17DCFA7DB3003946204686 +:1042900002F0030203F07C031343FB75FFF706FBF8 +:1042A0006B7BBB76029B3BB9FB7DC3F3840201327F +:1042B00062F38603FB75D0E76A7BBB7E9A42DBD153 +:1042C000029B002B35D0B309022B32D0039B142262 +:1042D00000210DA8BB60049BFB60FDF7FBFC039B6A +:1042E0000AA920460A93049BADF83EB00B932B1D00 +:1042F0008DF840A00C932B7B8DF84180013BDBB205 +:10430000ADF83C30069B8DF84230059B8DF843306C +:1043100094F82C3083F001038DF84430A36898475B +:10432000FB7DC3F38403013303F01F039B02FB8275 +:10433000A2E7FB7DC6F34012B2EBD31F40F0F4803E +:10434000C3F38403434540F0F280029AB6092B7B05 +:10435000002A4DD0F2075DD4032B40F2EB80039B83 +:10436000AE1D394604F10C00BB603246049BFB6075 +:104370002B7B033BDBB2FFF7ABFA00280CDA3946A4 +:104380002046FFF793FAFB7DC3F38403013303F068 +:104390001F039B02FB8209E7AB88DDE908843B83AE +:1043A0004FF6FF73C9F12000A9F1200228FA09F1A4 +:1043B00009F1080904FA00F024FA02F20143184650 +:1043C0001143C9B2FFF7C6F9B9F1400F0346E9D16D +:1043D000B88231462A7B033AD2B2FFF7CBF9FB7D94 +:1043E000B882DA43C2F3C01262F3C713FB7543E726 +:1043F00086B92E1D013B394604F10C00DBB2324672 +:10440000FFF766FA0028BADB2A7B3146B88A013A00 +:10441000D2B2E2E7F98A013BC1F30901DAB2042919 +:104420005BD8281D002307F11B069A4208D910F813 +:1044300001CB013306F801C00131DBB20529F4D10B +:10444000039993420A9138BF043304992CBF002387 +:1044500055FA83F30B9107F11B010C9179680E93C8 +:104460000D91291DFB8AADF83EB0C3F309038DF809 +:1044700040A08DF841801A44069B8DF84230059B80 +:10448000ADF83C208DF8433094F82C3083F00103D4 +:104490008DF844300023B88A7B602A7B013AFFF70D +:1044A00069F93B8BB882834203D1A3680AA92046ED +:1044B000984720460AA9FFF701FEFB7DBA8AC3F39D +:1044C0008403013303F01F039B02FB823B8B9A4260 +:1044D0000CBF00206FF01000C1E67B68002BAFD04E +:1044E000052001E01C3033461E68002EFAD1091A5F +:1044F0002E1D081D184401EB090C5FFA89F3BCF16D +:104500001B0F9DD89A429BD916F8013B09F101096E +:1045100000F8013BEFE76FF00900A0E66FF00A003A +:104520009DE66FF00B009AE66FF00D0097E66FF0D6 +:104530000E0094E66FF00F0091E600BF40420F00BE +:1045400080841E00EFF30983054968334A6B22F02B +:1045500001024A6383F30988002383F311887047BB +:1045600000EF00E0302080F3118862B60D4B0E4A58 +:10457000D96821F4E0610904090C0A430B49DA60A7 +:10458000D3F8FC2042F08072C3F8FC20084AC2F83D +:10459000B01F116841F0010111602022DA7783F821 +:1045A0002200704700ED00E00003FA0555CEACC5CF +:1045B000001000E0302310B583F311880E4B5B68C8 +:1045C00013F4006314D0F1EE103AEFF309844FF0C6 +:1045D0008073683CE361094BDB6B236684F30988D5 +:1045E00000F0A8FF10B1064BA36110BD054BFBE71F +:1045F00083F31188F9E700BF00ED00E000EF00E071 +:104600004307000846070008026843681143016039 +:1046100003B1184770470000024A136843F0C00313 +:10462000136070470078004013B50E4C204600F030 +:10463000A7FA04F1140000234FF400720A49009411 +:1046400000F064F9094B4FF40072094904F1380095 +:10465000009400F0DDF9074A074BC4E9172302B0C4 +:1046600010BD00BF34630020A0630020194600087D +:10467000A06500200078004000E1F505037C30B51E +:10468000244C002918BF0C46012B11D1224B984213 +:104690000ED1224BD3F8E82042F08042C3F8E82044 +:1046A000D3F8102142F08042C3F81021D3F8103122 +:1046B0002268036EC16D03EB52038466B3FBF2F311 +:1046C0006268150442BF23F0070503F0070343EABD +:1046D0004503CB60A36843F040034B60E36843F0BD +:1046E00001038B6042F4967343F001030B604FF0BB +:1046F000FF330B62510505D512F0102205D0B2F13F +:10470000805F04D080F8643030BD7F23FAE73F2318 +:10471000F8E700BF90790008346300200044025895 +:104720002DE9F047C66D05463768F4692107346204 +:104730001AD014F0080118BF4FF48071E20748BF87 +:1047400041F02001A3074FF0300348BF41F0400182 +:10475000600748BF41F0800183F31188281DFFF7EF +:1047600053FF002383F31188E2050AD5302383F336 +:1047700011884FF48061281DFFF746FF002383F363 +:1047800011884FF030094FF0000A14F0200838D19A +:104790003B0616D54FF0300905F1380A200610D532 +:1047A00089F31188504600F067F9002836DA0821AD +:1047B000281DFFF729FF27F080033360002383F3D0 +:1047C0001188790614D5620612D5302383F3118837 +:1047D000D5E913239A4208D12B6C33B127F0400757 +:1047E0001021281DFFF710FF3760002383F3118885 +:1047F000E30618D5AA6E1369ABB15069BDE8F0475E +:10480000184789F31188736A284695F8641019408F +:1048100000F0D0F98AF31188F469B6E7B06288F342 +:104820001188F469BAE7BDE8F0870000090100F1DA +:104830006043012203F56143C9B283F8001300F01D +:104840001F039A4043099B0003F1604303F5614352 +:10485000C3F880211A607047F8B51546826804468F +:104860000B46AA4200D28568A1692669761AB5422C +:104870000BD218462A46FDF707FAA3692B44A36119 +:104880002846A3685B1BA360F8BD0CD9AF1B184674 +:104890003246FDF7F9F93A46E1683044FDF7F4F99C +:1048A000E3683B44EBE718462A46FDF7EDF9E36879 +:1048B000E5E7000083689342F7B50446154600D249 +:1048C0008568D4E90460361AB5420BD22A46FDF752 +:1048D000DBF963692B4463612846A3685B1BA36013 +:1048E00003B0F0BD0DD93246AF1B0191FDF7CCF9F5 +:1048F00001993A46E0683144FDF7C6F9E3683B4464 +:10490000E9E72A46FDF7C0F9E368E4E710B50A4491 +:104910000024C361029B8460C16002610362C0E93C +:104920000000C0E9051110BD08B5D0E90532934279 +:1049300001D1826882B98268013282605A1C426168 +:1049400019700021D0E904329A4224BFC368436140 +:1049500000F0C2FE002008BD4FF0FF30FBE7000072 +:1049600070B5302304460E4683F31188A568A5B1BF +:10497000A368A269013BA360531CA3611578226957 +:10498000934224BFE368A361E3690BB120469847D3 +:10499000002383F31188284607E03146204600F0C3 +:1049A0008BFE0028E2DA85F3118870BD2DE9F74F00 +:1049B00004460E4617469846D0F81C904FF0300A31 +:1049C0008AF311884FF0000B154665B12A4631462F +:1049D0002046FFF741FF034660B94146204600F0FC +:1049E0006BFE0028F1D0002383F31188781B03B0FD +:1049F000BDE8F08FB9F1000F03D001902046C84701 +:104A0000019B8BF31188ED1A1E448AF31188DCE7B1 +:104A1000C160C361009B82600362C0E9051111445B +:104A2000C0E9000001617047F8B504460D4616461E +:104A3000302383F31188A768A7B1A368013BA36063 +:104A400063695A1C62611D70D4E904329A4224BF22 +:104A5000E3686361E3690BB120469847002080F367 +:104A6000118807E03146204600F026FE0028E2DAF1 +:104A700087F31188F8BD0000D0E9052310B59A42EC +:104A800001D182687AB982680021013282605A1CA1 +:104A900082611C7803699A4224BFC368836100F075 +:104AA0001BFE204610BD4FF0FF30FBE72DE9F74F0E +:104AB00004460E4617469846D0F81C904FF0300A30 +:104AC0008AF311884FF0000B154665B12A4631462E +:104AD0002046FFF7EFFE034660B94146204600F04E +:104AE000EBFD0028F1D0002383F31188781B03B07D +:104AF000BDE8F08FB9F1000F03D001902046C84700 +:104B0000019B8BF31188ED1A1E448AF31188DCE7B0 +:104B1000026843681143016003B118477047000001 +:104B20001430FFF743BF00004FF0FF331430FFF79E +:104B30003DBF00003830FFF7B9BF00004FF0FF3332 +:104B40003830FFF7B3BF00001430FFF709BF000093 +:104B50004FF0FF311430FFF703BF00003830FFF78C +:104B600063BF00004FF0FF323830FFF75DBF000039 +:104B7000012914BF6FF0130000207047FFF754BDE8 +:104B8000044B036000234360C0E902330123037434 +:104B9000704700BFA879000810B53023044683F39E +:104BA0001188FFF76BFD02230020237480F3118826 +:104BB00010BD000038B5C36904460D461BB9042179 +:104BC0000844FFF7A5FF294604F11400FFF7ACFEE7 +:104BD000002806DA201D4FF40061BDE83840FFF7D9 +:104BE00097BF38BD026843681143016003B118479D +:104BF0007047000013B5406B00F58054D4F8A4381A +:104C00001A681178042914D1017C022911D119796B +:104C1000012312898B4013420BD101A94C3002F0C1 +:104C200019F9D4F8A4480246019B2179206800F0C4 +:104C3000DFF902B010BD0000143002F09BB8000094 +:104C40004FF0FF33143002F095B800004C3002F002 +:104C50006DB900004FF0FF334C3002F067B900002F +:104C6000143002F069B800004FF0FF31143002F048 +:104C700063B800004C3002F039B900004FF0FF3249 +:104C80004C3002F033B900000020704710B500F539 +:104C90008054D4F8A4381A681178042917D1017CFB +:104CA000022914D15979012352898B4013420ED124 +:104CB000143001F0FBFF024648B1D4F8A4484FF489 +:104CC000407361792068BDE8104000F07FB910BDE5 +:104CD000406BFFF7DBBF0000704700007FB5124B51 +:104CE00001250426044603600023057400F18402B4 +:104CF00043602946C0E902330C4B02901430019303 +:104D00004FF44073009601F0ADFF094B04F6944256 +:104D1000294604F14C000294CDE900634FF440733E +:104D200002F074F804B070BDD0790008D14C0008CE +:104D3000F54B00080A68302383F311880B790B3395 +:104D400042F823004B79133342F823008B7913B1D7 +:104D50000B3342F8230000F58053C3F8A418022354 +:104D60000374002080F311887047000038B5037F7A +:104D7000044613B190F85430ABB90125201D02212F +:104D8000FFF730FF04F114006FF00101257700F008 +:104D9000AFFC04F14C0084F854506FF00101BDE801 +:104DA000384000F0A5BC38BD10B5012104460430E0 +:104DB000FFF718FF0023237784F8543010BD00005C +:104DC00038B504460025143001F064FF04F14C00AE +:104DD000257702F033F8201D84F854500121FFF7A5 +:104DE00001FF2046BDE83840FFF750BF90F8803003 +:104DF00003F06003202B06D190F881200023212AA4 +:104E000003D81F2A06D800207047222AFBD1C0E908 +:104E10001D3303E0034A426707228267C36701200C +:104E2000704700BF3C22002037B500F58055D5F80B +:104E3000A4381A68117804291AD1017C022917D1E3 +:104E40001979012312898B40134211D100F14C04CE +:104E5000204602F0B3F858B101A9204601F0FAFF4C +:104E6000D5F8A4480246019B2179206800F0C0F8DB +:104E700003B030BD01F10B03F0B550F8236085B0ED +:104E800004460D46FEB1302383F3118804EB8507F9 +:104E9000301D0821FFF7A6FEFB6806F14C005B6998 +:104EA0001B681BB1019001F0E3FF019803A901F019 +:104EB000D1FF024648B1039B2946204600F098F8EE +:104EC000002383F3118805B0F0BDFB685A691268AE +:104ED000002AF5D01B8A013B1340F1D104F1800276 +:104EE000EAE70000133138B550F82140ECB1302327 +:104EF00083F3118804F58053D3F8A42813685279FA +:104F000003EB8203DB689B695D6845B1042160188F +:104F1000FFF768FE294604F1140001F0D1FE204697 +:104F2000FFF7B4FE002383F3118838BD70470000FB +:104F300001F09EB901234022002110B5044600F87B +:104F4000303BFCF7C7FE0023C4E9013310BD00006D +:104F500010B53023044683F31188242241600021D8 +:104F60000C30FCF7B7FE204601F0A4F90223002024 +:104F7000237080F3118810BD70B500EB81030546E6 +:104F800050690E461446DA6018B110220021FCF771 +:104F9000A1FEA06918B110220021FCF79BFE31464A +:104FA0002846BDE8704001F08BBA000083682022DB +:104FB000002103F0011310B5044683601030FCF7A4 +:104FC00089FE2046BDE8104001F006BBF0B4012583 +:104FD00000EB810447898D40E4683D43A469458125 +:104FE00023600023A2606360F0BC01F023BB0000DB +:104FF000F0B4012500EB810407898D40E4683D434E +:105000006469058123600023A2606360F0BC01F045 +:1050100099BB000070B502230025044624220370CA +:105020002946C0F888500C3040F8045CFCF752FE6A +:10503000204684F8705001F0D7F963681B6823B1EB +:1050400029462046BDE87040184770BD0378052BFF +:1050500010B504460AD080F88C30052303704368ED +:105060001B680BB1042198470023A36010BD00000A +:105070000178052906D190F88C20436802701B68DE +:1050800003B118477047000070B590F870300446BF +:1050900013B1002380F8703004F18002204601F043 +:1050A000BFFA63689B68B3B994F8803013F0600569 +:1050B00035D00021204601F0B1FD0021204601F04D +:1050C000A1FD63681B6813B106212046984706239B +:1050D00084F8703070BD204698470028E4D0B4F8BA +:1050E0008630A26F9A4288BFA36794F98030A56F7B +:1050F000002B4FF0300380F20381002D00F0F2808E +:10510000092284F8702083F3118800212046D4E915 +:105110001D23FFF76DFF002383F31188DAE794F86E +:10512000812003F07F0343EA022340F202329342DC +:1051300000F0C58021D8B3F5807F48D00DD8012B71 +:105140003FD0022B00F09380002BB2D104F18802F3 +:1051500062670222A267E367C1E7B3F5817F00F0CF +:105160009B80B3F5407FA4D194F88230012BA0D16D +:10517000B4F8883043F0020332E0B3F5006F4DD04D +:1051800017D8B3F5A06F31D0A3F5C063012B90D829 +:105190006368204694F882205E6894F88310B4F81F +:1051A0008430B047002884D0436863670368A367EE +:1051B0001AE0B3F5106F36D040F6024293427FF406 +:1051C00078AF5C4B63670223A3670023C3E794F8BF +:1051D0008230012B7FF46DAFB4F8883023F00203E6 +:1051E000A4F88830C4E91D55E56778E7B4F8803045 +:1051F000B3F5A06F0ED194F88230204684F88A303F +:1052000001F050F963681B6813B1012120469847EB +:10521000032323700023C4E91D339CE704F18B03AF +:1052200063670123C3E72378042B10D1302383F372 +:1052300011882046FFF7BAFE85F3118803216368C1 +:1052400084F88B5021701B680BB12046984794F866 +:105250008230002BDED084F88B3004232370636807 +:105260001B68002BD6D0022120469847D2E794F83D +:10527000843020461D0603F00F010AD501F0C2F963 +:10528000012804D002287FF414AF2B4B9AE72B4B54 +:1052900098E701F0A9F9F3E794F88230002B7FF446 +:1052A00008AF94F8843013F00F01B3D01A062046EB +:1052B00002D501F0CBFCADE701F0BCFCAAE794F805 +:1052C0008230002B7FF4F5AE94F8843013F00F0198 +:1052D000A0D01B06204602D501F0A0FC9AE701F001 +:1052E00091FC97E7142284F8702083F311882B46F1 +:1052F0002A4629462046FFF769FE85F31188E9E62C +:105300005DB1152284F8702083F3118800212046B6 +:10531000D4E91D23FFF75AFEFDE60B2284F8702026 +:1053200083F311882B462A4629462046FFF760FE64 +:10533000E3E700BF007A0008F8790008FC7900086C +:1053400038B590F870300446002B3ED0063BDAB2F8 +:105350000F2A34D80F2B32D8DFE803F03731310869 +:10536000223231313131313131313737856FB0F857 +:1053700086309D4214D2C3681B8AB5FBF3F203FB4F +:1053800012556DB9302383F311882B462A462946DE +:10539000FFF72EFE85F311880A2384F870300EE0A3 +:1053A000142384F87030302383F3118800232046BF +:1053B0001A461946FFF70AFE002383F3118838BD09 +:1053C000C36F03B198470023E7E70021204601F0AF +:1053D00025FC0021204601F015FC63681B6813B111 +:1053E0000621204698470623D7E7000010B590F81D +:1053F00070300446142B29D017D8062B05D001D8BD +:105400001BB110BD093B022BFBD80021204601F047 +:1054100005FC0021204601F0F5FB63681B6813B111 +:10542000062120469847062319E0152BE9D10B23C6 +:1054300080F87030302383F3118800231A46194610 +:10544000FFF7D6FD002383F31188DAE7C3689B6971 +:105450005B68002BD5D1C36F03B19847002384F854 +:105460007030CEE700238268037503691B68996872 +:105470009142FBD25A6803604260106058607047E6 +:1054800000238268037503691B6899689142FBD801 +:105490005A680360426010605860704708B508465B +:1054A000302383F311880B7D032B05D0042B0DD003 +:1054B0002BB983F3118808BD8B6900221A604FF065 +:1054C000FF338361FFF7CEFF0023F2E7D1E900321B +:1054D00013605A60F3E70000FFF7C4BF054BD968BB +:1054E00008751868026853601A600122D860027556 +:1054F000FBF712B9A06700200C4B30B5DD684B1CE0 +:1055000087B004460FD02B46094A684600F084F95C +:105510002046FFF7E3FF009B13B1684600F086F9D1 +:10552000A86907B030BDFFF7D9FFF9E7A0670020F1 +:105530009D540008044B1A68DB6890689B68984289 +:1055400094BF002001207047A0670020084B10B5D1 +:105550001C68D868226853601A600122DC602275DA +:10556000FFF78EFF01462046BDE81040FBF7D4B898 +:10557000A0670020044B1A68DB6892689B689A4217 +:1055800001D9FFF7E3BF7047A067002038B5074C8B +:1055900001230025064907482370656001F04CFD92 +:1055A0000223237085F3118838BD00BF086A0020EC +:1055B000087A0008A067002008B572B6044B186589 +:1055C00000F06EFC00F040FD024B03221A70FEE773 +:1055D000A0670020086A002000F05EB9EFF3118098 +:1055E00020B9EFF30583302282F311887047000061 +:1055F00010B530B9EFF30584C4F3080414B180F397 +:10560000118810BDFFF7B6FF84F31188F9E7000099 +:10561000034A516853685B1A9842FBD8704700BF31 +:10562000001000E08B600223086108468B827047FF +:105630008368A3F1840243F8142C026943F8442CD4 +:10564000426943F8402C094A43F8242CC268A3F16C +:10565000200043F8182C022203F80C2C002203F837 +:105660000B2C034A43F8102C704700BF3107000889 +:10567000A067002008B5FFF7DBFFBDE80840FFF793 +:105680002BBF0000024BDB6898610F20FFF726BF9D +:10569000A0670020302383F31188FFF7F3BF0000D9 +:1056A00008B50146302383F311880820FFF724FF53 +:1056B000002383F3118808BD064BDB6839B14268CB +:1056C00018605A60136043600420FFF715BF4FF065 +:1056D000FF307047A06700200368984206D01A6820 +:1056E0000260506018469961FFF7F6BE70470000EF +:1056F00038B504460D462068844200D138BD0368A1 +:1057000023605C608561FFF7E7FEF4E7036810B58E +:105710009C68A2420CD85C688A600B604C60216077 +:10572000596099688A1A9A604FF0FF33836010BD00 +:10573000121B1B68ECE700000A2938BF0A2170B56C +:1057400004460D460A26601901F06EFC01F056FC75 +:10575000041BA54203D8751C04462E46F3E70A2E07 +:1057600004D90120BDE8704001F0A6BC70BD000066 +:10577000F8B5144B0D460A2A4FF00A07D96103F118 +:105780001001826038BF0A22416019691446016025 +:1057900048601861A81801F037FC01F02FFC431B8A +:1057A0000646A34206D37C1C28192746354601F03D +:1057B0003BFCF2E70A2F04D90120BDE8F84001F0D4 +:1057C0007BBCF8BDA0670020F8B506460D4601F089 +:1057D00015FC0F4A134653F8107F9F4206D12A4604 +:1057E00001463046BDE8F840FFF7C2BFD169BB684B +:1057F000441A2C1928BF2C46A34202D92946FFF788 +:105800009BFF224631460348BDE8F840FFF77EBFC4 +:10581000A0670020B0670020C0E90323002310B474 +:105820005DF8044B4361FFF7CFBF000010B5194C82 +:10583000236998420DD08168D0E9003213605A6024 +:105840009A680A449A60002303604FF0FF33A36113 +:1058500010BD0268234643F8102F536000220260F7 +:1058600022699A4203D1BDE8104001F0D7BB93688A +:1058700081680B44936001F0C1FB2269E169926881 +:10588000441AA242E4D91144BDE81040091AFFF7B6 +:1058900053BF00BFA06700202DE9F047DFF8BC80B0 +:1058A00008F110072C4ED8F8105001F0A7FBD8F8DB +:1058B0001C40AA68031B9A423ED814444FF00009CA +:1058C000D5E90032C8F81C4013605A60C5F8009052 +:1058D000D8F81030B34201D101F0A0FB89F3118850 +:1058E000D5E9033128469847302383F311886B6943 +:1058F000002BD8D001F082FB6A69A0EB0409824634 +:105900004A450DD2022001F0D7FB0022D8F8103012 +:10591000B34208D151462846BDE8F047FFF728BFFB +:10592000121A2244F2E712EB09092946384638BF19 +:105930004A46FFF7EBFEB5E7D8F81030B34208D07F +:105940001444C8F81C00211AA960BDE8F047FFF70D +:10595000F3BEBDE8F08700BFB0670020A06700205D +:1059600000207047FEE70000704700004FF0FF3056 +:105970007047000002290CD0032904D001290748F0 +:1059800018BF00207047032A05D8054800EBC20065 +:105990007047044870470020704700BFE07A000855 +:1059A0004C220020947A000870B59AB0054608464B +:1059B000144601A900F0C2F801A8FCF783F9431CC2 +:1059C0000022C6B25B001046C5E9003423700323F1 +:1059D000023404F8013C01ABD1B202348E4201D84A +:1059E0001AB070BD13F8011B013204F8010C04F861 +:1059F000021CF1E708B5302383F311880348FFF751 +:105A000013FA002383F3118808BD00BF106A002039 +:105A100090F8803003F01F02012A07D190F881200E +:105A20000B2A03D10023C0E91D3315E003F0600306 +:105A3000202B08D1B0F884302BB990F88120212A8E +:105A400003D81F2A04D8FFF7D1B9222AEBD0FAE7EE +:105A5000034A426707228267C3670120704700BF7D +:105A60004322002007B5052917D8DFE801F01916F1 +:105A700003191920302383F31188104A0121019062 +:105A8000FFF77AFA019802210D4AFFF775FA0D48DF +:105A9000FFF796F9002383F3118803B05DF804FB48 +:105AA000302383F311880748FFF760F9F2E73023CA +:105AB00083F311880348FFF777F9EBE7347A00089E +:105AC000587A0008106A002038B50C4D0C4C2A4654 +:105AD0000C4904F10800FFF767FF05F1CA0204F161 +:105AE00010000949FFF760FF05F5CA7204F11800BC +:105AF0000649BDE83840FFF757BF00BFE8820020E5 +:105B00004C220020147A00081E7A0008297A000826 +:105B100070B5044608460D46FCF7D4F8C6B22046D8 +:105B2000013403780BB9184670BD32462946FCF79C +:105B3000B5F80028F3D10120F6E700002DE9F04781 +:105B400005460C46FCF7BEF82C49C6B22846FFF7BE +:105B5000DFFF08B11036F6B229492846FFF7D8FF13 +:105B600008B11036F6B2632E0BD8DFF89080DFF85C +:105B70009090244FDFF898A02E7846B92670BDE8A3 +:105B8000F08729462046BDE8F04701F075BE252E76 +:105B900030D1072241462846FCF780F880B91A4BDD +:105BA000224603F1140153F8040B8B4242F8040B14 +:105BB000F9D1198807359B78173411809370DBE78A +:105BC000082249462846FCF769F898B9A21C0F4BF1 +:105BD000197802320909C95D02F8041C13F8011B87 +:105BE00001F00F015345C95D02F8031CF0D11834D0 +:105BF0000835C1E7013504F8016BBDE7007B0008FB +:105C0000297A0008087B00089678000800E8F11F50 +:105C10000CE8F11FBFF34F8F044B1A695107FCD1F9 +:105C2000D3F810215207F8D1704700BF002000526E +:105C300008B50D4B1B78ABB9FFF7ECFF0B4BDA68DF +:105C4000D10704D50A4A5A6002F188325A60D3F863 +:105C50000C21D20706D5064AC3F8042102F1883286 +:105C6000C3F8042108BD00BF468500200020005273 +:105C70002301674508B5114B1B78F3B9104B1A691E +:105C8000510703D5DA6842F04002DA60D3F81021F8 +:105C9000520705D5D3F80C2142F04002C3F80C217D +:105CA000FFF7B8FF064BDA6842F00102DA60D3F87A +:105CB0000C2142F00102C3F80C2108BD46850020EA +:105CC000002000520F289ABF00F580604004002099 +:105CD000704700004FF400307047000010207047FC +:105CE0000F2808B50BD8FFF7EDFF00F50033026869 +:105CF000013204D104308342F9D1012008BD0020D3 +:105D0000FCE700000F2838B505463FD8FFF782FFB3 +:105D10001F4CFFF78DFF4FF0FF3307286361C4F876 +:105D200014311DD82361FFF775FF030243F02403EC +:105D3000E360E36843F08003E36023695A07FCD41F +:105D40002846FFF767FFFFF7BDFF4FF4003100F073 +:105D500057F92846FFF78EFFBDE83840FFF7C0BF70 +:105D6000C4F81031FFF756FFA0F108031B0243F0FF +:105D70002403C4F80C31D4F80C3143F08003C4F888 +:105D80000C31D4F810315B07FBD4D9E7002038BDC3 +:105D9000002000522DE9F84F05460C46104645EA12 +:105DA0000203DE0602D00020BDE8F88F20F01F00BD +:105DB000DFF8BCB0DFF8BCA0FFF73AFF04EB000847 +:105DC000444503D10120FFF755FFEDE72022294686 +:105DD000204601F01FFD10B920352034F0E72B4696 +:105DE00005F120021F68791CDDD104339A42F9D1F4 +:105DF00005F178431B481C4EB3F5801F1B4B38BF81 +:105E0000184603F1F80332BFD946D1461E46FFF7C4 +:105E100001FF0760A5EB040C336804F11C0143F09B +:105E200002033360231FD9F8007017F00507FAD179 +:105E300053F8042F8B424CF80320F4D1BFF34F8F5B +:105E4000FFF7E8FE4FF0FF3320222146036028468B +:105E5000336823F00203336001F0DCFC0028BBD080 +:105E60003846B0E7142100520C2000521420005292 +:105E7000102000521021005210B5084C237828B190 +:105E80001BB9FFF7D5FE0123237010BD002BFCD0FA +:105E90002070BDE81040FFF7EDBE00BF4685002032 +:105EA00038B5054D00240334696855F80C0B00F033 +:105EB000B9F8122CF7D138BD1C7B0008084601F058 +:105EC000A1BC000070B5104E82B0FFF787FB0546FD +:105ED00001F094F8326803469042336037BF0B4AB2 +:105EE0000A495168146836BF0131D1E90041516057 +:105EF0000419284641F100010191FFF779FB204682 +:105F0000019902B070BD00BF488500205085002077 +:105F100070B5124E82B0FFF761FB054601F06EF8D6 +:105F2000326803469042336037BF0D4A0C495168CE +:105F3000146836BF0131D1E9004151600419284687 +:105F400041F100010191FFF753FB4FF47A720023F6 +:105F500020460199FAF7CCF902B070BD48850020BF +:105F6000508500200244074BD2B210B5904200D1B8 +:105F700010BD441C00B253F8200041F8040BE0B2FD +:105F8000F4E700BF504000580E4B30B51C6F24049E +:105F900005D41C6F1C671C6F44F400441C670A4C3A +:105FA00002442368D2B243F480732360074B9042CB +:105FB00000D130BD441C51F8045B00B243F82050BE +:105FC000E0B2F4E70044025800480258504000583C +:105FD00007B5012201A90020FFF7C4FF019803B013 +:105FE0005DF804FB13B50446FFF7F2FFA04205D0AD +:105FF000012201A900200194FFF7C6FF02B010BDE5 +:106000000144BFF34F8F064B884204D3BFF34F8F39 +:10601000BFF36F8F7047C3F85C022030F4E700BF16 +:1060200000ED00E00144BFF34F8F064B884204D3DC +:10603000BFF34F8FBFF36F8F7047C3F870022030EC +:10604000F4E700BF00ED00E070470000074B45F2A9 +:1060500055521A6002225A6040F6FF729A604CF65E +:10606000CC421A600122024B1A7070470048005857 +:106070005C850020034B1B781BB1034B4AF6AA2218 +:106080001A6070475C85002000480058034B1A686E +:106090001AB9034AD2F8D0241A60704758850020F4 +:1060A00000400258024B4FF48032C3F8D0247047AE +:1060B0000040025808B5FFF7E9FF024B1868C0F32B +:1060C000806008BD5885002070B5BFF34F8FBFF3C7 +:1060D0006F8F1A4A0021C2F85012BFF34F8FBFF3DF +:1060E0006F8F536943F400335361BFF34F8FBFF396 +:1060F0006F8FC2F88410BFF34F8FD2F8803043F611 +:10610000E074C3F3C900C3F34E335B0103EA040632 +:10611000014646EA81750139C2F86052F9D2203B46 +:1061200013F1200FF2D1BFF34F8F536943F4803343 +:106130005361BFF34F8FBFF36F8F70BD00ED00E071 +:10614000FEE70000214B2248224A70B5904237D327 +:10615000214BC11EDA1C121A22F003028B4238BFF7 +:1061600000220021FBF7B6FD1C4A0023C2F8843050 +:10617000BFF34F8FD2F8803043F6E074C3F3C90009 +:10618000C3F34E335B0103EA0406014646EA817518 +:106190000139C2F86C52F9D2203B13F1200FF2D131 +:1061A000BFF34F8FBFF36F8FBFF34F8FBFF36F8F6F +:1061B0000023C2F85032BFF34F8FBFF36F8F70BD13 +:1061C00053F8041B40F8041BC0E700BFB87D00086B +:1061D00030870020308700203087002000ED00E06D +:1061E000074BD3F8D81021EA0001C3F8D810D3F830 +:1061F000002122EA0002C3F80021D3F800317047E1 +:106200000044025870B5D0E9244300224FF0FF3516 +:106210009E6804EB42135101D3F80009002805DA07 +:10622000D3F8000940F08040C3F80009D3F8000B10 +:10623000002805DAD3F8000B40F08040C3F8000BCB +:10624000013263189642C3F80859C3F8085BE0D2DC +:106250004FF00113C4F81C3870BD0000890141F0F3 +:106260002001016103699B06FCD41220FFF7D0B91D +:1062700010B50A4C2046FEF75DFE094BC4F890307D +:10628000084BC4F89430084C2046FEF753FE074BE9 +:10629000C4F89030064BC4F8943010BD60850020DF +:1062A00000000840887B0008FC85002000000440B6 +:1062B000947B000870B503780546012B5CD1434BF5 +:1062C000D0F89040984258D1414B0E216520D3F828 +:1062D000D82042F00062C3F8D820D3F8002142F061 +:1062E0000062C3F80021D3F80021D3F8802042F0E7 +:1062F0000062C3F88020D3F8802022F00062C3F847 +:106300008020D3F88030FEF791FA324BE360324BB5 +:10631000C4F800380023D5F89060C4F8003EC023CC +:1063200023604FF40413A3633369002BFCDA0123C9 +:106330000C203361FFF76CF93369DB07FCD41220C2 +:10634000FFF766F93369002BFCDA00262846A660C1 +:10635000FFF758FF6B68C4F81068DB68C4F814686E +:10636000C4F81C6883BB1D4BA3614FF0FF3363610E +:10637000A36843F00103A36070BD194B9842C9D1D3 +:10638000134B4FF08060D3F8D82042F00072C3F86E +:10639000D820D3F8002142F00072C3F80021D3F8CE +:1063A0000021D3F8802042F00072C3F88020D3F897 +:1063B000802022F00072C3F88020D3F88030FFF7ED +:1063C0000FFF0E214D209EE7064BCDE76085002094 +:1063D000004402584014004003002002003C30C03A +:1063E000FC850020083C30C0F8B5D0F89040054648 +:1063F00000214FF000662046FFF730FFD5F89410DB +:1064000000234FF001128F684FF0FF30C4F834388A +:10641000C4F81C2804EB431201339F42C2F8006900 +:10642000C2F8006BC2F80809C2F8080BF2D20B6878 +:10643000D5F89020C5F8983063621023136116696F +:1064400016F01006FBD11220FFF7E2F8D4F800385E +:1064500023F4FE63C4F80038A36943F4402343F0F7 +:106460001003A3610923C4F81038C4F814380B4B87 +:10647000EB604FF0C043C4F8103B094BC4F8003B3D +:10648000C4F81069C4F80039D5F8983003F1100247 +:1064900043F48013C5F89820A362F8BD647B00081C +:1064A00040800010D0F8902090F88A10D2F8003880 +:1064B00023F4FE6343EA0113C2F80038704700007A +:1064C0002DE9F84300EB8103D0F890500C4680464C +:1064D000DA680FFA81F94801166806F00306731EA0 +:1064E000022B05EB41134FF0000194BFB604384E68 +:1064F000C3F8101B4FF0010104F1100398BF06F11F +:10650000805601FA03F3916998BF06F50046002909 +:106510003AD0578A04F15801374349016F50D5F8F2 +:106520001C180B430021C5F81C382B180127C3F891 +:106530001019A7405369611E9BB3138A928B9B0865 +:10654000012A88BF5343D8F89820981842EA034399 +:1065500001F140022146C8F89800284605EB820266 +:106560005360FFF77BFE08EB8900C3681B8A43EA90 +:10657000845348341E4364012E51D5F81C381F4300 +:10658000C5F81C78BDE8F88305EB4917D7F8001B60 +:1065900021F40041C7F8001BD5F81C1821EA0303B9 +:1065A000C0E704F13F030B4A2846214605EB83036D +:1065B0005A60FFF753FE05EB4910D0F8003923F479 +:1065C0000043C0F80039D5F81C3823EA0707D7E79D +:1065D0000080001000040002D0F894201268C0F877 +:1065E0009820FFF70FBE00005831D0F890304901D5 +:1065F0005B5813F4004004D013F4001F0CBF0220BA +:10660000012070474831D0F8903049015B5813F4AD +:10661000004004D013F4001F0CBF0220012070477B +:1066200000EB8101CB68196A0B6813604B685360FB +:106630007047000000EB810330B5DD68AA6913687C +:10664000D36019B9402B84BF402313606B8A146850 +:10665000D0F890201C4402EB4110013C09B2B4FB7D +:10666000F3F46343033323F0030343EAC44343F0E7 +:10667000C043C0F8103B2B6803F00303012B0ED17D +:10668000D2F8083802EB411013F4807FD0F8003BB9 +:1066900014BF43F0805343F00053C0F8003B02EBBB +:1066A0004112D2F8003B43F00443C2F8003B30BD36 +:1066B0002DE9F041D0F8906005460C4606EB4113F9 +:1066C000D3F8087B3A07C3F8087B08D5D6F8143806 +:1066D0001B0704D500EB8103DB685B689847FA076A +:1066E0001FD5D6F81438DB071BD505EB8403D96812 +:1066F000CCB98B69488A5A68B2FBF0F600FB1622C7 +:106700008AB91868DA6890420DD2121AC3E90024D7 +:10671000302383F3118821462846FFF78BFF84F34B +:106720001188BDE8F081012303FA04F26B8923EAA2 +:1067300002036B81CB68002BF3D021462846BDE8CD +:10674000F041184700EB81034A0170B5DD68D0F8CD +:1067500090306C692668E66056BB1A444FF40020FE +:10676000C2F810092A6802F00302012A0AB20ED107 +:10677000D3F8080803EB421410F4807FD4F8000922 +:1067800014BF40F0805040F00050C4F8000903EB03 +:106790004212D2F8000940F00440C2F80009012278 +:1067A000D3F8340802FA01F10143C3F8341870BD7C +:1067B00019B9402E84BF4020206020681A442E8AD8 +:1067C0008419013CB4FBF6F440EAC44040F00050A8 +:1067D000C6E700002DE9F843D0F8906005460C4666 +:1067E0004F0106EB4113D3F8088918F0010FC3F8E5 +:1067F00008891CD0D6F81038DB0718D500EB8103C8 +:10680000D3F80CC0DCF81430D3F800E0DA68964511 +:1068100030D2A2EB0E024FF000091A60C3F80490C8 +:10682000302383F31188FFF78DFF89F3118818F067 +:10683000800F1DD0D6F834380126A640334217D039 +:1068400005EB84030134D5F89050D3F80CC0E4B2C2 +:106850002F44DCF8142005EB0434D2F800E0516832 +:10686000714514D3D5F8343823EA0606C5F83468E0 +:10687000BDE8F883012303FA01F2038923EA020346 +:106880000381DCF80830002BD1D09847CFE7AEEB7E +:106890000103BCF81000834228BF0346D7F818094B +:1068A00080B2B3EB800FE3D89068A0F1040959F8E7 +:1068B000048FC4F80080A0EB09089844B8F1040FD5 +:1068C000F5D818440B4490605360C8E72DE9F84FA1 +:1068D000D0F8905004466E69AB691E4016F480589B +:1068E0006E6103D0BDE8F84FFEF794BB002E12DABC +:1068F000D5F8003E9B0705D0D5F8003E23F00303F2 +:10690000C5F8003ED5F80438204623F00103C5F849 +:106910000438FEF7ADFB370505D52046FFF772FCBE +:106920002046FEF793FBB0040CD5D5F8083813F0D9 +:10693000060FEB6823F470530CBF43F4105343F479 +:10694000A053EB6031071BD56368DB681BB9AB69EB +:1069500023F00803AB612378052B0CD1D5F8003E5A +:106960009A0705D0D5F8003E23F00303C5F8003E92 +:106970002046FEF77DFB6368DB680BB12046984735 +:10698000F30200F1BA80B70226D5D4F89090002720 +:106990004FF0010A09EB4712D2F8003B03F4402301 +:1069A000B3F5802F11D1D2F8003B002B0DDA6289AC +:1069B0000AFA07F322EA0303638104EB8703DB6827 +:1069C000DB6813B13946204698470137D4F8943034 +:1069D000FFB29B689F42DDD9F00619D5D4F890002C +:1069E000026AC2F30A1702F00F0302F4F012B2F5C2 +:1069F000802F00F0CA80B2F5402F09D104EB830349 +:106A0000002200F58050DB681B6A974240F0B0809E +:106A10003003D5F8185835D5E90303D500212046B1 +:106A2000FFF746FEAA0303D501212046FFF740FEEB +:106A30006B0303D502212046FFF73AFE2F0303D54F +:106A400003212046FFF734FEE80203D50421204647 +:106A5000FFF72EFEA90203D505212046FFF728FEE9 +:106A60006A0203D506212046FFF722FE2B0203D53A +:106A700007212046FFF71CFEEF0103D50821204621 +:106A8000FFF716FE700340F1A780E90703D5002148 +:106A90002046FFF79FFEAA0703D501212046FFF7F6 +:106AA00099FE6B0703D502212046FFF793FE2F07BF +:106AB00003D503212046FFF78DFEEE0603D5042102 +:106AC0002046FFF787FEA80603D505212046FFF7DD +:106AD00081FE690603D506212046FFF77BFE2A06C4 +:106AE00003D507212046FFF775FEEB0574D5204638 +:106AF0000821BDE8F84FFFF76DBED4F890904FF035 +:106B0000000B4FF0010AD4F894305FFA8BF79B68C2 +:106B10009F423FF638AF09EB4713D3F8002902F440 +:106B20004022B2F5802F20D1D3F80029002A1CDAA8 +:106B3000D3F8002942F09042C3F80029D3F8002985 +:106B4000002AFBDB3946D4F89000FFF787FB228947 +:106B50000AFA07F322EA0303238104EB8703DB68C5 +:106B60009B6813B13946204698470BF1010BCAE7E1 +:106B7000910701D1D0F80080072A02F101029CBFE1 +:106B800003F8018B4FEA18283FE704EB830300F575 +:106B90008050DA68D2F818C0DCF80820DCE9001C64 +:106BA000A1EB0C0C00218F4208D1DB689B699A682D +:106BB0003A449A605A683A445A6029E711F0030F40 +:106BC00001D1D0F800808C4501F1010184BF02F8A9 +:106BD000018B4FEA1828E6E7BDE8F88F08B50348AF +:106BE000FFF774FEBDE80840FDF7E4BC60850020B7 +:106BF00008B50348FFF76AFEBDE80840FDF7DABCB8 +:106C0000FC850020D0F8903003EB4111D1F8003B17 +:106C100043F40013C1F8003B70470000D0F89030F7 +:106C200003EB4111D1F8003943F40013C1F80039E6 +:106C300070470000D0F8903003EB4111D1F8003BD1 +:106C400023F40013C1F8003B70470000D0F89030E7 +:106C500003EB4111D1F8003923F40013C1F80039D6 +:106C60007047000030B50433039C0172002104FB1F +:106C70000325C160C0E90653049B0363059BC0E97B +:106C80000000C0E90422C0E90842C0E90A114363D8 +:106C900030BD00000022416AC260C0E90411C0E9B1 +:106CA0000A226FF00101FEF723BD0000D0E9043293 +:106CB000934201D1C2680AB9181D7047002070477D +:106CC000036919600021C2680132C260C2691344BD +:106CD00082699342036124BF436A0361FEF7FCBCEF +:106CE00038B504460D46E3683BB162690020131DC8 +:106CF0001268A3621344E36207E0237A33B929469A +:106D00002046FEF7D9FC0028EDDA38BD6FF001000F +:106D1000FBE70000C368C269013BC36043691344D9 +:106D200082699342436124BF436A436100238362C3 +:106D3000036B03B11847704770B53023044683F3E3 +:106D40001188866A3EB9FFF7CBFF054618B186F376 +:106D50001188284670BDA36AE26A13F8015B93426A +:106D6000A36202D32046FFF7D5FF002383F31188E7 +:106D7000EFE700002DE9F84F04460E461746984607 +:106D80004FF0300989F311880025AA46D4F828B0BD +:106D9000BBF1000F09D141462046FFF7A1FF20B10A +:106DA0008BF311882846BDE8F88FD4E90A12A7EBC7 +:106DB000050B521A934528BF9346BBF1400F1BD9D0 +:106DC000334601F1400251F8040B914243F8040BA1 +:106DD000F9D1A36A403640354033A362D4E90A238F +:106DE0009A4202D32046FFF795FF8AF31188BD42ED +:106DF000D8D289F31188C9E730465A46FAF744FFDA +:106E0000A36A5E445D445B44A362E7E710B5029C5D +:106E10000433017203FB0421C460C0E9061300239C +:106E2000C0E90A33039B0363049BC0E90000C0E987 +:106E30000422C0E90842436310BD0000026A6FF0FB +:106E40000101C260426AC0E904220022C0E90A22AC +:106E5000FEF74EBCD0E904239A4201D1C26822B9A0 +:106E6000184650F8043B0B60704700231846FAE7B9 +:106E7000C3680021C2690133C36043691344826956 +:106E80009342436124BF436A4361FEF725BC00007F +:106E900038B504460D46E3683BB1236900201A1D4E +:106EA000A262E2691344E36207E0237A33B9294618 +:106EB0002046FEF701FC0028EDDA38BD6FF0010036 +:106EC000FBE7000003691960C268013AC260C26949 +:106ED000134482699342036124BF436A0361002320 +:106EE0008362036B03B118477047000070B530230D +:106EF0000D460446114683F31188866A2EB9FFF7C2 +:106F0000C7FF10B186F3118870BDA36A1D70A36A14 +:106F1000E26A01339342A36204D3E1692046043953 +:106F2000FFF7D0FF002080F31188EDE72DE9F84F3F +:106F300004460D46904699464FF0300A8AF3118870 +:106F40000026B346A76A4FB949462046FFF7A0FF7F +:106F500020B187F311883046BDE8F88FD4E90A07DD +:106F60003A1AA8EB0607974228BF1746402F1BD9AD +:106F700005F1400355F8042B9D4240F8042BF9D14C +:106F8000A36A40364033A362D4E90A239A4204D369 +:106F9000E16920460439FFF795FF8BF311884645D8 +:106FA000D9D28AF31188CDE729463A46FAF76CFE22 +:106FB000A36A3D443E443B44A362E5E7D0E9042391 +:106FC0009A4217D1C3689BB1836A8BB1043B9B1A69 +:106FD0000ED01360C368013BC360C3691A44836960 +:106FE0009A42026124BF436A036100238362012342 +:106FF000184670470023FBE700F024B9014B586A9C +:10700000704700BF000C0040034B002258631A6118 +:107010000222DA60704700BF000C0040014B0022E2 +:10702000DA607047000C0040014B5863704700BFA6 +:10703000000C0040FEE7000070B51B4B0025044625 +:1070400086B058600E4685620163FDF78BFA04F145 +:107050001003A560E562C4E904334FF0FF33C4E9CF +:107060000044C4E90635FFF7C9FF2B46024604F188 +:1070700034012046C4E9082380230C4A2565FEF725 +:10708000D1FA01230A4AE0600092037568467268EB +:107090000192B268CDE90223064BCDE90435FEF733 +:1070A000E9FA06B070BD00BF086A0020A07B0008A6 +:1070B000A57B000835700008024AD36A1843D062E5 +:1070C000704700BFA06700204B6843608B688360F7 +:1070D000CB68C3600B6943614B6903628B69436290 +:1070E0000B6803607047000008B53C4B40F2FF712D +:1070F0003B48D3F888200A43C3F88820D3F8882077 +:1071000022F4FF6222F00702C3F88820D3F8882017 +:10711000D3F8E0200A43C3F8E020D3F808210A435B +:10712000C3F808212F4AD3F808311146FFF7CCFFE6 +:1071300000F5806002F11C01FFF7C6FF00F58060DA +:1071400002F13801FFF7C0FF00F5806002F1540141 +:10715000FFF7BAFF00F5806002F17001FFF7B4FF9E +:1071600000F5806002F18C01FFF7AEFF00F5806052 +:1071700002F1A801FFF7A8FF00F5806002F1C40149 +:10718000FFF7A2FF00F5806002F1E001FFF79CFF2E +:1071900000F5806002F1FC01FFF796FF02F58C71AB +:1071A00000F58060FFF790FF00F014F90E4BD3F864 +:1071B000902242F00102C3F89022D3F8942242F0C8 +:1071C0000102C3F894220522C3F898204FF06052C0 +:1071D000C3F89C20054AC3F8A02008BD004402580B +:1071E00000000258AC7B000800ED00E01F0008031F +:1071F00008B500F0D1FAFEF7C9F90F4BD3F8DC203F +:1072000042F04002C3F8DC20D3F8042122F040020F +:10721000C3F80421D3F80431084B1A6842F008027D +:107220001A601A6842F004021A60FEF72FFFBDE8E8 +:107230000840FEF749BC00BF00440258001802484D +:1072400070470000114BD3F8E82042F00802C3F861 +:10725000E820D3F8102142F00802C3F810210C4AAC +:10726000D3F81031D36B43F00803D363C722094B23 +:107270009A624FF0FF32DA6200229A615A63DA6052 +:107280005A6001225A611A60704700BF00440258D8 +:107290000010005C000C0040094A08B51169D36871 +:1072A0000B40D9B29B076FEA0101116107D530236A +:1072B00083F31188FEF790F9002383F3118808BD4A +:1072C000000C0040064BD3F8DC200243C3F8DC205E +:1072D000D3F804211043C3F80401D3F804317047F4 +:1072E000004402583A4B4FF0FF31D3F8802062F04F +:1072F0000042C3F88020D3F8802002F00042C3F897 +:107300008020D3F88020D3F88420C3F88410D3F8E9 +:1073100084200022C3F88420D3F88400D86F40F082 +:10732000FF4040F4FF0040F4DF4040F07F00D867AA +:10733000D86F20F0FF4020F4FF0020F4DF4020F061 +:107340007F00D867D86FD3F888006FEA40506FEAA3 +:107350005050C3F88800D3F88800C0F30A00C3F87F +:107360008800D3F88800D3F89000C3F89010D3F8C1 +:107370009000C3F89020D3F89000D3F89400C3F89D +:107380009410D3F89400C3F89420D3F89400D3F861 +:107390009800C3F89810D3F89800C3F89820D3F851 +:1073A0009800D3F88C00C3F88C10D3F88C00C3F885 +:1073B0008C20D3F88C00D3F89C00C3F89C10D3F831 +:1073C0009C10C3F89C20D3F89C3000F0B9B900BFE2 +:1073D0000044025808B50122534BC3F80821534B0F +:1073E000D3F8F42042F00202C3F8F420D3F81C21B1 +:1073F00042F00202C3F81C210222D3F81C314C4B8C +:10740000DA605A689104FCD54A4A1A6001229A60EF +:10741000494ADA6000221A614FF440429A61444BB3 +:107420009A699204FCD51A6842F480721A603F4B44 +:107430001A6F12F4407F04D04FF480321A67002292 +:107440001A671A6842F001021A60384B1A6850072E +:10745000FCD500221A611A6912F03802FBD1012111 +:1074600019604FF0804159605A67344ADA62344AF1 +:107470001A611A6842F480321A602C4B1A68910320 +:10748000FCD51A6842F480521A601A689204FCD53E +:107490002C4A2D499A6200225A63196301F57C0136 +:1074A000DA6301F5E77199635A64284A1A64284A35 +:1074B000DA621A6842F0A8521A601C4B1A6802F08D +:1074C0002852B2F1285FF9D148229A614FF48862BC +:1074D000DA6140221A621F4ADA641F4A1A651F4A9B +:1074E0005A651F4A9A6532231E4A1360136803F0D7 +:1074F0000F03022BFAD10D4A136943F00303136102 +:10750000136903F03803182BFAD14FF00050FFF73E +:10751000D9FE4FF08040FFF7D5FE4FF00040BDE8A8 +:107520000840FFF7CFBE00BF008000510044025862 +:107530000048025800C000F0020000010000FF01F6 +:10754000008890083220600063020901470E050898 +:10755000DD0BBF0120000020000001100910E00039 +:1075600000010110002000524FF0B04208B5D2F8DF +:10757000883003F00103C2F8883023B1044A13684D +:107580000BB150689847BDE80840FDF713B800BF3D +:10759000B08600204FF0B04208B5D2F8883003F032 +:1075A0000203C2F8883023B1044A93680BB1D06853 +:1075B0009847BDE80840FCF7FDBF00BFB08600203B +:1075C0004FF0B04208B5D2F8883003F00403C2F897 +:1075D000883023B1044A13690BB150699847BDE85C +:1075E0000840FCF7E7BF00BFB08600204FF0B04274 +:1075F00008B5D2F8883003F00803C2F8883023B108 +:10760000044A93690BB1D0699847BDE80840FCF77C +:10761000D1BF00BFB08600204FF0B04208B5D2F80D +:10762000883003F01003C2F8883023B1044A136A8B +:107630000BB1506A9847BDE80840FCF7BBBF00BFDC +:10764000B08600204FF0B04310B5D3F8884004F462 +:107650007872C3F88820A30604D5124A936A0BB146 +:10766000D06A9847600604D50E4A136B0BB1506B75 +:107670009847210604D50B4A936B0BB1D06B984702 +:10768000E20504D5074A136C0BB1506C9847A3056B +:1076900004D5044A936C0BB1D06C9847BDE81040F8 +:1076A000FCF788BFB08600204FF0B04310B5D3F888 +:1076B000884004F47C42C3F88820620504D5164A49 +:1076C000136D0BB1506D9847230504D5124A936D85 +:1076D0000BB1D06D9847E00404D50F4A136E0BB17F +:1076E000506E9847A10404D50B4A936E0BB1D06E2F +:1076F0009847620404D5084A136F0BB1506F98473E +:10770000230404D5044A936F0BB1D06F9847BDE8AA +:107710001040FCF74FBF00BFB086002008B50348FB +:10772000FCF7FEFFBDE80840FCF744BF34630020CF +:1077300008B5FFF7B1FDBDE80840FCF73BBF00000E +:10774000062108B50846FDF771F806210720FDF768 +:107750006DF806210820FDF769F806210920FDF7DC +:1077600065F806210A20FDF761F806211720FDF7CC +:107770005DF806212820FDF759F809217A20FDF748 +:1077800055F807213220FDF751F80C215220BDE8B1 +:107790000840FDF74BB8000008B5FFF7A3FD00F067 +:1077A0000DF8FDF7EBF9FDF7C3FBFDF795FAFFF7D1 +:1077B00047FDBDE80840FFF71FBC00000023054A55 +:1077C00019460133102BC2E9001102F10802F8D169 +:1077D000704700BFB08600200B460146184600F0F7 +:1077E00003B8000000F00EB810B5054C13462CB1DC +:1077F0000A4601460220AFF3008010BD2046FCE798 +:1078000000000000024B01461868FEF757BB00BF9E +:107810006C22002010B501390244904201D10020B1 +:1078200005E0037811F8014FA34201D0181B10BDE9 +:107830000130F2E72DE9F041A3B1C91A17780144EC +:10784000044603F1FF3C8C42204601D9002009E0A8 +:107850000578BD4204F10104F5D10CEB0405D618FE +:10786000A54201D1BDE8F08115F8018D16F801EDB2 +:10787000F045F5D0E7E70000034611F8012B03F8C7 +:10788000012B002AF9D170476F72672E61726475FF +:1078900070696C6F742E437562654F72616E6765B7 +:1078A0002D7065726970682D6865617679000000D9 +:1078B00053544D333248373F3F3F0053544D3332DA +:1078C000483733782F3732780053544D33324837A6 +:1078D00034332F3735332F373530000001105A003D +:1078E00003105900012058000320560040A2E4F183 +:1078F000646891060041A3E5F26569920700000003 +:1079000043414E464449666163653A204D65737351 +:107910006167652052414D204F766572666C6F77C6 +:10792000210000004261642043414E496661636565 +:1079300020696E6465782E00000100000001FF00E0 +:1079400000A0004000A40040000000000000000073 +:10795000DD2C0008B525000811340008AD2500080D +:1079600025260008352A00089D270008ED25000877 +:10797000F1250008C9250008B1250008F5290008EF +:10798000D525000879350008E1250008C929000837 +:107990000096000000000000000000000000000051 +:1079A0000000000000000000000000003D4B000847 +:1079B000294B0008654B0008514B00085D4B00083F +:1079C000494B0008354B0008214B0008714B00085B +:1079D00000000000554C0008414C00087D4C000898 +:1079E000694C0008754C0008614C00084D4C0008BB +:1079F000394C0008894C000800000000010000001C +:107A00000000000063300000047A0008F8670020DE +:107A1000086A00204172647550696C6F74002542D9 +:107A20004F415244252D424C002553455249414C6B +:107A3000250000000200000000000000754E000854 +:107A4000E54E000840004000B8820020C8820020B7 +:107A50000200000000000000030000000000000021 +:107A60002D4F00080000000010000000D882002008 +:107A70000000000001000000000000006085002000 +:107A800001010200655A000875590008115A0008E2 +:107A9000F5590008430000009C7A000809024300E1 +:107AA000020100C0320904000001020201000524A5 +:107AB000001001052401000104240202052406002F +:107AC00001070582030800FF09040100020A000003 +:107AD0000007050102400000070581024000000088 +:107AE00012000000E87A00081201100102000040B4 +:107AF00009124157000201020301000004030904B6 +:107B000025424F4152442500303132333435363727 +:107B1000383941424344454600000000000000203F +:107B20000000020002000000000100300000000020 +:107B3000080000000000002400000800040000000D +:107B40000004000000FC00000200000000000430FF +:107B50000080000008000000000000380000010064 +:107B60000100000000000000895000084153000897 +:107B7000ED530008400040009886002098860020C1 +:107B800001000000A88600208000000040010000E5 +:107B900008000000000100000010000008000000C4 +:107BA0006D61696E0069646C650000000000802AE8 +:107BB00000000000AAAAAAAA00000024FFFF0000FB +:107BC0000000000000A00A000021000200000000E8 +:107BD000AAAAAAAA00000000FFFF000000000009F6 +:107BE000000009001400005400000000AAAAAAAA7C +:107BF00014000054FFFF000000000000000000001F +:107C00000A40100000000000AAAA8AAA0040100042 +:107C1000FFFF00009900000000000000008102004A +:107C200000000000AAAAAAAA00410100FFFF00006C +:107C300000000070070000000000000000000000CD +:107C4000AAAAAAAA00000000FFFF0000000000008E +:107C5000000000000000000000000000AAAAAAAA7C +:107C600000000000FFFF0000000000000000000016 +:107C70000000000000000000AAAAAAAA000000005C +:107C8000FFFF0000000000000000000000000000F6 +:107C900000000000AAAAAAAA00000000FFFF00003E +:107CA00000000000000000000000000000000000D4 +:107CB000AAAAAAAA00000000FFFF0000000000001E +:107CC000000000000000000000000000AAAAAAAA0C +:107CD00000000000FFFF00000000000000000000A6 +:107CE0004086FF7F010000007805000000000000D2 +:107CF00000001E0000000000FE2A0100D204000067 +:107D0000FF000000106A0020346300200000000023 +:107D1000B078000883040000BB780008500400001D +:107D2000C9780008009600000000080096000000D6 +:107D30000008000004000000FC7A000800000000B9 +:107D40000000000000000000000000000000000033 +:107D50000000000070220020000000000000000071 +:107D60000000000000000000000000000000000013 +:107D70000000000000000000000000000000000003 +:107D800000000000000000000000000000000000F3 +:107D900000000000000000000000000000000000E3 +:107DA00000000000000000000000000000000000D3 +:087DB0000000000000000000CB :00000001FF diff --git a/Tools/bootloaders/CubeOrange-periph_bl.bin b/Tools/bootloaders/CubeOrange-periph_bl.bin index d5d6278e4dad5c..e0358397d22ef9 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 old mode 100755 new mode 100644 index a70909de553f2f..c1a27f91483174 --- a/Tools/bootloaders/CubeOrange-periph_bl.hex +++ b/Tools/bootloaders/CubeOrange-periph_bl.hex @@ -1,1926 +1,2013 @@ :020000040800F2 -:1000000000060020B5050008ED3100086D3100083C -:10001000C53100086D31000899310008B7050008A6 -:10002000B7050008B7050008B705000841400008FB -:10003000B7050008B7050008B7050008B7050008B0 -:10004000B7050008B7050008B7050008B7050008A0 -:10005000B7050008B7050008BD6E0008E96E000886 -:10006000156F0008416F00086D6F0008B7050008A4 -:10007000B7050008B7050008B7050008B705000870 -:10008000B7050008B7050008B7050008B52D00083A -:10009000DD2D0008C92D0008F12D0008996F00081A -:1000A000B7050008B7050008B7050008B705000840 -:1000B000B7050008B7050008B7050008B705000830 -:1000C000B7050008B7050008B7050008B705000820 -:1000D000B7050008B7050008B7050008B705000810 -:1000E000FD6F0008B7050008B7050008B705000850 -:1000F000B7050008B7050008B7050008B7050008F0 -:10010000B7050008B705000885700008B7050008A6 -:10011000B7050008B7050008B7050008B7050008CF -:10012000B7050008B7050008B7050008B7050008BF -:10013000B7050008B7050008B7050008B7050008AF -:10014000B7050008B7050008B7050008B70500089F -:10015000B7050008B7050008B7050008B70500088F -:10016000B7050008B7050008B7050008B70500087F -:10017000B7050008E5650008B7050008B7050008E1 -:10018000B7050008B705000871700008B70500083A -:10019000B7050008B7050008B7050008B70500084F -:1001A000B7050008B7050008B7050008B70500083F -:1001B000B7050008B7050008B7050008B70500082F -:1001C000B7050008B7050008B7050008B70500081F -:1001D000B7050008D1650008B7050008B705000895 -:1001E000B7050008B7050008B7050008B7050008FF -:1001F000B7050008B7050008B7050008B7050008EF -:10020000B7050008B7050008B7050008B7050008DE -:10021000B7050008B7050008B7050008B7050008CE -:10022000B7050008B7050008B7050008B7050008BE -:10023000B7050008B7050008B7050008B7050008AE -:10024000B7050008B7050008B7050008B70500089E -:10025000B7050008B7050008B7050008B70500088E -:10026000B7050008B7050008B7050008B70500087E -:10027000B7050008B7050008B7050008B70500086E -:10028000B7050008B7050008B7050008B70500085E -:10029000B7050008B7050008B7050008B70500084E -:1002A000391A0008000000000000000000000000F3 -:1002B00053B94AB9002908BF00281CBF4FF0FF31CD -:1002C0004FF0FF3000F074B9ADF1080C6DE904CEC9 -:1002D00000F006F8DDF804E0DDE9022304B0704721 -:1002E0002DE9F047089D04468E46002B4DD18A42E9 -:1002F000944669D9B2FA82F252B101FA02F3C2F11C -:10030000200120FA01F10CFA02FC41EA030E9440AC -:100310004FEA1C48210CBEFBF8F61FFA8CF708FBCD -:1003200016E341EA034306FB07F199420AD91CEBA5 -:10033000030306F1FF3080F01F81994240F21C81D7 -:10034000023E63445B1AA4B2B3FBF8F008FB10331F -:1003500044EA034400FB07F7A7420AD91CEB040454 -:1003600000F1FF3380F00A81A74240F20781644424 -:10037000023840EA0640E41B00261DB1D4400023A9 -:10038000C5E900433146BDE8F0878B4209D9002D0D -:1003900000F0EF800026C5E9000130463146BDE897 -:1003A000F087B3FA83F6002E4AD18B4202D3824201 -:1003B00000F2F980841A61EB030301209E46002DB0 -:1003C000E0D0C5E9004EDDE702B9FFDEB2FA82F205 -:1003D000002A40F09280A1EB0C014FEA1C471FFA63 -:1003E0008CFE0126200CB1FBF7F307FB131140EA4A -:1003F00001410EFB03F0884208D91CEB010103F117 -:10040000FF3802D2884200F2CB804346091AA4B2D8 -:10041000B1FBF7F007FB101144EA01440EFB00FEAC -:10042000A64508D91CEB040400F1FF3102D2A64511 -:1004300000F2BB800846A4EB0E0440EA03409CE7B0 -:10044000C6F12007B34022FA07FC4CEA030C20FA5D -:1004500007F401FA06F31C43F9404FEA1C4900FA7D -:1004600006F3B1FBF9F8200C1FFA8CFE09FB1811FA -:1004700040EA014108FB0EF0884202FA06F20BD96D -:100480001CEB010108F1FF3A80F08880884240F2BD -:100490008580A8F102086144091AA4B2B1FBF9F001 -:1004A00009FB101144EA014100FB0EFE8E4508D9FC -:1004B0001CEB010100F1FF346CD28E456AD9023881 -:1004C000614440EA0840A0FB0294A1EB0E01A14266 -:1004D000C846A64656D353D05DB1B3EB080261EBD4 -:1004E0000E0101FA07F722FA06F3F1401F43C5E9AE -:1004F000007100263146BDE8F087C2F12003D840E4 -:100500000CFA02FC21FA03F3914001434FEA1C4725 -:100510001FFA8CFEB3FBF7F007FB10360B0C43EA17 -:10052000064300FB0EF69E4204FA02F408D91CEBC7 -:10053000030300F1FF382FD29E422DD902386344C5 -:100540009B1B89B2B3FBF7F607FB163341EA034165 -:1005500006FB0EF38B4208D91CEB010106F1FF38B4 -:1005600016D28B4214D9023E6144C91A46EA0046AB -:1005700038E72E46284605E70646E3E61846F8E63D -:100580004B45A9D2B9EB020864EB0C0E0138A3E786 -:100590004646EAE7204694E74046D1E7D0467BE767 -:1005A000023B614432E7304609E76444023842E7DF -:1005B000704700BF02E000F000F8FEE772B63A486C -:1005C00080F30888394880F3098839484EF6085185 -:1005D000CEF20001086040F20000CCF200004EF6BE -:1005E0003471CEF200010860BFF34F8FBFF36F8FFD -:1005F00040F20000C0F2F0004EF68851CEF2000149 -:100600000860BFF34F8FBFF36F8F4FF00000E1EE34 -:10061000100A4EF63C71CEF200010860062080F30D -:100620001488BFF36F8F05F0E5FA05F087FA06F03E -:100630000BFA4FF055301F491B4A91423CBF41F81D -:10064000040BFAE71C49194A91423CBF41F8040BDC -:10065000FAE71A491A4A1B4B9A423EBF51F8040B5B -:1006600042F8040BF8E700201749184A91423CBFB2 -:1006700041F8040BFAE705F09FFA06F05DFA144C16 -:10068000144DAC4203DA54F8041B8847F9E700F034 -:1006900041F8114C114DAC4203DA54F8041B884761 -:1006A000F9E705F087BA00000006002000220020CC -:1006B00000000008000000200006002070770008FD -:1006C00000220020C8220020C82200202082002012 -:1006D000A0020008A4020008A4020008A402000866 -:1006E0002DE9F04F2DED108AC1F80CD0D0F80CD0C8 -:1006F000BDEC108ABDE8F08F002383F311882846F3 -:10070000A047002004F066FDFEE704F0D5FC00DF02 -:10071000FEE70000F8B501F0CFFA30B1264B002219 -:100720000E211A725A729972DA7205F08BF9074625 -:1007300005F0FAF90546A0BB204B9F4231D00133AA -:100740009F4231D027F0FF021D4B9A422FD12E46F7 -:1007500042F21074F8B200F09FFD00F0A7FF08B15C -:100760000024264600F09EFD08B90646044635B131 -:10077000144B9F4203D0002405F0CEF926460020FA -:1007800005F06AF90EB100F065F801F019FB00F010 -:10079000B1FF01F0D7F9204600F012F900F05AF845 -:1007A000F9E72E460024D8E704460126D5E7064699 -:1007B00041F28834D1E700BF00220020010007B0D9 -:1007C000000008B0263A09B008B501F087F9A0F199 -:1007D00020035842584108BD07B541F212030221D7 -:1007E00001A8ADF8043001F097F903B05DF804FBFF -:1007F000202310B583F311881248C3680BB104F0AD -:100800006FFD0023104A4FF47A710E4804F02CFD5E -:10081000002383F311880D4C236813B12368013B37 -:100820002360636813B16368013B6360084B1B7806 -:1008300033B9636823B9022001F044FA32236360BC -:1008400010BD00BFC8220020F1070008E4230020EB -:10085000DC220020F8B5534B534A1C46196801317D -:1008600000F09F8004339342F8D162684F4B9A4264 -:1008700040F297804E4B9B6803F1006303F5003311 -:100880009A4280F08E8005F01BF905F02DF90020CA -:1008900001F072F90220474B187001F011FA464B33 -:1008A0000021D3F8E820C3F8E810D3F81021C3F8EA -:1008B0001011D3F81021D3F8EC20C3F8EC10D3F8C2 -:1008C0001421C3F81411D3F81421D3F8F020C3F87D -:1008D000F010D3F81821C3F81811D3F81821D3F861 -:1008E000802042F00062C3F88020D3F8802022F0FC -:1008F0000062C3F88020D3F88020D3F8802042F033 -:100900000072C3F88020D3F8802022F00072C3F870 -:100910008020D3F8803072B64FF0E023C3F8084D42 -:10092000D4E90004BFF34F8FBFF36F8F234AC2F89F -:100930008410BFF34F8F536923F480335361BFF3A7 -:100940004F8FD2F8803043F6E076C3F3C905C3F386 -:100950004E335B0103EA060C29464CEA81770139E4 -:10096000C2F87472F9D2203B13F1200FF2D1BFF319 -:100970004F8FBFF36F8FBFF34F8FBFF36F8F5369ED -:1009800023F4003353610023C2F85032BFF34F8F7A -:10099000BFF36F8F202383F31188854680F3088887 -:1009A0002047F8BD0000020820000208FFFF0108F0 -:1009B00000220020DC2200200044025800ED00E06C -:1009C0002DE9F04F93B0AC4B2022FF2100900AA8F4 -:1009D0009D6801F09FF9A94A1378A3B90121A8489D -:1009E0001170C360202383F31188C3680BB104F036 -:1009F00077FC0023A34A4FF47A71A14804F034FC39 -:100A0000002383F31188009B9F4A03B113600023E6 -:100A10009E49009C98469B461E469A460B70536022 -:100A2000012001F04DF924B1974B1B68002B00F019 -:100A30001C82002001F052F80390039B002B01DA86 -:100A400000F0A8FE039B002BEDDB012001F036F93E -:100A5000039B213B162BE3D801A252F823F000BFE1 -:100A6000BD0A0008E50A0008790B0008210A000801 -:100A7000210A0008210A00080D0C0008DF0D0008FB -:100A8000F90C00085B0D0008830D0008A90D000893 -:100A9000210A0008BB0D0008210A00082D0E0008DD -:100AA0005D0B0008210A0008710E0008C90A000841 -:100AB0005D0B0008210A00085B0D00080220FFF70B -:100AC00083FE002840F0FB81009B022105A8B8F1BD -:100AD000000F08BF1C4641F21233ADF8143001F08C -:100AE0001BF89DE74FF47A7000F0F8FF071EEBDB70 -:100AF0000220FFF769FE0028E6D0013F052F00F233 -:100B0000E081DFE807F0030A0D1013360523042106 -:100B100005A8059301F000F817E004215648F9E70D -:100B200004215B48F6E704215A48F3E74FF01C091B -:100B3000484609F1040901F021F80421059005A8AF -:100B400000F0EAFFB9F12C0FF2D101204FF0000ABA -:100B500000FA07F747EA0B0B5FFA8BFB01F026F967 -:100B600026B10BF00B030B2B08BF0024FFF734FE5C -:100B700056E704214848CDE7002EA5D00BF00B0323 -:100B80000B2BA1D10220FFF71FFE074600289BD0A8 -:100B900001203E4E00F0F0FF4FF0000802203070C0 -:100BA00001F08EF85FFA88F9484600F0F5FF044638 -:100BB00090B1484608F1010800F0FEFF0028F1D18D -:100BC000B846044641F21213022105A83E46ADF88C -:100BD000143000F0A1FF23E70123254602203370E3 -:100BE00001F06CF8244B9B68AB4207D9284600F013 -:100BF000C5FF013040F068810435F3E70025234B41 -:100C0000B8463E461D70204B5D60A7E7002E3FF4BE -:100C10005BAF0BF00B030B2B7FF456AF02201B4B8B -:100C2000187001F04DF8322000F058FFB0F10009C3 -:100C3000FFF64AAF19F003077FF446AF0E4A09EBFF -:100C40000503926893423FF63FAFB9F5807F3FF7C7 -:100C50003BAF124BB945019322DD4FF47A7000F09F -:100C60003DFF0390039A002AFFF62EAF039A013747 -:100C7000019B03F8012BEDE700220020E023002078 -:100C8000C8220020F1070008E4230020DC22002015 -:100C900004220020082200200C220020E022002054 -:100CA000C820FFF791FD074600283FF40DAF1F2D28 -:100CB00011D8C5F120020AAB25F0030084494A454A -:100CC000184428BF4A46019200F0FEFF019AFF2116 -:100CD0007F4801F01FF84FEAA903C9F387027C4956 -:100CE0002846019301F01EF8064600283FF46AAF3B -:100CF000019B05EB830531E70220FFF765FD002826 -:100D00003FF4E2AE00F074FF00283FF4DDAE0027B0 -:100D1000B946704B9B68BB4218D91F2F11D80A9B4C -:100D200001330ED027F0030312AA134453F8203CDA -:100D300005934846042205A9043702F065FA814666 -:100D4000E7E7384600F01AFF0590F2E7CDF8149077 -:100D5000042105A800F0E0FE00E70023642104A8B8 -:100D6000049300F0CFFE00287FF4AEAE0220FFF720 -:100D70002BFD00283FF4A8AE049800F02FFF05904B -:100D8000E6E70023642104A8049300F0BBFE0028DA -:100D90007FF49AAE0220FFF717FD00283FF494AECF -:100DA000049800F01DFFEAE70220FFF70DFD002880 -:100DB0003FF48AAE00F02CFFE1E70220FFF704FDCC -:100DC00000283FF481AE05A9142000F027FF074654 -:100DD0000421049004A800F09FFE3946B9E73220B0 -:100DE00000F07CFE071EFFF66FAEBB077FF46CAE13 -:100DF000384A07EB0A03926893423FF665AE022039 -:100E0000FFF7E2FC00283FF45FAE27F003075744EA -:100E1000BA453FF4A3AE50460AF1040A00F0AEFE14 -:100E20000421059005A800F077FEF1E74FF47A70F1 -:100E3000FFF7CAFC00283FF447AE00F0D9FE0028B7 -:100E400044D00A9B01330BD008220AA9002000F0ED -:100E500069FF00283AD02022FF210AA800F05AFF9B -:100E6000FFF7BAFC1C4804F0BBF913B0BDE8F08FE3 -:100E7000002E3FF429AE0BF00B030B2B7FF424AEB6 -:100E80000023642105A8059300F03CFE07460028D6 -:100E90007FF41AAE0220FFF797FC814600283FF44A -:100EA00013AEFFF799FC41F2883004F099F90598E8 -:100EB00000F0C0FF4E463C4600F078FFB0E5064625 -:100EC0004CE64FF0000AFFE5B8467BE6374679E688 -:100ED000E022002000220020A0860100094A49F2F9 -:100EE0006900136899B21B0C00FB013344F2506196 -:100EF0001360054B186882B2000C01FB02001860F9 -:100F000080B27047142200201022002000211022FD -:100F100010B5044600F0FEFE034B03CB2060616079 -:100F20001868A06010BD00BF00E8F11F2DE9F04374 -:100F3000224DBBB002F062F940F2ED22AB68C31A59 -:100F4000934232D906AF2B4628220021A8603846AA -:100F500002F032FE05F10E0000F0D4FE0026044639 -:100F60005FFA80F905F10E08F3B2F100994501F13D -:100F7000280107D908EB060308223846013602F09B -:100F80001BFEF1E7082301220534297B0C48A4B29B -:100F9000CDE902320B4B01933023CDE90474009369 -:100FA00004A3D3E9002302F01FFC3BB0BDE8F083AB -:100FB000AFF3008078F6339F93CACD8D905D00200B -:100FC000043400209D5D002070B50D4614461E4679 -:100FD00002F0A0FB50B9022E10D1012C0ED112A3A9 -:100FE000D3E900230120C5E9002307E0282C10D015 -:100FF00005D8012C09D0052C0FD0002070BD302C55 -:10100000FBD10BA3D3E90023ECE70BA3D3E9002327 -:10101000E8E70BA3D3E90023E4E70BA3D3E900231C -:10102000E0E700BFAFF30080401DA12026812A0B1E -:1010300078F6339F93CACD8D9E6AC421818A46EE8D -:1010400026417272DF25D7B7F017304A39059E5610 -:1010500013B504460846202200212346019002F0E1 -:10106000ABFD227923460198032A4FF0200128BFC7 -:10107000032203F8042F022202F09EFD6279234628 -:101080000198072A4FF0220128BF072203F8052FF5 -:10109000032202F091FDA27923460198072A4FF01E -:1010A000250128BF072203F8062F032202F084FD42 -:1010B000019804F108031022282102F07DFD382058 -:1010C00002B010BD2DE9F04FADF5017D0F460021B6 -:1010D00040F275120EAE804622A8219100F01AFE51 -:1010E00048220021304600F015FE21AD02F086F8BE -:1010F0004FF47A72554B0DF15A09B0FBF2F01860BB -:1011000093E80700012386E807000DF15A003382B7 -:10111000FFF7FCFE47F605034D49338406AB18463E -:1011200006F0A0F81F2229463064304686F83C209D -:10113000FFF78EFF12AB044601460822284602F054 -:101140003BFD08220DF149032846A11804F1880A45 -:1011500002F032FD0DF14A03082204F11001284685 -:1011600004F5847B02F028FD13AB202204F1180162 -:10117000284602F021FD14AB402204F13801284634 -:1011800002F01AFD16AB082204F17801284602F09D -:1011900013FD0DF15903082204F18001284602F0E5 -:1011A0000BFD51460AF1080A4B460822284609F170 -:1011B000010902F001FDD345F3D104F588744FF025 -:1011C00000091BAB08225946284602F0F5FC96F8A8 -:1011D00034304B450AD9B36B2146082228464B448C -:1011E000083409F1010902F0E7FCF0E74FF00009CB -:1011F00096F83C3004EBC9014B4508D9336C082202 -:1012000028464B4409F1010902F0D6FCF0E700231F -:10121000073140460393C1F3CF01BB7E029307F130 -:10122000190301930123CDE904510093F97E05A32D -:10123000D3E9002302F0D8FA0DF5017DBDE8F08F67 -:10124000AFF300809E6AC421818A46EEEC23002021 -:1012500094720008F8B50E4C02260E4FA4F5805388 -:1012600043F8307C237E3BB965692DB1284601F0F7 -:1012700041FE284605F060FF2046A4F5A55401F084 -:1012800039FE012EA4F1100400D1F8BD0126E5E7D6 -:1012900010590020C4730008014B1870704700BF3C -:1012A000F8230020334BF0B51C7B85B034B1324BB2 -:1012B0000E221A810024204605B0F0BD2F4A02AB51 -:1012C0001068516803C308232D492E480DEB030213 -:1012D00005F05AFF054630B9274B0A222A481A81E1 -:1012E00001F090FDE6E70169B1F5F01F06D9224B48 -:1012F0000B2226481A8101F085FDDCE7438BB3F50C -:10130000AF6F09D01C4A0C21214811814FF4AF6204 -:10131000194601F077FDCEE71E4A024402F11003A0 -:10132000994204D2144B10221B481A81E3E710396A -:1013300020468E1A134901F067FF05F11801074690 -:101340003246204601F060FFAB689F4202D1EB6855 -:1013500098420AD0084B0D221A813B4600900F4854 -:10136000D5E9021201F04EFDA4E70D48012401F079 -:1013700049FDA0E7905D0020EC23002045730008A4 -:10138000DCFF1D0000000208B4720008C0720008F3 -:10139000D27200080800FEF7F07200080D73000812 -:1013A000367300082DE9F04FADB080460C4606AF0D -:1013B00002F0B0F90546002859D1237E022B1BD13B -:1013C000E38A012B18D101F019FF0646FFF786FDCD -:1013D00003464FF4C87006F51676DFF8CC92B3FBDF -:1013E000F0F202FB103316FA83F3C9F80030E37E03 -:1013F00033B9A84B00221A709C37BD46BDE8F08F68 -:10140000A38AEEB20135013BB3420BD93B1DE90083 -:10141000082220461E4401F0F8010023009602F045 -:101420008FFAEDE707F11400FFF770FD324607F180 -:101430001401381D05F098FE0028DAD10F2E08D8C7 -:10144000944B1E70D9F80030A3F51673C9F800301C -:10145000D2E7FB1CF87001460722009303462046A2 -:1014600002F06EFAF978404602F04CF9C4E7E38ADC -:10147000282B26D010D8012B1ED0052BBCD1BFF3B2 -:101480004F8F8549854BCA6802F4E0621343CB60F5 -:10149000BFF34F8F00BFFDE7302BADD1637EE94630 -:1014A0007F4D01336A7BDBB2934203D1E27E2B7B1B -:1014B0009A4265D0CD469FE721464046FFF702FE9F -:1014C0009AE7A38A013B9BB2C92B95D8744D2E7B1A -:1014D00026BB05F10C030822314600933346204613 -:1014E00002F02EFA731CF2B2D9001E46A38A013B09 -:1014F0009A4205DA0E3200232A4400920822EEE7CF -:1015000000230022C5E900230023AB6085F8D73013 -:10151000C5F8D8302B7B0BB9E37E2B73002507F180 -:1015200014093B1D082229464846FD60C7E90155BC -:1015300002F042FB3B7A05F1010AAB424FEACA06D0 -:1015400008D9FB680822314648462B44554602F02C -:1015500033FBEFE7C6F3CF060023E17E1934039394 -:101560004046CDE9049663780194029328230093C2 -:1015700046A3D3E9002302F037F9FFF7D7FC3BE796 -:101580004FF0000807F1140310222046A7F814803A -:1015900041460093012302F0D3F9A68A023EB6B277 -:1015A000F31C9B109B000733DB08A9EBC3039D468C -:1015B0000DF1180A1FFA88F34FEAC801B34201F18E -:1015C00010010AD20AEB08030822204608F101089C -:1015D0000093002302F0B4F9ECE795F8D70000F08F -:1015E000DBFAD5F8D83004461BB995F8D70000F0DF -:1015F000E3FAD5F8D83033449C4204D295F8D700AA -:10160000013000F0D9FA4FEA960B4FF000081FFAAC -:1016100088F18B45D5E9003209D90AEB880101220E -:1016200003EB880008F1010800F07CFBEFE7F318FA -:1016300095F8D70042F10002C5E90032D5F8D8305C -:1016400006EB0308C5F8D88000F0A6FA804509D358 -:1016500095F8D730D5F8D8000133001B85F8D7307E -:10166000C5F8D800FF2E08D800232B7300F0C0FA6D -:10167000FFF718FE08B1FFF7EDF82B68094A9B0A3F -:10168000013313810023AB6014E700BF264172725F -:10169000DF25D7B7FD33002000ED00E00400FA0598 -:1016A000905D0020EC2300200034002010B54FF0A6 -:1016B00040540C4B22689A4212D1627D0A4B0B486F -:1016C0001A70C922237D0E30094900F8023C00F04F -:1016D000FBFAE0220021204600F01CFB012010BD97 -:1016E0000020FCE79AAD44C5F8230020905D00205F -:1016F0001600003037B502231D4C1E4D0122204636 -:101700001D496B71236804F580545B689847D4F8D1 -:10171000B034012218495B6804F5966098470023AD -:1017200016494FF480520193154B16480093164BFF -:1017300001F0C2FF154B197811B1124801F0E2FF18 -:1017400001F05CFD0446FFF7C9FB4FF4C873B0FB22 -:10175000F3F202FB130304F5167010FA83F00C4B3E -:10176000186004F0E1F908B10F232B8103B030BDFC -:1017700030340020EC23002040420F00FC230020E6 -:10178000C90F000804340020A5130008F823002026 -:10179000003400202DE9F04F9C4D2DED028B93B0CD -:1017A000DFF890A29A4F284602F082F803460028FC -:1017B0003DD00024974E0E94A046ADF84440A1467B -:1017C000CDE90F44027B8DF844200FAA9968406848 -:1017D00003C21B6843F000430E93336804F22C5499 -:1017E000D3F810B001F00CFD10EB0A02CDF8009018 -:1017F000304606F5A55641F100030EA9D84740F63C -:1018000058230028C8BF48F0010810369C42E4D194 -:10181000B8F1000F05D0284602F04EF887F8009086 -:10182000C1E73B78072B00F2E08001333B700023D7 -:101830000DF12C084FF0010A0A93ADF834300B93E8 -:10184000C8F804309FED6B8B0026724C3746236836 -:101850004FF0000B0DF11D0207A920468DF81CA0CA -:101860008DF81DB08DED008BD3F808905B46C8470E -:101870009DF81C90B9F1000F1ED0102259460EA8F9 -:1018800000F048FA236808AA0AA95F6920460DF10A -:101890001E03B8470FAB4F4698E8030083E80300E8 -:1018A0009DF834300EA928468DF844300A9B0E93DB -:1018B000DDE9082302F0C8F906F22C5640F6582359 -:1018C00004F5A5549E4204F11004C0D1002FBBD1F1 -:1018D000284601F01FFF002840D14F4E01F08EFC3A -:1018E000336898423AD301F089FC0446FFF7F6FAD0 -:1018F0004FF4C87304F516748DF82870B0FBF3F23A -:1019000002FB130314FA83F33360444E377817B99C -:1019100001238DF82830C7F110040EA8FFF7F6FA5E -:101920000EABE4B20DF12900D919062C28BF06240C -:101930002246013400F0C8F90AABE4B2284603930A -:10194000182304940293364B0193012300932BA395 -:10195000D3E9002301F0E0FE0023337001F04EFCD8 -:10196000304A314C1368C31AB3F57A7F30D3106014 -:1019700001F046FC02460B46284601F0A7FF284628 -:1019800001F0C8FE20B3237B0EAF284E002B14BFFE -:1019900003230223737101F031FC4FF47A7339464B -:1019A000B0FBF3F030603046FFF752FB18230730EE -:1019B00002931F4BC0F3CF00019340F25513CDE9C2 -:1019C0000370009328460FA3D3E9002301F0A4FE7F -:1019D000237B2BB1FFF7AAFA237B002B7FF4E0AE29 -:1019E00013B0BDEC028BBDE8F08F284601F064FF18 -:1019F0001DE700BF0000000000000000401DA12006 -:101A000026812A0BF1C6A7C1D068080F0434002034 -:101A1000755E00203034002000340020FD330020AB -:101A2000FC330020705E0020905D0020EC2300203D -:101A3000745E002040420F0008B5064800F014FD17 -:101A4000054800F011FD054A05490020BDE80840A1 -:101A500005F06CBB30340020E0480020D05E002050 -:101A600055120008F7B50C46184E4FF47A7105462A -:101A700002FB01F396F90020501C0BD114482946B3 -:101A800001930268176A2246B8478442019B03D13A -:101A9000002310E0002AF1D096F90020511C01D05B -:101AA000012A0DD10B4829460268166A2246B04722 -:101AB000844205D10123084A0120137003B0F0BD10 -:101AC0004FF4FA7003F08CFB0020F7E71822002097 -:101AD000F8640020D45E0020BC5E0020002307B51F -:101AE000024601210DF107008DF80730FFF7BAFF1C -:101AF00020B19DF8070003B05DF804FB4FF0FF3004 -:101B0000F9E700000A46042108B5FFF7ABFF80F0B3 -:101B10000100C0B2404208BD074B0A4630B41978F4 -:101B2000064B53F82140014623682046DD69044BEB -:101B3000AC4630BC604700BFBC5E00206C73000840 -:101B4000A086010070B50A4E00240A4D03F0F4FD92 -:101B5000308028683388834208D903F0E9FD2B6878 -:101B600004440133B4F5003F2B60F2D370BD00BFD5 -:101B7000BE5E0020785E002003F0BCBE00F1006075 -:101B800000F500300068704700F10060920000F539 -:101B9000003003F033BE0000054B1A68054B1B886C -:101BA0009B1A834202D9104403F0C2BD0020704743 -:101BB000785E0020BE5E002038B5074D04462868D8 -:101BC000204403F0BBFD28B928682044BDE8384014 -:101BD00003F0C6BD38BD00BF785E0020002070470E -:101BE00000F1FF5000F58F10D0F80008704700009A -:101BF000064991F8243033B100230822086A81F89D -:101C00002430FFF7C1BF0120704700BF7C5E002079 -:101C1000014B1868704700BF0010005C244BF0B502 -:101C20001A680446234BC2F30B06120C1F8858682F -:101C3000BE4293F9085028D09F89BE4206D10120A8 -:101C40000C2505FB0033586893F9085041F2010355 -:101C50009A421CD041F203039A421AD042F2010385 -:101C60009A4218D042F203039A4208BF5625621ED8 -:101C70000B46441E0A4493420FD214F9016F581CBC -:101C80006EB1034600F8016CF5E70020D8E75A254D -:101C9000EDE75925EBE75825E9E7184605E02C2440 -:101CA00082421C7001D9981C5D70401AF0BD00BFC3 -:101CB0000010005C1C2200200020704770470000CC -:101CC0007047000070470000002310B5934203D016 -:101CD000CC5CC4540133F9E710BD0000013810B5E5 -:101CE00010F9013F3BB191F900409C4203D11AB178 -:101CF0000131013AF4E71AB191F90020981A10BDA8 -:101D00001046FCE703460246D01A12F9011B0029CF -:101D1000FAD1704702440346934202D003F8011BF4 -:101D2000FAE770472DE9F8431F4D144607468846E9 -:101D300095F8242052BBDFF870909CB395F82430BE -:101D40002BB92022FF2148462F62FFF7E3FF95F8C9 -:101D500024004146C0F1080205EB8000A24228BFE2 -:101D60002246D6B29200FFF7AFFF95F82430A41BAD -:101D700017441E449044E4B2F6B2082E85F824605D -:101D8000DBD1FFF735FF0028D7D108E02B6A03EB42 -:101D900082038342CFD0FFF72BFF0028CBD1002056 -:101DA000BDE8F8830120FBE77C5E0020024B1A7837 -:101DB000024B1A70704700BFBC5E00201822002042 -:101DC00038B5164C164D204602F000FD2946204637 -:101DD00002F028FD2D681348D5F89020D2F8043879 -:101DE00043F00203C2F8043803F0FAF90E4928461A -:101DF00002F026FED5F890200C48D2F804380C49A1 -:101E0000A04223F00203C2F804384FF4E1330B6020 -:101E100003D0BDE8384002F037BC38BDF86400207C -:101E20000C75000840420F0014750008D45E0020B5 -:101E3000A45E002038B50B4B04461A780A4B53F8C1 -:101E400022500A4B9D420CD0094B00211822184603 -:101E5000FFF760FF046001462846BDE8384002F005 -:101E600013BC38BDBC5E00206C730008F864002011 -:101E7000A45E0020202383F3118862B6704700001F -:101E8000002383F3118862B6704700000120704779 -:101E9000704700007047000010B4134602681468D1 -:101EA0000022A4465DF8044B6047000000F5805016 -:101EB00090F859047047000000F5805090F85204E3 -:101EC0007047000000F5805090F9580470470000FA -:101ED0004E20704700F5805208B5FFF7CBFFD2F8CF -:101EE0009834D2F894041844D2F890341844D2F8B4 -:101EF00078341844D2F888341844D2F8843418441A -:101F0000FFF7BEFF08BD00002DE9F74F0C4600F5B6 -:101F100080511F46054691F852349046BDF83090E6 -:101F20009BB1D1F874340133C1F8743423689A003A -:101F300006D4237B082B0BD9627B0AB10F2B07D960 -:101F4000D1F878340133C1F878344FF0FF300FE026 -:101F5000FFF790FFEB6AD3F8C42012F4001A0AD0FE -:101F6000D1F87C3400200133C1F87C34FFF788FFBE -:101F700003B0BDE8F08F22684FF0480BD3F8C4607F -:101F8000002A6B6AC6F30446B4BF42F08042920452 -:101F90001BFB063BCBF8002023685B004FEA06637F -:101FA00044BF42F00052CBF80020227B43EA0243B8 -:101FB0007201CBF80430607B18B343F44013CBF8C4 -:101FC0000430D1F8A4340133C1F8A434AB1803F5BC -:101FD0008353197B41F020011973207B019200F09B -:101FE0006DFF0330019A80105FFA8AF30AF1010A4B -:101FF00083420DDA04EB83010BEB8303496899609C -:10200000F2E7AB1803F58353197B60F34511E3E75F -:102010000121EB6A04F10C00B140C3F8D010AB18F9 -:10202000214603F58253C3E9048705EB461303F504 -:102030008253183351F804CB814243F804CBF9D1D1 -:1020400009882A442846198041F26803D65002F5CF -:10205000805209F0030392F86C1043F0100321F052 -:102060001F010B43214682F86C304246FFF708FF00 -:102070003B46CDF8309003B0BDE8F04F00F0E4BE31 -:102080002DE9F04700F58056044696F85254002D8D -:1020900040F00181037C032B40F092802B462846C0 -:1020A0002F465FFA83FC944510DA01EBCC0E51F811 -:1020B0003CC0BCF1000F04DBDEF804C0BCF1000F33 -:1020C00002DB01370133ECE70130FBE7FFF7D2FE1B -:1020D000E36AF0B9D3F8800040F00200C3F8800052 -:1020E0004E23E06A002F6ED1D0F8803043F0010318 -:1020F000C0F88030694B6A4A1B6803F1805303F5CE -:102100002C539B009342A36240F2AF80654801F0DC -:102110006FF84D2842D8DFF884814FEA004EDFF88F -:102120008891D8F800C04EEA8C0EC3F884E00CF118 -:10213000805303F52C539B00636100EB0C03D4F830 -:102140002CC0C8F80030C0F14E03DCF8800040F02D -:102150003000CCF880004FF0000CD4F81480E64634 -:102160005FFA8CF08242BCDD01EBC00A51F830000E -:10217000002810DBDAF804A0BAF1000F0BDA09EA44 -:1021800000400AF07F0A40EA0A0040F0084048F8A0 -:102190002E000EF1010E0CF1010CE1E79A6922F01C -:1021A00001029A6101F02AF80646E36A9B69D907A1 -:1021B00004D501F023F8831BFA2BF6D9FFF760FE54 -:1021C0002846BDE8F087B7EB530F3DD2DFF8CCE0EF -:1021D0004FEA074CDEF800304CEA830CC0F888C0A8 -:1021E00003F1805003EB4703002700F52C50CEF895 -:1021F0000030BC468000A061E06AD0F8803043F037 -:102200000C03C0F88030D4F818E0FBB29A427FF794 -:1022100071AF51F8330001EBC3080028D8F804303F -:1022200001DB002B0EDB20F0604023F0604340F028 -:10223000005043F000434EF83C000EEBCC000CF194 -:10224000010C43600137E0E7836923F001038361F8 -:1022500000F0D4FF0646E36A9B69DA07AED500F0CA -:10226000CDFF831BFA2BF6D9A8E7E26A936923F026 -:102270000103936100F0C2FF0746E36A9B69DB0735 -:1022800005D500F0BBFFC31BFA2BF6D996E7012555 -:1022900086F8525492E7002592E700BFCC5E0020FA -:1022A000FCB50040747300080000FF0713B500F58B -:1022B00080540191606C00F053FE1F280AD920223F -:1022C0000199606C00F0C2FEA0F120035842584111 -:1022D00002B010BD0020FBE700F5805008B5FFF705 -:1022E000C9FD406C00F010FEBDE80840FFF7C8BD16 -:1022F00000220260828142608260704700220023D7 -:1023000010B5C0E90023002304460C3020F8043C3B -:10231000FFF7EEFF204610BD2DE9F047074688B0D5 -:102320009A46884607F5805468469146FFF7A2FD15 -:10233000FFF7E4FF606C00F0F9FD1F282DD9202283 -:102340006946606C00F006FF202826D194F85234CC -:102350001BB303AD444605AB2E46083403CE9E4264 -:1023600044F8080C44F8041C3546F5D13068414661 -:1023700020603846B388A380DDE90023C9E9002343 -:10238000BDF808304A46AAF80030FFF779FD5346F9 -:1023900008B0BDE8F04700F045BD0020FFF770FD34 -:1023A00008B0BDE8F08700002DE9F84F002306468D -:1023B00000F58154054688461034C0E90133274BA7 -:1023C00046F8303B374638462037FFF797FFA7429D -:1023D000F9D105F580544FF4805305F5A3594FF01A -:1023E000000A26630026676405F5835709F1100982 -:1023F0004FF0000B1037E663C4E90D36012384F873 -:10240000403084F84830A7F11800203747E910AB76 -:10241000FFF76EFF47F8286C4F45F4D1B8F1010F74 -:1024200084F85884A4F85A64A4F85C64A4F85E6440 -:1024300084F86064A4F86264A4F86464A4F8666430 -:1024400084F8686402D9064800F0D2FE054B28469D -:1024500053F82830EB62BDE8F88F00BFC473000862 -:1024600098730008B4730008044B10B5197804463B -:102470004A1C1A70FFF798FF204610BDC95E002065 -:102480002DE9F04700295FD0304F3148B7FBF1F517 -:1024900081428CBF0A201120431EB5FBF0FC00FBDB -:1024A0001C50DCB220B1022B1846F5D8002037E0D2 -:1024B0000CF1FF35B5F5806F32D2C4EBC4094FF48F -:1024C0007A7009F103034FEAE308C3F3C70308F185 -:1024D000010AA4EB030E08FB00085FFA8EF65AFA15 -:1024E0008EFEB8FBFEFEBEF5617F1BDC1FFA8EF48C -:1024F000581C56FA80F00CFB00FCB7FBFCFC614555 -:10250000D4D1013BDBB20F2BD0D8711E0020C9B251 -:10251000072905D8107101201480558053719171DD -:10252000BDE8F08709F1FF334FEAE30EC3F3C703B9 -:102530000EF10108E41A0EFB0000E6B258FA84F42A -:10254000B0FBF4F4A4B2D3E70846E9E700B4C4044E -:102550003F420F0038B540F27772C36A154CC3F89A -:10256000BC200722C36AC3F8C8202268C16A93004E -:1025700043F4C023C1F8A03002F1805302F16C0192 -:10258000C56A03F52C53EA3289009B00226041F0B2 -:10259000E061094AC361C5F8C01003F5D87103F5BD -:1025A0006A7341629342836202D9044800F020FEBC -:1025B00038BD00BFCC5E0020FCB50040747300083D -:1025C0002DE9F04F00F58055994689B0044695F8FD -:1025D00058348A469046022B04D90027384609B061 -:1025E000BDE8F08F9E4A52F8231009B942F8230043 -:1025F0009C49C4F80CA00B7884F81090C3B9FFF77D -:1026000039FC994BD3F8EC2042F48072C3F8EC20EB -:10261000D3F8942042F48072C3F89420D3F8942025 -:1026200022F48072C3F8942001230B70FFF728FC7A -:1026300095F851346BB9FFF71DFC8C4A95F8583466 -:10264000D35CEBB1012B24D0012385F85134FFF783 -:1026500017FCFFF70FFCE26A936923F01003936104 -:1026600000F0CCFD0746E36A9E6916F0080617D015 -:1026700000F0C4FDC31BFA2BF5D9FFF701FCACE752 -:102680000221132001F04EFE0221152001F04AFE26 -:10269000DAE70221142001F045FE02211620F5E7B9 -:1026A0009A6942F001029A6100F0A8FD0746E36AC8 -:1026B0009A69D00705D400F0A1FDC31BFA2BF6D907 -:1026C000DBE79A69002704F5825B42F002020BF116 -:1026D000100B9A61E36A5F65FFF7D2FB686C00F04C -:1026E00013FC202200216846FFF714FB02A8FFF725 -:1026F000FFFD6A460BEB06030DF1180E0697944694 -:102700000833BCE80300F44543F8080C43F8041C04 -:102710006246F4D1DCF8000020361860B6F5806F10 -:102720009CF804201A71DCD1002304F5A252514612 -:1027300020461A3285F8503485F85334FFF7A0FE4E -:10274000074690B9E26A936923F00103936100F0B0 -:1027500055FD0546E36A9B69D9077FF53EAF00F05A -:102760004DFD431BFA2BF5D937E795F85F6495F8D3 -:102770005E243602C5F86CA4E36A46EA426695F820 -:1027800060241643B5F85C2446EA0246DE61B8F1DF -:10279000000F29D004F5A352414620460232FFF72C -:1027A0006FFE90B9E26A936923F00103936100F030 -:1027B00025FD0546E36A9B69DA077FF50EAF00F059 -:1027C0001DFD431BFA2BF5D907E795F8683495F8FA -:1027D00067141B01C5F87084E26A43EA0123B5F867 -:1027E000641443EA0143D360E36A00262046C3F839 -:1027F000BC60FFF7AFFE85F859646FF04042E36AB2 -:10280000B9F1030F1A651A4AE36A5A654FF00222BA -:10281000E36A9A654FF0FF32E36AC3F8E0204FF0B5 -:102820000302E36ADA65E26A936943F440739361F1 -:102830003FF4D4AEE26A936923F00103936100F0A0 -:10284000DDFC0646E36A9B69DB0705D500F0D6FC94 -:10285000831BFA2BF6D9C0E6012385F85234BDE676 -:10286000C05E0020C85E002000440258AC7300081F -:10287000550200022DE9F04F054689B09046994671 -:10288000002741F2680A00F58056EB6AD3F8D83089 -:10289000FB40D8074AD505EB47124FEA471B524485 -:1028A0001379190742D4D6F880340133C6F880343E -:1028B00013799A0605EB0B0248BFD6F8A8345244A8 -:1028C00044BF0133C6F8A834137943F008031371E9 -:1028D000DB0723D596F8533403B305F582546846D5 -:1028E000FFF70CFD03AB18345C4404F1080C2068BE -:1028F000083454F8041C1A46644503C21346F6D142 -:102900002068694610602846A2889A800123ADF8A5 -:1029100008302B68CDE900891B6C9847D6F85434F1 -:1029200023B1D6F89C340133C6F89C340137202FEC -:10293000ABD109B0BDE8F08F2DE9F04F0F468DB057 -:10294000044600F05DFC82468946002F5BD1E36AB5 -:10295000D3F8A02012F4FE0F03D100200DB0BDE883 -:10296000F08FD3F8A420920141BF04F58051D1F833 -:1029700094240132C1F89424D3F8A4205606ECD054 -:10298000D3F8A450E669C5F305254823E8464FF07F -:10299000000B03FB05664046FFF7AAFC32685100B6 -:1029A0004ABF22F06043C2F38A4343F000439200DF -:1029B00048BF43F080430093736813F400131BBFB8 -:1029C000012304F580528DF80D308DF80D301EBFB7 -:1029D000D2F8AC340133C2F8AC34F38803F00F03FF -:1029E0008DF80C309DF80C0000F068FA5FFA8BF35C -:1029F000984225D9F2180CA90BF1010B127A0B445D -:102A000003F82C2CEEE7012FA7D1E36AD3F8B0200E -:102A100012F4FE0FA1D0D3F8B420950141BF04F504 -:102A20008051D1F894240132C1F89424D3F8B42011 -:102A3000500692D0D3F8B450266AC5F30525A4E712 -:102A4000EFB9E36AC3F8A85004A807ADFFF756FC36 -:102A500098E80F0007C52B800023204604A9ADF895 -:102A60001830236804F580541B6CCDE904A99847FD -:102A700058B1D4F88C340133C4F88C346EE7012F8C -:102A8000E2D1E36AC3F8B850DEE7D4F8903401200D -:102A90000133C4F8903461E7F8B505460F4600F5F8 -:102AA0008054012639462846FFF746FF10B184F8C6 -:102AB0005364F7E7D4F8543423B1D4F89C34013389 -:102AC000C4F89C34F8BD0000C36AF0B51A6C12F467 -:102AD0007F0F2BD01B6C00F5805441F268054FF03E -:102AE000010CC4F8A0340023471900EB43125E0127 -:102AF0002A44117911F0020F15D0490713D4B9599E -:102B0000C66A0CFA01F1D6F8CCE011EA0E0F0AD031 -:102B1000C6F8D410117941F004011171D4F8882459 -:102B20000132C4F888240133202BDED1F0BD00002F -:102B30002B4B70B51E561B5C012B30D8294D2A4AF1 -:102B400055F8233052F8264013B349B3236D9A0544 -:102B500010D54FF40073236500F052FB50EA0102D8 -:102B60000B4602D0013861F10003024655F82600F9 -:102B7000FFF780FE236D9B012CD54FF0007255F8B6 -:102B80002630226503F58053012283F8592421E081 -:102B900001232365102323654FF48053236570BD03 -:102BA000236DDA0702D4236D5B0706D505230021C8 -:102BB00055F826002365FFF76FFF236DD80602D472 -:102BC000236D590606D55023012155F826002365AB -:102BD000FFF762FF55F82600BDE87040FFF774BFAD -:102BE000B0730008C05E0020B473000808B5FFF79A -:102BF00041F9FFF769FFBDE80840FFF741B9000060 -:102C0000C36AD3F8C00010F07C5005D0D3F8C400DC -:102C100080F40010C0F340507047000000F5805071 -:102C200008B5FFF727F9406C00F080F9FFF728F9A5 -:102C300043090CBF0120002008BD000000F58053AF -:102C400093F8592462B1C16A8A6922F001028A614B -:102C5000D3F898240132C3F89824002283F8592429 -:102C6000704700002DE9F74300F582519846002592 -:102C7000FFF700F9103141F2680E4FF0010900F53D -:102C8000805C00EB4514744423795E071CD4DB069A -:102C90001AD58E69C36A09FA06F6D3F8CC703E429B -:102CA00012D04F6801970F689742019F77EB080792 -:102CB0000AD2C3F8D460237943F004032371DCF80B -:102CC00084340133CCF8843401352031202DD8D11F -:102CD00003B0BDE8F043FFF7D3B80000F8B51E46D7 -:102CE00000230F46054613701446FFF797FF80F048 -:102CF000010038701EB12846FFF782FF2070F8BD32 -:102D00002DE9F04F994685B00B780E468046174660 -:102D100001931378DDE90EBA029300F071FA33786B -:102D200004460D4613B93B78002B41D022462B4672 -:102D30004046FFF797FFFFF759FFFFF77FFF4B462E -:102D40003A463146FFF7CAFF33782BB1019B1BB1DE -:102D5000012005B0BDE8F08F3B7813B1029B002B3A -:102D6000F6D108F5805303935C4575EB0A031FD237 -:102D7000039BD3F85404D8B1BBEB04020368D968B1 -:102D80006AEB050388474B463A4631464046FFF713 -:102D9000A5FF337813B1019B002BD9D13B7813B138 -:102DA000029B002BD4D100F02BFA04460D46DBE742 -:102DB0000020CEE7002108B50846FFF7B9FEBDE8C0 -:102DC000084001F075B9000008B501210020FFF7A7 -:102DD000AFFEBDE8084001F06BB9000008B5002166 -:102DE0000120FFF7A5FEBDE8084001F061B9000031 -:102DF000012108B50846FFF79BFEBDE8084001F039 -:102E000057B900000FB4002004B0704713B56C46EA -:102E1000031D84E8060094E8030083E80500012010 -:102E200002B010BD73B58568019155B11B885B0771 -:102E300007D4D0E90036DB6B9847019AC1B230461F -:102E4000A847012002B070BDF0B5866889B005467C -:102E50000C465EB1BDF838305B070AD4D0E90037C4 -:102E6000DB6B98472246C1B23846B047012009B013 -:102E7000F0BD0022002301F10806CDE90023002364 -:102E80000A46ADF8083003AB1068083252F8041C4B -:102E90001C46B24203C42346F6D1106820609288D3 -:102EA000A28000F0AFF90423ADF808302B68CDE91B -:102EB00000011B6C694628469847D7E7082817D9B0 -:102EC00009280CD00A280CD00B280CD00C280CD0C8 -:102ED0000D280CD00E2814BF4020302070470C2045 -:102EE000704710207047142070471820704720202A -:102EF0007047000010B5037C044613B9006804F065 -:102F00002BF9204610BD00000023BFF35B8FC36088 -:102F1000BFF35B8FBFF35B8F8360BFF35B8F704743 -:102F2000BFF35B8F0068BFF35B8F704770B50546DA -:102F30000C30FFF7F5FF044605F108063046FFF7B1 -:102F4000EFFFA04206D96D683046FFF7E9FF254440 -:102F5000281A70BD3046FFF7E3FF201AF9E700009A -:102F600070B505464068A0B105F10C0605F10800F2 -:102F7000FFF7D6FF04463046FFF7D2FF844204F144 -:102F8000FF34304694BF6D680025FFF7C9FF2C441D -:102F9000201A70BD38B50C460546FFF7C7FFA042A2 -:102FA00010D305F10800FFF7BBFF04446868BFF3C6 -:102FB0005B8FB4FBF0F100FB11440120AC60BFF368 -:102FC0005B8F38BD0020FCE72DE9F0411446074631 -:102FD0000D46FFF7C5FF844228BF0446D4B1B8466A -:102FE00058F80C6B4046FFF79BFF30442860404682 -:102FF0007E68FFF795FF331A9C4203D801206C606E -:10300000BDE8F081A41B6B603B682044AB60E860C6 -:103010000220F5E72046F3E738B50C460546FFF7F2 -:103020009FFFA04210D305F10C00FFF779FF044485 -:103030006868BFF35B8FB4FBF0F100FB1144012023 -:10304000EC60BFF35B8F38BD0020FCE72DE9FF414A -:103050008846694607466C46FFF7B6FF002506B26C -:1030600004EBC606B4420AD0626808EB050120688A -:103070000834FEF729FE54F8043C1D44F2E72946C3 -:103080003846FFF7C9FF284604B0BDE8F0810000CC -:10309000F8B505460C300F46FFF742FF05F108066C -:1030A00004463046FFF73CFFA042304688BF6C68BC -:1030B000FFF736FF201A386020B12C683046FFF742 -:1030C0002FFF2044F8BD000073B5144606460D4698 -:1030D000FFF72CFF8442019028BF0446DCB101A910 -:1030E0003046FFF7D5FF019B33B93268C5E902339B -:1030F000C5E9002401200CE09C42286038BF0194FF -:10310000019884426860F5D93368241A0220AB60C4 -:10311000EC6002B070BD2046FBE700002DE9FF41E6 -:103120000F4669466C46FFF7CFFF00B2002604EB5E -:10313000C005AC4209D0D4F80480B81954F8081B73 -:1031400042464644FEF7C0FDF3E7304604B0BDE812 -:10315000F081000038B50546FFF7E0FF0446014660 -:103160002846FFF717FF204638BD000000B59BB08A -:10317000EFF3098168226846FEF7A6FDEFF30583A9 -:10318000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A93 -:103190009B6AFEE700ED00E000B59BB0EFF309810C -:1031A00068226846FEF790FDEFF30583044B9A6BA7 -:1031B0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF52 -:1031C00000ED00E000B59BB0EFF30981682268468E -:1031D000FEF77AFDEFF30583034B5A6B9A6A9A6AFE -:1031E0009A6A9A6A9B6AFEE700ED00E0FEE700003B -:1031F0000FB408B5029801F083FFFEE702F0C2BBEE -:1032000002F09ABB02F098BB30B50A44084D9142D7 -:103210000DD011F8013B5840082340F30004013B56 -:103220002C4013F0FF0384EA5000F6D1EFE730BDE5 -:103230002083B8ED2DE9F041C56915B9C161BDE83C -:10324000F0814B68AC4623F06047C3F38A464FEAEF -:10325000D37EC3F3807816EA230638BF3E462B465A -:103260005A68BEEBD27F22F060440AD0002A18DAF6 -:10327000A40CB44217D19D420FD10D60DEE7134676 -:10328000EEE7A74207D102F08044C2F380724245C4 -:103290000BD054B1EFE708D2EDE7CCF800100B608B -:1032A000CDE7B44201D0B442E5D81A689C46002A62 -:1032B000E5D11960C3E700002DE9F047089D01F052 -:1032C000070400EBD1004FF47F494FEAD5082244B0 -:1032D00005F00705944201D1BDE8F08704F0070727 -:1032E00005F0070A111B08EBD50E57453E4613F8AB -:1032F0000EC038BF5646C6F108068E4228BF0E469D -:10330000E108415C34443544B94029FA06F721FA12 -:103310000AF1FFB28CEA010147FA0AF739408CEA58 -:10332000010C03F80EC0D5E780EA0120082341F222 -:10333000210201B2013B4000002980B2B8BF5040D9 -:1033400013F0FF03F5D1704738B50C468D18A54230 -:1033500000D138BD14F8011BFFF7E6FFF7E70000C6 -:1033600002684AB1136801890360C38801339BB2C4 -:103370009942C38038BF03811046704770B588B04A -:10338000044620220D4668460021FEF7C3FC204675 -:103390000495FFF7E5FF024660B16B46054608AEAF -:1033A0001C46083503CCB44245F8080C45F8041C0B -:1033B0002346F5D1104608B070BD0000082817D983 -:1033C00009280CD00A280CD00B280CD00C280CD0C3 -:1033D0000D280CD00E2814BF4020302070470C2040 -:1033E0007047102070471420704718207047202025 -:1033F00070470000082817D90C280CD910280CD9C0 -:1034000014280CD918280CD920280CD930288CBFA6 -:103410000F200E207047092070470A2070470B20AC -:1034200070470C2070470D207047000010B54B68A6 -:1034300023B9CA8A63F30902CA8210BDC4681A6834 -:103440001C60C360438A013B43824A60EFE700008F -:103450002DE9F84F1D46CB8A0F468146C3F309017B -:10346000924606290B4630D00020AAB207F1190473 -:103470009EB21FFA80F8052E0FD8904503F1010384 -:1034800006D30A44FB8A62F309030120FB821AE097 -:103490001AF800600130E654EAE79045F1D2A1F154 -:1034A000060B1C237C68BBFBF3F203FB12BB1FFA69 -:1034B0008BF6002C45D14846FFF752FF044638B939 -:1034C00078606FF00200BDE8F88F4FF00008E6E783 -:1034D000002606607860ADB24FF0000B454510D96C -:1034E0000AEB0803221D13F8011B08F1010891558E -:1034F000B1B21FFA88F81B292BD0454506F1010609 -:10350000F1D8FB8AC3F30902154465F30903BCE74C -:1035100001321C4692B22368002BF9D1AB1F0B4439 -:103520001C21B3FBF1F301339BB29A42D3D2BBF11E -:10353000000FD0D14846FFF713FF20B9C4F800B000 -:10354000BFE70122E7E7C0F800B05E46206004460E -:10355000C1E74545D5D94846FFF702FF08B92060C5 -:10356000AFE7C0F800B0002620600446B6E70000D0 -:103570002DE9F04F2DED028B83B007469146BDF843 -:103580003C50CDE90013002A00F092802DB10E9B33 -:10359000002B00F08D80072D32D807F10C00FFF7CB -:1035A000DFFE044638B96FF00204204603B0BDECDC -:1035B000028BBDE8F08F14220021FEF7ABFB2A46F8 -:1035C0000E9904F10800FEF77FFB681CC0B2FFF7FC -:1035D00011FFFFF7F3FE207499F80030013803F073 -:1035E0001F0314FA80F063F03F0303723846009B18 -:1035F00043F0004161602146FFF71CFE0124D4E73F -:103600004FF0000800F10C034FF0800A4646444694 -:1036100008EE103A18EE100AFFF7A2FE83460028C3 -:10362000C1D014220021FEF775FBC6BB019B02200E -:10363000ABF808300E9B00F1080299195BFA82F290 -:103640000130C0B2082801D0AE422AD3FFF7D2FE23 -:10365000AE4208BF4FF0400AFFF7B0FE99F80020D5 -:10366000411E009B02F01F0201345BFA81F142EA25 -:10367000481288F0010824B24AEA020A43F00042E4 -:1036800081F808A059468BF810003846CBF8042082 -:103690004FF0000AFFF7CEFDAE42BBD185E7002018 -:1036A000C8E711F801CB013602F801CBB6B2C7E783 -:1036B0006FF0010479E70000F8B515460E462822A0 -:1036C000002104461F46FEF725FB069BB5F5001FAB -:1036D000A760636004F10C00079B34BF6A094FF6D2 -:1036E000FF722362002397B29A4205D80023036039 -:1036F00027826382A382F8BD0660013330462036FC -:10370000F2E7000003781BB94BB2002BC8BF017071 -:1037100070470000007870472DE9F74FDDF83C90C6 -:10372000804692469B46BDF830500D9E9DF838402D -:10373000BDF84070B9F1000F01D1002F51D11F2CFD -:103740004FD898F80000B0B9072F47D835F00303D9 -:1037500047D13A4649464FF6FF702D02FFF7F4FD78 -:1037600020F0010045EA04644004400C44EA40248F -:103770004FF6FF7321E040EA0520072F40EA04647A -:10378000F6D900254FF6FF73C5F12000A5F1200200 -:103790002AFA05F108350BFA00F02BFA02F2014380 -:1037A00018461143C9B2FFF7BFFD402D0346EBD1C8 -:1037B0003A464946FFF7C8FD034632462146404691 -:1037C000CDE90097FFF7D4FE33780133DBB21F2B2E -:1037D00088BF0023337003B0BDE8F08F6FF00300A3 -:1037E000F9E76FF00100F6E72DE9F04F85B092465A -:1037F00006469B46DDF848800F9D9DF840209DF8C9 -:103800004490BDF84C70B8F1000F01D1002F49D1A0 -:103810001F2A47D83378002B47D00C029DF8381068 -:10382000072F44EA026444EAC93444EA014444EA02 -:10383000030444F0800432D900234FF6FF72C3F131 -:10384000200CA3F120002AFA03F103930BFA0CFCDD -:103850002BFA00F041EA0C0101431046C9B2FFF710 -:1038600063FD039B02460833402BE8D13A464146AC -:10387000FFF76AFD03462A4621463046CDE9008718 -:10388000FFF776FEB9F1010F06D12B780133DBB2D9 -:103890001F2B88BF00232B7005B0BDE8F08F4FF6BB -:1038A000FF73E8E76FF00100F6E76FF00300F3E75E -:1038B000C06900B104307047C3691A68C261C26848 -:1038C0001A60C360438A013B438270472DE9F0418F -:1038D000D0F8188014461D46184E4146002709B9F5 -:1038E000BDE8F081D1E90223A21A65EB03039642F9 -:1038F00077EB03031ED283698B420DD1FFF796FD50 -:1039000083691B688361C3680B60438AC160013BA4 -:10391000816943828846E2E7FFF788FD0B68C8F8B3 -:103920000030C3680B60438AC160013B4382D8F812 -:103930000010D4E788460968D1E700BF80841E00E4 -:103940002DE9F04F8BB00D4614469B46DDF85090A4 -:103950008046002800F01881B9F1000F00F01481B2 -:10396000531E3F2B00F21081012A03D1BBF1000F3F -:1039700040F00A810023CDE90833B8F81430B5EBE4 -:10398000C30F4FEAC30703D300200BB0BDE8F08F8D -:103990002B199F42D8F80C3036BF7F1B2746FFB249 -:1039A0001BB9D8F81030002B7AD02F2D4DD8C5F187 -:1039B000300600232946B742009308ABD8F8080028 -:1039C0002CBFF6B23E46A7EB060A354432465FFAF4 -:1039D0008AFAFFF771FCB8F81430302103F1005374 -:1039E000063BDB000493D8F80C300393039B13B120 -:1039F000BAF1000F2CD1D8F8100040B1BAF1000F85 -:103A000005D008AB5246691A0096FFF755FC38B24C -:103A1000002FB9D066070AD00AAB624203EBD4018B -:103A200002F0070211F8083C134101F8083C082C89 -:103A30003DD9102C40F2B580202C40F2B780BBF16C -:103A4000000F00F09C80082335E0BA460026C2E74C -:103A5000049BE02B28BFE02306930B44AB42059365 -:103A600015D95A1B0398691A0096924508AB00F1C4 -:103A7000040034BF5246D2B20792FFF71DFC079AEA -:103A80001644AAEB020A1544F6B25FFA8AFA049BBE -:103A9000069A05999B1A0493039B1B680393A5E759 -:103AA00000933A4608AB2946D8F80800ADE7BBF1C9 -:103AB000000F13D00123B4EBC30F6BD0082C12D826 -:103AC0009DF82030621E23FA02F2D50706D54FF08A -:103AD000FF3202FA04F423438DF820309DF82030A1 -:103AE00089F8003051E7102C12D8BDF82030621E42 -:103AF00023FA02F2D10706D54FF0FF3202FA04F49E -:103B00002343ADF82030BDF82030A9F800303CE761 -:103B1000202C0FD80899631E21FA03F3DA0705D584 -:103B20004FF0FF3202FA04F40C430894089BC9F8E2 -:103B300000302AE7402C2AD0611EC4F12102A4F1F2 -:103B40002103DDE9086526FA01F105FA02F225FAFA -:103B500003F311431943CB0711D50122A4F120032C -:103B6000C4F1200102FA03F322FA01F1A2400B434F -:103B7000524263EB430332432B43CDE90823DDE993 -:103B80000823C9E9002300E76FF00100FDE66FF0AC -:103B90000800FAE6082CA1D9102CB4D9202CEED8B4 -:103BA000C4E7BBF1000FAED0022384E7BBF1000FE6 -:103BB000BCD004237FE70000012A30B5144638BF8B -:103BC000012485B00025402C28BF4024012ACDE9DE -:103BD000025518D81B788DF8083063070AD004AB5B -:103BE000624203EBD40502F0070215F8083C93404B -:103BF00005F8083C034600912246002102A8FFF781 -:103C00005BFB05B030BD082AE4D9102A03D81B8815 -:103C1000ADF80830E1E7202A95BF1B68D3E90023FF -:103C20000293CDE90223D8E710B5CB681BB98B60AE -:103C30000B618B8210BDC4681A681C60C360438A24 -:103C4000013B4382CA60F0E72DE9F04FD1F80080D4 -:103C500093B004460D4618F0800FCDE90323C8F356 -:103C6000C01219BFC8F3C03BC8F306264FF0020BC1 -:103C70001646B8F1000F80F2D18118F0C0430593C9 -:103C800040F0CC810B7B002B00F0C881BBF1020F10 -:103C900003D00178B14240F0C48108F07F01069161 -:103CA0006AB3C8F3074A2B447606069A46EA0B46DF -:103CB00093F8039046EA82465FEAD91346EA0A0679 -:103CC000079300F090800022002367680AA920462D -:103CD000CDE90A23069B524600935B46B84700286D -:103CE0007ED0A7699FB9314604F10C00FFF746FB6F -:103CF0000746E0B96FF0020013B0BDE8F08FC8F3DB -:103D00000F2A18F07F0F08BF0AF0030ACBE73B69C0 -:103D10009E420DD03F68002FF9D1314604F10C00CE -:103D2000FFF72CFB07460028E4D0A3693B60A7619E -:103D300000264FF6FF70DDE90A23C6F1200E22FAB5 -:103D400006F1A6F1200C083603FA0EFE099223FABA -:103D50000CFC089341EA0E0141EA0C01C9B2FFF7DD -:103D6000E3FA402EDDE90832E7D1B882FB7D09F0A5 -:103D70001F06C8F30468C3F384039B1B98B2002B8F -:103D8000D7E90221BCBF00F120031BB252EA0100B7 -:103D90000FD00398821A049860EB0101A748904263 -:103DA0004FF000028A4104D3079A002A5BD0012B0E -:103DB00023DDFA7D4FEA89033946204602F00302EB -:103DC00003F07C031343FB75FFF730FB079BA3B99C -:103DD000FB7DC3F38402013262F38603FB7504E0CA -:103DE0006FF00B0088E7A76917B96FF00C0083E745 -:103DF0003B699E42BAD03F68F6E719F0400F32D0D7 -:103E0000039B142200210DA8BB60049BFB60FDF7FF -:103E100081FF039B0AA920460A93049BADF83EA0AC -:103E20000B932B1D8DF840B00C932B7B8DF84160CC -:103E3000013B8DF84280DBB2ADF83C30069B8DF83B -:103E4000433094F8243083F001038DF84430A368A4 -:103E50009847FB7DC3F38403013303F01F039B02E8 -:103E6000FB82002048E7FB7DC9F34012B2EBD31F71 -:103E700040F0DA80C3F38403B34240F0D88007995E -:103E80004FEA99122B7B002934D0D20741D4032B5F -:103E900040F2D080039BAE1D394604F10C00BB609C -:103EA0003246049BFB602B7B033BDBB2FFF7D0FA6F -:103EB00000280DDA20463946FFF7B8FAFB7D0320CB -:103EC000C3F38403013303F01F039B02FB8213E758 -:103ED000AB883B832A7B033AD2B2B88A3146FFF7DC -:103EE00033FAFB7DB882DA43C2F3C01262F3C71320 -:103EF000FB75B6E76AB92E1D013B394604F10C008B -:103F0000DBB23246FFF7A4FA0028D3DB2A7B013A62 -:103F1000E2E7F98A013BC1F30901DAB2052959D870 -:103F2000281D002307F11A0C9A4208D910F801EB5A -:103F300001330CF801E00131DBB20629F4D1039919 -:103F400093420A9138BF043304992CBF002355FAD9 -:103F500083F30B9107F11A010C9179680E930D917F -:103F6000291DFB8AADF83EA0C3F309038DF840B0CC -:103F70008DF841601A44069B8DF842808DF84330DD -:103F800094F82430ADF83C2083F001038DF84430E0 -:103F90000023B88A7B602A7B013AFFF7D5F93B8B77 -:103FA000B882834203D1A3680AA9204698472046D5 -:103FB0000AA9FFF739FEFB7DB88AC3F384030133F6 -:103FC00003F01F039B02FB823B8B984214BF11201E -:103FD000002091E67B68002BB1D0062001E01C3068 -:103FE0006346D3F800C0BCF1000FF8D1091A05F1FF -:103FF000040C081D00EB030905989DF8143001EB33 -:10400000000EBEF11B0F9AD89A4298D91CF8013BBA -:1040100009F8013B059B01330593EDE76FF00900BB -:104020006AE66FF00A0067E66FF00D0064E66FF075 -:104030000E0061E66FF00F005EE600BF80841E0098 -:10404000EFF30983054968334A6B22F001024A63A2 -:1040500083F30988002383F31188704700EF00E0A1 -:10406000202080F3118862B60D4B0E4AD96821F4E6 -:10407000E0610904090C0A430B49DA60D3F8FC201B -:1040800042F08072C3F8FC20084AC2F8B01F1168E1 -:1040900041F0010111601022DA7783F822007047A5 -:1040A00000ED00E00003FA0555CEACC5001000E0BD -:1040B000202310B583F311880E4B5B6813F4006363 -:1040C00014D0F1EE103AEFF309844FF08073683C9E -:1040D000E361094BDB6B236684F3098800F0C2FFC0 -:1040E00010B1064BA36110BD054BFBE783F31188AC -:1040F000F9E700BF00ED00E000EF00E00B0700086B -:104100000E070008026843681143016003B11847B5 -:1041100070470000024A136843F0C0031360704701 -:104120000078004013B50E4C204600F0A1FA04F1CF -:10413000140000234FF400720A49009400F062F961 -:10414000094B4FF40072094904F13800009400F063 -:10415000DBF9074A074BC4E9172302B010BD00BFC3 -:10416000D45E0020405F002015410008406100201F -:104170000078004000E1F505037C30B5244C0029AF -:1041800018BF0C46012B11D1224B98420ED1224B65 -:10419000D3F8E82042F08042C3F8E820D3F8102199 -:1041A00042F08042C3F81021D3F810312268036E28 -:1041B000C16D03EB52038466B3FBF2F3626815042E -:1041C00042BF23F0070503F0070343EA4503CB6032 -:1041D000A36843F040034B60E36843F001038B6046 -:1041E00042F4967343F001030B604FF0FF330B6210 -:1041F000510505D512F0102205D0B2F1805F04D030 -:1042000080F8643030BD7F23FAE73F23F8E700BF32 -:1042100008740008D45E0020004402582DE9F047DD -:10422000C66D05463768F4692107346219D014F069 -:10423000080118BF8021E20748BF41F02001A30711 -:104240004FF0200348BF41F04001600748BF41F4F0 -:10425000807183F31188281DFFF754FF002383F337 -:104260001188E2050AD5202383F311884FF40071E9 -:10427000281DFFF747FF002383F311884FF0200923 -:104280004FF0000A14F0200838D13B0616D54FF045 -:10429000200905F1380A200610D589F31188504607 -:1042A00000F066F9002836DA0821281DFFF72AFFFA -:1042B00027F080033360002383F31188790614D537 -:1042C000620612D5202383F31188D5E913239A427D -:1042D00008D12B6C33B127F040071021281DFFF7C0 -:1042E00011FF3760002383F31188E30618D5AA6E07 -:1042F0001369ABB15069BDE8F047184789F31188DD -:10430000736A284695F86410194000F0CBF98AF3D7 -:104310001188F469B6E7B06288F31188F469BAE7E6 -:10432000BDE8F087090100F16043012203F5614314 -:10433000C9B283F8001300F01F039A4043099B00A1 -:1043400003F1604303F56143C3F880211A607047AD -:10435000F8B51546826804460B46AA4200D2856825 -:10436000A1692669761AB5420BD218462A46FDF78E -:10437000ABFCA3692B44A3612846A3685B1BA36025 -:10438000F8BD0CD9AF1B18463246FDF79DFC3A46E6 -:10439000E1683044FDF798FCE3683B44EBE71846DE -:1043A0002A46FDF791FCE368E5E700008368934245 -:1043B000F7B50446154600D28568D4E90460361A7C -:1043C000B5420BD22A46FDF77FFC63692B4463613B -:1043D0002846A3685B1BA36003B0F0BD0DD932462D -:1043E000AF1B0191FDF770FC01993A46E06831443A -:1043F000FDF76AFCE3683B44E9E72A46FDF764FC05 -:10440000E368E4E710B50A440024C361029B8460BA -:10441000C16002610362C0E90000C0E9051110BD7E -:1044200008B5D0E90532934201D1826882B9826829 -:10443000013282605A1C426119700021D0E90432B5 -:104440009A4224BFC368436100F0E6FE002008BD25 -:104450004FF0FF30FBE7000070B5202304460E4606 -:1044600083F31188A568A5B1A368A269013BA36085 -:10447000531CA36115782269934224BFE368A361AA -:10448000E3690BB120469847002383F3118828463F -:1044900007E03146204600F0AFFE0028E2DA85F35F -:1044A000118870BD2DE9F74F04460E461746984611 -:1044B000D0F81C904FF0200A8AF311884FF0000BBF -:1044C000154665B12A4631462046FFF741FF0346AF -:1044D00060B94146204600F08FFE0028F1D000234D -:1044E00083F31188781B03B0BDE8F08FB9F1000F9A -:1044F00003D001902046C847019B8BF31188ED1A29 -:104500001E448AF31188DCE7C160C361009B8260AE -:104510000362C0E905111144C0E900000161704760 -:10452000F8B504460D461646202383F31188A76884 -:10453000A7B1A368013BA36063695A1C62611D7047 -:10454000D4E904329A4224BFE3686361E3690BB1A2 -:1045500020469847002080F3118807E03146204626 -:1045600000F04AFE0028E2DA87F31188F8BD000067 -:10457000D0E9052310B59A4201D182687AB98268E0 -:104580000021013282605A1C82611C7803699A42C0 -:1045900024BFC368836100F03FFE204610BD4FF08A -:1045A000FF30FBE72DE9F74F04460E4617469846C5 -:1045B000D0F81C904FF0200A8AF311884FF0000BBE -:1045C000154665B12A4631462046FFF7EFFE034601 -:1045D00060B94146204600F00FFE0028F1D00023CC -:1045E00083F31188781B03B0BDE8F08FB9F1000F99 -:1045F00003D001902046C847019B8BF31188ED1A28 -:104600001E448AF31188DCE70268436811430160A5 -:1046100003B11847704700001430FFF743BF000094 -:104620004FF0FF331430FFF73DBF00003830FFF785 -:10463000B9BF00004FF0FF333830FFF7B3BF0000C1 -:104640001430FFF709BF00004FF0FF311430FFF7BF -:1046500003BF00003830FFF763BF00004FF0FF32A8 -:104660003830FFF75DBF000000207047FFF75ABDEC -:10467000044B036000234360C0E902330123037449 -:10468000704700BF2074000810B52023044683F350 -:104690001188FFF771FD02232374002383F311882F -:1046A00010BD000038B5C36904460D461BB904218E -:1046B0000844FFF7A9FF294604F11400FFF7B0FEF4 -:1046C000002806DA201D4FF48061BDE83840FFF76E -:1046D0009BBF38BD026843681143016003B11847AE -:1046E0007047000013B5406B00F58054D4F8A4382F -:1046F0001A681178042914D1017C022911D1197981 -:10470000012312898B4013420BD101A94C3002F0D6 -:104710009BF8D4F8A4480246019B2179206800F058 -:10472000DFF902B010BD0000143002F01DB8000027 -:104730004FF0FF33143002F017B800004C3002F095 -:10474000EFB800004FF0FF334C3002F0E9B8000042 -:10475000143001F0EBBF00004FF0FF31143001F0D6 -:10476000E5BF00004C3002F0BBB800004FF0FF3254 -:104770004C3002F0B5B800000020704710B500F5CD -:104780008054D4F8A4381A681178042917D1017C10 -:10479000022914D15979012352898B4013420ED139 -:1047A000143001F07DFF024648B1D4F8A4484FF41C -:1047B000407361792068BDE8104000F07FB910BDFA -:1047C000406BFFF7DBBF0000704700007FB5124B66 -:1047D00001250426044603600023057400F18402C9 -:1047E00043602946C0E902330C4B02901430019318 -:1047F0004FF44073009601F02FFF094B04F69442EA -:10480000294604F14C000294CDE900634FF4407353 -:1048100001F0F6FF04B070BD48740008C1470008FD -:10482000E54600080A68202383F311880B790B33CF -:1048300042F823004B79133342F823008B7913B1EC -:104840000B3342F8230000F58053C3F8A418022369 -:104850000374002383F311887047000038B5037F89 -:10486000044613B190F85430ABB90125201D022144 -:10487000FFF730FF04F114006FF00101257700F01D -:10488000D7FC04F14C0084F854506FF00101BDE8EE -:10489000384000F0CDBC38BD10B5012104460430CD -:1048A000FFF718FF0023237784F8543010BD000071 -:1048B00038B504460025143001F0E6FE04F14C0042 -:1048C000257701F0B5FF201D84F854500121FFF732 -:1048D00001FF2046BDE83840FFF750BF90F8803018 -:1048E00003F06003202B06D190F881200023212AB9 -:1048F00003D81F2A06D800207047222AFBD1C0E91E -:104900001D3303E0034A426707228267C367012021 -:10491000704700BF3422002037B500F58055D5F828 -:10492000A4381A68117804291AD1017C022917D1F8 -:104930001979012312898B40134211D100F14C04E3 -:10494000204602F035F858B101A9204601F07CFF5D -:10495000D5F8A4480246019B2179206800F0C0F8F0 -:1049600003B030BD01F10B03F0B550F8236085B002 -:1049700004460D46FEB1202383F3118804EB85071E -:10498000301D0821FFF7A6FEFB6806F14C005B69AD -:104990001B681BB1019001F065FF019803A901F0AC -:1049A00053FF024648B1039B2946204600F098F881 -:1049B000002383F3118805B0F0BDFB685A691268C3 -:1049C000002AF5D01B8A013B1340F1D104F180028B -:1049D000EAE70000133138B550F82140ECB120234C -:1049E00083F3118804F58053D3F8A428136852790F -:1049F00003EB8203DB689B695D6845B104216018A5 -:104A0000FFF768FE294604F1140001F053FE20462A -:104A1000FFF7B4FE002383F3118838BD7047000010 -:104A200001F05CB901234022002110B5044600F8D2 -:104A3000303BFDF76FF90023C4E9013310BD0000DE -:104A400010B52023044683F31188242241600021FD -:104A50000C30FDF75FF9204601F062F90223237064 -:104A6000002383F3118810BD70B500EB8103054668 -:104A700050690E461446DA6018B110220021FDF785 -:104A800049F9A06918B110220021FDF743F9314618 -:104A90002846BDE8704001F055BA00008368202226 -:104AA000002103F0011310B5044683601030FDF7B8 -:104AB00031F92046BDE8104001F0D0BAF0B401252C -:104AC00000EB810447898D40E4683D43A46945813A -:104AD00023600023A2606360F0BC01F0EDBA000027 -:104AE000F0B4012500EB810407898D40E4683D4363 -:104AF0006469058123600023A2606360F0BC01F05B -:104B000063BB000070B50223002504462422037015 -:104B10002946C0F888500C3040F8045CFDF7FAF8DC -:104B2000204684F8705001F0A1F963681B6823B136 -:104B300029462046BDE87040184770BD037880F8CC -:104B40008C300523037043681B6810B504460BB115 -:104B5000042198470023A36010BD000090F88C202A -:104B6000436802701B680BB10521184770470000AD -:104B700070B590F87030044613B1002380F870309F -:104B800004F18002204601F08DFA63689B68B3B996 -:104B900094F8803013F0600535D00021204601F0F4 -:104BA00037FD0021204601F027FD63681B6813B123 -:104BB000062120469847062384F8703070BD2046B1 -:104BC00098470028E4D0B4F88630A26F9A4288BF94 -:104BD000A36794F98030A56F002B4FF0200380F27B -:104BE0000381002D00F0F280092284F8702083F305 -:104BF000118800212046D4E91D23FFF771FF00230F -:104C000083F31188DAE794F8812003F07F0343EA05 -:104C1000022340F20232934200F0C58021D8B3F55E -:104C2000807F48D00DD8012B3FD0022B00F093801D -:104C3000002BB2D104F1880262670222A267E36707 -:104C4000C1E7B3F5817F00F09B80B3F5407FA4D12D -:104C500094F88230012BA0D1B4F8883043F00203DD -:104C600032E0B3F5006F4DD017D8B3F5A06F31D057 -:104C7000A3F5C063012B90D86368204694F8822086 -:104C80005E6894F88310B4F88430B047002884D06C -:104C9000436863670368A3671AE0B3F5106F36D003 -:104CA00040F6024293427FF478AF5C4B6367022385 -:104CB000A3670023C3E794F88230012B7FF46DAF24 -:104CC000B4F8883023F00203A4F88830C4E91D55F5 -:104CD000E56778E7B4F88030B3F5A06F0ED194F8AB -:104CE0008230204684F88A3001F01EF963681B6820 -:104CF00013B1012120469847032323700023C4E900 -:104D00001D339CE704F18B0363670123C3E723781A -:104D1000042B10D1202383F311882046FFF7BEFE19 -:104D200085F311880321636884F88B5021701B6818 -:104D30000BB12046984794F88230002BDED084F8DF -:104D40008B300423237063681B68002BD6D00221AC -:104D500020469847D2E794F8843020461D0603F099 -:104D60000F010AD501F090F9012804D002287FF440 -:104D700014AF2B4B9AE72B4B98E701F077F9F3E749 -:104D800094F88230002B7FF408AF94F8843013F04D -:104D90000F01B3D01A06204602D501F051FCADE751 -:104DA00001F042FCAAE794F88230002B7FF4F5AEC4 -:104DB00094F8843013F00F01A0D01B06204602D5D2 -:104DC00001F026FC9AE701F017FC97E7142284F81B -:104DD000702083F311882B462A4629462046FFF788 -:104DE0006DFE85F31188E9E65DB1152284F8702027 -:104DF00083F3118800212046D4E91D23FFF75EFECE -:104E0000FDE60B2284F8702083F311882B462A4696 -:104E100029462046FFF764FEE3E700BF78740008E8 -:104E2000707400087474000838B590F87030044647 -:104E3000002B3ED0063BDAB20F2A34D80F2B32D8E3 -:104E4000DFE803F03731310822323131313131318D -:104E500031313737856FB0F886309D4214D2C36840 -:104E60001B8AB5FBF3F203FB12556DB9202383F3C4 -:104E700011882B462A462946FFF732FE85F3118812 -:104E80000A2384F870300EE0142384F87030202355 -:104E900083F31188002320461A461946FFF70EFEB9 -:104EA000002383F3118838BDC36F03B198470023F3 -:104EB000E7E70021204601F0ABFB0021204601F08E -:104EC0009BFB63681B6813B10621204698470623A5 -:104ED000D7E7000010B590F870300446142B29D0A5 -:104EE00017D8062B05D001D81BB110BD093B022BEA -:104EF000FBD80021204601F08BFB0021204601F069 -:104F00007BFB63681B6813B1062120469847062384 -:104F100019E0152BE9D10B2380F87030202383F39F -:104F2000118800231A461946FFF7DAFD002383F3A0 -:104F30001188DAE7C3689B695B68002BD5D1C36F22 -:104F400003B19847002384F87030CEE7024B00226B -:104F5000C3E900339A6070474063002000238268F1 -:104F60000374054B1B6899689142FBD25A68036031 -:104F700042601060586070474063002008B52023ED -:104F800083F31188037C032B05D0042B0DD02BB9A0 -:104F900083F3118808BD436900221A604FF0FF3384 -:104FA0004361FFF7DBFF0023F2E7D0E90032136033 -:104FB0005A60F3E7002382680374054B1B68996805 -:104FC0009142FBD85A680360426010605860704795 -:104FD00040630020054B1969087418680268536023 -:104FE0001A60186101230374FBF77ABB4063002049 -:104FF0004B1C30B5044687B00A4D10D02B6901A870 -:10500000094A00F031F92046FFF7E4FF049B13B191 -:1050100001A800F065F92B69586907B030BDFFF7AA -:10502000D9FFF8E7406300207D4F000838B50C4DEC -:10503000044641612B6981689A68914203D8BDE8B2 -:105040003840FFF78BBF1846FFF7B4FF01232C61F0 -:10505000014623742046BDE83840FBF741BB00BF42 -:1050600040630020044B1A681B6990689B68984253 -:1050700094BF0020012070474063002010B5084C09 -:10508000236820691A6854602260012223611A741F -:10509000FFF790FF01462069BDE81040FBF720BBF9 -:1050A0004063002008B5FFF7DDFF18B1BDE80840F8 -:1050B000FFF7E4BF08BD0000FFF7E0BFFEE7000018 -:1050C00010B50C4CFFF742FF00F0C0F880220A49EF -:1050D000204600F047F8012344F8180C0374FEF74B -:1050E000BFFF002383F3118862B60448BDE8104077 -:1050F00000F058B8686300207C7400088C740008C5 -:1051000008B572B6034B586200F008FC00F0D6FCFC -:10511000FEE700BF4063002000F01CB9EFF31180F0 -:1051200020B9EFF30583202282F311887047000035 -:1051300010B530B9EFF30584C4F3080414B180F35B -:10514000118810BDFFF7AEFF84F31188F9E7000066 -:10515000034A516853685B1A9842FBD8704700BFF6 -:10516000001000E082600222028270478368A3F18F -:105170007C0243F80C2C026943F83C2C426943F84A -:10518000382C074A43F81C2CC268A3F1180043F8D6 -:10519000102C022203F8082C002203F8072C704779 -:1051A000F906000810B5202383F31188FFF7DEFF0E -:1051B00000210446FFF73AFF002383F311882046BD -:1051C00010BD0000024B1B6958610F20FFF702BFA2 -:1051D00040630020202383F31188FFF7F3BF000012 -:1051E00008B50146202383F311880820FFF700FF4C -:1051F000002383F3118808BD49B1064B42681B693F -:1052000018605A60136043600420FFF7F1BE4FF04E -:10521000FF307047406300200368984206D01A6848 -:105220000260506018465961FFF798BE7047000051 -:1052300038B504460D462068844200D138BD036865 -:1052400023605C604561FFF789FEF4E7054B4FF092 -:10525000FF3103F11402C3E905220022C3E907125A -:10526000704700BF4063002070B51C4E05460C46D9 -:10527000C0E9032301F0D2FB334653F8142F9A42BE -:105280000DD130620A2C2CBF00190A302A60C5E902 -:105290000124C6E90555BDE8704001F0A9BB316A9B -:1052A000431AE31838BF1C469368A34202D9081971 -:1052B00001F0AEFB73699A6894420CD85A68AC60EE -:1052C0002B606A6015609A685D60121B9A604FF0EF -:1052D000FF33F36170BDA41A1B68ECE74063002044 -:1052E00038B51B4C636998420DD08168D0E9003213 -:1052F00013605A600022C2609A680A449A604FF0B4 -:10530000FF33E36138BD03682246002142F8143FB1 -:1053100093425A60C16003D1BDE8384001F072BBCE -:105320009A688168256A0A449A6001F077FB63698C -:10533000411B9A688A42E5D9AB181D1A206A092DCB -:1053400098BF01F10A02BDE83840104401F060BB8B -:10535000406300202DE9F041184C002704F11406A9 -:10536000656901F05BFB236AAA68C11A8A4215D8F5 -:105370001344D5F80C802362D5E9003213605A60DB -:105380006369EF60B34201D101F03CFB87F3118800 -:105390002869C047202383F31188E1E76169B1429E -:1053A00009D013441B1ABDE8F0410A2B2CBFC018CA -:1053B0000A3001F02DBBBDE8F08100BF4063002042 -:1053C00000207047FEE70000704700004FF0FF30FC -:1053D0007047000002290CD0032904D00129074896 -:1053E00018BF00207047032A05D8054800EBC2000B -:1053F0007047044870470020704700BF7075000870 -:10540000442200202475000870B59AB0054608466D -:10541000144601A900F0C2F801A8FCF773FC431C74 -:105420000022C6B25B001046C5E900342370032396 -:10543000023404F8013C01ABD1B202348E4201D8EF -:105440001AB070BD13F8011B013204F8010C04F806 -:10545000021CF1E708B5202383F311880348FFF706 -:105460005BFA002383F3118808BD00BFF8640020B5 -:1054700090F8803003F01F02012A07D190F88120B4 -:105480000B2A03D10023C0E91D3315E003F06003AC -:10549000202B08D1B0F884302BB990F88120212A34 -:1054A00003D81F2A04D8FFF719BA222AEBD0FAE74B -:1054B000034A426707228267C3670120704700BF23 -:1054C0003B22002007B5052917D8DFE801F019169F -:1054D00003191920202383F31188104A0121019018 -:1054E000FFF7C2FA019802210D4AFFF7BDFA0D48F5 -:1054F000FFF7DEF9002383F3118803B05DF804FBA6 -:10550000202383F311880748FFF7A8F9F2E7202347 -:1055100083F311880348FFF7BFF9EBE7C474000871 -:10552000E8740008F864002038B50C4D0C4C2A468D -:105530000C4904F10800FFF767FF05F1CA0204F106 -:1055400010000949FFF760FF05F5CA7204F1180061 -:105550000649BDE83840FFF757BF00BFD07D0020A7 -:1055600044220020A4740008AE740008B974000836 -:1055700070B5044608460D46FCF7C4FBC6B220468B -:10558000013403780BB9184670BD32462946FCF742 -:10559000A5FB0028F3D10120F6E700002DE9F04734 -:1055A00005460C46FCF7AEFB2B49C6B22846FFF772 -:1055B000DFFF08B10A36F6B228492846FFF7D8FFC0 -:1055C00008B11036F6B2632E0BD8DFF88C80DFF806 -:1055D0008C90234FDFF894A02E7846B92670BDE852 -:1055E000F08729462046BDE8F04701F03BBE252E56 -:1055F0002ED1072241462846FCF770FB70B9194BA3 -:10560000224603F1100153F8040B8B4242F8040BBD -:10561000F9D11B78073511341370DDE708224946AC -:105620002846FCF75BFB98B9A21C0F4B1978023295 -:105630000909C95D02F8041C13F8011B01F00F01F0 -:105640005345C95D02F8031CF0D118340835C3E78F -:10565000013504F8016BBFE790750008B9740008C4 -:1056600098750008A272000800E8F11F0CE8F11F0D -:10567000BFF34F8F044B1A695107FCD1D3F81021A7 -:105680005207F8D1704700BF0020005208B50D4BFB -:105690001B78ABB9FFF7ECFF0B4BDA68D10704D5E9 -:1056A0000A4A5A6002F188325A60D3F80C21D207B4 -:1056B00006D5064AC3F8042102F18832C3F8042152 -:1056C00008BD00BF2E800020002000522301674546 -:1056D00008B5114B1B78F3B9104B1A69510703D564 -:1056E000DA6842F04002DA60D3F81021520705D59B -:1056F000D3F80C2142F04002C3F80C21FFF7B8FFA9 -:10570000064BDA6842F00102DA60D3F80C2142F06D -:105710000102C3F80C2108BD2E8000200020005299 -:105720000F289ABF00F580604004002070470000F9 -:105730004FF4003070470000102070470F2808B564 -:105740000BD8FFF7EDFF00F500330268013204D1FA -:1057500004308342F9D1012008BD0020FCE700009D -:105760000F2870B5054645D8FFF7D8FC224CFFF747 -:105770007FFF0646FFF78AFF4FF0FF33072D636177 -:10578000C4F8143120D82361FFF772FF2B0243F0D5 -:105790002403E360E36843F08003E36023695A076E -:1057A000FCD42846FFF764FF4FF40031FFF7B8FF41 -:1057B00000F060F93046FFF78BFFFFF7B9FC284691 -:1057C000BDE87040FFF7BABFC4F81031FFF750FFD3 -:1057D000A5F108031B0243F02403C4F80C31D4F8EC -:1057E0000C3143F08003C4F80C31D4F810315B075E -:1057F000FBD4D6E7002070BD002000522DE9F84F01 -:1058000040EA020305460C461746D80602D000209F -:10581000BDE8F88F27F01F07DFF8D4B0FFF736FF99 -:105820002744BC4203D10120FFF752FFF0E72022BA -:105830002946204601F098FC10B920352034F0E7C5 -:105840002B4605F120021E68711CE0D104339A42F8 -:10585000F9D1FFF763FC05F17843234AB3F5801FC4 -:10586000224B28BF9A4603F1040338BF9046A2F1A9 -:10587000080228BF9846A3F108033ABF9146DA46CA -:105880009946FFF7F5FEC8F80060A5EB040CD9F8BF -:10589000002004F11C0142F00202C9F80020221F7E -:1058A000DAF8006016F00506FAD152F8043F8A4291 -:1058B0004CF80230F4D1BFF34F8FFFF7D9FE4FF011 -:1058C000FF32C8F80020D9F8002022F00202C9F8FF -:1058D0000020FFF72DFC20222146284601F044FC41 -:1058E0000028AAD030469FE7142000521021005211 -:1058F0001020005210B5084C237828B11BB9FFF7CF -:10590000C5FE0123237010BD002BFCD02070BDE824 -:105910001040FFF7DDBE00BF2E80002038B5054DDA -:1059200000240334696855F80C0B00F0B5F8122C0C -:10593000F7D138BDAC75000870B5104E82B0FFF7D6 -:10594000EDFB054601F06AF8326803469042336089 -:1059500037BF0B4A0A495168146836BF0131D1E993 -:10596000004151600419284641F100010191FFF7FF -:10597000DFFB2046019902B070BD00BF30800020DF -:105980003880002070B5124E82B0FFF7C7FB054685 -:1059900001F044F8326803469042336037BF0D4A45 -:1059A0000C495168146836BF0131D1E9004151609A -:1059B0000419284641F100010191FFF7B9FB4FF4AA -:1059C0007A72002320460199FAF772FC02B070BD8A -:1059D00030800020388000200244074BD2B210B53E -:1059E000904200D110BD441C00B253F8200041F891 -:1059F000040BE0B2F4E700BF504000580E4B30B546 -:105A00001C6F240405D41C6F1C671C6F44F40044F5 -:105A10001C670A4C02442368D2B243F480732360AB -:105A2000074B904200D130BD441C51F8045B00B2DA -:105A300043F82050E0B2F4E700440258004802580E -:105A40005040005807B5012201A90020FFF7C4FF0C -:105A5000019803B05DF804FB13B50446FFF7F2FFAD -:105A6000A04205D0012201A900200194FFF7C6FF42 -:105A700002B010BD0144BFF34F8F064B884204D3E0 -:105A8000BFF34F8FBFF36F8F7047C3F85C022030B6 -:105A9000F4E700BF00ED00E00144BFF34F8F064B79 -:105AA000884204D3BFF34F8FBFF36F8F7047C3F8A3 -:105AB00070022030F4E700BF00ED00E07047000006 -:105AC000074B45F255521A6002225A6040F6FF72A7 -:105AD0009A604CF6CC421A600122024B1A70704751 -:105AE0000048005844800020034B1B781BB1034B37 -:105AF0004AF6AA221A6070474480002000480058E5 -:105B0000034B1A681AB9034AD2F8D0241A607047B6 -:105B10004080002000400258024B4FF48032C3F80E -:105B2000D02470470040025808B5FFF7E9FF024B48 -:105B30001868C0F3806008BD4080002070B5BFF3D6 -:105B40004F8FBFF36F8F1A4A0021C2F85012BFF374 -:105B50004F8FBFF36F8F536943F400335361BFF32B -:105B60004F8FBFF36F8FC2F88410BFF34F8FD2F8FF -:105B7000803043F6E074C3F3C900C3F34E335B01D6 -:105B800003EA0406014646EA81750139C2F860520B -:105B9000F9D2203B13F1200FF2D1BFF34F8F53699D -:105BA00043F480335361BFF34F8FBFF36F8F70BDEA -:105BB00000ED00E0FEE700000A4B0B480B4A904264 -:105BC0000BD30B4BC11EDA1C121A22F003028B42BC -:105BD00038BF00220021FCF79DB853F8041B40F8A1 -:105BE000041BECE738780008208200202082002087 -:105BF000208200207047000070B5D0E924430022C5 -:105C00004FF0FF359E6804EB42135101D3F80009B1 -:105C1000002805DAD3F8000940F08040C3F80009F5 -:105C2000D3F8000B002805DAD3F8000B40F08040D1 -:105C3000C3F8000B013263189642C3F80859C3F841 -:105C4000085BE0D24FF00113C4F81C3870BD0000AF -:105C500000EB8103D3F80CC02DE9F043DCF81420ED -:105C60004E1CD0F89050D2F800E005EB063605EB5C -:105C70004118506870450AD30122D5F8343802FA29 -:105C800001F123EA0101C5F83418BDE8F083AEEB59 -:105C90000003BCF81040A34228BF2346D8F8184997 -:105CA000A4B2B3EB840FF0D89468A4F1040959F8B6 -:105CB000047F3760A4EB09071F44042FF7D81C4466 -:105CC000034494605360D4E7890141F020010161ED -:105CD00003699B06FCD41220FFF73ABA10B50A4CB0 -:105CE0002046FEF79FFE094BC4F89030084BC4F8DD -:105CF0009430084C2046FEF795FE074BC4F89030D0 -:105D0000064BC4F8943010BD4880002000000840C5 -:105D100018760008E4800020000004402476000883 -:105D200070B503780546012B5DD1494BD0F8904002 -:105D3000984259D1474B0E216520D3F8D82042F024 -:105D40000062C3F8D820D3F8002142F00062C3F803 -:105D50000021D3F80021D3F8802042F00062C3F87C -:105D60008020D3F8802022F00062C3F88020D3F88E -:105D70008030FEF7D7FA384BE360384BC4F8003870 -:105D80000023D5F89060C4F8003EC02323604FF490 -:105D90000413A3633369002BFCDA01230C20336165 -:105DA000FFF7D6F93369DB07FCD41220FFF7D0F9EF -:105DB0003369002BFCDA00262846A660FFF71CFF9B -:105DC0006B68C4F81068DB68C4F81468C4F81C6811 -:105DD000002B3AD1224BA3614FF0FF336361A368DC -:105DE00043F00103A36070BD1E4B9842C8D1194B0C -:105DF0000E214D20D3F8D82042F00072C3F8D820ED -:105E0000D3F8002142F00072C3F80021D3F800213A -:105E1000D3F8802042F00072C3F88020D3F88020AD -:105E200022F00072C3F88020D3F88020D3F8D82065 -:105E300022F08062C3F8D820D3F8002122F08062DB -:105E4000C3F80021D3F8003193E7074BC3E700BF45 -:105E50004880002000440258401400400300200203 -:105E6000003C30C0E4800020083C30C0F8B5D0F8D9 -:105E70009040054600214FF000662046FFF724FFC2 -:105E8000D5F8941000234FF001128F684FF0FF30C7 -:105E9000C4F83438C4F81C2804EB431201339F4281 -:105EA000C2F80069C2F8006BC2F80809C2F8080B12 -:105EB000F2D20B68D5F89020C5F8983063621023B1 -:105EC0001361166916F01006FBD11220FFF740F996 -:105ED000D4F8003823F4FE63C4F80038A36943F40F -:105EE000402343F01003A3610923C4F81038C4F819 -:105EF00014380B4BEB604FF0C043C4F8103B094B18 -:105F0000C4F8003BC4F81069C4F80039D5F89830DB -:105F100003F1100243F48013C5F89820A362F8BD82 -:105F2000F475000840800010D0F8902090F88A1096 -:105F3000D2F8003823F4FE6343EA0113C2F80038B4 -:105F4000704700002DE9F84300EB8103D0F8905032 -:105F50000C468046DA680FFA81F94801166806F0A7 -:105F60000306731E022B05EB41134FF0000194BF93 -:105F7000B604384EC3F8101B4FF0010104F11003B2 -:105F800098BF06F1805601FA03F3916998BF06F5B0 -:105F9000004600293AD0578A04F158013743490195 -:105FA0006F50D5F81C180B430021C5F81C382B186E -:105FB0000127C3F81019A7405369611E9BB3138AC8 -:105FC000928B9B08012A88BF5343D8F898209818D1 -:105FD00042EA034301F140022146C8F898002846EE -:105FE00005EB82025360FFF76FFE08EB8900C36880 -:105FF0001B8A43EA845348341E4364012E51D5F86A -:106000001C381F43C5F81C78BDE8F88305EB491719 -:10601000D7F8001B21F40041C7F8001BD5F81C1865 -:1060200021EA0303C0E704F13F030B4A2846214657 -:1060300005EB83035A60FFF747FE05EB4910D0F8E4 -:10604000003923F40043C0F80039D5F81C3823EA9E -:106050000707D7E70080001000040002D0F8942062 -:106060001268C0F89820FFF7C7BD00005831D0F87B -:10607000903049015B5813F4004004D013F4001F22 -:106080000CBF0220012070474831D0F89030490100 -:106090005B5813F4004004D013F4001F0CBF02201F -:1060A0000120704700EB8101CB68196A0B6813600F -:1060B0004B6853607047000000EB810330B5DD682A -:1060C000AA691368D36019B9402B84BF40231360B9 -:1060D0006B8A1468D0F890201C4402EB4110013CFC -:1060E00009B2B4FBF3F46343033323F0030343EA3D -:1060F000C44343F0C043C0F8103B2B6803F00303D4 -:10610000012B0ED1D2F8083802EB411013F4807F36 -:10611000D0F8003B14BF43F0805343F00053C0F865 -:10612000003B02EB4112D2F8003B43F00443C2F8BB -:10613000003B30BD2DE9F041D0F8906005460C469B -:1061400006EB4113D3F8087B3A07C3F8087B08D560 -:10615000D6F814381B0704D500EB8103DB685B68B5 -:106160009847FA071FD5D6F81438DB071BD505EB7F -:106170008403D968CCB98B69488A5A68B2FBF0F6B7 -:1061800000FB16228AB91868DA6890420DD2121AFA -:10619000C3E90024202383F3118821462846FFF712 -:1061A0008BFF84F31188BDE8F081012303FA04F228 -:1061B0006B8923EA02036B81CB68002BF3D0214665 -:1061C0002846BDE8F041184700EB81034A0170B54D -:1061D000DD68D0F890306C692668E66056BB1A44DA -:1061E0004FF40020C2F810092A6802F00302012AC5 -:1061F0000AB20ED1D3F8080803EB421410F4807FE2 -:10620000D4F8000914BF40F0805040F00050C4F8AA -:10621000000903EB4212D2F8000940F00440C2F832 -:1062200000090122D3F8340802FA01F10143C3F84E -:10623000341870BD19B9402E84BF402020602068FA -:106240001A442E8A8419013CB4FBF6F440EAC44097 -:1062500040F00050C6E700002DE9F041D0F8906012 -:1062600004460D4606EB4113D3F80879C3F80879C4 -:10627000FB071CD5D6F81038DA0718D500EB8103D8 -:10628000D3F80CC0DCF81430D3F800E0DA68964597 -:106290001BD2A2EB0E024FF000081A60C3F8048074 -:1062A000202383F31188FFF78FFF88F311883B06C3 -:1062B00018D50123D6F83428AB40134212D0294612 -:1062C0002046BDE8F041FFF7C3BC012303FA01F209 -:1062D000038923EA02030381DCF80830002BE6D0AF -:1062E0009847E4E7BDE8F0812DE9F84FD0F89050E9 -:1062F00004466E69AB691E4016F480586E6103D087 -:10630000BDE8F84FFEF7FEBB002E12DAD5F8003ECE -:106310009F0705D0D5F8003E23F00303C5F8003EE3 -:10632000D5F80438204623F00103C5F80438FEF7F9 -:1063300015FC300505D52046FFF75EFC2046FEF72C -:10634000FDFBB1040CD5D5F8083813F0060FEB6847 -:1063500023F470530CBF43F4105343F4A053EB6089 -:10636000320704D56368DB680BB120469847F30217 -:1063700000F1BA80B70226D5D4F8909000274FF0EC -:10638000010A09EB4712D2F8003B03F44023B3F5AE -:10639000802F11D1D2F8003B002B0DDA62890AFA66 -:1063A00007F322EA0303638104EB8703DB68DB68FE -:1063B00013B13946204698470137D4F89430FFB2DC -:1063C0009B689F42DDD9F00619D5D4F89000026A87 -:1063D000C2F30A1702F00F0302F4F012B2F5802F95 -:1063E00000F0CC80B2F5402F09D104EB83030022EA -:1063F00000F58050DB681B6A974240F0B2803003A2 -:10640000D5F8185835D5E90303D500212046FFF704 -:1064100091FEAA0303D501212046FFF78BFE6B03F3 -:1064200003D502212046FFF785FE2F0303D5032164 -:106430002046FFF77FFEE80203D504212046FFF740 -:1064400079FEA90203D505212046FFF773FE6A02F3 -:1064500003D506212046FFF76DFE2B0203D5072149 -:106460002046FFF767FEEF0103D508212046FFF71E -:1064700061FE700340F1A980E90703D500212046A1 -:10648000FFF7EAFEAA0703D501212046FFF7E4FE45 -:106490006B0703D502212046FFF7DEFE2F0703D549 -:1064A00003212046FFF7D8FEEE0603D5042120463F -:1064B000FFF7D2FEA80603D505212046FFF7CCFE44 -:1064C000690603D506212046FFF7C6FE2A0603D536 -:1064D00007212046FFF7C0FEEB0576D520460821B0 -:1064E000BDE8F84FFFF7B8BED4F8909000274FF002 -:1064F000010AD4F894305FFA87FB9B689B453FF60E -:1065000039AF09EB4B13D3F8002902F44022B2F55E -:10651000802F24D1D3F80029002A20DAD3F80029CB -:1065200042F09042C3F80029D3F80029002AFBDB8F -:106530005946D4F89000FFF7C7FB22890AFA0BF3FB -:1065400022EA0303238104EB8B03DB689B6813B10E -:1065500059462046984759462046FFF779FB0137B0 -:10656000C7E7910701D1D0F80080072A02F10102A4 -:106570009CBF03F8018B4FEA18283DE704EB830327 -:1065800000F58050DA68D2F818C0DCF80820DCE9A1 -:10659000001CA1EB0C0C00218F4208D1DB689B6929 -:1065A0009A683A449A605A683A445A6027E711F068 -:1065B000030F01D1D0F800808C4501F1010184BFA7 -:1065C00002F8018B4FEA1828E6E7BDE8F88F0000D3 -:1065D00008B50348FFF788FEBDE80840FDF768BD31 -:1065E0004880002008B50348FFF77EFEBDE808405C -:1065F000FDF75EBDE4800020D0F8903003EB411140 -:10660000D1F8003B43F40013C1F8003B7047000091 -:10661000D0F8903003EB4111D1F8003943F4001366 -:10662000C1F8003970470000D0F8903003EB4111F9 -:10663000D1F8003B23F40013C1F8003B7047000081 -:10664000D0F8903003EB4111D1F8003923F4001356 -:10665000C1F800397047000030B50433039C017263 -:10666000002104FB0325C160C0E90653049B0363BA -:10667000059BC0E90000C0E90422C0E90842C0E966 -:106680000A11436330BD00000022416AC260C0E9C4 -:106690000411C0E90A226FF00101FEF7C9BD000034 -:1066A000D0E90432934201D1C2680AB9181D70477B -:1066B00000207047036919600021C2680132C2607E -:1066C000C269134482699342036124BF436A036130 -:1066D000FEF7A2BD38B504460D46E3683BB16269DA -:1066E0000020131D1268A3621344E36207E0237ABB -:1066F00033B929462046FEF77FFD0028EDDA38BD84 -:106700006FF00100FBE70000C368C269013BC36092 -:106710004369134482699342436124BF436A4361DE -:1067200000238362036B03B11847704770B52023C1 -:10673000044683F31188866A3EB9FFF7CBFF05460E -:1067400018B186F31188284670BDA36AE26A13F86F -:10675000015B9342A36202D32046FFF7D5FF0023DB -:1067600083F31188EFE700002DE9F84F04460E4649 -:10677000174698464FF0200989F311880025AA464C -:10678000D4F828B0BBF1000F09D141462046FFF7ED -:10679000A1FF20B18BF311882846BDE8F88FD4E91A -:1067A0000A12A7EB050B521A934528BF9346BBF17B -:1067B000400F1BD9334601F1400251F8040B9142BE -:1067C00043F8040BF9D1A36A403640354033A36245 -:1067D000D4E90A239A4202D32046FFF795FF8AF3B1 -:1067E0001188BD42D8D289F31188C9E730465A468C -:1067F000FBF76AFAA36A5E445D445B44A362E7E781 -:1068000010B5029C0433017204FB0321C460C0E98B -:1068100006130023C0E90A33039B0363049BC0E90A -:106820000000C0E90422C0E90842436310BD000033 -:10683000026A6FF00101C260426AC0E904220022CC -:10684000C0E90A22FEF7F4BCD0E904239A4201D140 -:10685000C26822B9184650F8043B0B60704700200C -:1068600070470000C3680021C2690133C3604369F7 -:10687000134482699342436124BF436A4361FEF734 -:10688000CBBC000038B504460D46E3683BB1236934 -:1068900000201A1DA262E2691344E36207E0237A32 -:1068A00033B929462046FEF7A7FC0028EDDA38BDAB -:1068B0006FF00100FBE7000003691960C268013A4C -:1068C000C260C269134482699342036124BF436A70 -:1068D000036100238362036B03B118477047000014 -:1068E00070B520230D460446114683F31188866A4D -:1068F0002EB9FFF7C7FF10B186F3118870BDA36AE8 -:106900001D70A36AE26A01339342A36204D3E16972 -:1069100020460439FFF7D0FF002080F31188EDE70F -:106920002DE9F84F04460D46904699464FF0200A4F -:106930008AF311880026B346A76A4FB94946204614 -:10694000FFF7A0FF20B187F311883046BDE8F88F2C -:10695000D4E90A073A1AA8EB0607974228BF174658 -:10696000402F1BD905F1400355F8042B9D4240F8F8 -:10697000042BF9D1A36A40364033A362D4E90A2339 -:106980009A4204D3E16920460439FFF795FF8BF35F -:1069900011884645D9D28AF31188CDE729463A466F -:1069A000FBF792F9A36A3D443E443B44A362E5E70A -:1069B000D0E904239A4217D1C3689BB1836A8BB193 -:1069C000043B9B1A0ED01360C368013BC360C369CC -:1069D0001A4483699A42026124BF436A0361002317 -:1069E00083620123184670470023FBE700F0CEB80E -:1069F000034B002258631A610222DA60704700BF1D -:106A0000000C0040014B0022DA607047000C00408F -:106A1000014B5863704700BF000C0040014B586A9F -:106A2000704700BF000C00404B6843608B68836078 -:106A3000CB68C3600B6943614B6903628B69436236 -:106A40000B6803607047000008B5364B40F2FF71D9 -:106A50003548D3F888200A43C3F88820D3F8882023 -:106A600022F4FF6222F00702C3F88820D3F88820BE -:106A7000D3F8E0200A43C3F8E020D3F808210A4302 -:106A8000C3F80821294AD3F808311146FFF7CCFF93 -:106A900000F5806002F11C01FFF7C6FF00F5806081 -:106AA00002F13801FFF7C0FF00F5806002F15401E8 -:106AB000FFF7BAFF00F5806002F17001FFF7B4FF45 -:106AC00000F5806002F18C01FFF7AEFF00F58060F9 -:106AD00002F1A801FFF7A8FF00F5806002F1C401F0 -:106AE000FFF7A2FF00F5806002F1E001FFF79CFFD5 -:106AF00000F5806002F1FC01FFF796FF02F58C7152 -:106B000000F58060FFF790FF00F0F4F8084B0522D5 -:106B1000C3F898204FF06052C3F89C20054AC3F890 -:106B2000A02008BD0044025800000258307600083A -:106B300000ED00E01F00080308B500F0D7FAFEF7EB -:106B4000BFFA0F4BD3F8DC2042F04002C3F8DC2040 -:106B5000D3F8042122F04002C3F80421D3F8043111 -:106B6000084B1A6842F008021A601A6842F00402E0 -:106B70001A60FEF7C5FFBDE80840FEF7D5BC00BFB0 -:106B8000004402580018024870470000114BD3F827 -:106B9000E82042F00802C3F8E820D3F8102142F0C0 -:106BA0000802C3F810210C4AD3F81031D36B43F01C -:106BB0000803D363C722094B9A624FF0FF32DA62AF -:106BC00000229A615A63DA605A6001225A611A609F -:106BD000704700BF004402580010005C000C0040E9 -:106BE000094A08B51169D3680B40D9B29B076FEA0F -:106BF0000101116107D5202383F31188FEF78CFA78 -:106C0000002383F3118808BD000C0040384B4FF07F -:106C1000FF31D3F88020C3F88010D3F88020002201 -:106C2000C3F88020D3F88000D3F88400C3F8841020 -:106C3000D3F88400C3F88420D3F88400D86F40F0E0 -:106C4000FF4040F4FF0040F43F5040F03F00D86761 -:106C5000D86F20F0FF4020F4FF0020F43F5020F0D8 -:106C60003F00D867D86FD3F888006FEA40506FEACA -:106C70005050C3F88800D3F88800C0F30A00C3F866 -:106C80008800D3F88800D3F89000C3F89010D3F8A8 -:106C90009000C3F89020D3F89000D3F89400C3F884 -:106CA0009410D3F89400C3F89420D3F89400D3F848 -:106CB0009800C3F89810D3F89800C3F89820D3F838 -:106CC0009800D3F88C00C3F88C10D3F88C00C3F86C -:106CD0008C20D3F88C00D3F89C00C3F89C10D3F818 -:106CE0009C10C3F89C20D3F89C3000F0D3B900BFAF -:106CF00000440258614B0122C3F80821604BD3F8CD -:106D0000F42042F00202C3F8F420D3F81C2142F030 -:106D10000202C3F81C210222D3F81C31594BDA605D -:106D20005A689104FCD5584A1A6001229A60574A61 -:106D3000DA6000221A614FF440429A61514B9A691D -:106D40009204FCD51A6842F480721A604C4B1A6F98 -:106D500012F4407F04D04FF480321A6700221A6781 -:106D60001A6842F001021A60454B1A685007FCD5B8 -:106D700000221A611A6912F03802FBD10121196050 -:106D80004FF0804159605A67414ADA62414A1A61BC -:106D90001A6842F480321A60394B1A689103FCD5A4 -:106DA0001A6842F480521A601A689204FCD53A4A72 -:106DB0003A499A6200225A6319633949DA6399633E -:106DC0005A64384A1A64384ADA621A6842F0A85299 -:106DD0001A602B4B1A6802F02852B2F1285FF9D1E1 -:106DE00048229A614FF48862DA6140221A622F4A7F -:106DF000DA644FF080521A652D4A5A652D4A9A6519 -:106E000032232D4A1360136803F00F03022BFAD1CB -:106E10001B4B1A6942F003021A611A6902F0380228 -:106E2000182AFAD1D3F8DC2042F00052C3F8DC2053 -:106E3000D3F8042142F00052C3F80421D3F804210E -:106E4000D3F8DC2042F08042C3F8DC20D3F80421E0 -:106E500042F08042C3F80421D3F80421D3F8DC20A7 -:106E600042F00042C3F8DC20D3F8042142F0004293 -:106E7000C3F80421D3F80431704700BF00800051EB -:106E8000004402580048025800C000F0020000010F -:106E90000000FF01008890083220600063020901B1 -:106EA0001D02040047040508FD0BFF01200000201F -:106EB0000010E00000010100002000524FF0B0423D -:106EC00008B5D2F8883003F00103C2F8883023B146 -:106ED000044A13680BB150689847BDE80840FDF7B5 -:106EE000E7B800BF988100204FF0B04208B5D2F853 -:106EF000883003F00203C2F8883023B1044A936853 -:106F00000BB1D0689847BDE80840FDF7D1B800BF85 -:106F1000988100204FF0B04208B5D2F8883003F0D5 -:106F20000403C2F8883023B1044A13690BB15069D5 -:106F30009847BDE80840FDF7BBB800BF9881002026 -:106F40004FF0B04208B5D2F8883003F00803C2F819 -:106F5000883023B1044A93690BB1D0699847BDE8E2 -:106F60000840FDF7A5B800BF988100204FF0B0425F -:106F700008B5D2F8883003F01003C2F8883023B186 -:106F8000044A136A0BB1506A9847BDE80840FDF700 -:106F90008FB800BF988100204FF0B04310B5D3F8F0 -:106FA000884004F47872C3F88820A30604D5124AF6 -:106FB000936A0BB1D06A9847600604D50E4A136BEA -:106FC0000BB1506B9847210604D50B4A936B0BB15C -:106FD000D06B9847E20504D5074A136C0BB1506C8F -:106FE0009847A30504D5044A936C0BB1D06C98471D -:106FF000BDE81040FDF75CB8988100204FF0B04329 -:1070000010B5D3F8884004F47C42C3F888206205A8 -:1070100004D5164A136D0BB1506D9847230504D55E -:10702000124A936D0BB1D06D9847E00404D50F4A16 -:10703000136E0BB1506E9847A10404D50B4A936EA2 -:107040000BB1D06E9847620404D5084A136F0BB198 -:10705000506F9847230404D5044A936F0BB1D06F47 -:107060009847BDE81040FDF723B800BF9881002085 -:1070700008B50348FDF7D2F8BDE80840FDF718B899 -:10708000D45E002008B5FFF7ABFDBDE80840FDF772 -:107090000FB80000062108B50846FDF743F90621A0 -:1070A0000720FDF73FF906210820FDF73BF90621EF -:1070B0000920FDF737F906210A20FDF733F90621EB -:1070C0001720FDF72FF906212820FDF72BF90921BC -:1070D0007A20FDF727F907213220FDF723F90C214B -:1070E0005220BDE80840FDF71DB9000008B5FFF7C4 -:1070F0008DFD00F00DF8FDF7B9FAFDF791FCFDF7F5 -:1071000063FBFFF741FDBDE80840FFF76FBC0000DF -:107110000023054A19460133102BC2E9001102F180 -:107120000802F8D1704700BF988100200B46014645 -:10713000184600F003B8000000F00EB810B5054C7A -:1071400013462CB10A4601460220AFF3008010BD61 -:107150002046FCE700000000024B0146186800F0E2 -:1071600035B800BF6422002010B5013902449042B6 -:1071700001D1002005E0037811F8014FA34201D0AE -:10718000181B10BD0130F2E72DE9F041A3B1C91A77 -:1071900017780144044603F1FF3C8C42204601D994 -:1071A000002009E00578BD4204F10104F5D10CEBA3 -:1071B0000405D618A54201D1BDE8F08115F8018D6E -:1071C00016F801EDF045F5D0E7E7000037B50029E6 -:1071D00044D051F8043C0190002BA1F10404B8BF45 -:1071E000E41800F047F81E4A0198136833B9636049 -:1071F000146003B0BDE8304000F042B8A34208D9A3 -:10720000256861198B4201BF19685B6849192160C3 -:10721000EDE71A465B680BB1A342FAD9116855181D -:10722000A5420BD1246821445418A3421160E0D137 -:107230001C685B68536021441160DAE702D90C23B3 -:107240000360D6E7256861198B4204BF19685B6843 -:10725000636004BF491921605460CAE703B030BDC0 -:1072600018820020034611F8012B03F8012B002A95 -:10727000F9D17047014800F009B800BF1C82002016 -:10728000014800F005B800BF1C82002070470000D4 -:10729000704700006F72672E6172647570696C6F61 -:1072A000742E437562654F72616E67652D706572ED -:1072B000697068004E6F20617070207369670A0002 -:1072C000426164206677206C656E6774682025755E -:1072D0000A0042616420626F6172645F6964202504 -:1072E000752073686F756C642062652025750A00CF -:1072F0004261642066772064657363726970746F9D -:1073000072206C656E6774682025750A004261649E -:107310002061707020435243203078253038783A0D -:10732000307825303878203078253038783A307801 -:10733000253038780A00476F6F64206669726D7770 -:107340006172650A0040A2E4F164689106000000E1 -:1073500053544D333248373F3F3F0053544D33323F -:10736000483734332F37353300000000F8640020ED -:10737000D45E002043414E464449666163653A202D -:107380004D6573736167652052414D204F7665727C -:10739000666C6F77210000004261642043414E49D2 -:1073A0006661636520696E6465782E0000010000E7 -:1073B0000001FF0000A0004000A400400000000009 -:1073C00000000000C1250008991E0008012D0008DA -:1073D0008D1E0008091F00081923000881200008DD -:1073E000D11E0008D51E0008911E0008AD1E000821 -:1073F000951E0008D9220008B91E00080D2E0008AD -:10740000C51E0008AD220008009600000000000024 -:10741000000000000000000000000000000000006C -:107420000000000035460008214600085D460008BF -:107430004946000855460008414600082D46000808 -:10744000194600086946000800000000454700088A -:10745000314700086D470008594700086547000894 -:10746000514700083D4700082947000879470008B0 -:107470000000000001000000000000006D61696E66 -:107480000000000069646C6500000000847400085E -:1074900080630020F864002001000000BD50000857 -:1074A000000000004172647550696C6F74002542E1 -:1074B0004F415244252D424C002553455249414CE1 -:1074C00025000000020000000000000065490008DF -:1074D000D549000840004000A07D0020B07D00207C -:1074E0000200000000000000030000000000000097 -:1074F0001D4A00080000000010000000C07D0020B0 -:107500000000000001000000000000004880002092 -:1075100001010200C5540008D55300087154000849 -:1075200055540008430000002C7500080902430070 -:10753000020100C03209040000010202010005241A -:1075400000100105240100010424020205240600A4 -:1075500001070582030800FF09040100020A000078 -:1075600000070501024000000705810240000000FD -:10757000120000007875000812011001020000409E -:10758000091241570002010203010000040309042B -:1075900025424F415244250030313233343536379D -:1075A00038394142434445460000000000000020B5 -:1075B0000000020002000000000100300000000096 -:1075C000000000000000002400000800040000008B -:1075D0000004000000FC0000020000000000043075 -:1075E00000800000000000000000003800000100E2 -:1075F0000100000000000000714B0008294E000847 -:10760000D54E00084000400080810020808100208D -:107610000100000090810020800000004001000077 -:107620000800000000010000000400000800000045 -:107630000000802A00000000AAAAAAAA00000024D4 -:10764000FFFF00000000000000A00A00002100026F -:1076500000000000AAAAAAAA00000000FFFF000084 -:1076600000000009000009001400005400000000A0 -:10767000AAAAAAAA14000054FFFF000000000000FC -:10768000000000000A40100000000000AAAA8AAA18 -:1076900000401000FFFF0000990000000000000003 -:1076A0000081020000000000AAAAAAAA004101006D -:1076B000FFFF000000000070070000000000000055 -:1076C00000000000AAAAAAAA00000000FFFF000014 -:1076D00000000000000000000000000000000000AA -:1076E000AAAAAAAA00000000FFFF000000000000F4 -:1076F000000000000000000000000000AAAAAAAAE2 -:1077000000000000FFFF000000000000000000007B -:107710000000000000000000AAAAAAAA00000000C1 -:10772000FFFF00000000000000000000000000005B -:1077300000000000AAAAAAAA00000000FFFF0000A3 -:107740000000000000000000000000000000000039 -:10775000AAAAAAAA00000000FFFF00000000000083 -:10776000000000007C8BFF7F010000000000000093 -:10777000780500000000000000001E00000000006E -:10778000FE2A0100D2040000FF00000000000000FB -:10779000507300083F000000500400005B730008B5 -:1077A0003F00000000960000000008009600000066 -:1077B00000080000040000008C75000800000000B4 -:1077C00000000000000000000000000000000000B9 -:1077D00000000000682200200000000000000000FF -:1077E0000000000000000000000000000000000099 -:1077F0000000000000000000000000000000000089 -:107800000000000000000000000000000000000078 -:107810000000000000000000000000000000000068 -:107820000000000000000000000000000000000058 -:08783000000000000000000050 +:1000000000060020F50500086135000819350008D4 +:10001000413500081935000839350008F705000892 +:10002000F7050008F7050008F70500084545000832 +:10003000F7050008F7050008F7050008F7050008B0 +:10004000F7050008F7050008F7050008F7050008A0 +:10005000F7050008F70500086575000891750008A8 +:10006000BD750008E975000815760008F705000859 +:10007000F7050008F7050008F7050008F705000870 +:10008000F7050008F7050008F7050008C93400085F +:10009000F1340008DD340008053500084176000819 +:1000A000F7050008F7050008F7050008F705000840 +:1000B000F7050008F7050008F7050008F705000830 +:1000C000F7050008F7050008F7050008F705000820 +:1000D000F7050008F7050008F7050008F705000810 +:1000E000A5760008F7050008F7050008F7050008E1 +:1000F000F7050008F7050008F7050008F7050008F0 +:10010000F7050008F70500082D770008F705000837 +:10011000F7050008F7050008F7050008F7050008CF +:10012000F7050008F7050008F7050008F7050008BF +:10013000F7050008F7050008F7050008F7050008AF +:10014000F7050008F7050008F7050008F70500089F +:10015000F7050008F7050008F7050008F70500088F +:10016000F7050008F7050008F7050008F70500087F +:10017000F7050008ED6B0008F7050008F705000813 +:10018000F7050008F705000819770008F7050008CB +:10019000F7050008F7050008F7050008F70500084F +:1001A000F7050008F7050008F7050008F70500083F +:1001B000F7050008F7050008F7050008F70500082F +:1001C000F7050008F7050008F7050008F70500081F +:1001D000F7050008D96B0008F7050008F7050008C7 +:1001E000F7050008F7050008F7050008F7050008FF +:1001F000F7050008F7050008F7050008F7050008EF +:10020000F7050008F7050008F7050008F7050008DE +:10021000F7050008F7050008F7050008F7050008CE +:10022000F7050008F7050008F7050008F7050008BE +:10023000F7050008F7050008F7050008F7050008AE +:10024000F7050008F7050008F7050008F70500089E +:10025000F7050008F7050008F7050008F70500088E +:10026000F7050008F7050008F7050008F70500087E +:10027000F7050008F7050008F7050008F70500086E +:10028000F7050008F7050008F7050008F70500085E +:10029000F7050008F7050008F7050008F70500084E +:1002A000F7050008F7050008F7050008F70500083E +:1002B000F7050008F7050008F7050008F70500082E +:1002C000F7050008F7050008F7050008F70500081E +:1002D000F7050008F7050008F7050008F70500080E +:1002E000111A0008000000000000000000000000DB +: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 +:1006600005F030FD06F03EFD4FF055301F491B4AA6 +:1006700091423CBF41F8040BFAE71D49184A9142E8 +:100680003CBF41F8040BFAE71A491B4A1B4B9A423C +:100690003EBF51F8040B42F8040BF8E7002018495C +:1006A000184A91423CBF41F8040BFAE705F048FDB7 +:1006B00006F09CFD144C154DAC4203DA54F8041BB3 +:1006C0008847F9E700F042F8114C124DAC4203DACA +:1006D00054F8041B8847F9E705F030BD00060020F8 +:1006E000002200200000000808ED00E000000020CB +:1006F00000060020E07C000800220020D02200201C +:10070000D022002030870020E0020008E402000828 +:10071000E4020008E40200082DE9F04F2DED108AF4 +:10072000C1F80CD0D0F80CD0BDEC108ABDE8F08F29 +:10073000002383F311882846A047002004F0AAFF75 +:10074000FEE704F003FF00DFFEE70000F8B501F06C +:1007500075F905F03BFC074605F0AAFC0546B8BB59 +:10076000204B9F4234D001339F4234D027F0FF0208 +:100770001D4B9A4232D12E4642F21074F8B200F06C +:1007800093FF00F097FF08B10024264601F04CFDCE +:1007900020B10024032000F07BF8264635B1134B2E +:1007A0009F4203D0002405F07BFC2646002005F084 +:1007B00017FC0EB100F082F801F0E2FA00F0AEFF93 +:1007C00001F0B8F9204600F029F900F077F8F9E7D0 +:1007D0002E460024D5E704460126D2E7064641F21C +:1007E0008834CEE7010007B0000008B0263A09B00F +:1007F00008B501F06BF9A0F120035842584108BD3B +:1008000007B541F21203022101A8ADF8043001F04E +:100810007BF903B05DF804FB38B5302383F311880E +:10082000174803680BB105F001F80023154A4FF48F +:100830007A71134804F0F0FF002383F31188124CFF +:10084000236813B12368013B2360636813B16368B5 +:10085000013B63600D4D2B7833B963687BB902208F +:1008600001F010FA322363602B78032B07D1636801 +:100870002BB9022001F006FA4FF47A73636038BD99 +:10088000D022002019080008F0230020E8220020D0 +:10089000084B187003280CD8DFE800F008050208A0 +:1008A000022001F0EDB9022001F0E8B9024B00226C +:1008B0005A607047E8220020F0230020F8B501F0CC +:1008C000B3FC30B14D4B03221A7000224C4B5A60DE +:1008D000F8BD4C4B4C4A1C4619680131F8D0043322 +:1008E0009342F9D16268494B9A42F1D9484B9B68CF +:1008F00003F1006303F500339A42E9D205F0A4FB4B +:1009000005F0B6FB002001F02FF90220FFF7C0FF31 +:10091000404B0021D3F8E820C3F8E810D3F81021A9 +:10092000C3F81011D3F81021D3F8EC20C3F8EC1061 +:10093000D3F81421C3F81411D3F81421D3F8F020FC +:10094000C3F8F010D3F81821C3F81811D3F8182100 +:10095000D3F8802042F00072C3F88020D3F88020C2 +:1009600022F00072C3F88020D3F8803072B64FF0C6 +:10097000E023C3F8084DD4E90004BFF34F8FBFF361 +:100980006F8F254AC2F88410BFF34F8F536923F449 +:1009900080335361BFF34F8FD2F8803043F6E07657 +:1009A000C3F3C905C3F34E335B0103EA060C2946C2 +:1009B0004CEA81770139C2F87472F9D2203B13F105 +:1009C000200FF2D1BFF34F8FBFF36F8FBFF34F8F65 +:1009D000BFF36F8F536923F4003353610023C2F8D0 +:1009E0005032BFF34F8FBFF36F8F302383F31188E3 +:1009F000854680F3088820476AE700BFE822002088 +:100A0000F02300200000020820000208FFFF010878 +:100A1000002200200044025800ED00E02DE9F04FD4 +:100A200093B0B74B2022FF2100900AA89D6801F0E7 +:100A300051F9B44A1378A3B90121B3481170036086 +:100A4000302383F3118803680BB104F0EFFE002319 +:100A5000AE4A4FF47A71AC4804F0DEFE002383F313 +:100A60001188009B13B1AA4B009A1A60A94A137807 +:100A7000032B03D000231370A54A53604FF0000AE4 +:100A8000009CD3465646D146012001F0F9F824B126 +:100A90009F4B1B68002B00F02C82002001F016F801 +:100AA0000390039B002B01DA00F08CFE039B002BCC +:100AB000EDDB012001F0E2F8039B213B1F2BE3D883 +:100AC00001A252F823F000BF490B0008710B000887 +:100AD000050C0008890A0008890A0008890A00082C +:100AE000970C0008670E0008810D0008E30D000850 +:100AF0000B0E0008310E0008890A0008430E00089A +:100B0000890A0008B50E0008E90B0008890A0008E8 +:100B1000F90E0008550B0008E90B0008890A0008C7 +:100B2000E30D0008890A0008890A0008890A0008FC +:100B3000890A0008890A0008890A0008890A000849 +:100B4000890A0008050C00080220FFF751FE002862 +:100B500040F0F981009B022105A8BAF1000F08BFFF +:100B60001C4641F21233ADF8143000F0CDFF8BE794 +:100B70004FF47A7000F0AAFF071EEBDB0220FFF7AC +:100B800037FE0028E6D0013F052F00F2DE81DFE8C6 +:100B900007F0030A0D1013360523042105A8059359 +:100BA00000F0B2FF17E004215548F9E704215A4844 +:100BB000F6E704215948F3E74FF01C08404608F1D6 +:100BC000040800F0D3FF0421059005A800F09CFF65 +:100BD000B8F12C0FF2D101204FF0000900FA07F70D +:100BE00047EA0B0B5FFA8BFB01F0C0F826B10BF064 +:100BF0000B030B2B08BF0024FFF702FE44E7042180 +:100C00004748CDE7002EA5D00BF00B030B2BA1D14D +:100C10000220FFF7EDFD074600289BD001200026AB +:100C200000F0A2FF0220FFF733FE1FFA86F84046CD +:100C300000F0AAFF0446B0B1039940460136A1F185 +:100C400040025142514100F0B7FF0028EDD1BA46B1 +:100C5000044641F21213022105A83E46ADF81430B5 +:100C600000F052FF10E725460120FFF711FE244B4C +:100C70009B68AB4207D9284600F078FF013040F06E +:100C800067810435F3E70025224BBA463E461D70C6 +:100C90001F4B5D60A8E7002E3FF45CAF0BF00B0329 +:100CA0000B2B7FF457AF0220FFF7F2FD322000F04C +:100CB0000DFFB0F10008FFF64DAF18F003077FF409 +:100CC00049AF0F4A08EB0503926893423FF642AFE3 +:100CD000B8F5807F3FF73EAF124BB845019323DD57 +:100CE0004FF47A7000F0F2FE0390039A002AFFF6A8 +:100CF00031AF039A0137019B03F8012BEDE700BFE9 +:100D000000220020EC230020D02200201908000837 +:100D1000F0230020E82200200422002008220020E6 +:100D20000C220020EC220020C820FFF761FD0746BE +:100D300000283FF40FAF1F2D11D8C5F120020AABD8 +:100D400025F0030084494245184428BF42460192D9 +:100D500000F09AFF019AFF217F4800F0BBFF4FEAA5 +:100D6000A803C8F387027C492846019300F0BAFF24 +:100D7000064600283FF46DAF019B05EB830533E782 +:100D80000220FFF735FD00283FF4E4AE00F026FF17 +:100D900000283FF4DFAE0027B846704B9B68BB428B +:100DA00018D91F2F11D80A9B01330ED027F0030347 +:100DB00012AA134453F8203C05934046042205A987 +:100DC000043701F01BFA8046E7E7384600F0CEFE14 +:100DD0000590F2E7CDF81480042105A800F094FEF8 +:100DE00002E70023642104A8049300F083FE002896 +:100DF0007FF4B0AE0220FFF7FBFC00283FF4AAAE60 +:100E0000049800F0E1FE0590E6E70023642104A8C1 +:100E1000049300F06FFE00287FF49CAE0220FFF7E1 +:100E2000E7FC00283FF496AE049800F0CFFEEAE716 +:100E30000220FFF7DDFC00283FF48CAE00F0DEFE60 +:100E4000E1E70220FFF7D4FC00283FF483AE05A9B8 +:100E5000142000F0D9FE07460421049004A800F0F5 +:100E600053FE3946B9E7322000F030FE071EFFF688 +:100E700071AEBB077FF46EAE384A07EB0903926888 +:100E800093423FF667AE0220FFF7B2FC00283FF422 +:100E900061AE27F003074F44B9453FF4A5AE48467D +:100EA00009F1040900F062FE0421059005A800F094 +:100EB0002BFEF1E74FF47A70FFF79AFC00283FF41D +:100EC00049AE00F08BFE002844D00A9B01330BD0C2 +:100ED00008220AA9002000F005FF00283AD02022AD +:100EE000FF210AA800F0F6FEFFF78AFC1C4804F078 +:100EF000D7FB13B0BDE8F08F002E3FF42BAE0BF004 +:100F00000B030B2B7FF426AE0023642105A8059369 +:100F100000F0F0FD074600287FF41CAE0220FFF72A +:100F200067FC804600283FF415AEFFF769FC41F2EC +:100F3000883004F0B5FB059800F062FF46463C4659 +:100F400000F014FFA0E506464EE64FF0000901E66A +:100F5000BA467EE637467CE6EC22002000220020DE +:100F6000A0860100094A49F26900136899B21B0C76 +:100F700000FB013344F250611360054B186882B2E4 +:100F8000000C01FB0200186080B2704714220020A0 +:100F9000102200200021102210B5044600F09AFE15 +:100FA000034B03CB206061601868A06010BD00BFD8 +:100FB00000E8F11F2DE9F041ADF5507D0D4600210F +:100FC00040F275126EAC074610A80F9100F082FE39 +:100FD0004FF4C4720021204600F07CFE0DF13C0865 +:100FE00002F0C6FA4FF47A72264BB0FBF2F01860AA +:100FF00093E80700022384E807000DF5ED702382D3 +:10100000FFF7C8FF47F605031F4907A8238406F02A +:1010100031FC1F230DF2EB220DF1340C84F8323138 +:1010200007AB1E46083203CE664542F8080C42F86C +:10103000041C3346F5D1306810602046B188B3797E +:10104000918041469371012200F0FCFE002380B2A2 +:10105000E97E0393AB7E029305F11903019301230B +:10106000009306A3D3E90023CDE90480384602F0BB +:101070003DFE0DF5507DBDE8F08100BF9E6AC421A4 +:10108000818A46EEF8230020847800082DE9F0419B +:101090002C4CDAB080460D46237A5BBB27A9284644 +:1010A00000F0DEFF0746002842D19DF89D60C82E63 +:1010B0003ED801464FF4A662204600F00BFE4FF4E6 +:1010C000807332460DF19E01C4F8F8314FF400737D +:1010D00004F109002644C4F80C334FF44073C4F8FB +:1010E000203400F0D1FD9DF89C30777223720BB94B +:1010F000EB7E237206AC8122002127A800F0EAFDD6 +:101100000122214627A800F0E7FF002380B2E97EF4 +:101110000393AB7E029305F1190301932823CDE9D4 +:1011200004400093404605A3D3E9002302F0DEFD0E +:101130005AB0BDE8F08100BFAFF300802641727263 +:10114000DF25D7B7A05D0020F0B5254E4FF48A7596 +:10115000F1B0002405FB006596F8D830D82221466E +:1011600085F8DC303AA885F8E84006AF00F0B2FD1B +:1011700006F1090000F0A6FDD5F8E430C2B206F190 +:1011800009018DF8F0000DF1F100CDE93A3400F0DD +:101190007BFD394601223AA800F0CAFF082380B23D +:1011A000317ACDE9047001270E48CDE9023706F106 +:1011B000D80301933023009307A3D3E9002302F05F +:1011C00095FDA04206DD02F0D3F9C5F8E0003846EF +:1011D00071B0F0BD2046FBE778F6339F93CACD8D02 +:1011E000A05D0020103400202DE9F04F274F87B07C +:1011F000DFF8A480264E384602F0A4FD03460028FE +:101200003CD00024234DADF81440A1460294A246E0 +:10121000CDE90344027B8DF8142003AA9968406845 +:1012200003C21B6843F0004302932B6804F22C5462 +:10123000D3F810B002F09EF910EB0802CDF800A030 +:10124000284605F5A55541F1000302A9D84740F607 +:1012500058230028C8BF49F0010910359C42E4D149 +:10126000B9F1000F05D0384602F070FD86F800A0F5 +:10127000C1E73378072B04D80133337007B0BDE8DA +:10128000F08F024802F062FDF8E700BF1034002042 +:10129000D56200204034002040420F0070B50D465A +:1012A00014461E4602F07EFC50B9022E10D1012CCD +:1012B0000ED112A3D3E900230120C5E9002307E0E2 +:1012C000282C10D005D8012C09D0052C0FD00020D7 +:1012D00070BD302CFBD10BA3D3E90023ECE70BA3AB +:1012E000D3E90023E8E70BA3D3E90023E4E70BA34A +:1012F000D3E90023E0E700BFAFF30080401DA12049 +:1013000026812A0B78F6339F93CACD8D9E6AC4211D +:10131000818A46EE26417272DF25D7B7F017304A30 +:1013200039059E5638B505460E4C0021013500F0B2 +:1013300043FCA4F82C55B4F82C0500F025FC78B13A +:10134000B4F82C0500F030FC014648B9B4F82C057F +:1013500000F032FCB4F82C350133A4F82C35EAE760 +:1013600038BD00BFA05D0020F8B50E4C02260E4F20 +:10137000A4F5805343F8307C237E3BB965692DB1D9 +:10138000284600F0CBFF284606F02AFA2046A4F5AE +:10139000A55400F0C3FF012EA4F1100400D1F8BD44 +:1013A0000126E5E720590020447900082DE9F04F97 +:1013B0008FB005460C4600AF02F0F4FB002849D17F +:1013C000237E022B1BD1E38A012B18D102F0D0F827 +:1013D0000646FFF7C7FD03464FF4C87006F51676BC +:1013E000DFF8C082B3FBF0F202FB103316FA83F38E +:1013F000C8F80030E37E33B9A34B00221A703C37A3 +:10140000BD46BDE8F08F07F12401204600F0E6FD5F +:101410000028F4D107F11400FFF7BCFD97F826402F +:1014200007F1140107F12700224606F0F1F9002820 +:10143000E2D10F2C08D8944B1C70D8F80030A3F5DB +:101440001673C8F80030DAE797F82410284602F03F +:10145000A1FBD4E7E38A282B2BD010D8012B23D073 +:10146000052BCCD1BFF34F8F8849894BCA6802F452 +:10147000E0621343CB60BFF34F8F00BFFDE7302B1B +:10148000BDD1844EE17E327A9142B8D1607E314640 +:10149000002291F8DC50854200F0A580013201F570 +:1014A0008A71042AF5D1AAE721462846FFF782FD72 +:1014B000A5E721462846FFF7E9FDA0E7B2F8EC5082 +:1014C0007B6005F103094FEA99094FEA8902D11DB2 +:1014D000C908A8EBC10300219D46EB46584600F021 +:1014E000F9FB04F1EE012A465846314400F0CCFBEA +:1014F0007B6813B9012000F037FB96F8D20000F0AA +:1015000043FB044630B9307200F068FB204600F01F +:101510002BFBB1E0D6F8D4203AB996F8D200B6F851 +:101520002C25824201D8FFF7FDFED6F8D4202A44AC +:10153000944208D296F8D200B6F82C2501308242A7 +:1015400001D8FFF7EFFE5FFA89F25946706800F0A4 +:10155000C9FB08B9C54679E0726896F8D2002A44FA +:101560007260D6F8D42005EB0209C6F8D49000F0DA +:101570000BFB814509D396F8D220D6F8D40001326E +:10158000001B86F8D220C6F8D400FF2D0FD8002407 +:10159000347200F023FB204600F0E6FA00F044FE2F +:1015A0003D4B188108B9FFF789F9C54627E7BB68A5 +:1015B00096F8D9000AFB0362FB68D2F8E41082F8BF +:1015C000E83001F58061C2F8E030C2F8E410FFF7BE +:1015D000BBFDFFF709FE96F8D920013202F00302A5 +:1015E00086F8D920B6E74FF48A7A20460AFB02F53E +:1015F00005F1EA01314400F0C7FDF86000287FF4EE +:10160000FEAE0122354485F8E82001F0B1FFD5F89F +:10161000E020D6ED007A801A40F6B832B8EE677A4C +:10162000DFED1E6A192838BF1920904228BF1046E6 +:1016300007EE900AF8EEE77A67EEA67ADFED186A11 +:10164000E7EE267AFCEEE77AC6ED007A96F8D93016 +:10165000BB60BA6873680AFB02F4321992F8E810AA +:1016600059B1D2F8E410E8468B423FF427AF00218D +:1016700082F8E810C2F8E010C5467368064A9B0A73 +:1016800001331381BBE600BF0934002000ED00E008 +:101690000400FA05A05D0020F8230020CDCCCC3D4D +:1016A0006666663F0C340020014B1870704700BF1F +:1016B0000424002038B54FF04054144B22689A425D +:1016C00021D1627D0025124B12481A70C922237D58 +:1016D0000930114900F8013C4FF48073C0F8DB5029 +:1016E000C0F8EF314FF40073C0F803334FF4407388 +:1016F000C0F8173400F0C8FAE0222946204600F06E +:10170000E9FA012038BD0020FCE700BF9AAD44C5CE +:1017100004240020A05D00201600003037B500F042 +:1017200083FD1F4C1F4D022301221F496B7123684B +:101730002881204604F580545B6898470122D4F83C +:10174000B03404F5966018495B6898470023174940 +:101750004FF480520193164B16480093164B02F03B +:10176000F1F9164B197811B1124802F013FA01F091 +:10177000FFFE0446FFF7F6FB4FF4C873B0FBF3F22D +:1017800002FB130304F5167010FA83F00C4B18607B +:1017900004F08EFC08B10F232B8103B030BD00BFD5 +:1017A00040340020F823002040420F00082400208D +:1017B0009D12000810340020AD13000804240020FE +:1017C0000C3400202DE9F04F00252DED028B93B055 +:1017D0000DF12C084FF0010ADFF814B2FFF704FDF9 +:1017E0000A95ADF834500B95C8F804509FED798BED +:1017F00000267E4C374623680DF11D0207A92046BE +:101800008DF81CA08DF81D508DED008BD3F808903D +:101810000023C8479DF81C90B9F1000F1ED010227C +:1018200000210EA800F056FA236808AA0AA95F69E9 +:1018300020460DF11E03B8470FAB4F4698E8030052 +:1018400083E803009DF834300EA958468DF84430E3 +:101850000A9B0E93DDE9082302F056FC06F22C5693 +:1018600040F6582304F5A5549E4204F11004C2D159 +:10187000002FBDD15E4802F095F900283FD15D4EA2 +:1018800001F076FE3368984239D301F071FE0446C8 +:10189000FFF768FB4FF4C8738DF82870B0FBF3F2C4 +:1018A00002FB130304F5167010FA83F03060524EF9 +:1018B000377817B901238DF82830C7F110040EA826 +:1018C000FFF768FB0EABE4B20DF12900D919062C25 +:1018D00028BF06242246013400F0D6F90AABE4B250 +:1018E00043480393182304940293444B0193012328 +:1018F00000933AA3D3E9002302F09AF9357001F07E +:1019000037FE3F4A3F4C1368C31AB3F57A7F2FD393 +:10191000106001F02FFE02460B46354802F020FA17 +:10192000334802F03FF918B3237A0EAF364E002B3E +:1019300014BF03230223737101F01AFE4FF47A736C +:1019400001223946B0FBF3F03060304600F01EFB58 +:10195000182380B202932D4B019340F25513CDE929 +:101960000370009322481FA3D3E9002302F060F91B +:10197000237A93B101F0FCFD002607464FF48A78E4 +:1019800094F8D900304400F0030008FB004393F8BA +:10199000E82072B10136042EF2D1C82003F080FE97 +:1019A000237A002B7FF414AF13B0BDEC028BBDE89B +:1019B000F08FD3F8E02042B12368BA1AFA2B38BF6F +:1019C000FA230533B2EB430FE4D3FFF7BDFB002846 +:1019D000E0D1E2E70000000000000000401DA1206F +:1019E00026812A0BF1C6A7C1D068080F4034002019 +:1019F000103400200C34002009340020083400206A +:101A0000D0620020A05D0020F8230020D4620020D6 +:101A100008B5064801F0B6F8054801F0B3F8054AE4 +:101A200005490020BDE8084005F0D4BE4034002040 +:101A3000F048002030630020691300087047000060 +:101A40002DE9F84F4FF47A7306460D46002402FB49 +:101A500003F7DFF85080DFF8509098F900305FFA14 +:101A600084FA5A1C01D0A34212D159F824002A4604 +:101A700031460368D3F820B03B46D847854207D1AA +:101A8000074B012083F800A0BDE8F88F0124E4E7AC +:101A9000002CFBD04FF4FA7003F002FE0020F3E7B5 +:101AA0001C630020182200201C22002070B5044670 +:101AB0004FF47A76412C254628BF412506FB05F0D8 +:101AC00003F0EEFD641BF5D170BD0000002307B5E7 +:101AD000024601210DF107008DF80730FFF7B0FF36 +:101AE00020B19DF8070003B05DF804FB4FF0FF3014 +:101AF000F9E700000A46042108B5FFF7A1FF80F0CE +:101B00000100C0B2404208BD074B0A4630B4197804 +:101B1000064B53F82140014623682046DD69044BFB +:101B2000AC4630BC604700BF1C6300201C22002074 +:101B3000A086010070B50A4E00240A4D04F0CCF8CE +:101B4000308028683388834208D904F0C1F82B68B4 +:101B500004440133B4F5003F2B60F2D370BD00BFE5 +:101B60001E630020D862002004F084B900F10060F8 +:101B700000F500300068704700F10060920000F549 +:101B8000003004F005B90000054B1A68054B1B88AE +:101B90009B1A834202D9104404F09AB8002070477F +:101BA000D86200201E630020024B1B68184404F01A +:101BB00095B800BFD8620020024B1B68184404F09F +:101BC0009FB800BFD86200200020704700F1FF508E +:101BD00000F58F10D0F8000870470000064991F812 +:101BE000243033B100230822086A81F82430FFF73B +:101BF000C3BF0120704700BFDC620020014B1868A2 +:101C0000704700BF0010005C194B013803220844E4 +:101C100070B51D68174BC5F30B042D0C1E88A6422A +:101C20000BD15C680A46013C824213460FD214F97C +:101C3000016F4EB102F8016BF6E7013A03F10803B8 +:101C4000ECD181420B4602D22C2203F8012B042452 +:101C5000094A1688AE4204D1984284BF967803F8A8 +:101C6000016B013C02F10402F3D1581A70BD00BFB0 +:101C70000010005C24220020D0780008704700008B +:101C80007047000070470000002310B5934203D056 +:101C9000CC5CC4540133F9E710BD0000013810B525 +:101CA00010F9013F3BB191F900409C4203D11AB1B8 +:101CB0000131013AF4E71AB191F90020981A10BDE8 +:101CC0001046FCE703460246D01A12F9011B002910 +:101CD000FAD1704702440346934202D003F8011B35 +:101CE000FAE770472DE9F8431F4D1446074688462A +:101CF00095F8242052BBDFF870909CB395F82430FF +:101D00002BB92022FF2148462F62FFF7E3FF95F809 +:101D100024004146C0F1080205EB8000A24228BF22 +:101D20002246D6B29200FFF7AFFF95F82430A41BED +:101D300017441E449044E4B2F6B2082E85F824609D +:101D4000DBD1FFF74BFF0028D7D108E02B6A03EB6C +:101D500082038342CFD0FFF741FF0028CBD1002080 +:101D6000BDE8F8830120FBE7DC620020024B1A7813 +:101D7000024B1A70704700BF1C630020182200201D +:101D800038B51A4C1A4D204602F0A8FF29462046C5 +:101D900002F0D0FF2D684FF47A70D5F89020D2F879 +:101DA000043843F00203C2F80438FFF77FFE1149FC +:101DB000284603F0CDF8D5F890200F4DD2F804381E +:101DC000286823F002030D49A042C2F804384FF4FA +:101DD000E1330B6001D002F0DFFE6868A04204D05E +:101DE0000649BDE8384002F0D7BE38BD106A002071 +:101DF000707A0008787A00081C2200200463002012 +:101E00000C4B70B50C4D04461E780C4B55F8262033 +:101E10009A420DD00A4B002118221846FFF75AFFAC +:101E20000460014655F82600BDE8704002F0B4BEDB +:101E300070BD00BF1C6300201C220020106A00201F +:101E4000046300202DE9F0470D460446002190462A +:101E5000284640F27912FFF73DFF23462022002159 +:101E6000284604F1220702F0F1F8231D0222202166 +:101E70002846C02602F0EAF8631D032222212846E4 +:101E800002F0E4F8A31D03222521284602F0DEF823 +:101E900004F1080310222821284602F0D7F804F1A3 +:101EA000100308223821284602F0D0F804F111036B +:101EB00008224021284602F0C9F804F11203082242 +:101EC0004821284602F0C2F804F1140320225021D0 +:101ED000284602F0BBF804F118034022702128467E +:101EE00002F0B4F804F120030822B021284602F0E1 +:101EF000ADF804F121030822B821284602F0A6F823 +:101F0000314608363B4608222846013702F09EF843 +:101F1000B6F5A07FF4D1002704F1330A04F13203AF +:101F200008223146284602F091F894F832304FEA00 +:101F3000C7099F4209F5A47615D3B8F1000F08D15F +:101F4000314609F24F1604F599730722284602F02C +:101F50007DF827463B1B94F8322193420CD3F01DA9 +:101F6000C008BDE8F0870AEB07030822314628467F +:101F7000013702F06BF8D8E707F233133146082235 +:101F800028460836013702F061F8E3E713B5044646 +:101F9000084600212022234601900160C0F803106A +:101FA00002F054F8231D01980222202102F04EF87D +:101FB000631D01980322222102F048F8A31D019815 +:101FC0000322252102F042F8019804F108031022AF +:101FD000282102F03BF8072002B010BD0023F7B51E +:101FE0000E46047F072200911946054601F0F2FED5 +:101FF000731C0122072100932846002301F0EAFE0A +:10200000C4B9B31C052208212846009323460D2499 +:1020100001F0E0FE3746BB1BB278934211D3073480 +:102020002B7FA88AE408BBB9844294BF002001201A +:1020300003B0F0BDAB8A0824DB00083BDB08B370BB +:10204000E8E7FB1C214608222846009300230834B9 +:10205000013701F0BFFEDEE7201A18BF0120E7E7D5 +:102060000023F7B50E46047F082200911946054665 +:1020700001F0B0FE731CC4B908220093234610245B +:102080001146284601F0A6FE01235F1C7278013B31 +:10209000934211D307342B7FA88AE408BBB984424A +:1020A00094BF0020012003B0F0BDAB8A0824DB0000 +:1020B000083BDB087370E7E7F3192146082228463E +:1020C0000093002301F086FE08343B46DDE7201A2A +:1020D00018BF0120E7E70000F8B50E460546144694 +:1020E000002181223046FFF7F5FD2B460822002112 +:1020F000304601F0ABFF7CB90F246B1C072208218E +:10210000304601F0A3FF01235F1C6A78013B934234 +:1021100004D3E01DC008F8BD0824F4E7EB192146FC +:102120000822304601F092FF08343B46ECE70000FD +:10213000F8B50E46054614460021CE223046FFF77C +:10214000C9FD2B4628220021304601F07FFF7CB9D3 +:10215000302405F1080308222821304601F076FFDB +:102160002F467B1B2A7A934204D3E01DC008F8BD9A +:102170002824F5E707F109032146082230460834F0 +:10218000013701F063FFECE7F7B5047F0E460091DD +:10219000012310220021054601F01CFEC4B9B31C26 +:1021A00009221021284600932346192401F012FE2B +:1021B00037467288BB1B9A4211D807342B7FA88AF6 +:1021C000E408BBB9844294BF0020012003B0F0BDF5 +:1021D000AB8A1024DB00103BDB087380E8E73B1D73 +:1021E000214608222846009300230834013701F0D5 +:1021F000F1FDDEE7201A18BF0120E7E730B50A44F9 +:10220000084D91420DD011F8013B5840082340F38E +:102210000004013B2C4013F0FF0384EA5000F6D188 +:10222000EFE730BD2083B8EDF7B5364A6B4610684E +:1022300051686A4603C308233349344805F0F8FA65 +:10224000044690BB0A25324A6B46106851686A46BC +:1022500003C308232F492D4805F0EAFA0446002855 +:1022600047D00369B3F5F01F43D8B0F86620B2F544 +:10227000AF6F3ED1284A024402F15C018B4238D351 +:102280005C3B224900209E1AFFF7B8FF04F164016D +:10229000074632460020FFF7B1FFA3689F4228D1CE +:1022A000E368984208BF002523E00369B3F5F01FF7 +:1022B00026D8428BB2F5AF6F20D1174A024402F103 +:1022C00010018B4218D3103B104900209D1AFFF7D4 +:1022D00095FF04F1180106462A460020FFF78EFFFD +:1022E000A3689E4202D1E368984201D00D25AAE777 +:1022F0000025284603B0F0BD1025A4E70C25A2E771 +:102300000B25A0E7E0780008DCFF1D0000000208B4 +:10231000E978000890FF1D000800FEF710B5037C67 +:10232000044613B9006805F06BFA204610BD0000A2 +:102330000023BFF35B8FC360BFF35B8FBFF35B8F83 +:102340008360BFF35B8F7047BFF35B8F0068BFF3A1 +:102350005B8F704770B505460C30FFF7F5FF0446FC +:1023600005F108063046FFF7EFFFA04206D96D6879 +:102370003046FFF7E9FF2544281A70BD3046FFF7C5 +:10238000E3FF201AF9E7000070B505464068A0B1E8 +:1023900005F10C0605F10800FFF7D6FF04463046AC +:1023A000FFF7D2FF844204F1FF34304694BF6D68DA +:1023B0000025FFF7C9FF2C44201A70BD38B50C4624 +:1023C0000546FFF7C7FFA04210D305F10800FFF74D +:1023D000BBFF04446868BFF35B8FB4FBF0F100FB04 +:1023E00011440120AC60BFF35B8F38BD0020FCE7D7 +:1023F0002DE9F041144607460D46FFF7C5FF84421C +:1024000028BF0446D4B1B84658F80C6B4046FFF7D5 +:102410009BFF3044286040467E68FFF795FF331AE3 +:102420009C4203D801206C60BDE8F081A41B6B6066 +:102430003B682044AB60E8600220F5E72046F3E704 +:1024400038B50C460546FFF79FFFA04210D305F1B3 +:102450000C00FFF779FF04446868BFF35B8FB4FB9F +:10246000F0F100FB11440120EC60BFF35B8F38BD3D +:102470000020FCE72DE9FF418846694607466C4687 +:10248000FFF7B6FF002506B204EBC606B4420AD039 +:10249000626808EB050120680834FFF7F5FB54F883 +:1024A000043C1D44F2E729463846FFF7C9FF284699 +:1024B00004B0BDE8F0810000F8B505460C300F46C9 +:1024C000FFF742FF05F1080604463046FFF73CFFE0 +:1024D000A042304688BF6C68FFF736FF201A38608C +:1024E00020B12C683046FFF72FFF2044F8BD0000D4 +:1024F00073B5144606460D46FFF72CFF8442019043 +:1025000028BF0446DCB101A93046FFF7D5FF019B87 +:1025100033B93268C5E90233C5E9002401200CE073 +:102520009C42286038BF0194019884426860F5D9C4 +:102530003368241A0220AB60EC6002B070BD204604 +:10254000FBE700002DE9FF410F4669466C46FFF7A7 +:10255000CFFF00B2002604EBC005AC4209D0D4F88E +:102560000480B81954F8081B42464644FFF78CFB18 +:10257000F3E7304604B0BDE8F081000038B5054609 +:10258000FFF7E0FF044601462846FFF717FF204605 +:1025900038BD0000302383F3118862B67047000015 +:1025A000002383F3118862B6704700000120704752 +:1025B0007047000010B41346026814680022A44655 +:1025C0005DF8044B6047000000F5805090F8590416 +:1025D0007047000000F5805090F8520470470000EA +:1025E00000F5805090F95804704700004E20704765 +:1025F00000F5805208B5FFF7CDFFD2F89834D2F835 +:1026000094041844D2F890341844D2F8783418441A +:10261000D2F888341844D2F884341844FFF7C0FF45 +:1026200008BD00002DE9F04F0C4600F5805185B043 +:102630001F4691F8523405469046BDF838909BB13C +:10264000D1F874340133C1F8743423689A0006D485 +:10265000237B082B0BD9627B0AB10F2B07D9D1F84A +:1026600078340133C1F878344FF0FF300FE0FFF7D2 +:1026700091FFEB6AD3F8C42012F4001A0AD0D1F803 +:102680007C3400200133C1F87C34FFF789FF05B0AA +:10269000BDE8F08F22684FF0480BD3F8C460002AE1 +:1026A0006B6AC6F30446B4BF42F0804292041BFB3F +:1026B000063BCBF8002023685B004FEA066344BF6B +:1026C00042F00052CBF80020227B43EA0243720121 +:1026D000CBF80430607B18B343F44013CBF80430DC +:1026E000D1F8A4340133C1F8A434AB1803F58353F3 +:1026F000197B41F020011973207B039200F094FFB5 +:102700000330039A80105FFA8AF30AF1010A8342C8 +:102710000DDA04EB83010BEB830349689960F2E760 +:10272000AB1803F58353197B60F34511E3E70121EF +:10273000EB6A04F10C00B140C3F8D010AB1821468D +:1027400003F58253C3E9048705EB461303F582536F +:10275000183351F804CB814243F804CBF9D10988EE +:102760002A442846198041F26803D65002F5805267 +:1027700009F0030392F86C1043F0100321F01F01DD +:102780000B43214682F86C304246FFF709FF3B4677 +:10279000CDF8009000F00EFF012078E72DE9F0471A +:1027A00000F58056044696F85254002D40F0018101 +:1027B000037C032B40F092802B4628462F465FFA7D +:1027C00083FC944510DA01EBCC0E51F83CC0BCF10F +:1027D000000F04DBDEF804C0BCF1000F02DB0137A0 +:1027E0000133ECE70130FBE7FFF7D4FEE36AF0B911 +:1027F000D3F8800040F00200C3F880004E23E06A66 +:10280000002F6ED1D0F8803043F00103C0F8803043 +:10281000694B6A4A1B6803F1805303F52C539B00F4 +:102820009342A36240F2AF80654800F09BFE4D28C2 +:1028300042D8DFF884814FEA004EDFF88891D8F85B +:1028400000C04EEA8C0EC3F884E00CF1805303F50F +:102850002C539B00636100EB0C03D4F82CC0C8F828 +:102860000030C0F14E03DCF8800040F03000CCF8BE +:1028700080004FF0000CD4F81480E6465FFA8CF02C +:102880008242BCDD01EBC00A51F83000002810DBA9 +:10289000DAF804A0BAF1000F0BDA09EA00400AF0F6 +:1028A0007F0A40EA0A0040F0084048F82E000EF186 +:1028B000010E0CF1010CE1E79A6922F001029A6124 +:1028C00000F056FE0646E36A9B69D90704D500F07E +:1028D0004FFE831BFA2BF6D9FFF762FE2846BDE8B0 +:1028E000F087B7EB530F3DD2DFF8CCE04FEA074C4F +:1028F000DEF800304CEA830CC0F888C003F1805049 +:1029000003EB4703002700F52C50CEF80030BC46FF +:102910008000A061E06AD0F8803043F00C03C0F87A +:102920008030D4F818E0FBB29A427FF771AF51F8CB +:10293000330001EBC3080028D8F8043001DB002B7A +:102940000EDB20F0604023F0604340F0005043F085 +:1029500000434EF83C000EEBCC000CF1010C436040 +:102960000137E0E7836923F00103836100F000FE93 +:102970000646E36A9B69DA07AED500F0F9FD831BD2 +:10298000FA2BF6D9A8E7E26A936923F00103936171 +:1029900000F0EEFD0746E36A9B69DB0705D500F012 +:1029A000E7FDC31BFA2BF6D996E7012586F85254AA +:1029B00092E7002592E700BF2C630020FCB50040A1 +:1029C000F47800080000FF0713B500F5805401916A +:1029D000606CFFF7D9FC1F280AD920220199606C8E +:1029E000FFF748FDA0F120035842584102B010BD46 +:1029F0000020FBE700F5805008B5FFF7CBFD406CE9 +:102A0000FFF796FCBDE80840FFF7CABD0022026050 +:102A100082814260826070470022002310B5C0E9C5 +:102A20000023002304460C3020F8043CFFF7EEFF9F +:102A3000204610BD2DE9F047074688B09A468846E3 +:102A400007F5805468469146FFF7A4FDFFF7E4FFC1 +:102A5000606CFFF77FFC1F282DD920226946606C2F +:102A6000FFF78CFD202826D194F852341BB303AD18 +:102A7000444605AB2E46083403CE9E4244F8080C6B +:102A800044F8041C3546F5D130684146206038468C +:102A9000B388A380DDE90023C9E90023BDF808302D +:102AA0004A46AAF80030FFF77BFD534608B0BDE860 +:102AB000F04700F06DBD0020FFF772FD08B0BDE8E3 +:102AC000F08700002DE9F84F0023064600F58154F9 +:102AD000054688461034C0E90133274B46F8303BA1 +:102AE000374638462037FFF797FFA742F9D105F55B +:102AF00080544FF4805305F5A3594FF0000A266324 +:102B00000026676405F5835709F110094FF0000BA3 +:102B10001037E663C4E90D36012384F8403084F8A9 +:102B20004830A7F11800203747E910ABFFF76EFFD8 +:102B300047F8286C4F45F4D1B8F1010F84F8588458 +:102B4000A4F85A64A4F85C64A4F85E6484F8606431 +:102B5000A4F86264A4F86464A4F8666484F8686401 +:102B600002D9064800F0FEFC054B284653F82830F1 +:102B7000EB62BDE8F88F00BF4479000818790008BF +:102B800034790008044B10B5197804464A1C1A70B1 +:102B9000FFF798FF204610BD296300202DE9F0477C +:102BA00000295FD0304F3148B7FBF1F581428CBF2F +:102BB0000A201120431EB5FBF0FC00FB1C50DCB2C8 +:102BC00020B1022B1846F5D8002037E00CF1FF3574 +:102BD000B5F5806F32D2C4EBC4094FF47A7009F1B5 +:102BE00003034FEAE308C3F3C70308F1010AA4EBA8 +:102BF000030E08FB00085FFA8EF65AFA8EFEB8FB49 +:102C0000FEFEBEF5617F1BDC1FFA8EF4581C56FADF +:102C100080F00CFB00FCB7FBFCFC6145D4D1013B10 +:102C2000DBB20F2BD0D8711E0020C9B2072905D8FE +:102C3000107101201480558053719171BDE8F087A7 +:102C400009F1FF334FEAE30EC3F3C7030EF10108A6 +:102C5000E41A0EFB0000E6B258FA84F4B0FBF4F478 +:102C6000A4B2D3E70846E9E700B4C4043F420F002A +:102C700038B540F27772C36A154CC3F8BC200722FE +:102C8000C36AC3F8C8202268C16A930043F4C02312 +:102C9000C1F8A03002F1805302F16C01C56A03F55E +:102CA0002C53EA3289009B00226041F0E061094A1E +:102CB000C361C5F8C01003F5D87103F56A734162AA +:102CC0009342836202D9044800F04CFC38BD00BF37 +:102CD0002C630020FCB50040F47800082DE9F04F8B +:102CE00000F58055994689B0044695F858348A46CF +:102CF0009046022B04D90027384609B0BDE8F08F72 +:102D00009B4A52F8231009B942F823009949C4F8A4 +:102D10000CA00B7884F81090C3B9FFF73BFC964BDE +:102D2000D3F8EC2042F48072C3F8EC20D3F894205E +:102D300042F48072C3F89420D3F8942022F4807275 +:102D4000C3F8942001230B70FFF72AFC95F8513447 +:102D50006BB9FFF71FFC894A95F85834D35CEBB187 +:102D6000012B24D0012385F85134FFF719FCFFF71C +:102D700011FCE26A936923F01003936100F0F8FB01 +:102D80000746E36A9E6916F0080617D000F0F0FBCC +:102D9000C31BFA2BF5D9FFF703FCACE70321132083 +:102DA00001F044FD0321152001F040FDDAE7032185 +:102DB000142001F03BFD03211620F5E79A6942F04B +:102DC00001029A6100F0D4FB0746E36A9A69D007D2 +:102DD00005D400F0CDFBC31BFA2BF6D9DBE79A69CB +:102DE000002704F5825B42F002020BF1100B9A619E +:102DF000E36A5F65FFF7D4FB686CFFF799FA20225E +:102E000000216846FEF766FF02A8FFF7FFFD6A464D +:102E10000BEB06030DF1180E069794460833BCE839 +:102E20000300F44543F8080C43F8041C6246F4D14F +:102E3000DCF8000020361860B6F5806F9CF804209E +:102E40001A71DCD1002304F5A252514620461A32F1 +:102E500085F8503485F85334FFF7A0FE074690B943 +:102E6000E26A936923F00103936100F081FB054658 +:102E7000E36A9B69D9077FF53EAF00F079FB431BFE +:102E8000FA2BF5D937E795F85F6495F85E2436029A +:102E9000C5F86CA4E36A46EA426695F860241643D6 +:102EA000B5F85C2446EA0246DE61B8F1000F29D08D +:102EB00004F5A352414620460232FFF76FFE90B957 +:102EC000E26A936923F00103936100F051FB054628 +:102ED000E36A9B69DA077FF50EAF00F049FB431BFD +:102EE000FA2BF5D907E795F8683495F867141B01B4 +:102EF000C5F87084E26A43EA0123B5F8641443EA32 +:102F00000143D360E36A00262046C3F8BC60FFF7A4 +:102F1000AFFE85F859646FF04042E36A1A65184ABB +:102F2000E36A5A654FF00222E36A9A654FF0FF3276 +:102F3000E36AC3F8E0200322E36A9145DA653FF4CF +:102F4000DBAEE26A936923F00103936100F010FBAA +:102F50000646E36A9B69DB0705D500F009FB831B86 +:102F6000FA2BF6D9C7E6012385F85234C4E600BF30 +:102F70002063002028630020004402582C790008B8 +:102F8000550200022DE9F04F054689B0904699465A +:102F9000002741F2680A00F58056EB6AD3F8D83072 +:102FA000FB40D8074AD505EB47124FEA471B52446E +:102FB0001379190742D4D6F880340133C6F8803427 +:102FC00013799A0605EB0B0248BFD6F8A834524491 +:102FD00044BF0133C6F8A834137943F008031371D2 +:102FE000DB0723D596F8533403B305F582546846BE +:102FF000FFF712FD03AB18345C4404F1080C2068A1 +:10300000083454F8041C1A46644503C21346F6D12A +:103010002068694610602846A2889A800123ADF88E +:1030200008302B68CDE90089DB6B9847D6F854341B +:1030300023B1D6F89C340133C6F89C340137202FD5 +:10304000ABD109B0BDE8F08F2DE9F04F0F468DB040 +:10305000044600F08FFA82468946002F5BD1E36A6E +:10306000D3F8A02012F4FE0F03D100200DB0BDE86C +:10307000F08FD3F8A420920141BF04F58051D1F81C +:1030800094240132C1F89424D3F8A4205606ECD03D +:10309000D3F8A450E669C5F305254823E8464FF068 +:1030A000000B03FB05664046FFF7B0FC3268510099 +:1030B0004ABF22F06043C2F38A4343F000439200C8 +:1030C00048BF43F080430093736813F400131BBFA1 +:1030D000012304F580528DF80D308DF80D301EBFA0 +:1030E000D2F8AC340133C2F8AC34F38803F00F03E8 +:1030F0008DF80C309DF80C0000F096FA5FFA8BF317 +:10310000984225D9F2180CA90BF1010B127A0B4445 +:1031100003F82C2CEEE7012FA7D1E36AD3F8B020F7 +:1031200012F4FE0FA1D0D3F8B420950141BF04F5ED +:103130008051D1F894240132C1F89424D3F8B420FA +:10314000500692D0D3F8B450266AC5F30525A4E7FB +:10315000EFB9E36AC3F8A85004A807ADFFF75CFC19 +:1031600098E80F0007C52B800023204604A9ADF87E +:103170001830236804F58054DB6BCDE904A9984727 +:1031800058B1D4F88C340133C4F88C346EE7012F75 +:10319000E2D1E36AC3F8B850DEE7D4F890340120F6 +:1031A0000133C4F8903461E7F8B505460F4600F5E1 +:1031B0008054012639462846FFF746FF10B184F8AF +:1031C0005364F7E7D4F8543423B1D4F89C34013372 +:1031D000C4F89C34F8BD0000C36AF0B51A6C12F450 +:1031E0007F0F2BD01B6C00F5805441F268054FF027 +:1031F000010CC4F8A0340023471900EB43125E0110 +:103200002A44117911F0020F15D0490713D4B95986 +:10321000C66A0CFA01F1D6F8CCE011EA0E0F0AD01A +:10322000C6F8D410117941F004011171D4F8882442 +:103230000132C4F888240133202BDED1F0BD000018 +:103240002B4B70B51E561B5C012B30D8294D2A4ADA +:1032500055F8233052F8264013B349B3236D9A052D +:1032600010D54FF40073236500F084F950EA010291 +:103270000B4602D0013861F10003024655F82600E2 +:10328000FFF780FE236D9B012CD54FF0007255F89F +:103290002630226503F58053012283F8592421E06A +:1032A00001232365102323654FF48053236570BDEC +:1032B000236DDA0702D4236D5B0706D505230021B1 +:1032C00055F826002365FFF76FFF236DD80602D45B +:1032D000236D590606D55023012155F82600236594 +:1032E000FFF762FF55F82600BDE87040FFF774BF96 +:1032F00030790008206300203479000808B5FFF712 +:1033000049F9FFF769FFBDE80840FFF749B9000038 +:10331000C36AD3F8C00010F07C5005D0D3F8C400C5 +:1033200080F40010C0F340507047000000F580505A +:1033300008B5FFF72FF9406CFFF70CF8FFF730F9ED +:1033400043090CBF0120002008BD000000F5805398 +:1033500093F8592462B1C16A8A6922F001028A6134 +:10336000D3F898240132C3F89824002283F8592412 +:10337000704700002DE9F74300F58251984600257B +:10338000FFF708F9103141F2680E4FF0010900F51E +:10339000805C00EB4514744423795E071CD4DB0683 +:1033A0001AD58E69C36A09FA06F6D3F8CC703E4284 +:1033B00012D04F6801970F689742019F77EB08077B +:1033C0000AD2C3F8D460237943F004032371DCF8F4 +:1033D00084340133CCF8843401352031202DD8D108 +:1033E00003B0BDE8F043FFF7DBB80000F8B51E46B8 +:1033F00000230F46054613701446FFF797FF80F031 +:10340000010038701EB12846FFF782FF2070F8BD1A +:103410002DE9F04F85B099460D468046164691F845 +:1034200000B0DDE90EA302931378019300F0A2F837 +:103430002B7804460F4613B93378002B42D022462E +:103440003B464046FFF796FFFFF758FFFFF77EFF2A +:103450004B4632462946FFF7C9FF2B7833B1BBF103 +:10346000000F03D0012005B0BDE8F08F337813B111 +:10347000019B002BF6D108F5805303935445029B22 +:1034800077EB03031ED2039BD3F85404D0B1036837 +:10349000AAEB0401DB6889B298474B4632462946BD +:1034A0004046FFF7A3FF2B7813B1BBF1000FD9D132 +:1034B000337813B1019B002BD4D100F05BF80446A4 +:1034C0000F46DBE70020CEE7002108B50846FFF7EE +:1034D000B7FEBDE8084001F06DB8000008B5012155 +:1034E0000020FFF7ADFEBDE8084001F063B8000022 +:1034F00008B500210120FFF7A3FEBDE8084001F058 +:1035000059B80000012108B50846FFF799FEBDE84B +:10351000084001F04FB8000000B59BB0EFF30981FF +:1035200068226846FEF7B0FBEFF30583014B9B6B07 +:10353000FEE700BF00ED00E008B5FFF7EDFF00007B +:1035400000B59BB0EFF3098168226846FEF79CFB4B +:10355000EFF30583014B5B6BFEE700BF00ED00E07E +:10356000FEE700000FB408B5029802F025F8FEE768 +:1035700002F0CCBC02F0A4BC13B56C46031D84E879 +:10358000060094E8030083E80500012002B010BDA6 +:1035900073B58568019155B11B885B0707D4D0E9E5 +:1035A00000369B6B9847019AC1B23046A84701206C +:1035B00002B070BDF0B5866889B005460C465EB1B4 +:1035C000BDF838305B070AD4D0E900379B6B9847C9 +:1035D0002246C1B23846B047012009B0F0BD0022F2 +:1035E000002301F10806CDE9002300230A46ADF8C7 +:1035F000083003AB1068083252F8041C1C46B24273 +:1036000003C42346F6D1106820609288A280FFF799 +:10361000B1FF0423ADF808302B68CDE90001DB6B66 +:10362000694628469847D7E7082817D909280CD0B3 +:103630000A280CD00B280CD00C280CD00D280CD04C +:103640000E2814BF4020302070470C2070471020F7 +:1036500070471420704718207047202070470000E2 +:103660002DE9F041456A15B94162BDE8F0814B682A +:10367000AC4623F06047C3F38A464FEAD37EC3F3D8 +:10368000807816EA230638BF3E462B465A68BEEBC2 +:10369000D27F22F060440AD0002A18DAA40CB44287 +:1036A00017D19D420FD10D60DEE71346EEE7A7422A +:1036B00007D102F08044C2F3807242450BD054B16E +:1036C000EFE708D2EDE7CCF800100B60CDE7B4428D +:1036D00001D0B442E5D81A689C46002AE5D11960A9 +:1036E000C3E700002DE9F047089D01F0070400EB57 +:1036F000D1004FF47F494FEAD508224405F0070571 +:10370000944201D1BDE8F08704F0070705F0070AED +:10371000111B08EBD50E57453E4613F80EC038BFB7 +:103720005646C6F108068E4228BF0E46E108415CA7 +:1037300034443544B94029FA06F721FA0AF1FFB2B8 +:103740008CEA010147FA0AF739408CEA010C03F8C8 +:103750000EC0D5E780EA0120082341F2210201B220 +:10376000013B4000002980B2B8BF504013F0FF0376 +:10377000F5D1704738B50C468D18A54200D138BD3B +:1037800014F8011BFFF7E6FFF7E7000042684AB1B3 +:10379000136881894360438901339BB29942438115 +:1037A00038BF83811046704770B588B00446202228 +:1037B0000D4668460021FEF78DFA20460495FFF776 +:1037C000E5FF024660B16B46054608AE1C4608356B +:1037D00003CCB44245F8080C45F8041C2346F5D147 +:1037E000104608B070BD0000082817D909280CD071 +:1037F0000A280CD00B280CD00C280CD00D280CD08B +:103800000E2814BF4020302070470C207047102035 +:103810007047142070471820704720207047000020 +:10382000082817D90C280CD910280CD914280CD921 +:1038300018280CD920280CD930288CBF0F200E2036 +:103840007047092070470A2070470B2070470C20F2 +:1038500070470D20704700002DE9F843078C04469F +:10386000072F1ED900254FF6FF73D0E90298C5F146 +:103870002006A5F1200029FA05F1083508FA06F618 +:1038800028FA00F0314301431846C9B2FFF762FF3E +:10389000402D0346EBD13A46E169BDE8F843FFF716 +:1038A00069BF4FF6FF70BDE8F883000010B54B68A4 +:1038B00023B9CA8A63F30902CA8210BD04691A686F +:1038C0001C600361C38A013BC3824A60EFE70000CA +:1038D0002DE9F84F1D46CB8A0F468146C3F30901F7 +:1038E000924605290B4630D00020AAB207F11A04EF +:1038F0009EB21FFA80F8042E0FD8904503F1010301 +:1039000006D30A44FB8A62F309030120FB821AE012 +:103910001AF800600130E654EAE79045F1D2A1F1CF +:10392000050B1C237C68BBFBF3F203FB12BB1FFAE5 +:103930008BF6002C45D14846FFF728FF044638B9DE +:1039400078606FF00200BDE8F88F4FF00008E6E7FE +:10395000002606607860ADB24FF0000B454510D9E7 +:103960000AEB0803221D13F8011B08F10108915509 +:10397000B1B21FFA88F81B292BD0454506F1010684 +:10398000F1D8FB8AC3F30902154465F30903BCE7C8 +:1039900001321C4692B22368002BF9D16B1F0B44F5 +:1039A0001C21B3FBF1F301339BB29A42D3D2BBF19A +:1039B000000FD0D14846FFF7E9FE20B9C4F800B0A7 +:1039C000BFE70122E7E7C0F800B05E46206004468A +:1039D000C1E74545D5D94846FFF7D8FE08B920606C +:1039E000AFE7C0F800B0002620600446B6E700004C +:1039F0002DE9F04F1C46074688462DED028B83B01B +:103A00005B690192002B00F09A80238C2BB1E26954 +:103A1000002A00F09480072B35D807F10C00FFF73F +:103A2000B5FE054638B96FF00205284603B0BDEC77 +:103A3000028BBDE8F08F14220021FEF74BF9228C97 +:103A4000E16905F10800FEF71FF9208C48F00041FC +:103A5000013080B2FFF7E4FEFFF7C6FE013880B206 +:103A600020840130287438466369228C1B782A44EC +:103A700003F01F0363F03F03137269602946FFF7E9 +:103A8000EFFD0125D1E74FF0000900F10C034FF0E5 +:103A9000800A4E464D4608EE103A18EE100AFFF71F +:103AA00075FE83460028BED014220021FEF712F9CD +:103AB000002E3AD1019B0222ABF808300BF1080E20 +:103AC0001FFA82FC218C0CF10100BCF1060F80B2C0 +:103AD00001D88E422BD3FFF7A3FE8E4208BF4FF0D2 +:103AE000400AFFF781FE62690138013512781BFA3E +:103AF00080F1013002F01F022DB242EA491289F032 +:103B000001094AEA020A48F0004281F808A0594631 +:103B10008BF810003846CBF804204FF0000AFFF76E +:103B20009FFD238CB342B8D17FE70022C6E7E1694D +:103B3000895D01360EF80210B6B20132C0E76FF0AF +:103B4000010572E7F8B515460E46302200210446FD +:103B50001F46FEF7BFF8069BB5F5001FA760636020 +:103B600004F11000079B34BF6A094FF6FF72E6614B +:103B7000A362002397B29A4206D800230360A7826B +:103B8000E3822383E360F8BD0660013330462036CC +:103B9000F1E7000003781BB94BB2002BC8BF0170DE +:103BA0007047000000787047F8B50C46C9690746B1 +:103BB00011B9238C002B37D1257E1F2D34D83878AE +:103BC00028BB228C072A2CD8268A36F003032BD157 +:103BD0004FF6FF70FFF7CEFD20F0010031024FF6E7 +:103BE000FF72400441EA0561400C41EA402523464A +:103BF00029463846FFF7FCFE002807DD6269137886 +:103C00000133DBB21F2B88BF00231370F8BD218A5C +:103C10002D0645EA012505432046FFF71DFE024615 +:103C2000E5E76FF00300F1E76FF00100EEE7000059 +:103C300070B58AB0044616460021282268461D4603 +:103C4000FEF748F8BDF8383069462046ADF8103028 +:103C50000F9B05939DF840308DF81830119B07930A +:103C6000BDF84830CDE90265ADF82030FFF79CFF84 +:103C70000AB070BD2DE9F041D36905460C461646E1 +:103C80000BB9138C5BBB377E1F2F28D895F80080AB +:103C9000B8F1000F26D03046FFF7DEFD3378210261 +:103CA0000246284641EAC331338A41EA080141EA23 +:103CB000076141EA0341334641F08001FFF798FE76 +:103CC00000280ADD3378012B07D17269137801339C +:103CD000DBB21F2B88BF00231370BDE8F0816FF0AB +:103CE0000100FAE76FF00300F7E70000F0B58BB0D2 +:103CF00004460D4617460021282268461E46FDF759 +:103D0000E9FF9DF84C30294620465A1E5342534144 +:103D10006A468DF800309DF84030ADF81030119BA8 +:103D200005939DF848308DF81830149B0793BDF823 +:103D30005430CDE90276ADF82030FFF79BFF0BB091 +:103D4000F0BD0000406A00B104307047436A1A6851 +:103D5000426202691A600361C38A013BC3827047F1 +:103D60002DE9F041D0F8208014461D46184E4146FA +:103D7000002709B9BDE8F081D1E90223A21A65EB59 +:103D80000303964277EB03031ED2036A8B420DD1E5 +:103D9000FFF78CFD036A1B68036203690B60C38A2B +:103DA0000161013B016AC3828846E2E7FFF77EFDBD +:103DB0000B68C8F8003003690B60C38A0161013BDE +:103DC000C382D8F80010D4E788460968D1E700BF5D +:103DD00080841E002DE9F04F8BB00D4614469B46A3 +:103DE000DDF850908046002800F01881B9F1000FEE +:103DF00000F01481531E3F2B00F21081012A03D1E1 +:103E0000BBF1000F40F00A810023CDE90833B8F878 +:103E10001430B5EBC30F4FEAC30703D300200BB038 +:103E2000BDE8F08F2B199F42D8F80C3036BF7F1BAE +:103E30002746FFB21BB9D8F81030002B7AD0272DB7 +:103E40004DD8C5F1280600232946B742009308AB98 +:103E5000D8F808002CBFF6B23E46A7EB060A354458 +:103E600032465FFA8AFAFFF73DFCB8F81430282191 +:103E700003F10053053BDB000493D8F80C300393A7 +:103E8000039B13B1BAF1000F2CD1D8F8100040B148 +:103E9000BAF1000F05D008AB5246691A0096FFF739 +:103EA00021FC38B2002FB9D066070AD00AAB6242B3 +:103EB00003EBD40102F0070211F8083C134101F8AA +:103EC000083C082C3DD9102C40F2B580202C40F243 +:103ED000B780BBF1000F00F09C80082335E0BA46A4 +:103EE0000026C2E7049BE02B28BFE02306930B4487 +:103EF000AB42059315D95A1B0398691A009692454F +:103F000008AB00F1040034BF5246D2B20792FFF76B +:103F1000E9FB079A1644AAEB020A1544F6B25FFAC7 +:103F20008AFA049B069A05999B1A0493039B1B68C3 +:103F30000393A5E700933A4608AB2946D8F8080052 +:103F4000ADE7BBF1000F13D00123B4EBC30F6BD06F +:103F5000082C12D89DF82030621E23FA02F2D507F1 +:103F600006D54FF0FF3202FA04F423438DF82030D7 +:103F70009DF8203089F8003051E7102C12D8BDF898 +:103F80002030621E23FA02F2D10706D54FF0FF322D +:103F900002FA04F42343ADF82030BDF82030A9F82C +:103FA00000303CE7202C0FD80899631E21FA03F358 +:103FB000DA0705D54FF0FF3202FA04F40C430894F7 +:103FC000089BC9F800302AE7402C2AD0611EC4F1B2 +:103FD0002102A4F12103DDE9086526FA01F105FAC1 +:103FE00002F225FA03F311431943CB0711D501223D +:103FF000A4F12003C4F1200102FA03F322FA01F133 +:10400000A2400B43524263EB430332432B43CDE9BF +:104010000823DDE90823C9E9002300E76FF0010068 +:10402000FDE66FF00800FAE6082CA1D9102CB4D9EF +:10403000202CEED8C4E7BBF1000FAED0022384E7FA +:10404000BBF1000FBCD004237FE70000012A30B58C +:10405000144638BF012485B00025402C28BF4024D9 +:10406000012ACDE9025518D81B788DF8083063076E +:104070000AD004AB624203EBD40502F0070215F844 +:10408000083C934005F8083C034600912246002175 +:1040900002A8FFF727FB05B030BD082AE4D9102A93 +:1040A00003D81B88ADF80830E1E7202A95BF1B68CC +:1040B000D3E900230293CDE90223D8E710B5CB68FA +:1040C0001BB98B600B618B8210BD04691A681C6080 +:1040D0000361C38A013BC382CA60F0E703064CBF99 +:1040E000C0F3C0300220704708B50246FFF7F6FF64 +:1040F000022806D15306C2F30F2001D100F00300BD +:1041000008BDC2F30740FBE72DE9F04F93B004462A +:104110000D46CDE903230A681046FFF7DFFF0228AA +:10412000824614BFC2F306260026002A80F2F381DD +:1041300012F0C04940F0EF81097B002900F0EB81CB +:10414000022803D02378B34240F0E881C2F304632D +:1041500010462944069302F07F030593FFF7C4FF3E +:10416000059B002283464FEA8348002348EA0A4819 +:1041700048EA4668CE78CDE90823F30948EA000802 +:10418000029368D0059B024608A920460093534637 +:104190006768B847002800F0C481276A4FB94146D4 +:1041A00004F10C00FFF700FB074690B96FF0020026 +:1041B00055E03B6998450DD03F68002FF9D1414645 +:1041C00004F10C00FFF7F0FA07460028EED0236A4E +:1041D0003B60276297F817C006F01F08CCF3840CE9 +:1041E000ACEB0800A8EB0C031FFA80FE0028B8BF58 +:1041F0000EF120001FFA83FEB8BF00B2002B079318 +:10420000B8BF0EF12003D7E90221BCBF1BB2079350 +:1042100052EA010338D0039B4FF0000CDFF820E393 +:104220009A1A049B63EB010196457CEB01032BD3A7 +:104230006B7B97F81AE0734519D1029B002B78D05D +:10424000012821DC7868F8B9DFF8F0C2944570EBFA +:10425000010316D337E0276A27B96FF00C0013B0BB +:10426000BDE8F08F3B699845B4D03F68F4E7B348A8 +:1042700090427CEB010301D30020F0E7029B002B6E +:10428000FAD0079B0F2B17DCFA7DB3003946204686 +:1042900002F0030203F07C031343FB75FFF706FBF8 +:1042A0006B7BBB76029B3BB9FB7DC3F3840201327F +:1042B00062F38603FB75D0E76A7BBB7E9A42DBD153 +:1042C000029B002B35D0B309022B32D0039B142262 +:1042D00000210DA8BB60049BFB60FDF7FBFC039B6A +:1042E0000AA920460A93049BADF83EB00B932B1D00 +:1042F0008DF840A00C932B7B8DF84180013BDBB205 +:10430000ADF83C30069B8DF84230059B8DF843306C +:1043100094F82C3083F001038DF84430A36898475B +:10432000FB7DC3F38403013303F01F039B02FB8275 +:10433000A2E7FB7DC6F34012B2EBD31F40F0F4803E +:10434000C3F38403434540F0F280029AB6092B7B05 +:10435000002A4DD0F2075DD4032B40F2EB80039B83 +:10436000AE1D394604F10C00BB603246049BFB6075 +:104370002B7B033BDBB2FFF7ABFA00280CDA3946A4 +:104380002046FFF793FAFB7DC3F38403013303F068 +:104390001F039B02FB8209E7AB88DDE908843B83AE +:1043A0004FF6FF73C9F12000A9F1200228FA09F1A4 +:1043B00009F1080904FA00F024FA02F20143184650 +:1043C0001143C9B2FFF7C6F9B9F1400F0346E9D16D +:1043D000B88231462A7B033AD2B2FFF7CBF9FB7D94 +:1043E000B882DA43C2F3C01262F3C713FB7543E726 +:1043F00086B92E1D013B394604F10C00DBB2324672 +:10440000FFF766FA0028BADB2A7B3146B88A013A00 +:10441000D2B2E2E7F98A013BC1F30901DAB2042919 +:104420005BD8281D002307F11B069A4208D910F813 +:1044300001CB013306F801C00131DBB20529F4D10B +:10444000039993420A9138BF043304992CBF002387 +:1044500055FA83F30B9107F11B010C9179680E93C8 +:104460000D91291DFB8AADF83EB0C3F309038DF809 +:1044700040A08DF841801A44069B8DF84230059B80 +:10448000ADF83C208DF8433094F82C3083F00103D4 +:104490008DF844300023B88A7B602A7B013AFFF70D +:1044A00069F93B8BB882834203D1A3680AA92046ED +:1044B000984720460AA9FFF701FEFB7DBA8AC3F39D +:1044C0008403013303F01F039B02FB823B8B9A4260 +:1044D0000CBF00206FF01000C1E67B68002BAFD04E +:1044E000052001E01C3033461E68002EFAD1091A5F +:1044F0002E1D081D184401EB090C5FFA89F3BCF16D +:104500001B0F9DD89A429BD916F8013B09F101096E +:1045100000F8013BEFE76FF00900A0E66FF00A003A +:104520009DE66FF00B009AE66FF00D0097E66FF0D6 +:104530000E0094E66FF00F0091E600BF40420F00BE +:1045400080841E00EFF30983054968334A6B22F02B +:1045500001024A6383F30988002383F311887047BB +:1045600000EF00E0302080F3118862B60D4B0E4A58 +:10457000D96821F4E0610904090C0A430B49DA60A7 +:10458000D3F8FC2042F08072C3F8FC20084AC2F83D +:10459000B01F116841F0010111602022DA7783F821 +:1045A0002200704700ED00E00003FA0555CEACC5CF +:1045B000001000E0302310B583F311880E4B5B68C8 +:1045C00013F4006314D0F1EE103AEFF309844FF0C6 +:1045D0008073683CE361094BDB6B236684F30988D5 +:1045E00000F0A8FF10B1064BA36110BD054BFBE71F +:1045F00083F31188F9E700BF00ED00E000EF00E071 +:104600004307000846070008026843681143016039 +:1046100003B1184770470000024A136843F0C00313 +:10462000136070470078004013B50E4C204600F030 +:10463000A7FA04F1140000234FF400720A49009411 +:1046400000F064F9094B4FF40072094904F1380095 +:10465000009400F0DDF9074A074BC4E9172302B0C4 +:1046600010BD00BF34630020A0630020194600087D +:10467000A06500200078004000E1F505037C30B51E +:10468000244C002918BF0C46012B11D1224B984213 +:104690000ED1224BD3F8E82042F08042C3F8E82044 +:1046A000D3F8102142F08042C3F81021D3F8103122 +:1046B0002268036EC16D03EB52038466B3FBF2F311 +:1046C0006268150442BF23F0070503F0070343EABD +:1046D0004503CB60A36843F040034B60E36843F0BD +:1046E00001038B6042F4967343F001030B604FF0BB +:1046F000FF330B62510505D512F0102205D0B2F13F +:10470000805F04D080F8643030BD7F23FAE73F2318 +:10471000F8E700BF847900083463002000440258A1 +:104720002DE9F047C66D05463768F4692107346204 +:104730001AD014F0080118BF4FF48071E20748BF87 +:1047400041F02001A3074FF0300348BF41F0400182 +:10475000600748BF41F0800183F31188281DFFF7EF +:1047600053FF002383F31188E2050AD5302383F336 +:1047700011884FF48061281DFFF746FF002383F363 +:1047800011884FF030094FF0000A14F0200838D19A +:104790003B0616D54FF0300905F1380A200610D532 +:1047A00089F31188504600F067F9002836DA0821AD +:1047B000281DFFF729FF27F080033360002383F3D0 +:1047C0001188790614D5620612D5302383F3118837 +:1047D000D5E913239A4208D12B6C33B127F0400757 +:1047E0001021281DFFF710FF3760002383F3118885 +:1047F000E30618D5AA6E1369ABB15069BDE8F0475E +:10480000184789F31188736A284695F8641019408F +:1048100000F0D0F98AF31188F469B6E7B06288F342 +:104820001188F469BAE7BDE8F0870000090100F1DA +:104830006043012203F56143C9B283F8001300F01D +:104840001F039A4043099B0003F1604303F5614352 +:10485000C3F880211A607047F8B51546826804468F +:104860000B46AA4200D28568A1692669761AB5422C +:104870000BD218462A46FDF707FAA3692B44A36119 +:104880002846A3685B1BA360F8BD0CD9AF1B184674 +:104890003246FDF7F9F93A46E1683044FDF7F4F99C +:1048A000E3683B44EBE718462A46FDF7EDF9E36879 +:1048B000E5E7000083689342F7B50446154600D249 +:1048C0008568D4E90460361AB5420BD22A46FDF752 +:1048D000DBF963692B4463612846A3685B1BA36013 +:1048E00003B0F0BD0DD93246AF1B0191FDF7CCF9F5 +:1048F00001993A46E0683144FDF7C6F9E3683B4464 +:10490000E9E72A46FDF7C0F9E368E4E710B50A4491 +:104910000024C361029B8460C16002610362C0E93C +:104920000000C0E9051110BD08B5D0E90532934279 +:1049300001D1826882B98268013282605A1C426168 +:1049400019700021D0E904329A4224BFC368436140 +:1049500000F0C2FE002008BD4FF0FF30FBE7000072 +:1049600070B5302304460E4683F31188A568A5B1BF +:10497000A368A269013BA360531CA3611578226957 +:10498000934224BFE368A361E3690BB120469847D3 +:10499000002383F31188284607E03146204600F0C3 +:1049A0008BFE0028E2DA85F3118870BD2DE9F74F00 +:1049B00004460E4617469846D0F81C904FF0300A31 +:1049C0008AF311884FF0000B154665B12A4631462F +:1049D0002046FFF741FF034660B94146204600F0FC +:1049E0006BFE0028F1D0002383F31188781B03B0FD +:1049F000BDE8F08FB9F1000F03D001902046C84701 +:104A0000019B8BF31188ED1A1E448AF31188DCE7B1 +:104A1000C160C361009B82600362C0E9051111445B +:104A2000C0E9000001617047F8B504460D4616461E +:104A3000302383F31188A768A7B1A368013BA36063 +:104A400063695A1C62611D70D4E904329A4224BF22 +:104A5000E3686361E3690BB120469847002080F367 +:104A6000118807E03146204600F026FE0028E2DAF1 +:104A700087F31188F8BD0000D0E9052310B59A42EC +:104A800001D182687AB982680021013282605A1CA1 +:104A900082611C7803699A4224BFC368836100F075 +:104AA0001BFE204610BD4FF0FF30FBE72DE9F74F0E +:104AB00004460E4617469846D0F81C904FF0300A30 +:104AC0008AF311884FF0000B154665B12A4631462E +:104AD0002046FFF7EFFE034660B94146204600F04E +:104AE000EBFD0028F1D0002383F31188781B03B07D +:104AF000BDE8F08FB9F1000F03D001902046C84700 +:104B0000019B8BF31188ED1A1E448AF31188DCE7B0 +:104B1000026843681143016003B118477047000001 +:104B20001430FFF743BF00004FF0FF331430FFF79E +:104B30003DBF00003830FFF7B9BF00004FF0FF3332 +:104B40003830FFF7B3BF00001430FFF709BF000093 +:104B50004FF0FF311430FFF703BF00003830FFF78C +:104B600063BF00004FF0FF323830FFF75DBF000039 +:104B7000012914BF6FF0130000207047FFF754BDE8 +:104B8000044B036000234360C0E902330123037434 +:104B9000704700BF9C79000810B53023044683F3AA +:104BA0001188FFF76BFD02230020237480F3118826 +:104BB00010BD000038B5C36904460D461BB9042179 +:104BC0000844FFF7A5FF294604F11400FFF7ACFEE7 +:104BD000002806DA201D4FF40061BDE83840FFF7D9 +:104BE00097BF38BD026843681143016003B118479D +:104BF0007047000013B5406B00F58054D4F8A4381A +:104C00001A681178042914D1017C022911D119796B +:104C1000012312898B4013420BD101A94C3002F0C1 +:104C200017F9D4F8A4480246019B2179206800F0C6 +:104C3000DFF902B010BD0000143002F099B8000096 +:104C40004FF0FF33143002F093B800004C3002F004 +:104C50006BB900004FF0FF334C3002F065B9000033 +:104C6000143002F067B800004FF0FF31143002F04A +:104C700061B800004C3002F037B900004FF0FF324D +:104C80004C3002F031B900000020704710B500F53B +:104C90008054D4F8A4381A681178042917D1017CFB +:104CA000022914D15979012352898B4013420ED124 +:104CB000143001F0F9FF024648B1D4F8A4484FF48B +:104CC000407361792068BDE8104000F07FB910BDE5 +:104CD000406BFFF7DBBF0000704700007FB5124B51 +:104CE00001250426044603600023057400F18402B4 +:104CF00043602946C0E902330C4B02901430019303 +:104D00004FF44073009601F0ABFF094B04F6944258 +:104D1000294604F14C000294CDE900634FF440733E +:104D200002F072F804B070BDC4790008D14C0008DC +:104D3000F54B00080A68302383F311880B790B3395 +:104D400042F823004B79133342F823008B7913B1D7 +:104D50000B3342F8230000F58053C3F8A418022354 +:104D60000374002080F311887047000038B5037F7A +:104D7000044613B190F85430ABB90125201D02212F +:104D8000FFF730FF04F114006FF00101257700F008 +:104D9000AFFC04F14C0084F854506FF00101BDE801 +:104DA000384000F0A5BC38BD10B5012104460430E0 +:104DB000FFF718FF0023237784F8543010BD00005C +:104DC00038B504460025143001F062FF04F14C00B0 +:104DD000257702F031F8201D84F854500121FFF7A7 +:104DE00001FF2046BDE83840FFF750BF90F8803003 +:104DF00003F06003202B06D190F881200023212AA4 +:104E000003D81F2A06D800207047222AFBD1C0E908 +:104E10001D3303E0034A426707228267C36701200C +:104E2000704700BF3C22002037B500F58055D5F80B +:104E3000A4381A68117804291AD1017C022917D1E3 +:104E40001979012312898B40134211D100F14C04CE +:104E5000204602F0B1F858B101A9204601F0F8FF50 +:104E6000D5F8A4480246019B2179206800F0C0F8DB +:104E700003B030BD01F10B03F0B550F8236085B0ED +:104E800004460D46FEB1302383F3118804EB8507F9 +:104E9000301D0821FFF7A6FEFB6806F14C005B6998 +:104EA0001B681BB1019001F0E1FF019803A901F01B +:104EB000CFFF024648B1039B2946204600F098F8F0 +:104EC000002383F3118805B0F0BDFB685A691268AE +:104ED000002AF5D01B8A013B1340F1D104F1800276 +:104EE000EAE70000133138B550F82140ECB1302327 +:104EF00083F3118804F58053D3F8A42813685279FA +:104F000003EB8203DB689B695D6845B1042160188F +:104F1000FFF768FE294604F1140001F0CFFE204699 +:104F2000FFF7B4FE002383F3118838BD70470000FB +:104F300001F09CB901234022002110B5044600F87D +:104F4000303BFCF7C7FE0023C4E9013310BD00006D +:104F500010B53023044683F31188242241600021D8 +:104F60000C30FCF7B7FE204601F0A2F90223002026 +:104F7000237080F3118810BD70B500EB81030546E6 +:104F800050690E461446DA6018B110220021FCF771 +:104F9000A1FEA06918B110220021FCF79BFE31464A +:104FA0002846BDE8704001F089BA000083682022DD +:104FB000002103F0011310B5044683601030FCF7A4 +:104FC00089FE2046BDE8104001F004BBF0B4012585 +:104FD00000EB810447898D40E4683D43A469458125 +:104FE00023600023A2606360F0BC01F021BB0000DD +:104FF000F0B4012500EB810407898D40E4683D434E +:105000006469058123600023A2606360F0BC01F045 +:1050100097BB000070B502230025044624220370CC +:105020002946C0F888500C3040F8045CFCF752FE6A +:10503000204684F8705001F0D5F963681B6823B1ED +:1050400029462046BDE87040184770BD0378052BFF +:1050500010B504460AD080F88C30052303704368ED +:105060001B680BB1042198470023A36010BD00000A +:105070000178052906D190F88C20436802701B68DE +:1050800003B118477047000070B590F870300446BF +:1050900013B1002380F8703004F18002204601F043 +:1050A000BDFA63689B68B3B994F8803013F060056B +:1050B00035D00021204601F0AFFD0021204601F04F +:1050C0009FFD63681B6813B106212046984706239D +:1050D00084F8703070BD204698470028E4D0B4F8BA +:1050E0008630A26F9A4288BFA36794F98030A56F7B +:1050F000002B4FF0300380F20381002D00F0F2808E +:10510000092284F8702083F3118800212046D4E915 +:105110001D23FFF76DFF002383F31188DAE794F86E +:10512000812003F07F0343EA022340F202329342DC +:1051300000F0C58021D8B3F5807F48D00DD8012B71 +:105140003FD0022B00F09380002BB2D104F18802F3 +:1051500062670222A267E367C1E7B3F5817F00F0CF +:105160009B80B3F5407FA4D194F88230012BA0D16D +:10517000B4F8883043F0020332E0B3F5006F4DD04D +:1051800017D8B3F5A06F31D0A3F5C063012B90D829 +:105190006368204694F882205E6894F88310B4F81F +:1051A0008430B047002884D0436863670368A367EE +:1051B0001AE0B3F5106F36D040F6024293427FF406 +:1051C00078AF5C4B63670223A3670023C3E794F8BF +:1051D0008230012B7FF46DAFB4F8883023F00203E6 +:1051E000A4F88830C4E91D55E56778E7B4F8803045 +:1051F000B3F5A06F0ED194F88230204684F88A303F +:1052000001F04EF963681B6813B1012120469847ED +:10521000032323700023C4E91D339CE704F18B03AF +:1052200063670123C3E72378042B10D1302383F372 +:1052300011882046FFF7BAFE85F3118803216368C1 +:1052400084F88B5021701B680BB12046984794F866 +:105250008230002BDED084F88B3004232370636807 +:105260001B68002BD6D0022120469847D2E794F83D +:10527000843020461D0603F00F010AD501F0C0F965 +:10528000012804D002287FF414AF2B4B9AE72B4B54 +:1052900098E701F0A7F9F3E794F88230002B7FF448 +:1052A00008AF94F8843013F00F01B3D01A062046EB +:1052B00002D501F0C9FCADE701F0BAFCAAE794F809 +:1052C0008230002B7FF4F5AE94F8843013F00F0198 +:1052D000A0D01B06204602D501F09EFC9AE701F003 +:1052E0008FFC97E7142284F8702083F311882B46F3 +:1052F0002A4629462046FFF769FE85F31188E9E62C +:105300005DB1152284F8702083F3118800212046B6 +:10531000D4E91D23FFF75AFEFDE60B2284F8702026 +:1053200083F311882B462A4629462046FFF760FE64 +:10533000E3E700BFF4790008EC790008F079000891 +:1053400038B590F870300446002B3ED0063BDAB2F8 +:105350000F2A34D80F2B32D8DFE803F03731310869 +:10536000223231313131313131313737856FB0F857 +:1053700086309D4214D2C3681B8AB5FBF3F203FB4F +:1053800012556DB9302383F311882B462A462946DE +:10539000FFF72EFE85F311880A2384F870300EE0A3 +:1053A000142384F87030302383F3118800232046BF +:1053B0001A461946FFF70AFE002383F3118838BD09 +:1053C000C36F03B198470023E7E70021204601F0AF +:1053D00023FC0021204601F013FC63681B6813B115 +:1053E0000621204698470623D7E7000010B590F81D +:1053F00070300446142B29D017D8062B05D001D8BD +:105400001BB110BD093B022BFBD80021204601F047 +:1054100003FC0021204601F0F3FB63681B6813B115 +:10542000062120469847062319E0152BE9D10B23C6 +:1054300080F87030302383F3118800231A46194610 +:10544000FFF7D6FD002383F31188DAE7C3689B6971 +:105450005B68002BD5D1C36F03B19847002384F854 +:105460007030CEE700238268037503691B68996872 +:105470009142FBD25A6803604260106058607047E6 +:1054800000238268037503691B6899689142FBD801 +:105490005A680360426010605860704708B508465B +:1054A000302383F311880B7D032B05D0042B0DD003 +:1054B0002BB983F3118808BD8B6900221A604FF065 +:1054C000FF338361FFF7CEFF0023F2E7D1E900321B +:1054D00013605A60F3E70000FFF7C4BF054BD968BB +:1054E00008751868026853601A600122D860027556 +:1054F000FBF712B9A06700200C4B30B5DD684B1CE0 +:1055000087B004460FD02B46094A684600F084F95C +:105510002046FFF7E3FF009B13B1684600F086F9D1 +:10552000A86907B030BDFFF7D9FFF9E7A0670020F1 +:105530009D540008044B1A68DB6890689B68984289 +:1055400094BF002001207047A0670020084B10B5D1 +:105550001C68D868226853601A600122DC602275DA +:10556000FFF78EFF01462046BDE81040FBF7D4B898 +:10557000A0670020044B1A68DB6892689B689A4217 +:1055800001D9FFF7E3BF7047A067002038B5074C8B +:1055900001230025064907482370656001F04AFD94 +:1055A0000223237085F3118838BD00BF086A0020EC +:1055B000FC790008A067002008B572B6044B186596 +:1055C00000F06CFC00F03EFD024B03221A70FEE777 +:1055D000A0670020086A002000F05EB9EFF3118098 +:1055E00020B9EFF30583302282F311887047000061 +:1055F00010B530B9EFF30584C4F3080414B180F397 +:10560000118810BDFFF7B6FF84F31188F9E7000099 +:10561000034A516853685B1A9842FBD8704700BF31 +:10562000001000E08B600223086108468B827047FF +:105630008368A3F1840243F8142C026943F8442CD4 +:10564000426943F8402C094A43F8242CC268A3F16C +:10565000200043F8182C022203F80C2C002203F837 +:105660000B2C034A43F8102C704700BF3107000889 +:10567000A067002008B5FFF7DBFFBDE80840FFF793 +:105680002BBF0000024BDB6898610F20FFF726BF9D +:10569000A0670020302383F31188FFF7F3BF0000D9 +:1056A00008B50146302383F311880820FFF724FF53 +:1056B000002383F3118808BD064BDB6839B14268CB +:1056C00018605A60136043600420FFF715BF4FF065 +:1056D000FF307047A06700200368984206D01A6820 +:1056E0000260506018469961FFF7F6BE70470000EF +:1056F00038B504460D462068844200D138BD0368A1 +:1057000023605C608561FFF7E7FEF4E7036810B58E +:105710009C68A2420CD85C688A600B604C60216077 +:10572000596099688A1A9A604FF0FF33836010BD00 +:10573000121B1B68ECE700000A2938BF0A2170B56C +:1057400004460D460A26601901F06CFC01F054FC79 +:10575000041BA54203D8751C04462E46F3E70A2E07 +:1057600004D90120BDE8704001F0A4BC70BD000068 +:10577000F8B5144B0D460A2A4FF00A07D96103F118 +:105780001001826038BF0A22416019691446016025 +:1057900048601861A81801F035FC01F02DFC431B8E +:1057A0000646A34206D37C1C28192746354601F03D +:1057B00039FCF2E70A2F04D90120BDE8F84001F0D6 +:1057C00079BCF8BDA0670020F8B506460D4601F08B +:1057D00013FC0F4A134653F8107F9F4206D12A4606 +:1057E00001463046BDE8F840FFF7C2BFD169BB684B +:1057F000441A2C1928BF2C46A34202D92946FFF788 +:105800009BFF224631460348BDE8F840FFF77EBFC4 +:10581000A0670020B0670020C0E90323002310B474 +:105820005DF8044B4361FFF7CFBF000010B5194C82 +:10583000236998420DD08168D0E9003213605A6024 +:105840009A680A449A60002303604FF0FF33A36113 +:1058500010BD0268234643F8102F536000220260F7 +:1058600022699A4203D1BDE8104001F0D5BB93688C +:1058700081680B44936001F0BFFB2269E169926883 +:10588000441AA242E4D91144BDE81040091AFFF7B6 +:1058900053BF00BFA06700202DE9F047DFF8BC80B0 +:1058A00008F110072C4ED8F8105001F0A5FBD8F8DD +:1058B0001C40AA68031B9A423ED814444FF00009CA +:1058C000D5E90032C8F81C4013605A60C5F8009052 +:1058D000D8F81030B34201D101F09EFB89F3118852 +:1058E000D5E9033128469847302383F311886B6943 +:1058F000002BD8D001F080FB6A69A0EB0409824636 +:105900004A450DD2022001F0D5FB0022D8F8103014 +:10591000B34208D151462846BDE8F047FFF728BFFB +:10592000121A2244F2E712EB09092946384638BF19 +:105930004A46FFF7EBFEB5E7D8F81030B34208D07F +:105940001444C8F81C00211AA960BDE8F047FFF70D +:10595000F3BEBDE8F08700BFB0670020A06700205D +:1059600000207047FEE70000704700004FF0FF3056 +:105970007047000002290CD0032904D001290748F0 +:1059800018BF00207047032A05D8054800EBC20065 +:105990007047044870470020704700BFD47A000861 +:1059A0004C220020887A000870B59AB00546084657 +:1059B000144601A900F0C2F801A8FCF783F9431CC2 +:1059C0000022C6B25B001046C5E9003423700323F1 +:1059D000023404F8013C01ABD1B202348E4201D84A +:1059E0001AB070BD13F8011B013204F8010C04F861 +:1059F000021CF1E708B5302383F311880348FFF751 +:105A000013FA002383F3118808BD00BF106A002039 +:105A100090F8803003F01F02012A07D190F881200E +:105A20000B2A03D10023C0E91D3315E003F0600306 +:105A3000202B08D1B0F884302BB990F88120212A8E +:105A400003D81F2A04D8FFF7D1B9222AEBD0FAE7EE +:105A5000034A426707228267C3670120704700BF7D +:105A60004322002007B5052917D8DFE801F01916F1 +:105A700003191920302383F31188104A0121019062 +:105A8000FFF77AFA019802210D4AFFF775FA0D48DF +:105A9000FFF796F9002383F3118803B05DF804FB48 +:105AA000302383F311880748FFF760F9F2E73023CA +:105AB00083F311880348FFF777F9EBE7287A0008AA +:105AC0004C7A0008106A002038B50C4D0C4C2A4660 +:105AD0000C4904F10800FFF767FF05F1CA0204F161 +:105AE00010000949FFF760FF05F5CA7204F11800BC +:105AF0000649BDE83840FFF757BF00BFE8820020E5 +:105B00004C220020087A0008127A00081D7A00084A +:105B100070B5044608460D46FCF7D4F8C6B22046D8 +:105B2000013403780BB9184670BD32462946FCF79C +:105B3000B5F80028F3D10120F6E700002DE9F04781 +:105B400005460C46FCF7BEF82B49C6B22846FFF7BF +:105B5000DFFF08B10A36F6B228492846FFF7D8FF1A +:105B600008B11036F6B2632E0BD8DFF88C80DFF860 +:105B70008C90234FDFF894A02E7846B92670BDE8AC +:105B8000F08729462046BDE8F04701F073BE252E78 +:105B90002ED1072241462846FCF780F870B9194BF0 +:105BA000224603F1100153F8040B8B4242F8040B18 +:105BB000F9D11B78073511341370DDE70822494607 +:105BC0002846FCF76BF898B9A21C0F4B19780232E3 +:105BD0000909C95D02F8041C13F8011B01F00F014B +:105BE0005345C95D02F8031CF0D118340835C3E7EA +:105BF000013504F8016BBFE7F47A00081D7A00084C +:105C0000FC7A00089278000800E8F11F0CE8F11F08 +:105C1000BFF34F8F044B1A695107FCD1D3F8102101 +:105C20005207F8D1704700BF0020005208B50D4B55 +:105C30001B78ABB9FFF7ECFF0B4BDA68D10704D543 +:105C40000A4A5A6002F188325A60D3F80C21D2070E +:105C500006D5064AC3F8042102F18832C3F80421AC +:105C600008BD00BF46850020002000522301674583 +:105C700008B5114B1B78F3B9104B1A69510703D5BE +:105C8000DA6842F04002DA60D3F81021520705D5F5 +:105C9000D3F80C2142F04002C3F80C21FFF7B8FF03 +:105CA000064BDA6842F00102DA60D3F80C2142F0C8 +:105CB0000102C3F80C2108BD4685002000200052D7 +:105CC0000F289ABF00F58060400400207047000054 +:105CD0004FF4003070470000102070470F2808B5BF +:105CE0000BD8FFF7EDFF00F500330268013204D155 +:105CF00004308342F9D1012008BD0020FCE70000F8 +:105D00000F2838B505463FD8FFF782FF1F4CFFF735 +:105D10008DFF4FF0FF3307286361C4F814311DD89D +:105D20002361FFF775FF030243F02403E360E36898 +:105D300043F08003E36023695A07FCD42846FFF749 +:105D400067FFFFF7BDFF4FF4003100F057F9284619 +:105D5000FFF78EFFBDE83840FFF7C0BFC4F8103131 +:105D6000FFF756FFA0F108031B0243F02403C4F819 +:105D70000C31D4F80C3143F08003C4F80C31D4F862 +:105D800010315B07FBD4D9E7002038BD002000525A +:105D90002DE9F84F05460C46104645EA0203DE069B +:105DA00002D00020BDE8F88F20F01F00DFF8BCB063 +:105DB000DFF8BCA0FFF73AFF04EB0008444503D12D +:105DC0000120FFF755FFEDE720222946204601F08C +:105DD0001FFD10B920352034F0E72B4605F12002D5 +:105DE0001F68791CDDD104339A42F9D105F178435B +:105DF0001B481C4EB3F5801F1B4B38BF184603F1E0 +:105E0000F80332BFD946D1461E46FFF701FF0760AF +:105E1000A5EB040C336804F11C0143F0020333606A +:105E2000231FD9F8007017F00507FAD153F8042F93 +:105E30008B424CF80320F4D1BFF34F8FFFF7E8FEFD +:105E40004FF0FF332022214603602846336823F0B9 +:105E50000203336001F0DCFC0028BBD03846B0E719 +:105E6000142100520C200052142000521020005225 +:105E70001021005210B5084C237828B11BB9FFF748 +:105E8000D5FE0123237010BD002BFCD02070BDE88F +:105E90001040FFF7EDBE00BF4685002038B5054D28 +:105EA00000240334696855F80C0B00F0B9F8122C83 +:105EB000F7D138BD107B0008084601F0A1BC0000F6 +:105EC00070B5104E82B0FFF789FB054601F094F8DB +:105ED000326803469042336037BF0B4A0A49516823 +:105EE000146836BF0131D1E90041516004192846D8 +:105EF00041F100010191FFF77BFB2046019902B0BF +:105F000070BD00BF488500205085002070B5124E3E +:105F100082B0FFF763FB054601F06EF83268034676 +:105F20009042336037BF0D4A0C495168146836BF40 +:105F30000131D1E9004151600419284641F10001C5 +:105F40000191FFF755FB4FF47A7200232046019927 +:105F5000FAF7CEF902B070BD4885002050850020C8 +:105F60000244074BD2B210B5904200D110BD441C80 +:105F700000B253F8200041F8040BE0B2F4E700BF90 +:105F8000504000580E4B30B51C6F240405D41C6FD4 +:105F90001C671C6F44F400441C670A4C02442368CD +:105FA000D2B243F480732360074B904200D130BDDE +:105FB000441C51F8045B00B243F82050E0B2F4E70F +:105FC00000440258004802585040005807B50122CA +:105FD00001A90020FFF7C4FF019803B05DF804FB9E +:105FE00013B50446FFF7F2FFA04205D0012201A934 +:105FF00000200194FFF7C6FF02B010BD0144BFF3BB +:106000004F8F064B884204D3BFF34F8FBFF36F8F80 +:106010007047C3F85C022030F4E700BF00ED00E0F9 +:106020000144BFF34F8F064B884204D3BFF34F8F19 +:10603000BFF36F8F7047C3F870022030F4E700BFE2 +:1060400000ED00E070470000074B45F255521A6022 +:1060500002225A6040F6FF729A604CF6CC421A60F7 +:106060000122024B1A707047004800585C850020DE +:10607000034B1B781BB1034B4AF6AA221A607047E8 +:106080005C85002000480058034B1A681AB9034A7F +:10609000D2F8D0241A60704758850020004002587A +:1060A000024B4FF48032C3F8D024704700400258AE +:1060B00008B5FFF7E9FF024B1868C0F3806008BD20 +:1060C0005885002070B5BFF34F8FBFF36F8F1A4A0A +:1060D0000021C2F85012BFF34F8FBFF36F8F536987 +:1060E00043F400335361BFF34F8FBFF36F8FC2F898 +:1060F0008410BFF34F8FD2F8803043F6E074C3F3BF +:10610000C900C3F34E335B0103EA0406014646EAC5 +:1061100081750139C2F86052F9D2203B13F1200F8A +:10612000F2D1BFF34F8F536943F480335361BFF310 +:106130004F8FBFF36F8F70BD00ED00E0FEE70000F2 +:10614000214B2248224A70B5904237D3214BC11EC1 +:10615000DA1C121A22F003028B4238BF00220021FF +:10616000FBF7B8FD1C4A0023C2F88430BFF34F8F01 +:10617000D2F8803043F6E074C3F3C900C3F34E3362 +:106180005B0103EA0406014646EA81750139C2F85B +:106190006C52F9D2203B13F1200FF2D1BFF34F8F95 +:1061A000BFF36F8FBFF34F8FBFF36F8F0023C2F822 +:1061B0005032BFF34F8FBFF36F8F70BD53F8041B86 +:1061C00040F8041BC0E700BFB07D00083087002006 +:1061D000308700203087002000ED00E0074BD3F827 +:1061E000D81021EA0001C3F8D810D3F8002122EA20 +:1061F0000002C3F80021D3F8003170470044025870 +:1062000070B5D0E9244300224FF0FF359E6804EBBF +:1062100042135101D3F80009002805DAD3F8000928 +:1062200040F08040C3F80009D3F8000B002805DADD +:10623000D3F8000B40F08040C3F8000B0132631824 +:106240009642C3F80859C3F8085BE0D24FF0011337 +:10625000C4F81C3870BD0000890141F020010161C3 +:1062600003699B06FCD41220FFF7D2B910B50A4C83 +:106270002046FEF75FFE094BC4F89030084BC4F887 +:106280009430084C2046FEF755FE074BC4F890307A +:10629000064BC4F8943010BD608500200000084013 +:1062A0007C7B0008FC85002000000440887B0008FF +:1062B00070B503780546012B5CD1434BD0F8904074 +:1062C000984258D1414B0E216520D3F8D82042F096 +:1062D0000062C3F8D820D3F8002142F00062C3F86E +:1062E0000021D3F80021D3F8802042F00062C3F8E7 +:1062F0008020D3F8802022F00062C3F88020D3F8F9 +:106300008030FEF793FA324BE360324BC4F800382A +:106310000023D5F89060C4F8003EC02323604FF4FA +:106320000413A3633369002BFCDA01230C203361CF +:10633000FFF76EF93369DB07FCD41220FFF768F929 +:106340003369002BFCDA00262846A660FFF758FFC9 +:106350006B68C4F81068DB68C4F81468C4F81C687B +:1063600083BB1D4BA3614FF0FF336361A36843F010 +:106370000103A36070BD194B9842C9D1134B4FF074 +:106380008060D3F8D82042F00072C3F8D820D3F848 +:10639000002142F00072C3F80021D3F80021D3F8A5 +:1063A000802042F00072C3F88020D3F8802022F0D1 +:1063B0000072C3F88020D3F88030FFF70FFF0E2162 +:1063C0004D209EE7064BCDE7608500200044025833 +:1063D0004014004003002002003C30C0FC85002037 +:1063E000083C30C0F8B5D0F89040054600214FF089 +:1063F00000662046FFF730FFD5F8941000234FF0D9 +:1064000001128F684FF0FF30C4F83438C4F81C28EC +:1064100004EB431201339F42C2F80069C2F8006BDB +:10642000C2F80809C2F8080BF2D20B68D5F8902020 +:10643000C5F89830636210231361166916F01006D0 +:10644000FBD11220FFF7E4F8D4F8003823F4FE6300 +:10645000C4F80038A36943F4402343F01003A36158 +:106460000923C4F81038C4F814380B4BEB604FF014 +:10647000C043C4F8103B094BC4F8003BC4F8106992 +:10648000C4F80039D5F8983003F1100243F48013B2 +:10649000C5F89820A362F8BD587B00084080001022 +:1064A000D0F8902090F88A10D2F8003823F4FE63D8 +:1064B00043EA0113C2F80038704700002DE9F843A1 +:1064C00000EB8103D0F890500C468046DA680FFA52 +:1064D00081F94801166806F00306731E022B05EBCE +:1064E00041134FF0000194BFB604384EC3F8101B9F +:1064F0004FF0010104F1100398BF06F1805601FA34 +:1065000003F3916998BF06F5004600293AD0578AEF +:1065100004F15801374349016F50D5F81C180B435B +:106520000021C5F81C382B180127C3F81019A74003 +:106530005369611E9BB3138A928B9B08012A88BF03 +:106540005343D8F89820981842EA034301F14002D7 +:106550002146C8F89800284605EB82025360FFF7F1 +:106560007BFE08EB8900C3681B8A43EA84534834E6 +:106570001E4364012E51D5F81C381F43C5F81C7802 +:10658000BDE8F88305EB4917D7F8001B21F400415B +:10659000C7F8001BD5F81C1821EA0303C0E704F173 +:1065A0003F030B4A2846214605EB83035A60FFF759 +:1065B00053FE05EB4910D0F8003923F40043C0F82E +:1065C0000039D5F81C3823EA0707D7E70080001008 +:1065D00000040002D0F894201268C0F89820FFF759 +:1065E0000FBE00005831D0F8903049015B5813F4C9 +:1065F000004004D013F4001F0CBF0220012070479C +:106600004831D0F8903049015B5813F4004004D071 +:1066100013F4001F0CBF02200120704700EB810122 +:10662000CB68196A0B6813604B68536070470000B1 +:1066300000EB810330B5DD68AA691368D36019B92E +:10664000402B84BF402313606B8A1468D0F89020DD +:106650001C4402EB4110013C09B2B4FBF3F4634368 +:10666000033323F0030343EAC44343F0C043C0F8B9 +:10667000103B2B6803F00303012B0ED1D2F808382E +:1066800002EB411013F4807FD0F8003B14BF43F0BD +:10669000805343F00053C0F8003B02EB4112D2F8A4 +:1066A000003B43F00443C2F8003B30BD2DE9F0410C +:1066B000D0F8906005460C4606EB4113D3F8087BF2 +:1066C0003A07C3F8087B08D5D6F814381B0704D559 +:1066D00000EB8103DB685B689847FA071FD5D6F8A3 +:1066E0001438DB071BD505EB8403D968CCB98B695B +:1066F000488A5A68B2FBF0F600FB16228AB918687D +:10670000DA6890420DD2121AC3E90024302383F3D1 +:10671000118821462846FFF78BFF84F31188BDE8D6 +:10672000F081012303FA04F26B8923EA02036B81EF +:10673000CB68002BF3D021462846BDE8F04118472E +:1067400000EB81034A0170B5DD68D0F890306C69C8 +:106750002668E66056BB1A444FF40020C2F81009C0 +:106760002A6802F00302012A0AB20ED1D3F80808FF +:1067700003EB421410F4807FD4F8000914BF40F0FA +:10678000805040F00050C4F8000903EB4212D2F8E8 +:10679000000940F00440C2F800090122D3F834088F +:1067A00002FA01F10143C3F8341870BD19B9402E43 +:1067B00084BF4020206020681A442E8A8419013C3E +:1067C000B4FBF6F440EAC44040F00050C6E70000D5 +:1067D0002DE9F843D0F8906005460C464F0106EBD2 +:1067E0004113D3F8088918F0010FC3F808891CD0A9 +:1067F000D6F81038DB0718D500EB8103D3F80CC0AE +:10680000DCF81430D3F800E0DA68964530D2A2EB19 +:106810000E024FF000091A60C3F80490302383F38E +:106820001188FFF78DFF89F3118818F0800F1DD0B4 +:10683000D6F834380126A640334217D005EB84033E +:106840000134D5F89050D3F80CC0E4B22F44DCF8F2 +:10685000142005EB0434D2F800E05168714514D3DC +:10686000D5F8343823EA0606C5F83468BDE8F8835D +:10687000012303FA01F2038923EA02030381DCF80E +:106880000830002BD1D09847CFE7AEEB0103BCF81E +:106890001000834228BF0346D7F8180980B2B3EB33 +:1068A000800FE3D89068A0F1040959F8048FC4F868 +:1068B0000080A0EB09089844B8F1040FF5D81844FB +:1068C0000B4490605360C8E72DE9F84FD0F8905022 +:1068D00004466E69AB691E4016F480586E6103D0A1 +:1068E000BDE8F84FFEF796BB002E12DAD5F8003E51 +:1068F0009B0705D0D5F8003E23F00303C5F8003E02 +:10690000D5F80438204623F00103C5F80438FEF713 +:10691000AFFB370505D52046FFF772FC2046FEF792 +:1069200095FBB0040CD5D5F8083813F0060FEB68CA +:1069300023F470530CBF43F4105343F4A053EB60A3 +:1069400031071BD56368DB681BB9AB6923F008030B +:10695000AB612378052B0CD1D5F8003E9A0705D002 +:10696000D5F8003E23F00303C5F8003E2046FEF7AD +:106970007FFB6368DB680BB120469847F30200F1A8 +:10698000BA80B70226D5D4F8909000274FF0010ABC +:1069900009EB4712D2F8003B03F44023B3F5802FF4 +:1069A00011D1D2F8003B002B0DDA62890AFA07F305 +:1069B00022EA0303638104EB8703DB68DB6813B11E +:1069C0003946204698470137D4F89430FFB29B6887 +:1069D0009F42DDD9F00619D5D4F89000026AC2F3BF +:1069E0000A1702F00F0302F4F012B2F5802F00F044 +:1069F000CA80B2F5402F09D104EB8303002200F5D1 +:106A00008050DB681B6A974240F0B0803003D5F8B5 +:106A1000185835D5E90303D500212046FFF746FE77 +:106A2000AA0303D501212046FFF740FE6B0303D5DF +:106A300002212046FFF73AFE2F0303D5032120460B +:106A4000FFF734FEE80203D504212046FFF72EFEAF +:106A5000A90203D505212046FFF728FE6A0203D5C7 +:106A600006212046FFF722FE2B0203D507212046F0 +:106A7000FFF71CFEEF0103D508212046FFF716FEA5 +:106A8000700340F1A780E90703D500212046FFF7F6 +:106A90009FFEAA0703D501212046FFF799FE6B0749 +:106AA00003D502212046FFF793FE2F0703D50321CC +:106AB0002046FFF78DFEEE0603D504212046FFF7A2 +:106AC00087FEA80603D505212046FFF781FE69064B +:106AD00003D506212046FFF77BFE2A0603D50721B2 +:106AE0002046FFF775FEEB0574D520460821BDE86A +:106AF000F84FFFF76DBED4F890904FF0000B4FF0B9 +:106B0000010AD4F894305FFA8BF79B689F423FF6F6 +:106B100038AF09EB4713D3F8002902F44022B2F54D +:106B2000802F20D1D3F80029002A1CDAD3F80029BD +:106B300042F09042C3F80029D3F80029002AFBDB79 +:106B40003946D4F89000FFF787FB22890AFA07F349 +:106B500022EA0303238104EB8703DB689B6813B1FC +:106B60003946204698470BF1010BCAE7910701D13E +:106B7000D0F80080072A02F101029CBF03F8018BC4 +:106B80004FEA18283FE704EB830300F58050DA68EA +:106B9000D2F818C0DCF80820DCE9001CA1EB0C0CD2 +:106BA00000218F4208D1DB689B699A683A449A6059 +:106BB0005A683A445A6029E711F0030F01D1D0F81E +:106BC00000808C4501F1010184BF02F8018B4FEA7E +:106BD0001828E6E7BDE8F88F08B50348FFF774FE0C +:106BE000BDE80840FDF7E6BC6085002008B5034815 +:106BF000FFF76AFEBDE80840FDF7DCBCFC8500201D +:106C0000D0F8903003EB4111D1F8003B43F400136E +:106C1000C1F8003B70470000D0F8903003EB411101 +:106C2000D1F8003943F40013C1F80039704700006F +:106C3000D0F8903003EB4111D1F8003B23F400135E +:106C4000C1F8003B70470000D0F8903003EB4111D1 +:106C5000D1F8003923F40013C1F80039704700005F +:106C600030B50433039C0172002104FB0325C1608D +:106C7000C0E90653049B0363059BC0E90000C0E91B +:106C80000422C0E90842C0E90A11436330BD000094 +:106C90000022416AC260C0E90411C0E90A226FF013 +:106CA0000101FEF725BD0000D0E90432934201D175 +:106CB000C2680AB9181D704700207047036919603F +:106CC0000021C2680132C260C269134482699342E2 +:106CD000036124BF436A0361FEF7FEBC38B5044676 +:106CE0000D46E3683BB162690020131D1268A36280 +:106CF0001344E36207E0237A33B929462046FEF7BE +:106D0000DBFC0028EDDA38BD6FF00100FBE7000086 +:106D1000C368C269013BC3604369134482699342FB +:106D2000436124BF436A436100238362036B03B161 +:106D30001847704770B53023044683F31188866A7C +:106D40003EB9FFF7CBFF054618B186F311882846F8 +:106D500070BDA36AE26A13F8015B9342A36202D397 +:106D60002046FFF7D5FF002383F31188EFE70000EB +:106D70002DE9F84F04460E46174698464FF0300965 +:106D800089F311880025AA46D4F828B0BBF1000F7A +:106D900009D141462046FFF7A1FF20B18BF31188AE +:106DA0002846BDE8F88FD4E90A12A7EB050B521A62 +:106DB000934528BF9346BBF1400F1BD9334601F1E1 +:106DC000400251F8040B914243F8040BF9D1A36A35 +:106DD000403640354033A362D4E90A239A4202D3B5 +:106DE0002046FFF795FF8AF31188BD42D8D289F378 +:106DF0001188C9E730465A46FAF746FFA36A5E444F +:106E00005D445B44A362E7E710B5029C0433017262 +:106E100003FB0421C460C0E906130023C0E90A3360 +:106E2000039B0363049BC0E90000C0E90422C0E99E +:106E30000842436310BD0000026A6FF00101C260A6 +:106E4000426AC0E904220022C0E90A22FEF750BCCF +:106E5000D0E904239A4201D1C26822B9184650F8F9 +:106E6000043B0B60704700231846FAE7C368002113 +:106E7000C2690133C3604369134482699342436129 +:106E800024BF436A4361FEF727BC000038B50446BF +:106E90000D46E3683BB1236900201A1DA262E26936 +:106EA0001344E36207E0237A33B929462046FEF70C +:106EB00003FC0028EDDA38BD6FF00100FBE70000AD +:106EC00003691960C268013AC260C26913448269E9 +:106ED0009342036124BF436A036100238362036B0F +:106EE00003B118477047000070B530230D460446C3 +:106EF000114683F31188866A2EB9FFF7C7FF10B1D8 +:106F000086F3118870BDA36A1D70A36AE26A01331B +:106F10009342A36204D3E16920460439FFF7D0FF0E +:106F2000002080F31188EDE72DE9F84F04460D4667 +:106F3000904699464FF0300A8AF311880026B346EE +:106F4000A76A4FB949462046FFF7A0FF20B187F353 +:106F500011883046BDE8F88FD4E90A073A1AA8EB41 +:106F60000607974228BF1746402F1BD905F140035B +:106F700055F8042B9D4240F8042BF9D1A36A403602 +:106F80004033A362D4E90A239A4204D3E16920463C +:106F90000439FFF795FF8BF311884645D9D28AF360 +:106FA0001188CDE729463A46FAF76EFEA36A3D44BA +:106FB0003E443B44A362E5E7D0E904239A4217D15B +:106FC000C3689BB1836A8BB1043B9B1A0ED01360DC +:106FD000C368013BC360C3691A4483699A42026172 +:106FE00024BF436A0361002383620123184670476C +:106FF0000023FBE700F024B9014B586A704700BF3B +:10700000000C0040034B002258631A610222DA6030 +:10701000704700BF000C0040014B0022DA6070474F +:10702000000C0040014B5863704700BF000C00404B +:10703000FEE7000070B51B4B0025044686B0586083 +:107040000E4685620163FDF78DFA04F11003A56019 +:10705000E562C4E904334FF0FF33C4E90044C4E9F6 +:107060000635FFF7C9FF2B46024604F134012046DE +:10707000C4E9082380230C4A2565FEF7D3FA0123CF +:107080000A4AE06000920375684672680192B2682D +:10709000CDE90223064BCDE90435FEF7EBFA06B045 +:1070A00070BD00BF086A0020947B0008997B00082F +:1070B00031700008024AD36A1843D062704700BF9B +:1070C000A06700204B6843608B688360CB68C36017 +:1070D0000B6943614B6903628B6943620B68036010 +:1070E0007047000008B53C4B40F2FF713B48D3F8B5 +:1070F00088200A43C3F88820D3F8882022F4FF624E +:1071000022F00702C3F88820D3F88820D3F8E020C3 +:107110000A43C3F8E020D3F808210A43C3F8082142 +:107120002F4AD3F808311146FFF7CCFF00F58060F5 +:1071300002F11C01FFF7C6FF00F5806002F1380183 +:10714000FFF7C0FF00F5806002F15401FFF7BAFFBE +:1071500000F5806002F17001FFF7B4FF00F5806078 +:1071600002F18C01FFF7AEFF00F5806002F1A8018B +:10717000FFF7A8FF00F5806002F1C401FFF7A2FF4E +:1071800000F5806002F1E001FFF79CFF00F58060F0 +:1071900002F1FC01FFF796FF02F58C7100F58060AB +:1071A000FFF790FF00F014F90E4BD3F8902242F055 +:1071B0000102C3F89022D3F8942242F00102C3F8EE +:1071C00094220522C3F898204FF06052C3F89C2007 +:1071D000054AC3F8A02008BD004402580000025828 +:1071E000A07B000800ED00E01F00080308B500F0D8 +:1071F000D1FAFEF7CBF90F4BD3F8DC2042F0400276 +:10720000C3F8DC20D3F8042122F04002C3F80421A3 +:10721000D3F80431084B1A6842F008021A601A6861 +:1072200042F004021A60FEF72FFFBDE80840FEF7A7 +:107230004BBC00BF004402580018024870470000D1 +:10724000114BD3F8E82042F00802C3F8E820D3F845 +:10725000102142F00802C3F810210C4AD3F8103173 +:10726000D36B43F00803D363C722094B9A624FF0F4 +:10727000FF32DA6200229A615A63DA605A600122B0 +:107280005A611A60704700BF004402580010005C49 +:10729000000C0040094A08B51169D3680B40D9B207 +:1072A0009B076FEA0101116107D5302383F3118831 +:1072B000FEF792F9002383F3118808BD000C00400B +:1072C000064BD3F8DC200243C3F8DC20D3F80421BA +:1072D0001043C3F80401D3F8043170470044025846 +:1072E0003A4B4FF0FF31D3F8802062F00042C3F8F0 +:1072F0008020D3F8802002F00042C3F88020D3F829 +:107300008020D3F88420C3F88410D3F8842000228E +:10731000C3F88420D3F88400D86F40F0FF4040F4D5 +:10732000FF0040F4DF4040F07F00D867D86F20F0C6 +:10733000FF4020F4FF0020F4DF4020F07F00D867FA +:10734000D86FD3F888006FEA40506FEA5050C3F806 +:107350008800D3F88800C0F30A00C3F88800D3F887 +:107360008800D3F89000C3F89010D3F89000C3F8C9 +:107370009020D3F89000D3F89400C3F89410D3F879 +:107380009400C3F89420D3F89400D3F89800C3F87D +:107390009810D3F89800C3F89820D3F89800D3F841 +:1073A0008C00C3F88C10D3F88C00C3F88C20D3F871 +:1073B0008C00D3F89C00C3F89C10D3F89C10C3F841 +:1073C0009C20D3F89C3000F0B9B900BF00440258AB +:1073D00008B50122534BC3F80821534BD3F8F420CE +:1073E00042F00202C3F8F420D3F81C2142F002025A +:1073F000C3F81C210222D3F81C314C4BDA605A68C6 +:107400009104FCD54A4A1A6001229A60494ADA601E +:1074100000221A614FF440429A61444B9A699204E7 +:10742000FCD51A6842F480721A603F4B1A6F12F44E +:10743000407F04D04FF480321A6700221A671A681E +:1074400042F001021A60384B1A685007FCD500223E +:107450001A611A6912F03802FBD1012119604FF04C +:10746000804159605A67344ADA62344A1A611A68AC +:1074700042F480321A602C4B1A689103FCD51A68CA +:1074800042F480521A601A689204FCD52C4A2D49A5 +:107490009A6200225A63196301F57C01DA6301F5EF +:1074A000E77199635A64284A1A64284ADA621A68AA +:1074B00042F0A8521A601C4B1A6802F02852B2F12E +:1074C000285FF9D148229A614FF48862DA6140223C +:1074D0001A621F4ADA641F4A1A651F4A5A651F4A10 +:1074E0009A6532231E4A1360136803F00F03022BC0 +:1074F000FAD10D4A136943F003031361136903F0D2 +:107500003803182BFAD14FF00050FFF7D9FE4FF097 +:107510008040FFF7D5FE4FF00040BDE80840FFF780 +:10752000CFBE00BF008000510044025800480258FE +:1075300000C000F0020000010000FF010088900878 +:107540003220600063020901470E0508DD0BBF0110 +:1075500020000020000001100910E00000010110CF +:10756000002000524FF0B04208B5D2F8883003F046 +:107570000103C2F8883023B1044A13680BB1506884 +:107580009847BDE80840FDF715B800BFB086002059 +:107590004FF0B04208B5D2F8883003F00203C2F8C9 +:1075A000883023B1044A93680BB1D0689847BDE88E +:1075B0000840FCF7FFBF00BFB08600204FF0B0428C +:1075C00008B5D2F8883003F00403C2F8883023B13C +:1075D000044A13690BB150699847BDE80840FCF7AD +:1075E000E9BF00BFB08600204FF0B04208B5D2F826 +:1075F000883003F00803C2F8883023B1044A936945 +:107600000BB1D0699847BDE80840FCF7D3BF00BF75 +:10761000B08600204FF0B04208B5D2F8883003F0B1 +:107620001003C2F8883023B1044A136A0BB1506AC0 +:107630009847BDE80840FCF7BDBF00BFB0860020FA +:107640004FF0B04310B5D3F8884004F47872C3F813 +:107650008820A30604D5124A936A0BB1D06A9847D2 +:10766000600604D50E4A136B0BB1506B9847210688 +:1076700004D50B4A936B0BB1D06B9847E20504D548 +:10768000074A136C0BB1506C9847A30504D5044A04 +:10769000936C0BB1D06C9847BDE81040FCF78ABFE3 +:1076A000B08600204FF0B04310B5D3F8884004F402 +:1076B0007C42C3F88820620504D5164A136D0BB1CD +:1076C000506D9847230504D5124A936D0BB1D06DC8 +:1076D0009847E00404D50F4A136E0BB1506E9847DB +:1076E000A10404D50B4A936E0BB1D06E9847620487 +:1076F00004D5084A136F0BB1506F9847230404D583 +:10770000044A936F0BB1D06F9847BDE81040FCF767 +:1077100051BF00BFB086002008B50348FDF700F850 +:10772000BDE80840FCF746BF3463002008B5FFF70A +:10773000B1FDBDE80840FCF73DBF0000062108B5DB +:107740000846FDF773F806210720FDF76FF80621BC +:107750000820FDF76BF806210920FDF767F80621E0 +:107760000A20FDF763F806211720FDF75FF80621D0 +:107770002820FDF75BF809217A20FDF757F807214B +:107780003220FDF753F80C215220BDE80840FDF7E8 +:107790004DB8000008B5FFF7A3FD00F00DF8FDF7A8 +:1077A000EDF9FDF7C5FBFDF797FAFFF747FDBDE8DB +:1077B0000840FFF71FBC00000023054A19460133AB +:1077C000102BC2E9001102F10802F8D1704700BF86 +:1077D000B08600200B460146184600F003B80000B2 +:1077E00000F00EB810B5054C13462CB10A46014600 +:1077F0000220AFF3008010BD2046FCE7000000002F +:10780000024B01461868FEF757BB00BF6C220020F0 +:1078100010B501390244904201D1002005E00378FF +:1078200011F8014FA34201D0181B10BD0130F2E73F +:107830002DE9F041A3B1C91A17780144044603F1B8 +:10784000FF3C8C42204601D9002009E00578BD426A +:1078500004F10104F5D10CEB0405D618A54201D1C1 +:10786000BDE8F08115F8018D16F801EDF045F5D071 +:10787000E7E70000034611F8012B03F8012B002A6B +:10788000F9D170476F72672E6172647570696C6FA1 +:10789000742E437562654F72616E67652D706572F7 +:1078A0006970680053544D333248373F3F3F0053AF +:1078B000544D3332483733782F3732780053544D94 +:1078C0003332483734332F3735332F3735300000D4 +:1078D00001105A00031059000120580003205600DF +:1078E00040A2E4F1646891060041A3E5F265699263 +:1078F0000700000043414E464449666163653A20F3 +:107900004D6573736167652052414D204F766572F6 +:10791000666C6F77210000004261642043414E494C +:107920006661636520696E6465782E000001000061 +:107930000001FF0000A0004000A400400000000083 +:1079400000000000DD2C0008B525000811340008F7 +:10795000AD25000825260008352A00089D270008C7 +:10796000ED250008F1250008C9250008B12500080B +:10797000F5290008D525000879350008E12500081B +:10798000C929000800960000000000000000000067 +:1079900000000000000000000000000000000000E7 +:1079A0003D4B0008294B0008654B0008514B00086F +:1079B0005D4B0008494B0008354B0008214B00087F +:1079C000714B000800000000554C0008414C0008B5 +:1079D0007D4C0008694C0008754C0008614C00089B +:1079E0004D4C0008394C0008894C0008000000008C +:1079F000010000000000000063300000F87900087A +:107A0000F8670020086A00204172647550696C6F45 +:107A1000740025424F415244252D424C00255345C8 +:107A20005249414C25000000020000000000000007 +:107A3000754E0008E54E000840004000B882002066 +:107A4000C8820020020000000000000003000000C7 +:107A5000000000002D4F0008000000001000000092 +:107A6000D88200200000000001000000000000009B +:107A70006085002001010200655A00087559000860 +:107A8000115A0008F559000843000000907A0008D8 +:107A900009024300020100C0320904000001020291 +:107AA0000100052400100105240100010424020244 +:107AB0000524060001070582030800FF09040100F0 +:107AC000020A0000000705010240000007058102CC +:107AD0004000000012000000DC7A000812011001D2 +:107AE0000200004009124157000201020301000098 +:107AF0000403090425424F415244250030313233FA +:107B00003435363738394142434445460000000099 +:107B10000000002000000200020000000001003010 +:107B20000000000008000000000000240000080021 +:107B3000040000000004000000FC0000020000003F +:107B40000000043000800000080000000000003841 +:107B50000000010001000000000000008950000842 +:107B600041530008ED530008400040009886002073 +:107B70009886002001000000A886002080000000F8 +:107B8000400100000800000000010000001000009B +:107B9000080000006D61696E0069646C650000009A +:107BA0000000802A00000000AAAAAAAA000000245F +:107BB000FFFF00000000000000A00A0000210002FA +:107BC00000000000AAAAAAAA00000000FFFF00000F +:107BD000000000090000090014000054000000002B +:107BE000AAAAAAAA14000054FFFF00000000000087 +:107BF000000000000A40100000000000AAAA8AAAA3 +:107C000000401000FFFF000099000000000000008D +:107C10000081020000000000AAAAAAAA00410100F7 +:107C2000FFFF0000000000700700000000000000DF +:107C300000000000AAAAAAAA00000000FFFF00009E +:107C40000000000000000000000000000000000034 +:107C5000AAAAAAAA00000000FFFF0000000000007E +:107C6000000000000000000000000000AAAAAAAA6C +:107C700000000000FFFF0000000000000000000006 +:107C80000000000000000000AAAAAAAA000000004C +:107C9000FFFF0000000000000000000000000000E6 +:107CA00000000000AAAAAAAA00000000FFFF00002E +:107CB00000000000000000000000000000000000C4 +:107CC000AAAAAAAA00000000FFFF0000000000000E +:107CD000000000004C86FF7F010000000000000053 +:107CE000780500000000000000001E0000000000F9 +:107CF000FE2A0100D2040000FF000000106A0020EC +:107D00003463002000000000A47800088304000011 +:107D1000AF78000850040000BD780008009600000D +:107D200000000800960000000008000004000000A9 +:107D3000F07A0008000000000000000000000000D1 +:107D40000000000000000000000000007022002081 +:107D50000000000000000000000000000000000023 +:107D60000000000000000000000000000000000013 +:107D70000000000000000000000000000000000003 +:107D800000000000000000000000000000000000F3 +:107D900000000000000000000000000000000000E3 +:107DA00000000000000000000000000000000000D3 :00000001FF diff --git a/Tools/bootloaders/CubeOrangePlus_bl.bin b/Tools/bootloaders/CubeOrangePlus_bl.bin index 22cee0be3a7bc9..93755be351bb07 100755 Binary files a/Tools/bootloaders/CubeOrangePlus_bl.bin and b/Tools/bootloaders/CubeOrangePlus_bl.bin differ diff --git a/Tools/bootloaders/CubeOrangePlus_bl.elf b/Tools/bootloaders/CubeOrangePlus_bl.elf index 34a0a2b4a1820b..262cba9f89baec 100755 Binary files a/Tools/bootloaders/CubeOrangePlus_bl.elf and b/Tools/bootloaders/CubeOrangePlus_bl.elf differ diff --git a/Tools/bootloaders/CubeOrangePlus_bl.hex b/Tools/bootloaders/CubeOrangePlus_bl.hex index a01ab8adc35d70..07d3f9ad04bb78 100644 --- a/Tools/bootloaders/CubeOrangePlus_bl.hex +++ b/Tools/bootloaders/CubeOrangePlus_bl.hex @@ -1,1105 +1,2420 @@ :020000040800F2 -:1000000000060020A1020008FD0F00087D0F000877 -:10001000D50F00087D0F0008A90F0008A3020008F3 -:10002000A3020008A3020008A3020008DD290008BB -:10003000A3020008A3020008A3020008A30200080C -:10004000A3020008A3020008A3020008A3020008FC -:10005000A3020008A3020008653E0008913E0008C4 -:10006000BD3E0008E93E0008153F0008A302000855 -:10007000A3020008A3020008A3020008A3020008CC -:10008000A3020008A3020008A3020008A3020008BC -:10009000A3020008A3020008A3020008413F0008D1 -:1000A000A3020008A3020008A3020008A30200089C -:1000B000A3020008A3020008A3020008A30200088C -:1000C000A3020008A3020008A3020008A30200087C -:1000D000A3020008A3020008194000082D400008F0 -:1000E000A53F0008A3020008A3020008A30200081D -:1000F000A3020008A3020008A3020008A30200084C -:10010000A3020008A302000855400008A30200084B -:10011000A3020008A3020008A3020008A30200082B -:10012000A3020008A3020008A3020008A30200081B -:10013000A3020008A3020008A3020008A30200080B -:10014000A3020008A3020008A3020008A3020008FB -:10015000A3020008A3020008A3020008A3020008EB -:10016000A3020008A3020008A3020008A3020008DB -:10017000A302000849350008A3020008A3020008F2 -:10018000A3020008A302000841400008A3020008DF -:10019000A3020008A3020008A3020008A3020008AB -:1001A000A3020008A3020008A3020008A30200089B -:1001B000A3020008A3020008A3020008A30200088B -:1001C000A3020008A3020008A3020008A30200087B -:1001D000A302000835350008A3020008A3020008A6 -:1001E000A3020008A3020008A3020008A30200085B -:1001F000A3020008A3020008A3020008A30200084B -:10020000A3020008A3020008A3020008A30200083A -:10021000A3020008A3020008A3020008A30200082A -:10022000A3020008A3020008A3020008A30200081A -:10023000A3020008A3020008A3020008A30200080A -:10024000A3020008A3020008A3020008A3020008FA -:10025000A3020008A3020008A3020008A3020008EA -:10026000A3020008A3020008A3020008A3020008DA -:10027000A3020008A3020008A3020008A3020008CA -:10028000A3020008A3020008A3020008A3020008BA -:10029000A3020008A3020008A3020008A3020008AA -:1002A00002E000F000F8FEE772B63A4880F30888F2 -:1002B000394880F3098839484EF60851CEF20001DA -:1002C000086040F20000CCF200004EF63471CEF22D -:1002D00000010860BFF34F8FBFF36F8F40F2000043 -:1002E000C0F2F0004EF68851CEF200010860BFF374 -:1002F0004F8FBFF36F8F4FF00000E1EE100A4EF604 -:100300003C71CEF200010860062080F31488BFF330 -:100310006F8F02F021FC02F0C3FB03F05DFB4FF096 -:1003200055301F491B4A91423CBF41F8040BFAE784 -:100330001C49194A91423CBF41F8040BFAE71A499B -:100340001A4A1B4B9A423EBF51F8040B42F8040B69 -:10035000F8E700201749184A91423CBF41F8040BC6 -:10036000FAE702F0DBFB03F0BBFB144C144DAC428C -:1003700003DA54F8041B8847F9E700F041F8114C00 -:10038000114DAC4203DA54F8041B8847F9E702F038 -:10039000C3BB00000006002000220020000000086F -:1003A00000000020000600209044000800220020E9 -:1003B0005C22002060220020D44F0020A002000810 -:1003C000A0020008A0020008A00200082DE9F04FDA -:1003D0002DED108AC1F80CD0D0F80CD0BDEC108AED -:1003E000BDE8F08F002383F311882846A047002042 -:1003F00001F0DAFEFEE701F055FE00DFFEE7000047 -:1004000038B500F0D7FC30B1164B00220E211A721D -:100410005A729972DA7202F0A1FA054602F0D4FA21 -:100420000446D0B9104B9D4219D001339D4241F290 -:10043000883512BF044600250124002002F098FAF6 -:100440000CB100F059F800F039FD00F0F9FB284636 -:1004500000F004F900F050F8F9E70025EDE7054653 -:10046000EBE700BF00220020010007B008B500F054 -:10047000B3FBA0F120035842584108BD07B541F233 -:100480001203022101A8ADF8043000F0C3FB03B051 -:100490005DF804FB202310B583F311881248C3686C -:1004A0000BB101F007FF0023104A4FF47A710E4898 -:1004B00001F0C4FE002383F311880D4C236813B1AF -:1004C0002368013B2360636813B16368013B636089 -:1004D000084B1B7833B9636823B9022000F070FC25 -:1004E0003223636010BD00BF602200209504000825 -:1004F0007C23002074220020F8B5514B514A1C4641 -:100500001968013100F09B8004339342F8D162688E -:100510004D4B9A4240F293804C4B9B6803F1006331 -:1005200003F500339A4280F08A80002000F0A2FB9D -:100530000220474B187000F041FC464B0021D3F8D5 -:10054000E820C3F8E810D3F81021C3F81011D3F84D -:100550001021D3F8EC20C3F8EC10D3F81421C3F821 -:100560001411D3F81421D3F8F020C3F8F010D3F805 -:100570001821C3F81811D3F81821D3F8802042F0BD -:100580000062C3F88020D3F8802022F00062C3F814 -:100590008020D3F88020D3F8802042F00072C3F886 -:1005A0008020D3F8802022F00072C3F88020D3F896 -:1005B000803072B64FF0E023C3F8084DD4E9000450 -:1005C000BFF34F8FBFF36F8F234AC2F88410BFF37E -:1005D0004F8F536923F480335361BFF34F8FD2F8A9 -:1005E000803043F6E076C3F3C905C3F34E335B01B5 -:1005F00003EA060C29464CEA81770139C2F8747285 -:10060000F9D2203B13F1200FF2D1BFF34F8FBFF38C -:100610006F8FBFF34F8FBFF36F8F536923F4003396 -:1006200053610023C2F85032BFF34F8FBFF36F8F77 -:10063000202383F31188854680F308882047F8BD7E -:100640000000020820000208FFFF0108002200202D -:10065000742200200044025800ED00E02DE9F04F24 -:1006600093B0A94B2022FF2100900AA89D6800F0BA -:10067000CFFBA64A1378A3B90121A5481170C36026 -:10068000202383F31188C3680BB101F013FE00230C -:10069000A04A4FF47A719E4801F0D0FD002383F305 -:1006A0001188009B9C4A03B1136000239B49009C66 -:1006B00098469B461E469A460B705360012000F0F8 -:1006C0007DFB24B1944B1B68002B00F016820020A8 -:1006D00000F082FA0390039B002BF2DB012000F074 -:1006E0006BFB039B213B162BE8D801A252F823F0A9 -:1006F0004D0700087507000809080008BD06000836 -:10070000BD060008BD0600089D0800086F0A000825 -:1007100089090008EB090008130A0008390A0008D3 -:10072000BD0600084B0A0008BD060008BD0A000807 -:10073000ED070008BD060008010B00085907000876 -:10074000ED070008BD060008EB0900080220FFF7CE -:100750008DFE002840F0FB81009B022105A8B8F126 -:10076000000F08BF1C4641F21233ADF8143000F000 -:1007700051FAA3E74FF47A7000F02EFA071EEBDB74 -:100780000220FFF773FE0028E6D0013F052F00F29C -:10079000E081DFE807F0030A0D101336052304217A -:1007A00005A8059300F036FA17E004215648F9E74A -:1007B00004215B48F6E704215A48F3E74FF01C098F -:1007C000484609F1040900F057FA0421059005A8EC -:1007D00000F020FAB9F12C0FF2D101204FF0000AFD -:1007E00000FA07F747EA0B0B5FFA8BFB00F05CFBA4 -:1007F00026B10BF00B030B2B08BF0024FFF73EFEC6 -:100800005CE704214848CDE7002EA5D00BF00B0390 -:100810000B2BA1D10220FFF729FE074600289BD011 -:1008200001203E4E00F026FA4FF000080220307002 -:1008300000F0C4FA5FFA88F9484600F02BFA044643 -:1008400090B1484608F1010800F034FA0028F1D1CF -:10085000B846044641F21213022105A83E46ADF8FF -:10086000143000F0D7F929E7012325460220337020 -:1008700000F0A2FA244B9B68AB4207D9284600F04F -:10088000FBF9013040F068810435F3E70025234B84 -:10089000B8463E461D70204B5D60A7E7002E3FF432 -:1008A0005BAF0BF00B030B2B7FF456AF02201B4BFF -:1008B000187000F083FA322000F08EF9B0F10009D0 -:1008C000FFF64AAF19F003077FF446AF0E4A09EB73 -:1008D0000503926893423FF63FAFB9F5807F3FF73B -:1008E0003BAF124BB945019322DD4FF47A7000F013 -:1008F00073F90390039A002AFFF62EAF039A01378B -:10090000019B03F8012BEDE7002200207823002053 -:1009100060220020950400087C230020742200201F -:1009200004220020082200200C220020782200202F -:10093000C820FFF79BFD074600283FF40DAF1F2D91 -:1009400011D8C5F120020AAB25F0030084494A45BD -:10095000184428BF4A46019200F034FA019AFF2158 -:100960007F4800F055FA4FEAA903C9F387027C4992 -:100970002846019300F054FA064600283FF46AAF77 -:10098000019B05EB830531E70220FFF76FFD00288F -:100990003FF4E2AE00F0AAF900283FF4DDAE0027F4 -:1009A000B946704B9B68BB4218D91F2F11D80A9BC0 -:1009B00001330ED027F0030312AA134453F8203C4E -:1009C00005934846042205A9043700F019FB814627 -:1009D000E7E7384600F050F90590F2E7CDF81490BB -:1009E000042105A800F016F900E70023642104A8FB -:1009F000049300F005F900287FF4AEAE0220FFF763 -:100A000035FD00283FF4A8AE049800F065F9059084 -:100A1000E6E70023642104A8049300F0F1F800281D -:100A20007FF49AAE0220FFF721FD00283FF494AE38 -:100A3000049800F053F9EAE70220FFF717FD0028B9 -:100A40003FF48AAE00F062F9E1E70220FFF70EFD05 -:100A500000283FF481AE05A9142000F05DF9074697 -:100A60000421049004A800F0D5F83946B9E73220F3 -:100A700000F0B2F8071EFFF66FAEBB077FF46CAE56 -:100A8000384A07EB0A03926893423FF665AE0220AC -:100A9000FFF7ECFC00283FF45FAE27F00307574454 -:100AA000BA453FF4A3AE50460AF1040A00F0E4F858 -:100AB0000421059005A800F0ADF8F1E74FF47A7035 -:100AC000FFF7D4FC00283FF447AE00F00FF90028F0 -:100AD00044D00A9B01330BD008220AA9002000F061 -:100AE0009FF900283AD02022FF210AA800F090F9AF -:100AF000FFF7C4FC1C4801F05DFB13B0BDE8F08FAC -:100B0000002E3FF429AE0BF00B030B2B7FF424AE29 -:100B10000023642105A8059300F072F80746002819 -:100B20007FF41AAE0220FFF7A1FC814600283FF4B3 -:100B300013AEFFF7A3FC41F2883001F03BFB0598B0 -:100B400000F0FCF94E463C4600F0AEF9B6E506462C -:100B50004CE64FF0000AFFE5B8467BE6374679E6FB -:100B60007822002000220020A08601002DE9F84F05 -:100B70004FF47A7306460D46002402FB03F7DFF8B4 -:100B80005080DFF8509098F900305FFA84FA5A1CD0 -:100B900001D0A34210D159F824002A4631460368F7 -:100BA000D3F820B03B46D847854205D1074B0120FA -:100BB00083F800A0BDE8F88F0134042CE3D14FF492 -:100BC000FA7001F0F7FA0020F4E700BFC823002014 -:100BD0001022002058410008002307B502460121D9 -:100BE0000DF107008DF80730FFF7C0FF20B19DF829 -:100BF000070003B05DF804FB4FF0FF30F9E7000099 -:100C00000A46042108B5FFF7B1FF80F00100C0B229 -:100C1000404208BD074B0A4630B41978064B53F8DA -:100C20002140014623682046DD69044BAC4630BCB8 -:100C3000604700BFC823002058410008A08601007B -:100C400070B50A4E00240A4D01F060FD308028681E -:100C50003388834208D901F055FD2B6804440133E1 -:100C6000B4F5003F2B60F2D370BD00BFCA23002053 -:100C70008423002001F028BE00F1006000F5003060 -:100C80000068704700F10060920000F5003001F04C -:100C90009FBD0000054B1A68054B1B889B1A8342B9 -:100CA00002D9104401F02EBD00207047842300209B -:100CB000CA23002038B5074D04462868204401F0B7 -:100CC00027FD28B928682044BDE8384001F032BD2E -:100CD00038BD00BF842300200020704700F1FF5082 -:100CE00000F58F10D0F8000870470000064991F811 -:100CF000243033B100230822086A81F82430FFF73A -:100D0000C1BF0120704700BF88230020014B186835 -:100D1000704700BF0010005C244BF0B51A68044611 -:100D2000234BC2F30B06120C1F885868BE4293F97E -:100D3000085028D09F89BE4206D101200C2505FB12 -:100D40000033586893F9085041F201039A421CD0CD -:100D500041F203039A421AD042F201039A4218D098 -:100D600042F203039A4208BF5625621E0B46441EF8 -:100D70000A4493420FD214F9016F581C6EB1034616 -:100D800000F8016CF5E70020D8E75A25EDE7592572 -:100D9000EBE75825E9E7184605E02C2482421C7051 -:100DA00001D9981C5D70401AF0BD00BF0010005CB6 -:100DB0001422002000207047704700007047000098 -:100DC00070470000002310B5934203D0CC5CC4549C -:100DD0000133F9E710BD0000013810B510F9013FEB -:100DE0003BB191F900409C4203D11AB10131013A63 -:100DF000F4E71AB191F90020981A10BD1046FCE7EB -:100E000003460246D01A12F9011B0029FAD1704795 -:100E100002440346934202D003F8011BFAE77047ED -:100E20002DE9F8431F4D14460746884695F82420BF -:100E300052BBDFF870909CB395F824302BB9202278 -:100E4000FF2148462F62FFF7E3FF95F82400414653 -:100E5000C0F1080205EB8000A24228BF2246D6B2AC -:100E60009200FFF7AFFF95F82430A41B17441E44EF -:100E70009044E4B2F6B2082E85F82460DBD1FFF787 -:100E800035FF0028D7D108E02B6A03EB82038342A9 -:100E9000CFD0FFF72BFF0028CBD10020BDE8F8838F -:100EA0000120FBE788230020024B1A78024B1A70BE -:100EB000704700BFC823002010220020F8B5194C4D -:100EC000194800F079FC2146174800F0A1FC24687D -:100ED0001648D4F89020164ED2F80438154D43F039 -:100EE0000203114FC2F8043801F064F92046124998 -:100EF00000F09CFDD4F890200424D2F8043823F0AC -:100F00000203C2F804384FF4E133336055F8040BA0 -:100F1000B84202D0314600F0ADFB013C14F0FF04B2 -:100F2000F4D1F8BD70420008C832002040420F00E2 -:100F3000B0230020584100087842000838B50B4B18 -:100F400004461A780A4B53F822500A4B9D420CD0A3 -:100F5000094B002118221846FFF75AFF046001468A -:100F60002846BDE8384000F085BB38BDC8230020C6 -:100F700058410008C8320020B023002000B59BB0C3 -:100F8000EFF3098168226846FFF71CFFEFF3058342 -:100F9000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6AA5 -:100FA0009B6AFEE700ED00E000B59BB0EFF309811E -:100FB00068226846FFF706FFEFF30583044B9A6B40 -:100FC0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF64 -:100FD00000ED00E000B59BB0EFF3098168226846A0 -:100FE000FFF7F0FEEFF30583034B5A6B9A6A9A6A98 -:100FF0009A6A9A6A9B6AFEE700ED00E0FEE700004D -:1010000030B50A44084D91420DD011F8013B5840CB -:10101000082340F30004013B2C4013F0FF0384EA53 -:101020005000F6D1EFE730BD2083B8ED0268436889 -:101030001143016003B1184770470000024A13686A -:1010400043F0C0031360704700440040024A136835 -:1010500043F0C0031360704700480040024A136821 -:1010600043F0C003136070470078004037B5274C49 -:10107000274D204600F0F2FA04F1140000940023FA -:101080004FF40072234900F0B3F94FF40072224983 -:1010900004F138000094214B00F02CFA204BC4E9F5 -:1010A0001735204C204600F0D9FA04F114000094C2 -:1010B00000234FF400721C4900F09AF94FF40072BB -:1010C0001A4904F138000094194B00F013FA194B37 -:1010D000C4E91735184C204600F0C0FA04F114009A -:1010E00000234FF400721549009400F081F9144B6D -:1010F0004FF40072134904F13800009400F0FAF93B -:10110000114BC4E9173503B030BD00BFCC2300201C -:1011100000E1F50510250020102B00203D100008EF -:10112000004400403824002010270020102D00200B -:101130004D10000800480040A42400201029002081 -:101140005D100008102F002000780040037C30B5AF -:10115000334C002918BF0C46012B18D1314B984253 -:101160000FD1314BD3F8E82042F40032C3F8E82025 -:10117000D3F8102142F40032C3F81021D3F8103113 -:1011800005E02A4B98422FD0294B984238D022684C -:10119000036EC16D03EB52038466B3FBF2F3626826 -:1011A000150442BF23F0070503F0070343EA450394 -:1011B000CB60A36843F040034B60E36843F0010356 -:1011C0008B6042F4967343F001030B604FF0FF33E2 -:1011D0000B62510505D512F010221DD0B2F1805FCF -:1011E0001CD080F8643030BD0F4BD3F8E82042F4B7 -:1011F0008022C3F8E820D3F8102142F48022BBE714 -:10120000094BD3F8E82042F08042C3F8E820D3F835 -:10121000102142F08042AFE77F23E2E73F23E0E77F -:1012200068410008CC2300200044025838240020E4 -:10123000A42400202DE9F047C66D05463768F469FF -:101240002107346219D014F0080118BF8021E20789 -:1012500048BF41F02001A3074FF0200348BF41F0F1 -:101260004001600748BF41F4807183F31188281D55 -:10127000FFF7DCFE002383F31188E2050AD5202363 -:1012800083F311884FF40071281DFFF7CFFE002370 -:1012900083F311884FF020094FF0000A14F0200862 -:1012A00038D13B0616D54FF0200905F1380A200643 -:1012B00010D589F31188504600F050F9002836DA2D -:1012C0000821281DFFF7B2FE27F0800333600023BA -:1012D00083F31188790614D5620612D5202383F38F -:1012E0001188D5E913239A4208D12B6C33B127F02A -:1012F00040071021281DFFF799FE3760002383F374 -:101300001188E30618D5AA6E1369ABB15069BDE820 -:10131000F047184789F31188736A284695F86410D6 -:10132000194000F0B5F98AF31188F469B6E7B062A4 -:1013300088F31188F469BAE7BDE8F087F8B5154677 -:10134000826804460B46AA4200D28568A1692669D4 -:10135000761AB5420BD218462A46FFF733FDA36929 -:101360002B44A3612846A3685B1BA360F8BD0CD97E -:10137000AF1B18463246FFF725FD3A46E168304478 -:10138000FFF720FDE3683B44EBE718462A46FFF7EA -:1013900019FDE368E5E7000083689342F7B504466A -:1013A000154600D28568D4E90460361AB5420BD2DE -:1013B0002A46FFF707FD63692B4463612846A3684B -:1013C0005B1BA36003B0F0BD0DD93246AF1B01918A -:1013D000FFF7F8FC01993A46E0683144FFF7F2FC68 -:1013E000E3683B44E9E72A46FFF7ECFCE368E4E7FF -:1013F00010B50A440024C361029B8460C16002618D -:101400000362C0E90000C0E9051110BD08B5D0E9CC -:101410000532934201D1826882B9826801328260CA -:101420005A1C426119700021D0E904329A4224BF4B -:10143000C368436100F0DAFE002008BD4FF0FF30C2 -:10144000FBE7000070B5202304460E4683F31188A5 -:10145000A568A5B1A368A269013BA360531CA36161 -:1014600015782269934224BFE368A361E3690BB155 -:1014700020469847002383F31188284607E0314629 -:10148000204600F0A3FE0028E2DA85F3118870BD43 -:101490002DE9F74F04460E4617469846D0F81C90A3 -:1014A0004FF0200A8AF311884FF0000B154665B102 -:1014B0002A4631462046FFF741FF034660B94146C0 -:1014C000204600F083FE0028F1D0002383F311882A -:1014D000781B03B0BDE8F08FB9F1000F03D0019085 -:1014E0002046C847019B8BF31188ED1A1E448AF3EE -:1014F0001188DCE7C160C361009B82600362C0E9C0 -:1015000005111144C0E9000001617047F8B50446B7 -:101510000D461646202383F31188A768A7B1A36858 -:10152000013BA36063695A1C62611D70D4E90432F7 -:101530009A4224BFE3686361E3690BB12046984790 -:10154000002080F3118807E03146204600F03EFE7F -:101550000028E2DA87F31188F8BD0000D0E90523FE -:1015600010B59A4201D182687AB9826800210132AD -:1015700082605A1C82611C7803699A4224BFC36846 -:10158000836100F033FE204610BD4FF0FF30FBE7D3 -:101590002DE9F74F04460E4617469846D0F81C90A2 -:1015A0004FF0200A8AF311884FF0000B154665B101 -:1015B0002A4631462046FFF7EFFE034660B9414612 -:1015C000204600F003FE0028F1D0002383F31188A9 -:1015D000781B03B0BDE8F08FB9F1000F03D0019084 -:1015E0002046C847019B8BF31188ED1A1E448AF3ED -:1015F0001188DCE7026843681143016003B11847B2 -:10160000704700001430FFF743BF00004FF0FF3376 -:101610001430FFF73DBF00003830FFF7B9BF0000BE -:101620004FF0FF333830FFF7B3BF00001430FFF73F -:1016300009BF00004FF0FF311430FFF703BF000077 -:101640003830FFF763BF00004FF0FF323830FFF74C -:101650005DBF000000207047FFF708BD044B03602A -:1016600000234360C0E9023301230374704700BFC5 -:101670008041000810B52023044683F31188FFF74A -:1016800065FD02232374002383F3118810BD00003D -:1016900038B5C36904460D461BB904210844FFF759 -:1016A000A9FF294604F11400FFF7B0FE002806DA6E -:1016B000201D4FF48061BDE83840FFF79BBF38BD67 -:1016C000026843681143016003B118477047000086 -:1016D00013B5406B00F58054D4F8A4381A6811781B -:1016E000042914D1017C022911D11979012312890D -:1016F0008B4013420BD101A94C3002F06DF8D4F8A5 -:10170000A4480246019B2179206800F0DFF902B06D -:1017100010BD0000143001F0EFBF00004FF0FF33A8 -:10172000143001F0E9BF00004C3002F0C1B80000F5 -:101730004FF0FF334C3002F0BBB80000143001F022 -:10174000BDBF00004FF0FF31143001F0B7BF000003 -:101750004C3002F08DB800004FF0FF324C3002F0F8 -:1017600087B800000020704710B500F58054D4F809 -:10177000A4381A681178042917D1017C022914D1E0 -:101780005979012352898B4013420ED1143001F054 -:101790004FFF024648B1D4F8A4484FF44073617932 -:1017A0002068BDE8104000F07FB910BD406BFFF726 -:1017B000DBBF0000704700007FB5124B01250426F7 -:1017C000044603600023057400F184024360294647 -:1017D000C0E902330C4B0290143001934FF4407374 -:1017E000009601F001FF094B04F69442294604F1EA -:1017F0004C000294CDE900634FF4407301F0C8FF40 -:1018000004B070BDA8410008AD170008D11600084B -:101810000A68202383F311880B790B3342F82300E5 -:101820004B79133342F823008B7913B10B3342F811 -:10183000230000F58053C3F8A41802230374002387 -:1018400083F311887047000038B5037F044613B155 -:1018500090F85430ABB90125201D0221FFF730FF6D -:1018600004F114006FF00101257700F0CBFC04F1C6 -:101870004C0084F854506FF00101BDE8384000F08E -:10188000C1BC38BD10B5012104460430FFF718FF74 -:101890000023237784F8543010BD000038B5044687 -:1018A0000025143001F0B8FE04F14C00257701F05A -:1018B00087FF201D84F854500121FFF701FF2046C7 -:1018C000BDE83840FFF750BF90F8803003F0600368 -:1018D000202B06D190F881200023212A03D81F2A2B -:1018E00006D800207047222AFBD1C0E91D3303E04F -:1018F000034A426707228267C3670120704700BF1F -:101900002C22002037B500F58055D5F8A4381A6888 -:10191000117804291AD1017C022917D119790123E0 -:1019200012898B40134211D100F14C04204602F081 -:1019300007F858B101A9204601F04EFFD5F8A44898 -:101940000246019B2179206800F0C0F803B030BD49 -:1019500001F10B03F0B550F8236085B004460D4645 -:10196000FEB1202383F3118804EB8507301D082185 -:10197000FFF7A6FEFB6806F14C005B691B681BB114 -:10198000019001F037FF019803A901F025FF0246FD -:1019900048B1039B2946204600F098F8002383F3C2 -:1019A000118805B0F0BDFB685A691268002AF5D0AD -:1019B0001B8A013B1340F1D104F18002EAE70000E9 -:1019C000133138B550F82140ECB1202383F311884E -:1019D00004F58053D3F8A4281368527903EB8203EB -:1019E000DB689B695D6845B104216018FFF768FEFC -:1019F000294604F1140001F025FE2046FFF7B4FE4D -:101A0000002383F3118838BD7047000001F018B936 -:101A100001234022002110B5044600F8303BFFF7B7 -:101A2000F7F90023C4E9013310BD000010B52023ED -:101A3000044683F311882422416000210C30FFF713 -:101A4000E7F9204601F01EF902232370002383F3F7 -:101A5000118810BD70B500EB8103054650690E4634 -:101A60001446DA6018B110220021FFF7D1F9A069FD -:101A700018B110220021FFF7CBF931462846BDE806 -:101A8000704001F011BA000083682022002103F0A9 -:101A9000011310B5044683601030FFF7B9F92046F2 -:101AA000BDE8104001F08CBAF0B4012500EB8104D0 -:101AB00047898D40E4683D43A46945812360002344 -:101AC000A2606360F0BC01F0A9BA0000F0B4012587 -:101AD00000EB810407898D40E4683D43646905811A -:101AE00023600023A2606360F0BC01F01FBB000014 -:101AF00070B5022300250446242203702946C0F84D -:101B000088500C3040F8045CFFF782F9204684F8D6 -:101B1000705001F05DF963681B6823B129462046C7 -:101B2000BDE87040184770BD037880F88C300523FD -:101B3000037043681B6810B504460BB10421984735 -:101B40000023A36010BD000090F88C204368027051 -:101B50001B680BB1052118477047000070B590F85D -:101B60007030044613B1002380F8703004F1800215 -:101B7000204601F049FA63689B68B3B994F8803055 -:101B800013F0600535D00021204601F0F3FC002160 -:101B9000204601F0E3FC63681B6813B10621204670 -:101BA0009847062384F8703070BD20469847002877 -:101BB000E4D0B4F88630A26F9A4288BFA36794F944 -:101BC0008030A56F002B4FF0200380F20381002DA1 -:101BD00000F0F280092284F8702083F3118800213C -:101BE0002046D4E91D23FFF771FF002383F31188FA -:101BF000DAE794F8812003F07F0343EA022340F2FE -:101C00000232934200F0C58021D8B3F5807F48D0DE -:101C10000DD8012B3FD0022B00F09380002BB2D1C6 -:101C200004F1880262670222A267E367C1E7B3F5A5 -:101C3000817F00F09B80B3F5407FA4D194F882307F -:101C4000012BA0D1B4F8883043F0020332E0B3F5A1 -:101C5000006F4DD017D8B3F5A06F31D0A3F5C06396 -:101C6000012B90D86368204694F882205E6894F82F -:101C70008310B4F88430B047002884D04368636789 -:101C80000368A3671AE0B3F5106F36D040F602423E -:101C900093427FF478AF5C4B63670223A367002312 -:101CA000C3E794F88230012B7FF46DAFB4F888302D -:101CB00023F00203A4F88830C4E91D55E56778E7EE -:101CC000B4F88030B3F5A06F0ED194F8823020467E -:101CD00084F88A3001F0DAF863681B6813B10121D7 -:101CE00020469847032323700023C4E91D339CE753 -:101CF00004F18B0363670123C3E72378042B10D11E -:101D0000202383F311882046FFF7BEFE85F3118858 -:101D10000321636884F88B5021701B680BB1204647 -:101D2000984794F88230002BDED084F88B3004235F -:101D3000237063681B68002BD6D002212046984789 -:101D4000D2E794F8843020461D0603F00F010AD52F -:101D500001F04CF9012804D002287FF414AF2B4B7A -:101D60009AE72B4B98E701F033F9F3E794F88230C8 -:101D7000002B7FF408AF94F8843013F00F01B3D038 -:101D80001A06204602D501F00DFCADE701F0FEFB7E -:101D9000AAE794F88230002B7FF4F5AE94F88430F3 -:101DA00013F00F01A0D01B06204602D501F0E2FB84 -:101DB0009AE701F0D3FB97E7142284F8702083F3AD -:101DC00011882B462A4629462046FFF76DFE85F3EB -:101DD0001188E9E65DB1152284F8702083F311883B -:101DE00000212046D4E91D23FFF75EFEFDE60B220D -:101DF00084F8702083F311882B462A462946204612 -:101E0000FFF764FEE3E700BFD8410008D0410008B7 -:101E1000D441000838B590F870300446002B3ED00D -:101E2000063BDAB20F2A34D80F2B32D8DFE803F0A2 -:101E300037313108223231313131313131313737B7 -:101E4000856FB0F886309D4214D2C3681B8AB5FBFB -:101E5000F3F203FB12556DB9202383F311882B464F -:101E60002A462946FFF732FE85F311880A2384F8B3 -:101E700070300EE0142384F87030202383F311882F -:101E8000002320461A461946FFF70EFE002383F36F -:101E9000118838BDC36F03B198470023E7E70021DD -:101EA000204601F067FB0021204601F057FB6368E4 -:101EB0001B6813B10621204698470623D7E7000088 -:101EC00010B590F870300446142B29D017D8062B83 -:101ED00005D001D81BB110BD093B022BFBD8002156 -:101EE000204601F047FB0021204601F037FB6368E4 -:101EF0001B6813B1062120469847062319E0152BCD -:101F0000E9D10B2380F87030202383F3118800235C -:101F10001A461946FFF7DAFD002383F31188DAE742 -:101F2000C3689B695B68002BD5D1C36F03B1984729 -:101F3000002384F87030CEE7024B0022C3E900335F -:101F40009A60704710310020002382680374054BAB -:101F50001B6899689142FBD25A6803604260106026 -:101F6000586070471031002008B5202383F3118892 -:101F7000037C032B05D0042B0DD02BB983F31188E0 -:101F800008BD436900221A604FF0FF334361FFF739 -:101F9000DBFF0023F2E7D0E9003213605A60F3E779 -:101FA000002382680374054B1B6899689142FBD833 -:101FB0005A6803604260106058607047103100201A -:101FC000054B196908741868026853601A60186133 -:101FD00001230374FEF7FAB9103100204B1C30B511 -:101FE000044687B00A4D10D02B6901A8094A00F0B9 -:101FF00025F92046FFF7E4FF049B13B101A800F088 -:1020000059F92B69586907B030BDFFF7D9FFF8E7D8 -:1020100010310020691F000838B50C4D044641619D -:102020002B6981689A68914203D8BDE83840FFF770 -:102030008BBF1846FFF7B4FF01232C6101462374C0 -:102040002046BDE83840FEF7C1B900BF103100207E -:10205000044B1A681B6990689B68984294BF0020E3 -:10206000012070471031002010B5084C236820690A -:102070001A6854602260012223611A74FFF790FFEE -:1020800001462069BDE81040FEF7A0B910310020DC -:1020900008B5FFF7DDFF18B1BDE80840FFF7E4BF62 -:1020A00008BD0000FFF7E0BFFEE7000010B50C4CD4 -:1020B000FFF742FF00F0B4F880220A49204600F002 -:1020C0003BF8012344F8180C037400F097FC00233C -:1020D00083F3118862B60448BDE8104000F04CB8A4 -:1020E00038310020DC410008EC41000800F01CB948 -:1020F000EFF3118020B9EFF30583202282F31188DA -:102100007047000010B530B9EFF30584C4F308043C -:1021100014B180F3118810BDFFF7BAFF84F3118862 -:10212000F9E70000034A516853685B1A9842FBD8EC -:10213000704700BF001000E08260022202827047F8 -:102140008368A3F17C0243F80C2C026943F83C2C11 -:10215000426943F8382C074A43F81C2CC268A3F1A3 -:10216000180043F8102C022203F8082C002203F870 -:10217000072C7047E503000810B5202383F311886E -:10218000FFF7DEFF00210446FFF746FF002383F33D -:102190001188204610BD0000024B1B6958610F20BA -:1021A000FFF70EBF10310020202383F31188FFF7C3 -:1021B000F3BF000008B50146202383F311880820EF -:1021C000FFF70CFF002383F3118808BD49B1064BCC -:1021D00042681B6918605A60136043600420FFF76F -:1021E000FDBE4FF0FF307047103100200368984269 -:1021F00006D01A680260506018465961FFF7A4BE05 -:102200007047000038B504460D462068844200D16E -:1022100038BD036823605C604561FFF795FEF4E715 -:10222000054B4FF0FF3103F11402C3E905220022F0 -:10223000C3E90712704700BF1031002070B51C4E73 -:1022400005460C46C0E9032301F0B0FB334653F8C2 -:10225000142F9A420DD130620A2C2CBF00190A307B -:102260002A60C5E90124C6E90555BDE8704001F0C2 -:1022700087BB316A431AE31838BF1C469368A342F0 -:1022800002D9081901F08CFB73699A6894420CD842 -:102290005A68AC602B606A6015609A685D60121BBA -:1022A0009A604FF0FF33F36170BDA41A1B68ECE72E -:1022B0001031002038B51B4C636998420DD08168FD -:1022C000D0E9003213605A600022C2609A680A4462 -:1022D0009A604FF0FF33E36138BD03682246002166 -:1022E00042F8143F93425A60C16003D1BDE83840C0 -:1022F00001F050BB9A688168256A0A449A6001F02F -:1023000055FB6369411B9A688A42E5D9AB181D1ACF -:10231000206A092D98BF01F10A02BDE83840104437 -:1023200001F03EBB103100202DE9F041184C002790 -:1023300004F11406656901F039FB236AAA68C11A21 -:102340008A4215D81344D5F80C802362D5E90032AF -:1023500013605A606369EF60B34201D101F01AFB68 -:1023600087F311882869C047202383F31188E1E7A8 -:102370006169B14209D013441B1ABDE8F0410A2B30 -:102380002CBFC0180A3001F00BBBBDE8F08100BFC4 -:102390001031002000207047FEE700007047000069 -:1023A0004FF0FF307047000002290CD0032904D001 -:1023B0000129074818BF00207047032A05D805489F -:1023C00000EBC2007047044870470020704700BF10 -:1023D000D44200083C2200208842000870B59AB020 -:1023E00005460846144601A900F0C2F801A8FEF708 -:1023F00007FD431C0022C6B25B001046C5E900344D -:1024000023700323023404F8013C01ABD1B202343F -:102410008E4201D81AB070BD13F8011B013204F8C6 -:10242000010C04F8021CF1E708B5202383F311889E -:102430000348FFF767FA002383F3118808BD00BF44 -:10244000C832002090F8803003F01F02012A07D123 -:1024500090F881200B2A03D10023C0E91D3315E039 -:1024600003F06003202B08D1B0F884302BB990F82A -:102470008120212A03D81F2A04D8FFF725BA222A4F -:10248000EBD0FAE7034A426707228267C36701205D -:10249000704700BF3322002007B5052917D8DFE8B1 -:1024A00001F0191603191920202383F31188104A0B -:1024B00001210190FFF7CEFA019802210D4AFFF7A2 -:1024C000C9FA0D48FFF7EAF9002383F3118803B036 -:1024D0005DF804FB202383F311880748FFF7B4F964 -:1024E000F2E7202383F311880348FFF7CBF9EBE7EA -:1024F000284200084C420008C832002038B50C4D74 -:102500000C4C2A460C4904F10800FFF767FF05F15F -:10251000CA0204F110000949FFF760FF05F5CA720D -:1025200004F118000649BDE83840FFF757BF00BF67 -:10253000A04B00203C220020044200080E4200086C -:102540001D42000870B5044608460D46FEF758FCCB -:10255000C6B22046013403780BB9184670BD324626 -:102560002946FEF739FC0028F3D10120F6E70000E8 -:102570002DE9F04705460C46FEF742FC2B49C6B252 -:102580002846FFF7DFFF08B10736F6B2284928468C -:10259000FFF7D8FF08B11036F6B2632E0BD8DFF87C -:1025A0008C80DFF88C90234FDFF894A02E7846B90A -:1025B0002670BDE8F08729462046BDE8F04701F0C7 -:1025C000B5BD252E2ED1072241462846FEF704FC34 -:1025D00070B9194B224603F10C0153F8040B8B42DE -:1025E00042F8040BF9D11B8807350E341380DDE760 -:1025F000082249462846FEF7EFFB98B9A21C0F4B6C -:10260000197802320909C95D02F8041C13F8011B8C -:1026100001F00F015345C95D02F8031CF0D11834D5 -:102620000835C3E7013504F8016BBFE7F442000841 -:102630001D4200080B430008FC42000800E8F11F9F -:102640000CE8F11FBFF34F8F044B1A695107FCD1FF -:10265000D3F810215207F8D1704700BF0020005274 -:1026600008B50D4B1B78ABB9FFF7ECFF0B4BDA68E5 -:10267000D10704D50A4A5A6002F188325A60D3F869 -:102680000C21D20706D5064AC3F8042102F188328C -:10269000C3F8042108BD00BFFE4D002000200052F9 -:1026A0002301674508B5114B1B78F3B9104B1A6924 -:1026B000510703D5DA6842F04002DA60D3F81021FE -:1026C000520705D5D3F80C2142F04002C3F80C2183 -:1026D000FFF7B8FF064BDA6842F00102DA60D3F880 -:1026E0000C2142F00102C3F80C2108BDFE4D002070 -:1026F000002000520F289ABF00F58060400400209F -:10270000704700004FF40030704700001020704701 -:102710000F2808B50BD8FFF7EDFF00F5003302686E -:10272000013204D104308342F9D1012008BD0020D8 -:10273000FCE700000F2870B5054645D8FFF7D8FC28 -:10274000224CFFF77FFF0646FFF78AFF4FF0FF336B -:10275000072D6361C4F8143120D82361FFF772FF9D -:102760002B0243F02403E360E36843F08003E3605B -:1027700023695A07FCD42846FFF764FF4FF4003161 -:10278000FFF7B8FF00F002F93046FFF78BFFFFF7C5 -:10279000B9FC2846BDE87040FFF7BABFC4F8103155 -:1027A000FFF750FFA5F108031B0243F02403C4F810 -:1027B0000C31D4F80C3143F08003C4F80C31D4F858 -:1027C00010315B07FBD4D6E7002070BD002000521B -:1027D0002DE9F84F40EA020305460C461746D80695 -:1027E00002D00020BDE8F88F27F01F07DFF8D4B033 -:1027F000FFF736FF2744BC4203D10120FFF752FF09 -:10280000F0E720222946204601F080FC10B920354F -:102810002034F0E72B4605F120021E68711CE0D140 -:1028200004339A42F9D1FFF763FC05F17843234A58 -:10283000B3F5801F224B28BF9A4603F1040338BF2B -:102840009046A2F1080228BF9846A3F108033ABFB8 -:102850009146DA469946FFF7F5FEC8F80060A5EB09 -:10286000040CD9F8002004F11C0142F00202C9F85E -:102870000020221FDAF8006016F00506FAD152F89F -:10288000043F8A424CF80230F4D1BFF34F8FFFF778 -:10289000D9FE4FF0FF32C8F80020D9F8002022F00E -:1028A0000202C9F80020FFF72DFC2022214628460D -:1028B00001F02CFC0028AAD030469FE714200052DB -:1028C000102100521020005210B5084C237828B176 -:1028D0001BB9FFF7C5FE0123237010BD002BFCD0F0 -:1028E0002070BDE81040FFF7DDBE00BFFE4D0020A8 -:1028F0000244074BD2B210B5904200D110BD441C27 -:1029000000B253F8200041F8040BE0B2F4E700BF36 -:10291000504000580E4B30B51C6F240405D41C6F7A -:102920001C671C6F44F400441C670A4C0244236873 -:10293000D2B243F480732360074B904200D130BD84 -:10294000441C51F8045B00B243F82050E0B2F4E7B5 -:1029500000440258004802585040005807B5012270 -:1029600001A90020FFF7C4FF019803B05DF804FB44 -:1029700013B50446FFF7F2FFA04205D0012201A9DA -:1029800000200194FFF7C6FF02B010BD0144BFF361 -:102990004F8F064B884204D3BFF34F8FBFF36F8F27 -:1029A0007047C3F85C022030F4E700BF00ED00E0A0 -:1029B000034B1A681AB9034AD2F8D0241A60704738 -:1029C000004E00200040025808B5FFF7F1FF024B0F -:1029D0001868C0F3806008BD004E0020EFF3098343 -:1029E000054968334A6B22F001024A6383F3098880 -:1029F000002383F31188704700EF00E0202080F36C -:102A0000118862B60D4B0E4AD96821F4E0610904C1 -:102A1000090C0A430B49DA60D3F8FC2042F08072BB -:102A2000C3F8FC20084AC2F8B01F116841F0010148 -:102A300011601022DA7783F82200704700ED00E081 -:102A40000003FA0555CEACC5001000E0202310B5F8 -:102A500083F311880E4B5B6813F4006314D0F1EE1E -:102A6000103AEFF309844FF08073683CE361094B3F -:102A7000DB6B236684F30988FFF7EAFA10B1064B93 -:102A8000A36110BD054BFBE783F31188F9E700BF95 -:102A900000ED00E000EF00E0F7030008FA03000893 -:102AA00070B5BFF34F8FBFF36F8F1A4A0021C2F882 -:102AB0005012BFF34F8FBFF36F8F536943F400334E -:102AC0005361BFF34F8FBFF36F8FC2F88410BFF312 -:102AD0004F8FD2F8803043F6E074C3F3C900C3F3DC -:102AE0004E335B0103EA0406014646EA817501396B -:102AF000C2F86052F9D2203B13F1200FF2D1BFF39C -:102B00004F8F536943F480335361BFF34F8FBFF34B -:102B10006F8F70BD00ED00E0FEE700000A4B0B4830 -:102B20000B4A90420BD30B4BC11EDA1C121A22F037 -:102B300003028B4238BF00220021FEF769B953F827 -:102B4000041B40F8041BECE7EC440008D44F0020C1 -:102B5000D44F0020D44F00207047000070B5D0E95A -:102B6000244300224FF0FF359E6804EB42135101CD -:102B7000D3F80009002805DAD3F8000940F08040B6 -:102B8000C3F80009D3F8000B002805DAD3F8000BCE -:102B900040F08040C3F8000B013263189642C3F83E -:102BA0000859C3F8085BE0D24FF00113C4F81C3891 -:102BB00070BD000000EB8103D3F80CC02DE9F04399 -:102BC000DCF814204E1CD0F89050D2F800E005EB51 -:102BD000063605EB4118506870450AD30122D5F836 -:102BE000343802FA01F123EA0101C5F83418BDE8CE -:102BF000F083AEEB0003BCF81040A34228BF23468D -:102C0000D8F81849A4B2B3EB840FF0D89468A4F1B3 -:102C1000040959F8047F3760A4EB09071F44042F07 -:102C2000F7D81C44034494605360D4E7890141F011 -:102C30002001016103699B06FCD41220FFF772BAE0 -:102C400010B50A4C2046FEF7E3FE094BC4F890305D -:102C5000084BC4F89430084C2046FEF7D9FE074BC9 -:102C6000C4F89030064BC4F8943010BD044E0020D8 -:102C70000000084040430008A04E0020000004402F -:102C80004C43000870B503780546012B5DD1494BD4 -:102C9000D0F89040984259D1474B0E216520D3F887 -:102CA000D82042F00062C3F8D820D3F8002142F0C7 -:102CB0000062C3F80021D3F80021D3F8802042F04D -:102CC0000062C3F88020D3F8802022F00062C3F8AD -:102CD0008020D3F8803000F071FC384BE360384B33 -:102CE000C4F800380023D5F89060C4F8003EC02333 -:102CF00023604FF40413A3633369002BFCDA012330 -:102D00000C203361FFF70EFA3369DB07FCD4122085 -:102D1000FFF708FA3369002BFCDA00262846A66084 -:102D2000FFF71CFF6B68C4F81068DB68C4F8146810 -:102D3000C4F81C68002B3AD1224BA3614FF0FF333B -:102D40006361A36843F00103A36070BD1E4B98420A -:102D5000C8D1194B0E214D20D3F8D82042F0007273 -:102D6000C3F8D820D3F8002142F00072C3F8002144 -:102D7000D3F80021D3F8802042F00072C3F88020FD -:102D8000D3F8802022F00072C3F88020D3F880208E -:102D9000D3F8D82022F08062C3F8D820D3F80021DD -:102DA00022F08062C3F80021D3F8003193E7074B8B -:102DB000C3E700BF044E0020004402584014004006 -:102DC00003002002003C30C0A04E0020083C30C070 -:102DD000F8B5D0F89040054600214FF00066204637 -:102DE000FFF724FFD5F8941000234FF001128F68ED -:102DF0004FF0FF30C4F83438C4F81C2804EB4312F9 -:102E000001339F42C2F80069C2F8006BC2F808099A -:102E1000C2F8080BF2D20B68D5F89020C5F89830AC -:102E2000636210231361166916F01006FBD112209D -:102E3000FFF778F9D4F8003823F4FE63C4F80038BB -:102E4000A36943F4402343F01003A3610923C4F8AA -:102E50001038C4F814380B4BEB604FF0C043C4F883 -:102E6000103B094BC4F8003BC4F81069C4F80039A2 -:102E7000D5F8983003F1100243F48013C5F8982078 -:102E8000A362F8BD1C43000840800010D0F89020D9 -:102E900090F88A10D2F8003823F4FE6343EA011355 -:102EA000C2F80038704700002DE9F84300EB8103B9 -:102EB000D0F890500C468046DA680FFA81F9480144 -:102EC000166806F00306731E022B05EB41134FF044 -:102ED000000194BFB604384EC3F8101B4FF0010137 -:102EE00004F1100398BF06F1805601FA03F39169CB -:102EF00098BF06F5004600293AD0578A04F15801D8 -:102F0000374349016F50D5F81C180B430021C5F811 -:102F10001C382B180127C3F81019A7405369611EEC -:102F20009BB3138A928B9B08012A88BF5343D8F81E -:102F30009820981842EA034301F140022146C8F85C -:102F40009800284605EB82025360FFF76FFE08EBFE -:102F50008900C3681B8A43EA845348341E436401D2 -:102F60002E51D5F81C381F43C5F81C78BDE8F883EE -:102F700005EB4917D7F8001B21F40041C7F8001BE7 -:102F8000D5F81C1821EA0303C0E704F13F030B4AFC -:102F90002846214605EB83035A60FFF747FE05EB01 -:102FA0004910D0F8003923F40043C0F80039D5F8AF -:102FB0001C3823EA0707D7E700800010000400024E -:102FC000D0F894201268C0F89820FFF7C7BD000021 -:102FD0005831D0F8903049015B5813F4004004D0C8 -:102FE00013F4001F0CBF0220012070474831D0F8B5 -:102FF000903049015B5813F4004004D013F4001FD3 -:103000000CBF02200120704700EB8101CB68196AD8 -:103010000B6813604B6853607047000000EB81033E -:1030200030B5DD68AA691368D36019B9402B84BF35 -:10303000402313606B8A1468D0F890201C4402EB84 -:103040004110013C09B2B4FBF3F46343033323F0B2 -:10305000030343EAC44343F0C043C0F8103B2B686A -:1030600003F00303012B0ED1D2F8083802EB411014 -:1030700013F4807FD0F8003B14BF43F0805343F03B -:103080000053C0F8003B02EB4112D2F8003B43F082 -:103090000443C2F8003B30BD2DE9F041D0F8906008 -:1030A00005460C4606EB4113D3F8087B3A07C3F8F4 -:1030B000087B08D5D6F814381B0704D500EB81032C -:1030C000DB685B689847FA071FD5D6F81438DB072A -:1030D0001BD505EB8403D968CCB98B69488A5A683B -:1030E000B2FBF0F600FB16228AB91868DA68904243 -:1030F0000DD2121AC3E90024202383F3118821463C -:103100002846FFF78BFF84F31188BDE8F081012387 -:1031100003FA04F26B8923EA02036B81CB68002B6C -:10312000F3D021462846BDE8F041184700EB810363 -:103130004A0170B5DD68D0F890306C692668E660A9 -:1031400056BB1A444FF40020C2F810092A6802F056 -:103150000302012A0AB20ED1D3F8080803EB421485 -:1031600010F4807FD4F8000914BF40F0805040F084 -:103170000050C4F8000903EB4212D2F8000940F0F5 -:103180000440C2F800090122D3F8340802FA01F120 -:103190000143C3F8341870BD19B9402E84BF4020D4 -:1031A000206020681A442E8A8419013CB4FBF6F48E -:1031B00040EAC44040F00050C6E700002DE9F0416D -:1031C000D0F8906004460D4606EB4113D3F8087919 -:1031D000C3F80879FB071CD5D6F81038DA0718D5DC -:1031E00000EB8103D3F80CC0DCF81430D3F800E016 -:1031F000DA6896451BD2A2EB0E024FF000081A6067 -:10320000C3F80480202383F31188FFF78FFF88F32E -:1032100011883B0618D50123D6F83428AB40134259 -:1032200012D029462046BDE8F041FFF7C3BC012378 -:1032300003FA01F2038923EA02030381DCF8083070 -:10324000002BE6D09847E4E7BDE8F0812DE9F84F80 -:10325000D0F8905004466E69AB691E4016F4805851 -:103260006E6103D0BDE8F84FFEF742BC002E12DAC3 -:10327000D5F8003E9F0705D0D5F8003E23F00303A4 -:10328000C5F8003ED5F80438204623F00103C5F800 -:103290000438FEF759FC300505D52046FFF75EFCE3 -:1032A0002046FEF741FCB1040CD5D5F8083813F0E0 -:1032B000060FEB6823F470530CBF43F4105343F430 -:1032C000A053EB60320704D56368DB680BB120467E -:1032D0009847F30200F1BA80B70226D5D4F890904F -:1032E00000274FF0010A09EB4712D2F8003B03F424 -:1032F0004023B3F5802F11D1D2F8003B002B0DDA1B -:1033000062890AFA07F322EA0303638104EB870365 -:10331000DB68DB6813B13946204698470137D4F89B -:103320009430FFB29B689F42DDD9F00619D5D4F8DE -:103330009000026AC2F30A1702F00F0302F4F012BF -:10334000B2F5802F00F0CC80B2F5402F09D104EB0C -:103350008303002200F58050DB681B6A974240F02F -:10336000B2803003D5F8185835D5E90303D50021CC -:103370002046FFF791FEAA0303D501212046FFF75F -:103380008BFE6B0303D502212046FFF785FE2F033A -:1033900003D503212046FFF77FFEE80203D5042171 -:1033A0002046FFF779FEA90203D505212046FFF745 -:1033B00073FE6A0203D506212046FFF76DFE2B023D -:1033C00003D507212046FFF767FEEF0103D508214B -:1033D0002046FFF761FE700340F1A980E90703D59D -:1033E00000212046FFF7EAFEAA0703D50121204667 -:1033F000FFF7E4FE6B0703D502212046FFF7DEFE50 -:103400002F0703D503212046FFF7D8FEEE0603D58C -:1034100004212046FFF7D2FEA80603D50521204649 -:10342000FFF7CCFE690603D506212046FFF7C6FE4E -:103430002A0603D507212046FFF7C0FEEB0576D507 -:1034400020460821BDE8F84FFFF7B8BED4F89090A9 -:1034500000274FF0010AD4F894305FFA87FB9B688D -:103460009B453FF639AF09EB4B13D3F8002902F423 -:103470004022B2F5802F24D1D3F80029002A20DA87 -:10348000D3F8002942F09042C3F80029D3F800296C -:10349000002AFBDB5946D4F89000FFF7C7FB2289CE -:1034A0000AFA0BF322EA0303238104EB8B03DB68A4 -:1034B0009B6813B159462046984759462046FFF766 -:1034C00079FB0137C7E7910701D1D0F80080072ABF -:1034D00002F101029CBF03F8018B4FEA18283DE777 -:1034E00004EB830300F58050DA68D2F818C0DCF8EA -:1034F0000820DCE9001CA1EB0C0C00218F4208D154 -:10350000DB689B699A683A449A605A683A445A6000 -:1035100027E711F0030F01D1D0F800808C4501F1AD -:10352000010184BF02F8018B4FEA1828E6E7BDE8E5 -:10353000F88F000008B50348FFF788FEBDE8084093 -:10354000FFF784BA044E002008B50348FFF77EFE5B -:10355000BDE80840FFF77ABAA04E0020D0F89030BE -:1035600003EB4111D1F8003B43F40013C1F8003BD9 -:1035700070470000D0F8903003EB4111D1F80039CA -:1035800043F40013C1F8003970470000D0F89030C0 -:1035900003EB4111D1F8003B23F40013C1F8003BC9 -:1035A00070470000D0F8903003EB4111D1F800399A -:1035B00023F40013C1F8003970470000090100F13D -:1035C0006043012203F56143C9B283F8001300F0A0 -:1035D0001F039A4043099B0003F1604303F56143D5 -:1035E000C3F880211A60704730B50433039C017220 -:1035F000002104FB0325C160C0E90653049B03635B -:10360000059BC0E90000C0E90422C0E90842C0E906 -:103610000A11436330BD00000022416AC260C0E964 -:103620000411C0E90A226FF00101FEF7EBBD0000B2 -:10363000D0E90432934201D1C2680AB9181D70471B -:1036400000207047036919600021C2680132C2601E -:10365000C269134482699342036124BF436A0361D0 -:10366000FEF7C4BD38B504460D46E3683BB1626958 -:103670000020131D1268A3621344E36207E0237A5B -:1036800033B929462046FEF7A1FD0028EDDA38BD02 -:103690006FF00100FBE70000C368C269013BC36033 -:1036A0004369134482699342436124BF436A43617F -:1036B00000238362036B03B11847704770B5202362 -:1036C000044683F31188866A3EB9FFF7CBFF0546AF -:1036D00018B186F31188284670BDA36AE26A13F810 -:1036E000015B9342A36202D32046FFF7D5FF00237C -:1036F00083F31188EFE700002DE9F84F04460E46EA -:10370000174698464FF0200989F311880025AA46EC -:10371000D4F828B0BBF1000F09D141462046FFF78D -:10372000A1FF20B18BF311882846BDE8F88FD4E9BA -:103730000A12A7EB050B521A934528BF9346BBF11B -:10374000400F1BD9334601F1400251F8040B91425E -:1037500043F8040BF9D1A36A403640354033A362E5 -:10376000D4E90A239A4202D32046FFF795FF8AF351 -:103770001188BD42D8D289F31188C9E730465A462C -:10378000FDF720FBA36A5E445D445B44A362E7E768 -:1037900010B5029C0433017204FB0321C460C0E92C -:1037A00006130023C0E90A33039B0363049BC0E9AB -:1037B0000000C0E90422C0E90842436310BD0000D4 -:1037C000026A6FF00101C260426AC0E9042200226D -:1037D000C0E90A22FEF716BDD0E904239A4201D1BE -:1037E000C26822B9184650F8043B0B6070470020AD -:1037F00070470000C3680021C2690133C360436998 -:10380000134482699342436124BF436A4361FEF7D4 -:10381000EDBC000038B504460D46E3683BB12369B2 -:1038200000201A1DA262E2691344E36207E0237AD2 -:1038300033B929462046FEF7C9FC0028EDDA38BD29 -:103840006FF00100FBE7000003691960C268013AEC -:10385000C260C269134482699342036124BF436A10 -:10386000036100238362036B03B1184770470000B4 -:1038700070B520230D460446114683F31188866AED -:103880002EB9FFF7C7FF10B186F3118870BDA36A88 -:103890001D70A36AE26A01339342A36204D3E16913 -:1038A00020460439FFF7D0FF002080F31188EDE7B0 -:1038B0002DE9F84F04460D46904699464FF0200AF0 -:1038C0008AF311880026B346A76A4FB949462046B5 -:1038D000FFF7A0FF20B187F311883046BDE8F88FCD -:1038E000D4E90A073A1AA8EB0607974228BF1746F9 -:1038F000402F1BD905F1400355F8042B9D4240F899 -:10390000042BF9D1A36A40364033A362D4E90A23D9 -:103910009A4204D3E16920460439FFF795FF8BF3FF -:1039200011884645D9D28AF31188CDE729463A460F -:10393000FDF748FAA36A3D443E443B44A362E5E7F1 -:10394000D0E904239A4217D1C3689BB1836A8BB133 -:10395000043B9B1A0ED01360C368013BC360C3696C -:103960001A4483699A42026124BF436A03610023B7 -:1039700083620123184670470023FBE700F0DAB8A2 -:10398000034B002258631A610222DA60704700BFBD -:10399000000C0040014B0022DA607047000C004030 -:1039A000014B5863704700BF000C0040014B586A40 -:1039B000704700BF000C00404B6843608B68836019 -:1039C000CB68C3600B6943614B6903628B694362D7 -:1039D0000B6803607047000008B53C4B40F2FF7174 -:1039E0003B48D3F888200A43C3F88820D3F88820BE -:1039F00022F4FF6222F00702C3F88820D3F888205F -:103A0000D3F8E0200A43C3F8E020D3F808210A43A2 -:103A1000C3F808212F4AD3F808311146FFF7CCFF2D -:103A200000F5806002F11C01FFF7C6FF00F5806021 -:103A300002F13801FFF7C0FF00F5806002F1540188 -:103A4000FFF7BAFF00F5806002F17001FFF7B4FFE5 -:103A500000F5806002F18C01FFF7AEFF00F5806099 -:103A600002F1A801FFF7A8FF00F5806002F1C40190 -:103A7000FFF7A2FF00F5806002F1E001FFF79CFF75 -:103A800000F5806002F1FC01FFF796FF02F58C71F2 -:103A900000F58060FFF790FF00F000F90E4BD3F8BF -:103AA000902242F00102C3F89022D3F8942242F00F -:103AB0000102C3F894220522C3F898204FF0605207 -:103AC000C3F89C20054AC3F8A02008BD0044025852 -:103AD000000002585843000800ED00E01F000803F2 -:103AE00008B500F0F3FAFEF7E1FA0F4BD3F8DC204B -:103AF00042F04002C3F8DC20D3F8042122F0400257 -:103B0000C3F80421D3F80431084B1A6842F00802C4 -:103B10001A601A6842F004021A60FEF749FFBDE815 -:103B20000840FEF7EBBC00BF0044025800180248F2 -:103B300070470000114BD3F8E82042F00802C3F8A8 -:103B4000E820D3F8102142F00802C3F810210C4AF3 -:103B5000D3F81031D36B43F00803D363C722094B6A -:103B60009A624FF0FF32DA6200229A615A63DA6099 -:103B70005A6001225A611A60704700BF004402581F -:103B80000010005C000C0040094A08B51169D368B8 -:103B90000B40D9B29B076FEA0101116107D52023C1 -:103BA00083F31188FEF7A2FA002383F3118808BD7E -:103BB000000C0040384B4FF0FF31D3F88020C3F8A1 -:103BC0008010D3F880200022C3F88020D3F8800032 -:103BD000D3F88400C3F88410D3F88400C3F8842099 -:103BE000D3F88400D86F40F0FF4040F4FF0040F469 -:103BF0003F5040F03F00D867D86F20F0FF4020F4DE -:103C0000FF0020F43F5020F03F00D867D86FD3F872 -:103C100088006FEA40506FEA5050C3F88800D3F82C -:103C20008800C0F30A00C3F88800D3F88800D3F8EE -:103C30009000C3F89010D3F89000C3F89020D3F808 -:103C40009000D3F89400C3F89410D3F89400C3F80C -:103C50009420D3F89400D3F89800C3F89810D3F8C0 -:103C60009800C3F89820D3F89800D3F88C00C3F8D4 -:103C70008C10D3F88C00C3F88C20D3F88C00D3F8C8 -:103C80009C00C3F89C10D3F89C10C3F89C20D3F878 -:103C90009C3000F0E7B900BF00440258614B01229C -:103CA000C3F80821604BD3F8F42042F00202C3F8B5 -:103CB000F420D3F81C2142F00202C3F81C21042294 -:103CC000D3F81C31594BDA605A689104FCD5584A34 -:103CD0001A6001229A60574ADA6000221A614FF492 -:103CE00040429A61514B9A699204FCD51A6842F499 -:103CF00080721A604C4B1A6F12F4407F04D04FF45C -:103D000080321A6700221A671A6842F001021A60AC -:103D1000454B1A685007FCD500221A611A6912F047 -:103D20003802FBD1012119604FF0804159605A6778 -:103D3000414ADA62414A1A611A6842F480321A60D2 -:103D4000394B1A689103FCD51A6842F480521A6004 -:103D50001A689204FCD53A4A3A499A6200225A6398 -:103D600019633949DA6399635A64384A1A64384ADC -:103D7000DA621A6842F0A8521A602B4B1A6802F0F5 -:103D80002852B2F1285FF9D148229A614FF4886233 -:103D9000DA6140221A622F4ADA644FF080521A65C3 -:103DA0002D4A5A652D4A9A6532232D4A13601368AD -:103DB00003F00F03022BFAD11B4B1A6942F00302E6 -:103DC0001A611A6902F03802182AFAD1D3F8DC20F5 -:103DD00042F00052C3F8DC20D3F8042142F0005234 -:103DE000C3F80421D3F80421D3F8DC2042F0804248 -:103DF000C3F8DC20D3F8042142F08042C3F8042148 -:103E0000D3F80421D3F8DC2042F00042C3F8DC20D0 -:103E1000D3F8042142F00042C3F80421D3F804315E -:103E2000704700BF0080005100440258004802580B -:103E300000C000F0040000010000FF0100889008AD -:103E400032206000630209011D02040047040508D6 -:103E5000FD0BFF01200000200010E0000001010028 -:103E6000002000524FF0B04208B5D2F8883003F07D -:103E70000103C2F8883023B1044A13680BB15068BB -:103E80009847BDE80840FEF7E1BD00BF544F002051 -:103E90004FF0B04208B5D2F8883003F00203C2F800 -:103EA000883023B1044A93680BB1D0689847BDE8C5 -:103EB0000840FEF7CBBD00BF544F00204FF0B0428A -:103EC00008B5D2F8883003F00403C2F8883023B173 -:103ED000044A13690BB150699847BDE80840FEF7E2 -:103EE000B5BD00BF544F00204FF0B04208B5D2F826 -:103EF000883003F00803C2F8883023B1044A93697C -:103F00000BB1D0699847BDE80840FEF79FBD00BFE0 -:103F1000544F00204FF0B04208B5D2F8883003F07B -:103F20001003C2F8883023B1044A136A0BB1506AF7 -:103F30009847BDE80840FEF789BD00BF544F0020F8 -:103F40004FF0B04310B5D3F8884004F47872C3F84A -:103F50008820A30604D5124A936A0BB1D06A984709 -:103F6000600604D50E4A136B0BB1506B98472106BF -:103F700004D50B4A936B0BB1D06B9847E20504D57F -:103F8000074A136C0BB1506C9847A30504D5044A3B -:103F9000936C0BB1D06C9847BDE81040FEF756BD4E -:103FA000544F00204FF0B04310B5D3F8884004F4CC -:103FB0007C42C3F88820620504D5164A136D0BB104 -:103FC000506D9847230504D5124A936D0BB1D06DFF -:103FD0009847E00404D50F4A136E0BB1506E984712 -:103FE000A10404D50B4A936E0BB1D06E98476204BE -:103FF00004D5084A136F0BB1506F9847230404D5BA -:10400000044A936F0BB1D06F9847BDE81040FEF79C -:104010001DBD00BF544F002008B50348FDF70AF945 -:10402000BDE80840FEF712BDCC23002008B50348C8 -:10403000FDF700F9BDE80840FEF708BD3824002070 -:1040400008B50348FDF7F6F8BDE80840FEF7FEBCEA -:10405000A424002008B5FFF797FDBDE80840FEF74F -:10406000F5BC0000062108B50846FFF7A7FA0621AF -:104070000720FFF7A3FA06210820FFF79FFA062181 -:104080000920FFF79BFA06210A20FFF797FA06217D -:104090001720FFF793FA06212820FFF78FFA09214E -:1040A0007A20FFF78BFA07213220FFF787FA0C21DD -:1040B0002620FFF783FA0C212720FFF77FFA0C2137 -:1040C0005220BDE80840FFF779BA000008B5FFF7B5 -:1040D00071FD00F00DF8FDF7BFFAFDF797FCFDF755 -:1040E00069FBFFF725FDBDE80840FFF747BC00006E -:1040F0000023054A19460133102BC2E9001102F1D1 -:104100000802F8D1704700BF544F002010B50139A4 -:104110000244904201D1002005E0037811F8014FDC -:10412000A34201D0181B10BD0130F2E7034611F87D -:10413000012B03F8012B002AF9D1704753544D335A -:104140003248373F3F3F0053544D333248373433C2 -:104150002F37353300000000C8320020CC23002068 -:1041600038240020A4240020009600000000000055 -:10417000000000000000000000000000000000003F -:1041800000000000211600080D160008491600085E -:1041900035160008411600082D16000819160008EB -:1041A0000516000855160008000000003117000829 -:1041B0001D17000859170008451700085117000877 -:1041C0003D17000829170008151700086517000893 -:1041D0000000000001000000000000006D61696E39 -:1041E0000000000069646C6500000000E441000804 -:1041F00050310020C832002001000000A920000832 -:10420000000000004375626550696C6F740043756F -:1042100062654F72616E67652B2D424C00255345D8 -:104220005249414C2500000002000000000000003F -:1042300051190008C119000840004000704B0020CF -:10424000804B00200200000000000000030000007E -:1042500000000000091A0008000000001000000023 -:10426000904B002000000000010000000000000052 -:10427000044E00200101020099240008A92300082F -:10428000452400082924000843000000904200084B -:1042900009024300020100C03209040000010202C9 -:1042A000010005240010010524010001042402027C -:1042B0000524060001070582030800FF0904010028 -:1042C000020A000000070501024000000705810204 -:1042D0004000000012000000DC4200081201100142 -:1042E00002000040AE2D5810000201020301000040 -:1042F0000403090425424F41524425004375626579 -:104300004F72616E6765506C7573003031323334B3 -:1043100035363738394142434445460000000000F5 -:104320005D1B0008151E0008C11E0008400040006B -:104330003C4F00203C4F0020010000004C4F00206B -:1043400080000000400100000800000000010000A3 -:1043500000040000080000000000812A00000000A6 -:10436000AAAAAAAA00000024FFFE00000000000084 -:1043700000A00A000001000000000000AAAAAAAAEA -:1043800000000000FFFF000000000000000000002F -:104390001400005400000000AAAAAAAA14000054A5 -:1043A000FFFF0000000000000000000000681A008D -:1043B00000000000AAAA8AAA00541500FFFF00000E -:1043C000000070077700000040810200000000003C -:1043D000AAAAAAAA00410100F7FF0000000000708D -:1043E000070000000000000000000000AAAAAAAA1E -:1043F00000000000FFFF00000000000000000000BF -:104400000000000000000000AAAAAAAA0000000004 -:10441000FFFF00000000000000000000000000009E -:1044200000000000AAAAAAAA00000000FFFF0000E6 -:10443000000000000000000000000000000000007C -:10444000AAAAAAAA00000000FFFF000000000000C6 -:10445000000000000000000000000000AAAAAAAAB4 -:1044600000000000FFFF000000000000000000004E -:104470000000000000000000AAAAAAAA0000000094 -:10448000FFFF00000000000000000000000000002E -:10449000270400000000000000001E0000000000D3 -:1044A000FF000000000000003C4100083F00000049 -:1044B00050040000474100083F0000000096000043 -:1044C0000000080096000000000800000400000042 -:1044D000F0420008000000000000000000000000A2 -:0C44E000000000000000000000000000D0 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008358A000842 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008E17E00080D7F0008CB +:10006000397F0008657F0008917F0008E3020008DF +:10007000E3020008E3020008E3020008E3020008CC +:10008000E3020008E3020008E3020008E3020008BC +:10009000E3020008E3020008E3020008BD7F000855 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008A9800008BD800008D0 +:1000E00021800008E3020008E3020008E3020008A0 +:1000F000E3020008E3020008E3020008E30200084C +:10010000E302000895800008E5800008E30200088B +:10011000E3020008E3020008E3020008E30200082B +:10012000E3020008E3020008E3020008E30200081B +:10013000E3020008E3020008E3020008E30200080B +:10014000E3020008E3020008E3020008E3020008FB +:10015000E3020008E3020008E3020008E3020008EB +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008D97B0008E3020008E30200085C +:10018000E3020008E3020008D1800008E30200084F +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008C57B0008E3020008E302000810 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F06F0BAFEB2 +:1003500006F0D4F84FF055301F491B4A91423CBF7C +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE706F0D2FE06F030F954 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F0C4F9114C124DAC4203DA54F8041B9E +:1003C0008847F9E706F0BABE0006002000220020A8 +:1003D0000000000808ED00E00000002000060020FA +:1003E0004896000800220020D8220020D8220020B1 +:1003F00020670020E0020008E0020008E002000898 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002005F05AFEFEE705F097 +:1004300099FD00DFFEE7000053B94AB9002908BF63 +: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 +:1007300009E76444023842E7704700BF38B500F06B +:10074000D1FB06F0CDFB054606F0B2FC0446E0B94D +:10075000104B9D421BD001339D4241F2883504BFAE +:1007600001240025002006F0C5FB0CB100F07AF84A +:1007700001F02EFB01F0EAF900F01CFD08B100F0D9 +:1007800071F8284600F010F9F9E70025EAE7054678 +:10079000E8E700BF010007B008B501F0A3F9A0F138 +:1007A00020035842584108BD07B541F21203022107 +:1007B00001A8ADF8043001F0B3F903B05DF804FB13 +:1007C00038B5302383F31188174803680BB105F05F +:1007D0006BFD0023154A4FF47A71134805F05AFD5A +:1007E000002383F31188124C236813B12368013B63 +:1007F0002360636813B16368013B63600D4D2B7820 +:1008000033B963687BB9022001F05CFA322363607C +:100810002B78032B07D163682BB9022001F052FA21 +:100820004FF47A73636038BDD8220020C1070008F6 +:10083000F8230020F0220020084B187003280CD861 +:10084000DFE800F008050208022001F031BA0220BA +:1008500001F024BA024B00225A607047F0220020B7 +:10086000F8230020F8B5494B494A1C461968013164 +:1008700000F08A8004339342F8D16268454B9A4273 +:1008800040F28280444B9B6803F1006303F5003320 +:100890009A4279D2002001F073F90220FFF7CCFFD1 +:1008A0003E4B00219A6C99641A6F19671A6FDA6CC3 +:1008B000D9645A6F59675A6F1A6D19659A6F99679B +:1008C0009B6F374BD3F8802042F00062C3F8802042 +:1008D000D3F8802022F00062C3F88020D3F8802073 +:1008E000D3F8802042F00072C3F88020D3F8802033 +:1008F00022F00072C3F88020D3F8803072B64FF037 +:10090000E023C3F8084DD4E90004BFF34F8FBFF3D1 +:100910006F8F244AC2F88410BFF34F8F536923F4BA +:1009200080335361BFF34F8FD2F8803043F6E076C7 +:10093000C3F3C905C3F34E335B0103EA060C294632 +:100940004CEA81770139C2F87472F9D2203B13F175 +:10095000200FF2D1BFF34F8FBFF36F8FBFF34F8FD5 +:10096000BFF36F8F536923F4003353610023C2F840 +:100970005032BFF34F8FBFF36F8F302383F3118853 +:10098000854680F308882047F8BD00BF00000208B4 +:1009900020000208FFFF0108002200200045025845 +:1009A0000044025800ED00E02DE9F04F93B0B44B45 +:1009B0002022FF2100900AA89D6801F0B3F9B14AF6 +:1009C0001378A3B90121B04811700360302383F379 +:1009D000118803680BB105F067FC0023AB4A4FF4A4 +:1009E0007A71A94805F056FC002383F31188009B17 +:1009F00013B1A74B009A1A60A64A1378032B03D0B1 +:100A000000231370A24A53604FF0000A009CD346A3 +:100A10005646D146012001F04BF924B19C4B1B688E +:100A2000002B00F02682002001F05CF80390039B6D +:100A3000002BF2DB012001F031F9039B213B1F2B3E +:100A4000E8D801A252F823F0C90A0008F10A000808 +:100A5000850B0008150A0008150A0008150A000889 +:100A6000170C0008E70D0008010D0008630D0008D1 +:100A70008B0D0008B10D0008150A0008C30D000811 +:100A8000150A0008350E0008690B0008150A000851 +:100A9000790E0008D50A0008690B0008150A00083D +:100AA000630D0008150A0008150A0008150A000859 +:100AB000150A0008150A0008150A0008150A00089A +:100AC000150A0008850B00080220FFF765FE0028C4 +:100AD00040F0F981009B022105A8BAF1000F08BF80 +:100AE0001C4641F21233ADF8143001F019F891E7C9 +:100AF0004FF47A7000F0F6FF071EEBDB0220FFF7E1 +:100B00004BFE0028E6D0013F052F00F2DE81DFE832 +:100B100007F0030A0D1013360523042105A80593D9 +:100B200000F0FEFF17E004215548F9E704215A4878 +:100B3000F6E704215948F3E74FF01C08404608F156 +:100B4000040801F01FF80421059005A800F0E8FF53 +:100B5000B8F12C0FF2D101204FF0000900FA07F78D +:100B600047EA0B0B5FFA8BFB01F028F926B10BF07B +:100B70000B030B2B08BF0024FFF716FE4AE70421E6 +:100B80004748CDE7002EA5D00BF00B030B2BA1D1CE +:100B90000220FFF701FE074600289BD00120002617 +:100BA00000F0EEFF0220FFF747FE1FFA86F84046EE +:100BB00000F0F6FF0446B0B1039940460136A1F1BA +:100BC00040025142514100F0FBFF0028EDD1BA46EE +:100BD000044641F21213022105A83E46ADF8143036 +:100BE00000F09EFF16E725460120FFF725FE244B67 +:100BF0009B68AB4207D9284600F0C4FF013040F0A3 +:100C000067810435F3E70025224BBA463E461D7046 +:100C10001F4B5D60A8E7002E3FF45CAF0BF00B03A9 +:100C20000B2B7FF457AF0220FFF706FE322000F0B7 +:100C300059FFB0F10008FFF64DAF18F003077FF43D +:100C400049AF0F4A08EB0503926893423FF642AF63 +:100C5000B8F5807F3FF73EAF124BB845019323DDD7 +:100C60004FF47A7000F03EFF0390039A002AFFF6DB +:100C700031AF039A0137019B03F8012BEDE700BF69 +:100C800000220020F4230020D8220020C107000801 +:100C9000F8230020F0220020042200200822002057 +:100CA0000C220020F4220020C820FFF775FD074623 +:100CB00000283FF40FAF1F2D11D8C5F120020AAB59 +:100CC00025F0030084494245184428BF424601925A +:100CD00001F002F8019AFF217F4801F023F84FEA62 +:100CE000A803C8F387027C492846019301F022F843 +:100CF000064600283FF46DAF019B05EB830533E703 +:100D00000220FFF749FD00283FF4E4AE00F076FF33 +:100D100000283FF4DFAE0027B846704B9B68BB420B +:100D200018D91F2F11D80A9B01330ED027F00303C7 +:100D300012AA134453F8203C05934046042205A907 +:100D4000043701F0A5F88046E7E7384600F01AFFBF +:100D50000590F2E7CDF81480042105A800F0E0FE2C +:100D600002E70023642104A8049300F0CFFE0028CA +:100D70007FF4B0AE0220FFF70FFD00283FF4AAAECB +:100D8000049800F031FF0590E6E70023642104A8F1 +:100D9000049300F0BBFE00287FF49CAE0220FFF716 +:100DA000FBFC00283FF496AE049800F01FFFEAE732 +:100DB0000220FFF7F1FC00283FF48CAE00F02EFF7C +:100DC000E1E70220FFF7E8FC00283FF483AE05A925 +:100DD000142000F029FF07460421049004A800F025 +:100DE0009FFE3946B9E7322000F07CFE071EFFF671 +:100DF00071AEBB077FF46EAE384A07EB0903926809 +:100E000093423FF667AE0220FFF7C6FC00283FF48E +:100E100061AE27F003074F44B9453FF4A5AE4846FD +:100E200009F1040900F0AEFE0421059005A800F0C8 +:100E300077FEF1E74FF47A70FFF7AEFC00283FF43D +:100E400049AE00F0DBFE002844D00A9B01330BD0F2 +:100E500008220AA9002000F06DFF00283AD02022C5 +:100E6000FF210AA800F05EFFFFF79EFC1C4805F07A +:100E70003DF913B0BDE8F08F002E3FF42BAE0BF020 +:100E80000B030B2B7FF426AE0023642105A80593EA +:100E900000F03CFE074600287FF41CAE0220FFF75E +:100EA0007BFC804600283FF415AEFFF77DFC41F245 +:100EB000883005F01BF9059800F0C8FF46463C460F +:100EC00000F07CFFA6E506464EE64FF0000901E67D +:100ED000BA467EE637467CE6F42200200022002057 +:100EE000A0860100704700007047000070470000B6 +:100EF000704700002DE9F04100F5803704461646A2 +:100F00003B7C5BB9C0681030204400F0E5FEE5682A +:100F10003544B5F5004FE56002D816B1BDE8F08163 +:100F2000DEB905F07F0605F110000021C6F180064C +:100F30002044F6B232462E4400F0F4FEA06804F1DC +:100F40001008324600F10060414600F5003005F01F +:100F50008FFD30B901233B74E0E74FF4004635467E +:100F6000ECE7A26805F11001404632442144A2603A +:100F7000E268521BE26000F0AFFE0220BDE8F041E3 +:100F800000F0A0BE183000F0E9BC000010B5044627 +:100F900007F0FAFD204610BD10B5044607F0F4FD39 +:100FA000204610BDC3B280B2A3F14102052A02D887 +:100FB000373800B27047613B052B94BF5738303843 +:100FC000F7E70000F8B504461546084603220C4929 +:100FD00000F08CFE014688B908346F1C15F9110029 +:100FE000FFF7E0FF064617F911000131FFF7DAFFBE +:100FF000102940EA061004F8010BEFD1F8BD00BF3C +:10100000008D00082DE9F04FADF53F7D07464168A2 +:1010100001222AA802F030FE002840F08780064610 +:10102000824681461125DFF80C81DFF80CB101AB57 +:101030004FF4805241462AA802F07EFF002875D165 +:10104000019AB2F5805F71D8002A65D00446019AF2 +:101050009442ECD2282D0FD008DC132D2DD01E2D5C +:1010600039D0112D13D00134A4B2F0E7322D2DD098 +:10107000372D2FD02D2DF6D13B68121B08EB040124 +:1010800038461B692D259847BDF80440EBE7121B35 +:10109000022A09D9594608EB040000F027FE18B9C6 +:1010A00002342825A4B2DEE718F804303A2B3DD0EC +:1010B0000A2B1CBFA1461325D5E718F804300A2BCC +:1010C00034D03A2B04BFA2463225CCE718F80430BE +:1010D000202BC8D0264618F804300A2B1AD1AAEBC8 +:1010E000090208EB090102A811254F2A28BF4F2247 +:1010F00007F0F2FDA21B08EB060116A84F2A28BF35 +:101100004F2207F0E9FD3B6816AA02A9DB683846C2 +:101110009847A8E71E25A6E73B68384604491B699F +:10112000984701200DF53F7DBDE8F08F0020F9E7DD +:10113000028E000800240020048D000800F1180130 +:1011400010B5044686B00846019100F0F1FB204638 +:10115000FFF758FF60B1019902A800F049FC102286 +:1011600004F1080102A807F033FDB0FA80F040094D +:1011700006B010BD70B504460025EEB2304600F052 +:101180000FFD58B100213046013500F019FD08B9B6 +:10119000002070BD022000F095FDEEE72046FFF72D +:1011A00031FF0028F4D004F58034207C80F0010069 +:1011B000EFE70000F0B5C9B005F0AAFE00F096FE1A +:1011C00018B90025284649B0F0BD69462A4802F002 +:1011D00075FF00284BD1294C204602F09FFF28487C +:1011E00002F09CFF274802F099FF2146224803F0B5 +:1011F00011F80028E5D1702007F0C8FC064610B1B0 +:10120000214B44600360336830469B68984705462D +:1012100000282ED01A4F1948394602F0FBFF054628 +:101220000028CED1194807F0B1FC044638B1184B5C +:101230004760036000F58033C0E902551D742368E0 +:1012400020469B689847054628B10E490C4802F095 +:10125000E1FF0028B5D1336830465B6898471CB180 +:10126000236820465B68984700F028FEAAE700251F +:10127000FAE70446EFE700BF088D0008188D000864 +:101280002F8D0008458D0008688D000814000100AE +:10129000848D00082DE9F04FD44A8DB00B68D0F84A +:1012A00004A001931A440368D14E1A44D1F81C904B +:1012B000DFF8B4C3DFF8B4B3D0E90234634003EA23 +:1012C0000A03634013444A6802920AEB7363029C68 +:1012D000C84A2244C468224484688AEA04051D403E +:1012E000654015448A68039203EB3555039CC24A56 +:1012F0002244846822448AEA03042C4084EA0A04D3 +:101300001444CA6805EBF4340492164483EA0502D7 +:10131000224056445A4032440E69059604EBB222EC +:10132000059FB64E3E441E4485EA040313406B40BD +:1013300033444E69069602EB7363069FB04E3E44FB +:101340002E4484EA02051D40654035448E690796A7 +:1013500003EB3555079FAB4E3E44264482EA030417 +:101360002C4054403444A84E4E4405EBF43416440B +:1013700083EA050222405A4032440E6A089604EB82 +:10138000B222089FA14E3E441E4485EA0403134046 +:101390006B4033444E6A099602EB7363099F9C4E7F +:1013A000D1F830E03E44D1F83880F3442E4484EA4A +:1013B00002051D40654035448E6AA6F5244703EBBF +:1013C00035550A964F3F274482EA03042C40544087 +:1013D0003C44CF6A0B9705EBF4340B9E8D4F37449A +:1013E000029E174483EA050222405A403A448A4F3B +:1013F000774404EBB2221F4485EA040313406B4098 +:101400003B444F6BBC4402EB7363654484EA020CBB +:101410000CEA030C8CEA040C6544DFF854C2C444A3 +:1014200003EB3555A44482EA03042C405440644441 +:10143000D1F83CC0794905EBF4346144114483EAA6 +:10144000050222405A400A44754904EBB222314455 +:10145000079E194484EA02032B4063400B44714900 +:1014600002EBF36331440B9E0D4482EA03012140F9 +:10147000514029446C4D03EBF1513544019E254404 +:1014800083EA010414405C402C44684D01EBB444F1 +:101490003544069E154481EA04021A404A402A4413 +:1014A000634D04EB323235440A9E1D4484EA020344 +:1014B0000B4063402B445F4D02EBF3633544059EC4 +:1014C0000D4482EA03012140514029445A4D03EB67 +:1014D000F1516544254483EA010414405C402C44E6 +:1014E000564D01EBB4443544099E154481EA04028B +:1014F0001A404A402A44524D04EB32323544049E8D +:101500001D4484EA02030B4063402B444D4D02EB23 +:10151000F36345440D4482EA0301214051402944CC +:10152000494D03EBF1513544089E2C4483EA0105F3 +:1015300015405D402C44454D01EBB4443544039EB9 +:101540002A4481EA04051D404D402A44404D04EBE5 +:1015500032323D442B4484EA020593440D406540F9 +:101560002B443C4D02EBF3633544069E294482EA4A +:101570000305254055402944374D03EBF1514D44B7 +:101580002C4483EA010515405D40254401EBB54537 +:1015900081EA050404EA03024A405A44A6F5B82B3E +:1015A000089E05EB3232ABF2BE6B54405B442344E1 +:1015B0002A4C344402EB33730B9E0C4485EA02013F +:1015C00059402144264C344403EB7151029E25447A +:1015D00082EA03044C402544224C444401EB354547 +:1015E000144483EA01026A40224443E078A46AD7A3 +:1015F000EECEBDC156B7C7E8DB702024AF0F7CF537 +:101600002AC68747134630A8019546FDD8988069B9 +:10161000AFF7448BBED75C892211906B2108B44987 +:1016200062251EF640B340C0515A5E26AAC7B6E9ED +:101630005D102FD65314440281E6A1D8C8FBD3E72E +:10164000E6CDE121D60737C3870DD5F4ED145A4511 +:1016500005E9E3A9F8A3EFFCD9026F6781F671876A +:1016600022619D6D0C38E5FD937198FD8A4C2A8DA1 +:101670008E4379A6934C344405EB7222059E1C449C +:1016800081EA0503534023448F4C344402EB337307 +:101690000A9E0C4485EA0201594021448B4C4C447B +:1016A00003EB7151254482EA03044C402C44884DDD +:1016B000354401EB3444019E154483EA0102624043 +:1016C0002A44844D3D4404EB72221D4481EA040304 +:1016D00053402B44804D354402EB3373049E294420 +:1016E00084EA02055D4029447C4D354403EB715189 +:1016F000079E254482EA03044C402C44784D35442F +:1017000001EB3444099E2A4483EA010565401544EF +:10171000744A324404EB7525039E134481EA0402A3 +:101720006A401A44704B734405EB32720B4484EAEE +:101730000501514019446D4B634402EB71511C4447 +:1017400085EA02034B401C44694B334401EB3444AB +:10175000019E1D4482EA010363402B44654D04EB66 +:1017600073233544069E154463EA010262402A440D +:10177000614D03EBB2624D4462EA040929445F4DB6 +:1017800089EA0309454449442C445D4D02EBB151BB +:101790003544049E61EA03081D4488EA0208444473 +:1017A00001EB744464EA02034B402B44554D04EBB7 +:1017B000F323754463EA010E15448EEA040E0EEB22 +:1017C0000502514D03EBB262354462EA040E29442E +:1017D0000A9D8EEA030EA5F580164C4D7144A6F6BF +:1017E000833602EBB151264461EA03045440344489 +:1017F000029E01EB7444354464EA02061D444E40E7 +:101800007319089E424D04EBF323354463EA010645 +:101810001544664072193F4D03EBB262654462EABB +:10182000040629443C4D5E403144079E02EBB15111 +:10183000354461EA03062C44384D56403D44344457 +:10184000059E1D4401EB744464EA02034B402B44A3 +:10185000334D04EBF32335440B9E154463EA010238 +:1018600062402A442F4D03EBB2623544039E0D447F +:1018700062EA0401594029442B4D02EBB151354431 +:101880002A4E254461EA030454402C44099D01EB8F +:1018900074442E4464EA02051E4485EA01039D193E +:1018A00003681A440AEB040303EBF5230260436068 +:1018B00083681C44C36819448460C1600DB0BDE8EE +:1018C000F08F00BF44EABEA4A9CFDE4B604BBBF64D +:1018D00070BCBFBEC67E9B28FA27A1EA8530EFD434 +:1018E000051D880439D0D4D9E599DBE6F87CA21F20 +:1018F0006556ACC4442229F497FF2A43A72394AB2E +:1019000039A093FCC3595B6592CC0C8FD15D848563 +:101910004F7EA86FE0E62CFE144301A3A111084EF0 +:10192000827E53F735F23ABDBBD2D72A91D386EBEC +:10193000094B036003F18833436003F12943A3F5A6 +:101940009613A3F68B638360A3F18833C3600023EF +:10195000C0E90433704700BF012345672DE9F84310 +:101960001446026905460E46E300C2F3C50800F1BD +:1019700018079B18036122BF43690133436112F4C6 +:10198000FC7F436903EB5473436114D0C8F14009F1 +:1019900007EB08004C4504D22246BDE8F84307F0A7 +:1019A00027B9403C4A464E4407F022F944443946A0 +:1019B0002846FFF76FFCA04606EB0409B8F13F0F7D +:1019C000A9EB08010AD94022384607F011F9394637 +:1019D0002846A8F14008FFF75DFCEFE7A1096FF08A +:1019E0003F02384602FB014206EB8111D5E70000B9 +:1019F00070B50B6901F1180506460C46C3F3C50323 +:101A0000EA18501C8022EA54C3F13F02072A1FD86B +:101A1000002100F087F929462046FFF73BFC3822D9 +:101A20000021284600F07EF92369294620462365D7 +:101A300063696365FFF72EFC21461022304607F0EC +:101A4000D7F8204658220021BDE8704000F06AB95E +:101A5000C3F137020021E5E72DE9F84F4FF47A731F +:101A600006460D46002402FB03F7DFF85080DFF83E +:101A7000509098F900305FFA84FA5A1C01D0A342C2 +:101A800010D159F824002A4631460368D3F820B013 +:101A90003B46D847854205D1074B012083F800A07B +:101AA000BDE8F88F0134042CE3D14FF4FA7004F050 +:101AB0001DFB0020F4E700BF44340020102200206A +:101AC0001422002070B504464FF47A76412C254646 +:101AD00028BF412506FB05F004F008FB641BF5D187 +:101AE00070BD0000002307B5024601210DF107007B +:101AF0008DF80730FFF7B0FF20B19DF8070003B065 +:101B00005DF804FB4FF0FF30F9E700000A460421BE +:101B100008B5FFF7A1FF80F00100C0B2404208BD48 +:101B2000074B0A4630B41978064B53F8214001465A +:101B300023682046DD69044BAC4630BC604700BFDB +:101B40004434002014220020A086010070B50A4E03 +:101B500000240A4D04F030FF308028683388834227 +:101B600008D904F025FF2B6804440133B4F5003F85 +:101B70002B60F2D370BD00BF46340020003400203B +:101B800004F0E8BF00F1006000F500300068704725 +:101B900000F10060920000F5003004F069BF000021 +:101BA000054B1A68054B1B889B1A834202D91044C7 +:101BB00004F0FEBE002070470034002046340020B0 +:101BC00038B50446074D29B128682044BDE838409F +:101BD00004F006BF2868204404F0F0FE0028F3D08B +:101BE00038BD00BF003400200020704700F1FF50D6 +:101BF00000F58F10D0F8000870470000064991F8F2 +:101C0000243033B100230822086A81F82430FFF71A +:101C1000BFBF0120704700BF04340020014B18688B +:101C2000704700BF0010005C194B013803220844C4 +:101C300070B51D68174BC5F30B042D0C1E88A6420A +:101C40000BD15C680A46013C824213460FD214F95C +:101C5000016F4EB102F8016BF6E7013A03F1080398 +:101C6000ECD181420B4602D22C2203F8012B042432 +:101C7000094A1688AE4204D1984284BF967803F888 +:101C8000016B013C02F10402F3D1581A70BD00BF90 +:101C90000010005C24220020C48D0008022803D11B +:101CA000024B4FF080529A61704700BF00100258FB +:101CB000022803D1024B4FF480529A61704700BF53 +:101CC00000100258022804D1024A536983F4805359 +:101CD0005361704700100258002310B5934203D09F +:101CE000CC5CC4540133F9E710BD0000013810B5D5 +:101CF00010F9013F3BB191F900409C4203D11AB168 +:101D00000131013AF4E71AB191F90020981A10BD97 +:101D10001046FCE703460246D01A12F9011B0029BF +:101D2000FAD1704702440346934202D003F8011BE4 +:101D3000FAE770472DE9F8431F4D144607468846D9 +:101D400095F8242052BBDFF870909CB395F82430AE +:101D50002BB92022FF2148462F62FFF7E3FF95F8B9 +:101D600024004146C0F1080205EB8000A24228BFD2 +:101D70002246D6B29200FFF7AFFF95F82430A41B9D +:101D800017441E449044E4B2F6B2082E85F824604D +:101D9000DBD1FFF733FF0028D7D108E02B6A03EB34 +:101DA00082038342CFD0FFF729FF0028CBD1002048 +:101DB000BDE8F8830120FBE704340020024B1A78C9 +:101DC000024B1A70704700BF4434002010220020DC +:101DD000F8B5194C194803F077FC2146174803F071 +:101DE0009FFC24684FF47A70154ED4F89020154D5E +:101DF000D2F80438114F43F00203C2F80438FFF759 +:101E000061FE2046104903F099FDD4F89020042487 +:101E1000D2F8043823F00203C2F804384FF4E13357 +:101E2000336055F8040BB84202D0314603F0AAFBE8 +:101E3000013CF6D1F8BD00BFC4940008F048002072 +:101E40002C34002014220020CC9400080C4B70B5D8 +:101E50000C4D04461E780C4B55F826209A420DD0A6 +:101E60000A4B002118221846FFF75CFF0460014668 +:101E700055F82600BDE8704003F084BB70BD00BF7C +:101E80004434002014220020F04800202C3400208C +:101E900030B50A44084D91420DD011F8013B58402D +:101EA000082340F30004013B2C4013F0FF0384EAB5 +:101EB0005000F6D1EFE730BD2083B8ED10B5084CE7 +:101EC00001220849002001F0B3FE23783BB1064807 +:101ED00003F0D0FA044803F003FB0023237010BD85 +:101EE00048340020D48D0008A43600201D482DE978 +:101EF000F041036D2BB901224FF48051503005F0B1 +:101F000049F8194E33780BB1FFF7D8FF0324174F68 +:101F10004FF00008134D15492846C7F8048003F018 +:101F2000D1FA284603F00AF948B1013C284603F0EB +:101F3000D7FA14F0FF04EED1204634700FE00C49BC +:101F400001220C4801F074FE014618B1284603F046 +:101F500091FAEAE7084800F011F801203070BDE876 +:101F6000F08100BFA4360020483400203C2200202D +:101F7000D48D00084C340020D88D00080FB4002008 +:101F800004B070470068704703460068596870479E +:101F90000B0A017043700B0C090E8370C1707047FF +:101FA000110A027003714170110C120E8170C2701F +:101FB0001A0A42711A0C1B0E8271C371704700001D +:101FC000C36A0239023B8B4283BF4389006C01FB29 +:101FD0000300002070470000C2F307238A76CB7607 +:101FE0000378032B01BF120C0A75120A4A75704759 +:101FF00000F10B010022D30143EA520310F8012B38 +:1020000052FA83F38842DAB2F5D1104670470000E5 +:1020100010B5417804460020013102464901022AE8 +:1020200016BFA35C032203EBC03302F101021EBF03 +:102030009BB203EB500398B29142F0D810BD000060 +:1020400002684AB1134613F8011B1F290DD93A291A +:10205000F9D1911C8B4202D04FF0FF3070471278BB +:10206000302AF9D1036000207047014B187870477F +:102070009836002038B50D46044618B909200023CB +:102080002B6038BD0368002BF8D01A78002AF5D0F1 +:102090008188DA889142F1D1587804F0B3F910F0D0 +:1020A0000100EBD12368EBE738B50D4640F2523121 +:1020B000144602F0B9F9FF2807D9012C0BD9030AFD +:1020C000022468702B70204638BD30B1002CFAD045 +:1020D00001242870F7E70024F5E70446F3E7000041 +:1020E0002DE9F8430026D0F8008005460C468E7690 +:1020F000836B002B4AD098F80030042B4BD1334629 +:102100003546402720E0B7F5187F80F0C480F906F7 +:1021100006F1010608BF0237D05B02372BB900F584 +:10212000205292B2B2F5006F0DD305F11A01C5F13C +:10213000FF0240EA03402144FFF7B6FF002800F009 +:10214000AA80054400200346D8F8102092F82310F6 +:10215000B142D8D8002B40F09E80002D00F09B802B +:1021600000232544AB766373D8F81020137903F06D +:102170003701DB0621730BD402F13800FFF704FFAF +:10218000C4E9000193896381D3892381BDE8F88381 +:1021900000200146F4E7C36C01335ED1EA6B0023F3 +:1021A0002E26551E184615F8011F013020290CD087 +:1021B000052908BFE521092804D10B2B9EBFE7188C +:1021C00001337E73E718013379730B28EBD1E118E3 +:1021D00000204873A17E00294BD1002B40D06FF026 +:1021E0000C0604F10D000825361B331810F8011BEE +:1021F000002938D02E298BB24AD0A3F141011929E8 +:1022000003D8117B0D4200D020330373EDE7B9F101 +:10221000000F05D100F520539BB2B3F5006F0BD32F +:1022200007F11A01C7F1FF0240EA09402144FFF714 +:102230003BFF48B10744002002368146D8F80C30F5 +:10224000985B0028E3D13846B9F1000F4FF0000247 +:1022500018BF002023189A76A0E7B1463746EDE76D +:102260003F23A3760123234400219976137B03B9EE +:102270006373D37A02F11C0003F03F03237300233E +:10228000FFF780FE20606360D38A6381138B7CE755 +:1022900010250B46B9E73F230125A37660E7000030 +:1022A00038B50546002435F8020B08B9204638BD7C +:1022B00002F0EEF86308C2B203EBC43312FA83F300 +:1022C0009AB2C0F3072303EB520303EBC2339CB271 +:1022D000E9E7000037B5C37804461BB90025284656 +:1022E00003B030BD00F14C01826C012340780191B4 +:1022F00004F0AEF8054680B9A36BE070A06C226BC9 +:10230000C31A9342EAD2A3780199022BE6D1024480 +:102310000123607804F09CF8E1E70125DFE7000085 +:1023200038B5836C05460C468B4210D0FFF7D2FFC0 +:1023300060B92246012305F14C01687804F064F885 +:1023400000281CBF4FF0FF340120AC6438BD0020D2 +:10235000FCE7000038B500230446C3704FF0FF339C +:102360008364FFF7DDFF00284BD1B4F84A524AF6E8 +:1023700055239D4207D10B22254904F14C0006F05C +:1023800027FC00283FD094F84C30EB2B03D01833B7 +:10239000DBB2012B2ED84AF655239D4206D10822E6 +:1023A0001C4904F19E0006F013FC48B3B4F8573002 +:1023B000B3F5007F1ED194F85930DBB15A1E1A4292 +:1023C00018D1B4F85A30ABB194F85C30013B012B12 +:1023D00010D8B4F85D306BB1B4F85F307F2B06D8FD +:1023E00004F16C00FFF7CEFDB0F5803F02D3B4F8E6 +:1023F000623053B94AF6552085420CBF02200320B3 +:1024000038BD0420FCE70120FAE70020F8E700BF10 +:10241000048E0008108E000802392DE9F04701F003 +:1024200007044FF0010A466C05460AFA04F4174601 +:10243000984606EB1136C1F3C809E4B23146284686 +:102440000136FFF76DFF18B10120BDE8F08799460E +:1024500005EB090292F84C30234214BF0121002100 +:10246000414513D06340013F82F84C3085F803A00A +:10247000EBD0640014F0FF04EAD109F10103012458 +:102480004FF00009B3F5007FE1D1D7E70220DCE788 +:1024900001290246F8B50C4640F28C800668F36AC2 +:1024A0008B4240F287803378013B032B00F282801D +:1024B000DFE803F00229384B04EB5405B16B3046DA +:1024C00001EB5521FFF72CFF10B14FF0FF30F8BDA5 +:1024D0006F1CC5F30805B16B3046354401EB57213D +:1024E00095F84C50FFF71CFF0028EED1C7F3080702 +:1024F000E3073E4496F84C0045EA00204CBF000933 +:10250000C0F30B00E3E7B16B304601EB1421FFF79A +:1025100007FF0028D9D1640004F4FF742644B6F8FC +:102520004C00D4E7B16B304601EBD411FFF7F8FE55 +:102530000028CAD1A40006F14C0004F4FE74204423 +:10254000FFF720FD20F07040C1E7D0E90430D579D5 +:1025500053EA000101D0916801B95DBB9168022D79 +:10256000A4EB01010DD1013B728940F1FF305B0A00 +:1025700043EAC053B3FBF2F399421BD81CD0601C52 +:10258000A5E7032D02D193698B42F8D8D3699BB993 +:10259000B16B304601EBD411FFF7C2FE002894D195 +:1025A000A0004C3600F4FE703044FFF7EBFC20F046 +:1025B00000408CE701208AE76FF0004087E70000C9 +:1025C000F8B5066804460D463378042B0CBF4FF06F +:1025D00080524FF400128A4201D80220F8BDCA0688 +:1025E000FBD182680163D2B9022B13D83389B3EBD4 +:1025F000551FF2D9F36BA363A36B6263002BECD07E +:1026000003EB55234C36C5F308050020A36335447E +:10261000E563E3E7F36BC271002BE7D01A467789D5 +:102620007F02BD42114604D23046FFF7C9FCA063C9 +:10263000E2E72046FFF72CFF431C024606D00128A4 +:10264000CBD9F36A8342C8D9ED1BEAE70120C5E77D +:1026500001292DE9F04706460C46174608D9C36AFA +:102660008B4205D90378022B62D003D8012B22D0EC +:10267000022552E0033B012BFAD8816B01EBD41108 +:10268000FFF74EFE0546002847D1A40006F14C0393 +:1026900004F4FE741C443378042B07D0204627F042 +:1026A0007047FFF76FFC00F0704007433946204643 +:1026B000FFF76EFC2FE001EB5108816B01EB582115 +:1026C000FFF72EFE054640BB14F0010406F14C094D +:1026D00008F1010AC8F3080808BFFBB230461FBF63 +:1026E00019F8083003F00F023B0103F0F00318BFA4 +:1026F000134309F808300123B16BF37001EB5A2141 +:10270000FFF70EFE054640B9CAF3080A44B1C7F305 +:10271000071709F80A700123F3702846BDE8F0870F +:1027200019F80A30C7F3032723F00F031F43F0E71C +:10273000816B01EB1421FFF7F3FD05460028ECD176 +:10274000640006F14C0304F4FF741F551919C7F314 +:1027500007274F70DFE70000F8B504460E4617461E +:10276000E3690BB91846F8BD012BA6EB03052068F9 +:1027700014BFAA1C3A46691CFFF76AFF0028F2D171 +:10278000E369013BE361EBE701292DE9F8430646E4 +:102790000C461746056802D80220BDE8F883EB6AAC +:1027A0008B42F9D97AB9A14621463046A046FFF7B7 +:1027B0006FFE0446B0B92B78042B02D1002F43D111 +:1027C000F7710020E9E72B78042B02D1C379022BA3 +:1027D000E9D04FF0FF3239462846FFF739FF00288D +:1027E000E1D0DAE70128D7D0421C01D10120D4E79B +:1027F0002B78042B19D1EA6AAB69023A93421CD3B5 +:1028000008F10102A2420CD02B78042B08D100233E +:10281000A2EB090249462846FFF7FEFD0028BCD17D +:10282000A146EB6AA342BFD8C5E70022414628462D +:10283000FFF70EFF0028DED0AFE70133AB612B7945 +:1028400043F001032B71DBE7F3798BB9B468BC4229 +:1028500002D10223F371B4E721463046FFF718FE98 +:10286000012899D9431CC1D001348442EFD0A8E794 +:10287000032BA6D1B368BB42A3D8B2691344BB42B1 +:102880009FD3E6E770B5C3790446032B06D1816870 +:102890008369CD18A94203D10023E371002070BDE4 +:1028A0004E1C20683246FFF7D3FE0028F7D1314690 +:1028B000F0E700002DE9F74305460191FFF70AFD17 +:1028C0000446002849D105F14C09019928464FF4E6 +:1028D0000072FFF775FB2146A86407464846FFF7DC +:1028E00021FA6C896402B4F5004F28BF4FF400440C +:1028F000B4F5007F2FD9204604F00CFA804630B1A1 +:1029000022460021640A0026FFF70CFA09E0640859 +:10291000EEE72346BA194146687803F099FD18B9E5 +:1029200026446B899E42F4D3404604F003FA68893A +:10293000801B18BF012003B0BDE8F08301366B890E +:102940009E42F4D20123BA194946687803F080FD0B +:102950000028F3D0EBE70026F1E70120EBE70000C9 +:10296000F8B50446FFF7B6FC0546002842D12378A7 +:10297000032B37D12779012F34D104F14C060146BE +:102980004FF400723046FFF7CDF9552341227221F2 +:1029900084F84A32AA2304F50D7084F84F2084F895 +:1029A0004B32522384F8301284F84C3084F84D3086 +:1029B000612384F8311284F84E3084F83332A169EF +:1029C00084F83222FFF7E4FA616904F50E70FFF72C +:1029D000DFFA626B3B46314601326078A26403F055 +:1029E00037FD257100226078114603F055FD00384F +:1029F00018BF0120F8BD000000232DE9F0430B6053 +:102A000085B00F461546FFF71BFB061EC0F2B281CC +:102A1000804B53F82640002C00F0AE813C6005F05E +:102A2000FE0523786BB1607803F0ECFCC70708D48F +:102A30001DB110F0040500D00A25284605B0BDE8F8 +:102A4000F0830023F0B22370607003F0C7FCC1076D +:102A500000F194810DB14207EED400212046FFF72A +:102A600079FC022840F099806E4604F2122304F2A9 +:102A70005221324618461033FFF784FA42F8040B0D +:102A80008B42F7D1002556F8041B00297DD0204643 +:102A9000FFF760FC012879D80128A26C40F0C080C3 +:102AA00004F1570304F18C0113F8015B002D7BD175 +:102AB0008B42F9D1B4F8B430B3F5807F74D194F877 +:102AC000B830092B70D104F19400FFF75DFA4FF094 +:102AD000FF33171841F10001BB4275EB010363D3CB +:102AE00004F1A000FFF74EFA94F8BA302063012BEE +:102AF000A37059D194F8B99003FA09F91FFA89F330 +:102B00006381002B50D0444B04F1A800FFF73AFA40 +:102B10000646984248D8831C626304F1A400E3622D +:102B2000FFF730FA00EB020804F19C00C4F8408083 +:102B3000FFF728FA10441FFA89F2A06306FB02F39C +:102B400013EB080345EB05029F4271EB02032BD305 +:102B50002E4604F1AC00FFF715FAE06365B963890E +:102B6000B34221D9E16B2046FFF72AFA81192046AA +:102B7000FFF7D6FB98B90136631993F84C30812BD7 +:102B800014D02035C5F30805E8E703200135042DEE +:102B90007FF479AF042807D101E0042801D1012591 +:102BA0004BE701287FF678AF0D2546E705F11400C5 +:102BB00004F14C063044FFF7E5F901280546F3D946 +:102BC000E36A8342F0D96189821E236C02FB0133E0 +:102BD0006364A16B204601EBD511FFF7A1FB002830 +:102BE000DDD105F07F0006EB8000FFF7CBF9431C39 +:102BF00003D00135A842ECD0D6E70425C4E905008E +:102C0000064A257000251388E56101339BB21380C5 +:102C1000E38012E79C360020FDFFFF7FA0360020F6 +:102C2000B4F85730B3F5007FBED1B4F8626026B96E +:102C300004F17000FFF7A6F9064694F85C302663AD +:102C4000591EA3700129AFD894F859506581002D01 +:102C5000AAD0691E2942A7D1B4F85D8018F00F0FE1 +:102C6000A4F80880A0D1B4F85F0018B904F16C0092 +:102C7000FFF788F9B4F85A10002995D006FB03FE37 +:102C800001EB181CF44460458ED3A0EB0C00A84265 +:102C9000B0FBF5F388D33E48834285D84FF6F570F4 +:102CA00083426DD903259F1C114402EB0C03032DB5 +:102CB000E7626263A16323644CD1B4F8763053EACF +:102CC00008037FF471AFBB0004F17800FFF75AF9F5 +:102CD000E06303F2FF13B6EB532FFFF465AF4FF041 +:102CE000FF33032DC4E905334FF08003237187D1EF +:102CF000B4F87C30012B83D1511C2046FFF710FB28 +:102D000000287FF47DAFB4F84A224AF6552320719B +:102D10009A427FF475AF1F4B04F14C00FFF732F974 +:102D200098427FF46DAF03F1FF5304F50C70FFF789 +:102D300029F903F50053203398427FF461AF04F57D +:102D40000D70FFF71FF9A06104F50E70FFF71AF977 +:102D5000606155E7B8F1000F3FF426AF7144022DD2 +:102D60004FEA4703E1631EBFD91907F0010303EBE4 +:102D70005103AEE70B2560E60C255EE603255CE615 +:102D800040F6F575AB428CBF022501258BE700BFED +:102D9000F5FFFF0F525261412DE9F84F07460568D4 +:102DA000884649B96E69C6B1EB6AB34298BF01263D +:102DB000AB69A3B9002405E0FFF76AFB01280446CC +:102DC00003D801242046BDE8F88F421C00F0D280D1 +:102DD000EB6A8342F6D84646EAE70126E8E72A7816 +:102DE000EB6A042A40F08380A6F1020A023B4FF00E +:102DF000010B9A4528BF4FF0000AD146696C28465E +:102E000001EB1931FFF78CFA00283BD109F00703D9 +:102E1000EA6AC9F3C8010BFA03F3901EDBB26A1821 +:102E20004C4609F1010992F84C20814502EA03025F +:102E300033BF5B0000234FF40071DBB228BF99461B +:102E4000B2B90234631E0333BCD80123214628469D +:102E50001A46FFF7E1FA0228B3D0012800F08A8071 +:102E6000B8F1000F13D10223FB710028A9D130E083 +:102E7000CA450AD0002BD2D10131B1F5007FBDD2B5 +:102E80000123CCE74FF0FF34DCE70024DAE7FB79DD +:102E9000022B07D1731CA342E7D0BB68F31ABB61B6 +:102EA0000323FB7108F10102FB69A24205D113B1B2 +:102EB0000133FB61D9E70223FBE70BB90123FB6177 +:102EC000224641463846FFF747FC00284FD10123F0 +:102ED000FB61EA6AAB69023A6C6193429CBF03F101 +:102EE000FF33AB612B7943F001032B716AE7464551 +:102EF00014D1741C3846A34298BF02242146FFF720 +:102F0000C7FA01283FF45DAF431C33D0E0B16B69D1 +:102F1000012B03D9EA6A934238BF1E463446013476 +:102F2000EB6AA34203D8012E7FF644AF0224214668 +:102F30003846FFF7ADFA48B101283FF442AF0130FF +:102F400018D0B442EBD135E7002CE7D04FF0FF3278 +:102F500021462846FFF77CFB48B9B8F1000FB8D0EE +:102F6000224641462846FFF773FB0028B1D00128CE +:102F70007FF427AF4FF0FF3424E700002DE9F8433A +:102F800006680446076B894633782037042B0CBF4C +:102F90004FF080534FF40013BB429CBF0023836368 +:102FA000836B73B1C7F30808B8F1000F3CD101334C +:102FB000416B836339B93389B3EB571F34D800238E +:102FC000A36304200AE07389013B13EA57232BD142 +:102FD000FFF75EFA0128054602D80220BDE8F88313 +:102FE000421C01D10120F9E7F36A834216D8B9F1F6 +:102FF000000FE4D0616B2046FFF7CEFE0546C8B156 +:103000000128EAD0431CEDD001463046FFF752FCC0 +:103010000028E7D1E37943F00403E3712946304601 +:103020006563FEF7CDFFA0634C360020276346445E +:10303000E663D3E70720D1E7F8B50E460021044642 +:103040000768FFF7BDFA98B90546A16B3846FFF748 +:1030500067F968B93A78E36B042A1B780CD11B0630 +:103060000ED5054601212046FFF788FF0028ECD049 +:10307000042808BF072006E0E52B01D0002BF0D183 +:103080000135B542EED1F8BDC16C4B1C2DE9F041C4 +:1030900004460568066B1FD1E5274FF00108A16BB8 +:1030A0002846FFF73DF998B92A78E36B042A09BF4F +:1030B0001A781F7002F07F021A7085F80380236B64 +:1030C000B3420DD200212046FFF758FF0028E6D07A +:1030D000042808BF022003E0FFF772FA0028DBD0C3 +:1030E000BDE8F0812DE9F04105460068A96B06694D +:1030F000FFF716F9044620B9EB6B1A78852A03D03E +:1031000002242046BDE8F081324603F1200153F845 +:10311000040B8B4242F8040BF9D1777801377F0119 +:10312000A7F16003B3F5007FEAD800212846FFF736 +:1031300025FF04280446E3D00028E2D1A96B2868C3 +:10314000FFF7EEF804460028DBD1EB6B1A78C02AB3 +:10315000D6D106F1200203F1200153F8040B8B4273 +:1031600042F8040BF9D196F823300F222C33B3FB2D +:10317000F2F3B7EB431FC3D34FF0400800212846BA +:10318000FFF7FCFE04280446BAD00028B9D1A96B89 +:103190002868FFF7C5F804460028B2D1EB6B1A780F +:1031A000C12AADD1B8F5187F09D206EB080203F1A8 +:1031B000200153F8040B8B4242F8040BF9D108F1BB +:1031C00020084745DAD8B8F5187F9AD83046FEF778 +:1031D0001FFF7388834294D092E700000B6800229F +:1031E00010B5036004460B6A83604B6AC261C37109 +:1031F00023F0FF03896AC0E90432C164FFF7E0F9F4 +:1032000020B92046BDE81040FFF76CBF10BD00009C +:10321000F8B50368054601271C692046FEF7F8FE4D +:10322000A070000A6678E0702846E96CFFF7C8F9DC +:1032300020B1022828BF0220C0B2F8BDA96B2868BF +:10324000FFF76EF80028F4D1EB6B04F1200254F87C +:10325000041B944243F8041BF9D12B68DF70002E45 +:10326000E7D000212846013EFFF788FEE0E7000096 +:103270002DE9F8434FF0FF08064607680424454649 +:103280004FF6FF79B16B11B9002C73D063E038466B +:10329000FFF746F8044600285DD1F06B0378002B59 +:1032A0006ED03A78042A11D1852B4DD1336B30463C +:1032B000F364FFF717FF044600284CD13B691B79E4 +:1032C00003F03F03B3712046BDE8F883C27AE52BD3 +:1032D00002F03F02B27143D02E2B41D022F02001E8 +:1032E00008293DD00F2A40D1590637D503F0BF0534 +:1032F000336B90F80D80F364437B434530D1428BB0 +:1033000072BB03780D21FC6823F04003DFF874E002 +:10331000013B4B4301211EF801CB30F80CC009B32F +:10332000FF2B1DD824F813C06146013301320D2A4A +:10333000F1D10278520605D521B1FF2B10D8002219 +:1033400024F81320013DEDB200213046FFF716FEB0 +:103350000446002896D00023B363B4E7AB42CBD039 +:10336000FF25F1E7CC45E1D0FAE72DB9FEF740FEA5 +:10337000404501D10024A6E74FF0FF33F364A2E7F4 +:103380000424E8E7AC8E00082DE9F04F002187B057 +:103390000446D0F80090FFF713F9804670B999F809 +:1033A0000030042B33D1D9F80C00FEF779FF074623 +:1033B0002046FFF75DFF054620B18046404607B036 +:1033C000BDE8F08FD9F810309A8CBA42F0D193F85A +:1033D00023B040265D4506D1D9F80C3033F81530BE +:1033E000002BE5D1EAE7F106D9F8103008BF023624 +:1033F000985B01F04DF8D9F80C30824633F815008F +:1034000001F046F88245D3D102360135E2E74FF0AC +:10341000FF0A4FF0FF3B5546C4F84CB0A16B48463D +:10342000FEF77EFF00285CD1E66B3778002F77D05F +:10343000F27AE52F02F03F03A37103D0120704D5FF +:103440000F2B04D0C4F84CB04FE00F2B54D194F89C +:103450004B3058063FD4790645D5236B07F0BF079C +:1034600096F80DA0E364737B53453ED1738B002B1C +:103470003BD135780121D9F80C3005F03F05019397 +:103480000D23013D5D43284B13F8012BB25A71B354 +:10349000FF2D059329D81046049200F0F9FF6B1C0C +:1034A00003900293019B33F8150000F0F1FF03999C +:1034B00081421AD1049A029D1146059B1B4A9342F0 +:1034C000E2D133785A0604D519B1019B33F815308F +:1034D0005BB97D1EEDB200212046FFF74FFD0028AD +:1034E0009CD080466AE7BD42BDD0FF25F3E74FF68A +:1034F000FF708242E2D0F8E72DB93046FEF778FD42 +:1035000050453FF45BAF94F84B30DB079AD40B2265 +:1035100004F14001304605F05BFB002892D14DE7F5 +:103520004FF004084AE700BFAC8E0008B98E0008CF +:103530002DE9F04F90F84BB099B004461BF0A00570 +:1035400040F068810668F26832F81530002B4AD1E5 +:103550003378042B40F087800F230E352046B5FBCF +:10356000F3F5A91CFFF768FD8146002877D1236B8E +:103570000135A3EB4515E3795A07E56435D523F00A +:1035800004032046E371FFF77DF950BB4FF0FF3293 +:10359000616B2046FFF7E0F818BBA3682BB3214608 +:1035A00004A8FFF71BFEE0B970894FF40071D4E95D +:1035B0000423E0FB01233069C4E904233830FEF71B +:1035C000EFFC3069D4E904232830FEF7E9FCE37905 +:1035D000326904A843F0010382F82130FFF718FE96 +:1035E00018B181463BE00135AEE7D6E903544022ED +:1035F00000212046FEF796FB8523012140222370FF +:10360000C0234FF0C10C04EB010884F820300023E4 +:103610001E469E46571C04F802C0F0B2023204F85F +:1036200007E021B135F8131009B10133DBB20F0AFD +:10363000A15408F802700232D706F2D135F813709F +:103640000136002FE6D184F82330831C28466370AE +:10365000FEF726FE84F82400000A84F82500484678 +:1036600019B0BDE8F08F04F140070DF1100A1BF00E +:10367000010F97E807008AE8070000F0D380402395 +:103680004FF0010884F84B30BC46F368B8F1050FE1 +:103690009AE80700ACE803002CF8022B4FEA12422C +:1036A0008CF8002059D9981E424630F8021F002994 +:1036B00042D10DF10F0C072102F00F0E91461209B5 +:1036C0000EF13000392888BF0EF1370001390CF8AF +:1036D000010902D0B9F10F0FEED818AB7E205A18AD +:1036E00002F8580C38460022914206D010F801CB5F +:1036F00002F1010EBCF1200F31D104F13F0C07297A +:1037000002F1010297BF18AB20205818013198BF71 +:1037100010F8580C072A0CF80200F0D92046FFF7E1 +:1037200033FE8146002878D108F10108B8F1640F12 +:10373000AAD14FF0070992E74FF0100C01F0010EEB +:1037400049080EEB4202D30344BF82F4883282F070 +:103750002102BCF1010CF1D1A7E74246A9E772466C +:10376000C2E7216B2046A1EB4511FEF729FF8146F8 +:1037700000287FF474AF4FF6FF783846FEF738FC28 +:103780000190A16B3046FEF7CBFD814600287FF407 +:1037900066AFE36BE9B2019A4FF00D0CD6F80CE07E +:1037A0005A734FF00F02DFF8E0A0DA724A1E187366 +:1037B0000CFB02F284469876D87640451AF8019BB5 +:1037C0000CF1010C18BF3EF8120003EB090B18BFF7 +:1037D000013203F809004FEA1029002808BF4046CB +:1037E000BCF10D0F8BF80190E7D1404502D03EF8B7 +:1037F00012200AB941F0400119700123002120462E +:10380000F370FFF7BBFB814600287FF428AF013D32 +:10381000B7D11BE04FF0060921E704287FF41FAF62 +:1038200084F84BB01BF0020F20461BBF0C350D2156 +:103830000125B5FBF1F518BF01352946FFF7FCFB63 +:10384000814600287FF40BAF013D8AD1A16B304641 +:10385000FEF766FD814600287FF401AF0146202275 +:10386000E06BFEF75FFAE36B03CF18605960BA783C +:1038700039889A72198194F84B30E26B03F018037F +:1038800013730123F370EAE6AC8E000810B504460A +:103890000A463430FEF776FB886004F13800FEF704 +:1038A00073FBC2E9040194F8213003F00203D371E1 +:1038B0000023D36110BD000003284B8B04BF8A8A0C +:1038C00043EA0243184670472DE9F04F0B7899B050 +:1038D000044689462F2BD0F800B001D05C2B09D1CB +:1038E0004A461378914601322F2BFAD05C2BF8D040 +:1038F000002301E0DBF81C30A3600023E3619BF8A8 +:103900000030042B1ED1A368E3B1DBF82030214640 +:1039100004A82362DBF824306362DBF82830A3625A +:10392000FFF75CFC0346002854D1DBF8102002F1BD +:103930003800FEF727FBC4E9040392F8213003F0B6 +:103940000203E37199F800301F2B00F235818023C8 +:103950000021204684F84B3019B0BDE8F04FFEF747 +:103960002FBE49460B78894601312F2BFAD05C2BAC +:10397000F8D01F2B8CBF00250425012F2FD11388D1 +:103980002E2B31D1002322F8173004F140029F4240 +:103990008CBF2E21202101330B2B02F8011BF6D105 +:1039A00045F02005204684F84B50FFF7EDFC94F8D5 +:1039B0004B30002800F0E78004280BD1990603F073 +:1039C000040240F1DC80002A00F0F6808023002011 +:1039D00084F84B3019B0BDE8F08F0425CDE7022FF5 +:1039E00002D153882E2BCAD0911E87BB002322F808 +:1039F0001730002F00F0118132F8130019460133FF +:103A00002028F9D009B92E2801D145F00305901ED0 +:103A100030F817302E2B01D0013FF9D14FF0203371 +:103A20004FF0000A6364D0462364C4F8473008238B +:103A3000481C32F811600090F6B1202E03D02E2ED3 +:103A40000DD1B84210D045F003050099F0E731F8E8 +:103A50001730202B01D02E2BC8D1013FC5E79A4546 +:103A600005D20099B9423BD10B2B30D101E00B2B91 +:103A700027D145F003050B2394F84020E52A04BF25 +:103A8000052284F84020082B04BF4FEA88085FFA1B +:103A900088F808F00C030C2B03D008F00303032B69 +:103AA00001D145F00205A8073FF57CAF18F0010FE2 +:103AB00018BF45F0100518F0040F18BF45F00805B1 +:103AC00070E70099B94202D045F00305D4D84FEA17 +:103AD00088080B234FF0080A00975FFA88F8B4E7CC +:103AE0007F2E15D9304640F25231CDE9022345F000 +:103AF0000203019300F098FC10F0800F0646DDE908 +:103B0000022316D000F07F0646498E5D019D46B324 +:103B100031464548CDE9012305F0C8F8DDE9012328 +:103B2000F8B9A6F1410189B219291ED848F0020856 +:103B300010E0FF28EAD9591E8A4503D345F0030552 +:103B40009A4682E704EB0A01000A0AF1010A019D84 +:103B500081F8400004EB0A010AF1010A81F8406093 +:103B600073E745F003055F26F4E7A6F1610189B22A +:103B700019299EBF203E48F00108B6B2EAE7002AA4 +:103B800008BF052026E75A073FF524AFA379DB06D7 +:103B900045D59BF80000042835D1A3682146E27979 +:103BA00023622369DBF8100023F0FF0313436362F1 +:103BB000E36CA362FFF76AFE23680027DA6819F84E +:103BC000010B00283FF409AF40F25231009200F09F +:103BD0004BFC054608B31F28009A7FF6FEAE2F283F +:103BE0003FF4BFAE5C283FF4BCAE7F2805D8014649 +:103BF0000E4805F05BF8009A78B9FF2F0DD022F837 +:103C000017500137DBE7216B0BF14C03C1F30801BF +:103C10001944FFF751FEA060CEE70620DAE6052042 +:103C2000D8E600BF2C8E0008258E00081C8E0008E8 +:103C30001FB5CDE9001003A814460391FEF700FA62 +:103C4000002815DB0B4A52F820300BB10021197007 +:103C5000019B0BB10021197042F820302CB10022D9 +:103C600001A96846FEF7C8FE0446204604B010BD10 +:103C70000B24FAE79C3600202DE9F04798B09046D7 +:103C800005460191002800F0528102F03F0603A989 +:103C900001A83246FEF7B0FE002840F04681039BA3 +:103CA0004FF48C60049303F035F80746002800F0C9 +:103CB0004081039B00F500720199D86004A81A6145 +:103CC000FFF702FE044620B99DF95B30002BB8BF18 +:103CD000062418F01C0F00F0CD80002C4CD0042CD2 +:103CE00040D104A8FFF724FC044600283AD146F04E +:103CF0000806039B1A78042A40F083801869294635 +:103D00002B60FFF7C3FD039B1E22002118690230C0 +:103D1000FEF708F8039C00211A2220692630FEF7DE +:103D200001F8236920221A71246903F011F8014671 +:103D3000012208342046FEF72BF9039B04A81B69D7 +:103D400083F82120FFF764FA044658B9A96801B343 +:103D500002462846FEF718FDAB68039A0446013B6D +:103D60005361B4B1384602F0E5FF0CB100232B607B +:103D7000204618B0BDE8F0879DF8163013F0110FFB +:103D800040F0848018F0040F40F0C98018F0080F4C +:103D9000AFD1039A31071399936C48BF46F04006A0 +:103DA000E964AB641078042872D1069B9DF8171063 +:103DB0002B62089B106923F0FF030B4329466B62BB +:103DC000179BAB62FFF762FDDDF80CA00024002218 +:103DD00005F15008BAF8063021464046C5F800A063 +:103DE000AB80002385F8306085F831406C64C5E90C +:103DF0000E234FF40072FDF795FFB20653D4002452 +:103E0000B0E702F0A5FF0146009013980E30FEF7D0 +:103E1000BFF8139800991630FEF7BAF8039C13996F +:103E20002078FFF749FD202300228046CB722046F0 +:103E30001399FEF7D1F8139B002201211A775A77C4 +:103E40009A77DA77039BD970B8F1000FA1D0414679 +:103E500004A8D3F84890FEF797FC0446002881D1C7 +:103E600049460398FEF75CFA039B044608F1FF30CD +:103E7000586176E7002C7FF475AF9DF81630DC06AC +:103E80004FD418F0020F84D0D80782D5072469E7F1 +:103E9000FFF712FD0023A86001F11C00FEF772F885 +:103EA0006B61286190E7D5E9046956EA0903A6D059 +:103EB000BAF80AA0A9684FEA4A2AC5E90E69B245CC +:103EC00074EB09031BD300242964002C7FF44AAF50 +:103ED000C6F30803002B92D0039C2046FEF770F82F +:103EE00008B3760A0123414646EAC95682196A6434 +:103EF000607802F089FA041E18BF012432E72846D0 +:103F0000FEF7C6FAB6EB0A06014669F10009012878 +:103F100003D9431CD3D10124D6E70224D4E70824D3 +:103F200020E704241EE702241CE704461EE70924B8 +:103F30001EE711241CE700002DE9F04F994685B0DB +:103F40000023884603A90446C9F800301646FEF748 +:103F500091F8054680BB94F831506DBB94F8303031 +:103F600013F00103009300F0A68004F1500AD4E995 +:103F70000432D4E90E011B1A62EB0102B34272F162 +:103F8000000238BF1E46BEB1D4E90E10C1F30803CB +:103F9000002B40F08280039B5A894B0A013A43EA86 +:103FA000C0531A401BD151EA000309D1A06801286F +:103FB0000DD8022584F83150284605B0BDE8F08FB1 +:103FC000216C20460192FEF763FA019AEFE7431C49 +:103FD00004D10123009D84F83130EDE72064DDF841 +:103FE0000CB0216C5846FDF7EBFF0028E1D0B6F588 +:103FF000007F02EB000731D3BBF80A1002EB56201A +:10400000730A88429BF8010088BF8B1A3A464146E2 +:10401000019302F0F9F90028DBD194F93020019BDB +:10402000002A0BDA606CC01B984207D24FF4007272 +:10403000514608EB4020FDF74FFE019B5F02D9F887 +:104040000030F61BB8443B44C9F80030D4E90E32C6 +:10405000DB1942F10002C4E90E3294E7626CBA4205 +:104060001AD094F93030002B0DDA012351469BF819 +:10407000010002F0EDF90028ABD194F8303003F0E4 +:104080007F0384F83030039801233A465146407844 +:1040900002F0BAF900289CD16764A16B4046C1F3D5 +:1040A0000801C1F500775144B74228BF37463A4668 +:1040B000FDF712FEC3E707257EE7000070B596B056 +:1040C0000E460022019002A901A8FEF795FC0446C5 +:1040D000E0B94FF48C6002F01DFE0546D8B1029B9A +:1040E00000F500720199D86002A81A61FFF7ECFB95 +:1040F000044640B99DF95330002B0ADB1EB131460E +:1041000002A8FDF7EDFF284602F014FE204616B087 +:1041100070BD0624F7E71124F8E7000070B5B8B0C9 +:104120000222019003A901A8FEF766FC044608BB21 +:10413000039B4FF48C60109302F0ECFD05460028C1 +:1041400066D0039B00F500720199D86010A81A612F +:10415000FFF7BAFB044650B99DF88B30980655D44A +:10416000190653D49DF84630DA0706D507242846A9 +:1041700002F0E0FD204638B070BD039B0493187830 +:10418000042814D104A91869FFF780FB069E9DF846 +:104190004630DB0610D410A8FEF776FF0446002850 +:1041A000E5D156BB0398FEF7DBFB0446DFE71F991A +:1041B000FFF782FB0646EAE7039BDA69B242D5D0F5 +:1041C00024930021269624A81B78042B01BFDDE947 +:1041D0000823CDE928239DF817308DF89730FEF796 +:1041E000EFF904460028C2D124A8FFF741F804469D +:1041F0000028BBD00428BAD1CDE70246314604A836 +:10420000FEF7C2FA04460028B1D1CBE70624AEE798 +:104210001124AFE7F0B5BDB0CDE900106846FDF759 +:104220000FFF022203A901A8FEF7E6FB04460028BF +:1042300041D1039B4FF48C60149302F06BFD054653 +:10424000002800F0EE80039B00F5007214AE019987 +:10425000D8601A613046FFF737FB044640BB9DF833 +:104260009B3013F0A00F40F0D880039B009F1A787A +:10427000042A68D11B6904AC03F1400C18680833A8 +:1042800053F8041C2246634503C21446F6D150225B +:10429000314628A8FDF720FD394628A8FFF714FB72 +:1042A000044600284CD12A9A169B9A4206D008242C +:1042B000284602F03FFD20463DB0F0BD349A209BD9 +:1042C0009A42F4D128A8FFF733F904460028EFD129 +:1042D000039B04AF1B6993F801E093F823C09C8C07 +:1042E0003A46083303CAB24243F8080C43F8041CA8 +:1042F0001746F5D1039B28A81B6983F801E0039BAF +:104300001A6982F823C01A6982F82440240A82F8C4 +:1043100025401A691379D9065CBF43F02003137155 +:10432000FEF776FF04460028C2D13046FEF7ACFE09 +:1043300004460028BCD10398FEF712FB0446B7E7F9 +:104340000428B5D1BEE7239A04AB02F1200C106813 +:10435000083252F8041C1C46624503C42346F6D1B9 +:104360005022314628A8FDF7B7FC394628A8FFF7A8 +:10437000ABFA044600284CD12A9A169B9A4296D151 +:10438000349A209B9A4292D128A8FFF7D1F804468C +:1043900000288DD137990DF11D030DF12D0001F18C +:1043A0000D0253F8044B834242F8044BF9D11888AC +:1043B000012710809B7893709DF81B30039CDA06D0 +:1043C00058BF43F02003CB72E770CB7ADB06ACD545 +:1043D000169A2A9B9A42A8D02078FFF76DFA0146D8 +:1043E0002046FDF7EDFD0146C8B12046FDF798FFD8 +:1043F000044600287FF45CAF039890F86D302E2BB4 +:1044000093D12A9A00F16C01FDF7E6FD039BDF7062 +:104410008BE704287FF44CAFB6E7062448E7022474 +:1044200046E7112447E700007F2810B501D880B285 +:1044300010BDB0F5803F13D240F2523399420FD1F4 +:104440000849002231F8024B93B2844203D103F1B0 +:104450008000C0B2ECE70132802AF3D11346F6E7C0 +:104460000020E5E76C9100087F280DD940F2523317 +:10447000994208D1FF2806D800F10040034B80384C +:1044800033F8100070470020704700BF6C9100089F +:10449000B0F5803FF0B522D21F4A83B21F49B0F574 +:1044A000805F28BF0A46141D34F8042C2146AAB1A7 +:1044B000934213D334F8025C2E0AEFB252FA85F518 +:1044C000A84222DA082E09D8DFE806F0050A101201 +:1044D0001416181A1C00801A34F810301846F0BD53 +:1044E000981A00F001001B1A9BB2F7E7103BFBE79C +:1044F000203BF9E7303BF7E71A3BF5E70833F3E7F2 +:10450000503BF1E7A3F5E353EEE70434002ECBD1A3 +:1045100001EB4702C7E700BFBC8E0008B09000085F +:10452000084BC26A994228BF1946836C50688B4277 +:1045300010B506D95A1E4C0002EB4103B3FBF4F34D +:10454000184410BD20BCBE0001F001038A0748BF1B +:1045500043F002034A0748BF43F008030A0748BF75 +:1045600043F00403CA0648BF43F010038A06426BB7 +:1045700048BF43F0200313434363704710B5074C13 +:10458000204600F093FF064B0022C4E91023054BA0 +:10459000A364054BE363054BE36410BDA436002020 +:1045A0000070005200B4C404F8360020F83800202F +:1045B000C36A0BB90E4BC3620379012B0CD10D4BAF +:1045C000984209D10C4B5A6B42F480325A63DA6D2F +:1045D00042F48032DA65DB6D436C00221A65DA62E0 +:1045E0001A605A605A624FF0FF329A63704700BFF8 +:1045F0006C920008A4360020004502580379012B74 +:1046000016D0436C00221A65DA621A605A605A6248 +:104610004FF0FF329A63074B984209D1064B5A6B11 +:1046200022F480325A63DA6D22F48032DA65DB6D6F +:10463000704700BFA43600200045025810B5446CF6 +:104640000649FFF76DFF6060236842F2107043F087 +:1046500003032360BDE8104001F048BD801A060046 +:104660000129F8B5466C0B4F09D175680A493D40E0 +:10467000FFF756FF054345F480557560F8BD746833 +:1046800006493C40FFF74CFF044344F480547460F7 +:10469000F4E700BF00ECFFFF80F0FA0240787D01F4 +:1046A000436C00225A601A6070470000426C012976 +:1046B000536823F4404304D0022905D001B9536064 +:1046C000704743F48043FAE743F40043F7E7000000 +:1046D000436C41F480519A60D9605A6B1206FCD544 +:1046E00080229A637047000010B541F48851446CF1 +:1046F000A260E160616B11F04502FBD0A26311F092 +:10470000040203D0FFF720FF012010BD61691046AD +:104710001960FAE710B541F48851446CA260E16079 +:10472000616B11F04502FBD0A26311F0050203D0CA +:10473000FFF70AFF012010BD616910461960FAE712 +:1047400073B5134604460E46302282F31188426C3C +:10475000D26B32B14FF0FF314030019301F0D2FC07 +:10476000019B606C00220265C263C262456B15F456 +:10477000807504D185F31188012002B070BD4FF01F +:10478000FF31816382F31188012E06D90C21204666 +:1047900002B0BDE87040FFF7BDBF1046EDE7000076 +:1047A00073B5446C0E4600250192616BA1632565CB +:1047B000E562FFF7C9FE012E07D9019B2A460C21AD +:1047C00002B0BDE87040FFF7A5BF02B070BD0000A9 +:1047D00010B541F49851446CA260E160616B11F036 +:1047E0004502FBD0A26311F03F0203D0FFF7ACFEFD +:1047F000012010BD216A10461960E1695960A16964 +:1048000099606169D960F4E72DE9F74304460191A5 +:10481000006D01A91746984602F0D4FB0646002811 +:104820004AD0626C2046DDF804905568C5F309054E +:1048300001356B00A56CB5FBF3F54FF47A73B5FB4E +:10484000F3F55D43556200F0F7FD50BB636C4FF02C +:10485000FF3201254146C3F8589020461D659A63F2 +:104860004FF49572DA6342F207029F62DA62E36CF8 +:104870000A9AFFF74FFFA0B9E26C104B11680B408A +:104880007BB929462046FFF75BFF054648B92E460F +:104890003A460199206D02F0BDFB304603B0BDE8F9 +:1048A000F0833A460199206D02F0B4FBE26C0121DD +:1048B0002046FFF775FFF0E70126EEE708E0FFFD71 +:1048C0002DE9F7431F46436C01924FF47A725D68FD +:1048D00004468846C5F3090501356E00856CB5FBB5 +:1048E000F6F5B5FBF2F555435D6200F0A5FD20B18C +:1048F0000125284603B0BDE8F0837E0201A9206DA2 +:10490000324602F05FFB05460028F1D0636C019A45 +:10491000D4F84C909A6501221A654FF0FF329A63E1 +:104920004FF49572DA639E62236BDB064B4658BFE9 +:104930004FEA4828012F42461BD912212046FFF793 +:10494000E9FEC0B9D9F80020104B13409BB9636C45 +:1049500042F2930239462046DA62E26CFFF7F0FE3B +:10496000804640B932460199206D454602F052FB1F +:10497000BFE71121E2E732460199206D02F04AFBC0 +:10498000E26C39462046FFF70BFFB2E708E0FFFD77 +:104990002DE9F3411F46436C01924FF47A725D6832 +:1049A00004468846C5F3090501356E00856CB5FBE4 +:1049B000F6F5B5FBF2F555435D6200F03DFD20B123 +:1049C0000125284602B0BDE8F0817E0201A9206DD4 +:1049D000324602F02DFB05460028F1D0636C019AA7 +:1049E0009A6501221A654FF0FF329A634FF48D7277 +:1049F000DA639E62236BE66CDB06334658BF4FEAF0 +:104A00004828012F424619D919212046FFF782FE76 +:104A1000B0B932680F4B134093B9636C42F2910204 +:104A200039462046DA62E26CFFF78AFE064638B95C +:104A300001993546206D02F027FBC2E71821E4E713 +:104A40000199206D02F020FBE26C39462046FFF709 +:104A5000A7FEB6E708E0FFFD12F0030F2DE9F041D5 +:104A600007460C4615461E4617D00E44B44202D1E6 +:104A70000020BDE8F0810123FA6B21463846FFF79C +:104A80001FFF0028F5D128464FF40072F96B05F599 +:104A900000750134FDF720F9E8E7BDE8F041FFF7C4 +:104AA0000FBF000012F0030F2DE9F04107460C463E +:104AB00015461E4617D00E44B44202D10020BDE870 +:104AC000F08129464FF40072F86B05F50075FDF78B +:104AD00003F90123FA6B21463846FFF759FF0028F6 +:104AE000EDD10134E8E7BDE8F041FFF751BF000028 +:104AF00000207047302310B583F311880024436CE5 +:104B000040302146DC6301F00BFB84F3118810BDBB +:104B1000026843681143016003B118477047000001 +:104B2000024A136843F0C00313607047004400401A +:104B3000024A136843F0C003136070470048004006 +:104B4000024A136843F0C0031360704700780040C6 +:104B5000044B9A6C02439A641A6F104318671B6FD8 +:104B6000704700BF0045025837B5274C274D2046F7 +:104B700000F0FCFC04F11400009400234FF40072D8 +:104B8000234900F097F94FF40072224904F13800EC +:104B90000094214B00F010FA204BC4E91735204C4B +:104BA000204600F0E3FC04F11400009400234FF4CD +:104BB00000721C4900F07EF94FF400721A4904F1AA +:104BC00038000094194B00F0F7F9194BC4E9173578 +:104BD000184C204600F0CAFC04F1140000234FF4E6 +:104BE00000721549009400F065F9144B4FF40072FF +:104BF000134904F13800009400F0DEF9114BC4E9C8 +:104C0000173503B030BD00BFFC38002000E1F505CA +:104C1000403A002040400020214B00080044004062 +:104C200068390020403C002040420020314B000801 +:104C300000480040D4390020403E0020414B00088D +:104C4000404400200078004038B5264D0446037CDF +:104C5000002918BF0D46012B06D1234B984230D1B5 +:104C60004FF40030FFF774FF2A68236EE16D03EB09 +:104C70005203A566B3FBF2F36A68100442BF23F047 +:104C8000070003F0070343EA4003CB60AB6843F03F +:104C900040034B60EB6843F001038B6042F4967372 +:104CA00043F001030B604FF0FF330B62510505D554 +:104CB00012F0102211D0B2F1805F10D084F864306D +:104CC00038BD0A4B984205D0094B9842CCD14FF0E1 +:104CD0008040C7E74FF48020C4E77F23EEE73F23FF +:104CE000ECE700BF74920008FC380020683900200F +:104CF000D43900202DE9F047C66D05463768F469C0 +:104D0000210734621AD014F0080118BF4FF48071E3 +:104D1000E20748BF41F02001A3074FF0300348BF2E +:104D200041F04001600748BF41F0800183F31188E2 +:104D3000281DFFF7EDFE002383F31188E2050AD555 +:104D4000302383F311884FF48061281DFFF7E0FEC4 +:104D5000002383F311884FF030094FF0000A14F05C +:104D6000200838D13B0616D54FF0300905F1380A36 +:104D7000200610D589F31188504600F051F900281B +:104D800036DA0821281DFFF7C3FE27F080033360C1 +:104D9000002383F31188790614D5620612D53023D7 +:104DA00083F31188D5E913239A4208D12B6C33B1D0 +:104DB00027F040071021281DFFF7AAFE37600023C7 +:104DC00083F31188E30618D5AA6E1369ABB1506955 +:104DD000BDE8F047184789F31188736A284695F8AB +:104DE0006410194000F0DCFB8AF31188F469B6E71F +:104DF000B06288F31188F469BAE7BDE8F087000073 +:104E0000F8B51546826804460B46AA4200D285686A +:104E1000A1692669761AB5420BD218462A46FCF7D4 +:104E20005BFFA3692B44A3612846A3685B1BA360B7 +:104E3000F8BD0CD9AF1B18463246FCF74DFF3A4679 +:104E4000E1683044FCF748FFE3683B44EBE7184671 +:104E50002A46FCF741FFE368E5E7000083689342D8 +:104E6000F7B50446154600D28568D4E90460361AC1 +:104E7000B5420BD22A46FCF72FFF63692B446361CE +:104E80002846A3685B1BA36003B0F0BD0DD9324672 +:104E9000AF1B0191FCF720FF01993A46E0683144CD +:104EA000FCF71AFFE3683B44E9E72A46FCF714FFE6 +:104EB000E368E4E710B50A440024C361029B846000 +:104EC000C16002610362C0E90000C0E9051110BDC4 +:104ED00008B5D0E90532934201D1826882B982686F +:104EE000013282605A1C426119700021D0E90432FB +:104EF0009A4224BFC368436101F02CF9002008BD29 +:104F00004FF0FF30FBE7000070B5302304460E463B +:104F100083F31188A568A5B1A368A269013BA360CA +:104F2000531CA36115782269934224BFE368A361EF +:104F3000E3690BB120469847002383F31188284684 +:104F400007E03146204601F0F5F80028E2DA85F363 +:104F5000118870BD2DE9F74F04460E461746984656 +:104F6000D0F81C904FF0300A8AF311884FF0000BF4 +:104F7000154665B12A4631462046FFF741FF0346F4 +:104F800060B94146204601F0D5F80028F1D0002351 +:104F900083F31188781B03B0BDE8F08FB9F1000FDF +:104FA00003D001902046C847019B8BF31188ED1A6E +:104FB0001E448AF31188DCE7C160C361009B8260F4 +:104FC0000362C0E905111144C0E9000001617047A6 +:104FD000F8B504460D461646302383F31188A768BA +:104FE000A7B1A368013BA36063695A1C62611D708D +:104FF000D4E904329A4224BFE3686361E3690BB1E8 +:1050000020469847002080F3118807E0314620466B +:1050100001F090F80028E2DA87F31188F8BD00006B +:10502000D0E9052310B59A4201D182687AB9826825 +:105030000021013282605A1C82611C7803699A4205 +:1050400024BFC368836101F085F8204610BD4FF08E +:10505000FF30FBE72DE9F74F04460E46174698460A +:10506000D0F81C904FF0300A8AF311884FF0000BF3 +:10507000154665B12A4631462046FFF7EFFE034646 +:1050800060B94146204601F055F80028F1D00023D0 +:1050900083F31188781B03B0BDE8F08FB9F1000FDE +:1050A00003D001902046C847019B8BF31188ED1A6D +:1050B0001E448AF31188DCE70379052B05BF836A58 +:1050C000002001204B6004BF4FF400730B60704759 +:1050D00070B55D1E866A04460D44B54205D9436B22 +:1050E00043F080034363012070BD06250571FFF77F +:1050F000B3FC05232371F7E770B55D1E866A04468D +:105100000D44B54205D9436B43F08003436301204E +:1051100070BD07250571FFF7C5FC05232371F7E76F +:1051200038B505790446052D05D108230371FFF72D +:10513000DFFC257138BD0120FCE700000323F0B53A +:10514000037185B00446FFF779FA00222046114624 +:10515000FFF7BEFA4FF4D57203AB08212046FFF7E4 +:10516000D9FA0246B8B901232363039BC3F303238F +:10517000012B09D103AB37212046FFF7CBFA18B931 +:10518000A44B039A1340ABB120460125FFF788FAE0 +:105190000223237137E103AB002237212046FFF7BA +:1051A000B9FA28B99B4A039B1A40002A00F0A7804D +:1051B00002232363236B03F00F03022B40F0A9802B +:1051C0006425954E42F2107000F090FF03AB32461A +:1051D00001212046FFF788FA0028D5D1039B002B38 +:1051E00080F293805A0003D5236B43F010032363AE +:1051F000002204F1080302212046FFF7E9FA0246E3 +:105200000028C1D104F1380303212046FFF782FAB8 +:105210000028B9D104F11805A26B092120462B46BC +:10522000FFF7D6FA0028AFD102ABA26B07212046C8 +:10523000FFF770FA06460028A6D1236B03F00F0390 +:10524000022B40F08F807E227F21284603F07EF9DA +:10525000012840F28780E76B42F2107000F046FFB1 +:1052600008234FF40072394620460096FFF7CCFA27 +:10527000002889D1384603F0B7F9236BA06203F008 +:105280000F03022B72D103AB644A06212046FFF7BD +:1052900041FA002871D15F49039B1940B1FA81F1AD +:1052A00049092046FFF7DCF902AB4FF400721021E8 +:1052B0002046FFF72FFA054600287FF465AF554ECC +:1052C000029B33427FF460AF236B13F00E0F03F0A9 +:1052D0000F0273D0022A7FF457AFE36A19780129CD +:1052E00000F09480022900F09380002900F089806A +:1052F0004B4F2046FFF7DAF903AB3A4676E011460A +:1053000020462263FFF7E4F954E7013D7FF45AAFEA +:105310003AE7444D6426444A3E4F012B18BF1546D8 +:1053200003AB002237212046FFF7F4F900287FF471 +:105330002BAF039B3B427FF427AF03AB2A462921C7 +:105340002046FFF7D1F900287FF41EAF039B002B06 +:10535000FFF648AF013E3FF417AF42F2107000F085 +:10536000C5FEDDE7284603F013F986E77E227F219C +:105370002846E66B03F0EAF808B9002191E700231C +:1053800040223146204600930623FFF73DFA0028CD +:10539000F3D1B3895BBA9B07EFD5244B402231464A +:1053A000204600930623FFF72FFA0028E5D1317C31 +:1053B00001F00F010F3918BF012172E7E36A197874 +:1053C000F9B101297FF4E0AE2046FFF76FF903AB96 +:1053D000A26B37212046FFF79DF900287FF4D4AE59 +:1053E000039B33427FF4D0AE03AB0222062120465A +:1053F000FFF790F900287FF4C7AE039B33427FF498 +:10540000C3AE05232371284605B0F0BD084F70E7F1 +:10541000084F6EE708E0FFFD0080FFC00001B90300 +:105420000000B7030080FF5000001080F1FFFF80F4 +:105430000001B7030002B70337B504460C4D01ABBA +:10544000A26B0D212046FFF765F978B9019B2B422D +:105450000BD1C3F34323042B08D0053B022B04D804 +:105460004FF47A7000F042FEE9E7012003B030BD4E +:1054700008E0FFFD70B53023054683F311880379FA +:105480000024022B03D184F31188204670BD04232D +:10549000037184F311880226FFF7CEFF04462846E5 +:1054A000FFF7FEF82E71F0E7FFF768B8044B0360D2 +:1054B0000123037100234363C0E90A33704700BF2F +:1054C0008C92000810B53023044683F31188C16222 +:1054D000FFF76EF802230020237180F3118810BDBE +:1054E00010B53023044683F31188FFF787F80023B3 +:1054F0000122E362227183F3118810BD02684368C0 +:105500001143016003B11847704700001430FFF7E2 +:1055100021BD00004FF0FF331430FFF71BBD00002A +:105520003830FFF797BD00004FF0FF333830FFF7FA +:1055300091BD00001430FFF7E7BC00004FF0FF31D1 +:105540001430FFF7E1BC00003830FFF741BD000028 +:105550004FF0FF323830FFF73BBD0000012914BF88 +:105560006FF0130000207047FFF7FEBA044B036092 +:1055700000234360C0E9023301230374704700BF76 +:10558000B092000810B53023044683F31188FFF76A +:105590005BFB02230020237480F3118810BD000000 +:1055A00038B5C36904460D461BB904210844FFF70A +:1055B000A5FF294604F11400FFF78AFC002806DA4B +:1055C000201D4FF40061BDE83840FFF797BF38BD9C +:1055D000026843681143016003B118477047000037 +:1055E00013B5406B00F58054D4F8A4381A681178CC +:1055F000042914D1017C022911D1197901231289BE +:105600008B4013420BD101A94C3002F0CDFED4F8EF +:10561000A4480246019B2179206800F0DFF902B01E +:1056200010BD0000143002F04FBE00004FF0FF33F9 +:10563000143002F049BE00004C3002F021BF0000DF +:105640004FF0FF334C3002F01BBF0000143002F06B +:105650001DBE00004FF0FF31143002F017BE0000F5 +:105660004C3002F0EDBE00004FF0FF324C3002F043 +:10567000E7BE00000020704710B500F58054D4F854 +:10568000A4381A681178042917D1017C022914D191 +:105690005979012352898B4013420ED1143002F004 +:1056A000AFFD024648B1D4F8A4484FF44073617985 +:1056B0002068BDE8104000F07FB910BD406BFFF7D7 +:1056C000DBBF0000704700007FB5124B01250426A8 +:1056D000044603600023057400F1840243602946F8 +:1056E000C0E902330C4B0290143001934FF4407325 +:1056F000009602F061FD094B04F69442294604F13C +:105700004C000294CDE900634FF4407302F028FE90 +:1057100004B070BDD8920008BD560008E1550008DD +:105720000A68302383F311880B790B3342F8230086 +:105730004B79133342F823008B7913B10B3342F8C2 +:10574000230000F58053C3F8A4180223037400203B +:1057500080F311887047000038B5037F044613B109 +:1057600090F85430ABB90125201D0221FFF730FF1E +:1057700004F114006FF00101257700F0F7FC04F14B +:105780004C0084F854506FF00101BDE8384000F03F +:10579000EDBC38BD10B5012104460430FFF718FFF9 +:1057A0000023237784F8543010BD000038B5044638 +:1057B0000025143002F018FD04F14C00257702F0AA +:1057C000E7FD201D84F854500121FFF701FF20461A +:1057D000BDE83840FFF750BF90F8803003F0600319 +:1057E000202B06D190F881200023212A03D81F2ADC +:1057F00006D800207047222AFBD1C0E91D3303E000 +:10580000034A426707228267C3670120704700BFCF +:105810004422002037B500F58055D5F8A4381A6821 +:10582000117804291AD1017C022917D11979012391 +:1058300012898B40134211D100F14C04204602F032 +:1058400067FE58B101A9204602F0AEFDD5F8A44884 +:105850000246019B2179206800F0C0F803B030BDFA +:1058600001F10B03F0B550F8236085B004460D46F6 +:10587000FEB1302383F3118804EB8507301D082126 +:10588000FFF7A6FEFB6806F14C005B691B681BB1C5 +:10589000019002F097FD019803A902F085FD0246F0 +:1058A00048B1039B2946204600F098F8002383F373 +:1058B000118805B0F0BDFB685A691268002AF5D05E +:1058C0001B8A013B1340F1D104F18002EAE700009A +:1058D000133138B550F82140ECB1302383F31188EF +:1058E00004F58053D3F8A4281368527903EB82039C +:1058F000DB689B695D6845B104216018FFF768FEAD +:10590000294604F1140002F085FC2046FFF7B4FE9E +:10591000002383F3118838BD7047000001F0A2BC5A +:1059200001234022002110B5044600F8303BFCF76B +:10593000F9F90023C4E9013310BD000010B530238C +:10594000044683F311882422416000210C30FCF7C7 +:10595000E9F9204601F0A8FC02230020237080F31F +:10596000118810BD70B500EB8103054650690E46E5 +:105970001446DA6018B110220021FCF7D3F9A069AF +:1059800018B110220021FCF7CDF931462846BDE8B8 +:10599000704001F089BD000083682022002103F0DF +:1059A000011310B5044683601030FCF7BBF92046A4 +:1059B000BDE8104001F004BEF0B4012500EB810405 +:1059C00047898D40E4683D43A469458123600023F5 +:1059D000A2606360F0BC01F021BE0000F0B40125BC +:1059E00000EB810407898D40E4683D4364690581CB +:1059F00023600023A2606360F0BC01F097BE00004A +:105A000070B5022300250446242203702946C0F8FD +:105A100088500C3040F8045CFCF784F9204684F888 +:105A2000705001F0D5FC63681B6823B129462046FD +:105A3000BDE87040184770BD0378052B10B50446CB +:105A40000AD080F88C300523037043681B680BB1C3 +:105A5000042198470023A36010BD000001780529A8 +:105A600006D190F88C20436802701B6803B1184778 +:105A70007047000070B590F87030044613B10023F1 +:105A800080F8703004F18002204601F0BDFD6368AB +:105A90009B68B3B994F8803013F0600535D00021CD +:105AA000204602F0AFF80021204602F09FF863681C +:105AB0001B6813B1062120469847062384F87030EE +:105AC00070BD204698470028E4D0B4F88630A26F15 +:105AD0009A4288BFA36794F98030A56F002B4FF0DE +:105AE000300380F20381002D00F0F280092284F857 +:105AF000702083F3118800212046D4E91D23FFF78D +:105B00006DFF002383F31188DAE794F8812003F016 +:105B10007F0343EA022340F20232934200F0C58041 +:105B200021D8B3F5807F48D00DD8012B3FD0022B70 +:105B300000F09380002BB2D104F188026267022248 +:105B4000A267E367C1E7B3F5817F00F09B80B3F5FF +:105B5000407FA4D194F88230012BA0D1B4F88830D2 +:105B600043F0020332E0B3F5006F4DD017D8B3F520 +:105B7000A06F31D0A3F5C063012B90D86368204695 +:105B800094F882205E6894F88310B4F88430B047AB +:105B9000002884D0436863670368A3671AE0B3F5FD +:105BA000106F36D040F6024293427FF478AF5C4BE0 +:105BB00063670223A3670023C3E794F88230012BB5 +:105BC0007FF46DAFB4F8883023F00203A4F8883076 +:105BD000C4E91D55E56778E7B4F88030B3F5A06FE8 +:105BE0000ED194F88230204684F88A3001F04EFCC1 +:105BF00063681B6813B10121204698470323237073 +:105C00000023C4E91D339CE704F18B036367012380 +:105C1000C3E72378042B10D1302383F31188204667 +:105C2000FFF7BAFE85F311880321636884F88B506F +:105C300021701B680BB12046984794F88230002BE6 +:105C4000DED084F88B300423237063681B68002B3C +:105C5000D6D0022120469847D2E794F884302046D7 +:105C60001D0603F00F010AD501F0C0FC012804D085 +:105C700002287FF414AF2B4B9AE72B4B98E701F0E7 +:105C8000A7FCF3E794F88230002B7FF408AF94F878 +:105C9000843013F00F01B3D01A06204602D501F06C +:105CA000C9FFADE701F0BAFFAAE794F88230002BF4 +:105CB0007FF4F5AE94F8843013F00F01A0D01B06EA +:105CC000204602D501F09EFF9AE701F08FFF97E78B +:105CD000142284F8702083F311882B462A46294623 +:105CE0002046FFF769FE85F31188E9E65DB11522CC +:105CF00084F8702083F3118800212046D4E91D2305 +:105D0000FFF75AFEFDE60B2284F8702083F311881A +:105D10002B462A4629462046FFF760FEE3E700BFF0 +:105D200008930008009300080493000838B590F821 +:105D300070300446002B3ED0063BDAB20F2A34D82E +:105D40000F2B32D8DFE803F03731310822323131FE +:105D50003131313131313737856FB0F886309D427E +:105D600014D2C3681B8AB5FBF3F203FB12556DB95D +:105D7000302383F311882B462A462946FFF72EFE4F +:105D800085F311880A2384F870300EE0142384F818 +:105D90007030302383F31188002320461A461946B9 +:105DA000FFF70AFE002383F3118838BDC36F03B1E8 +:105DB00098470023E7E70021204601F023FF002158 +:105DC000204601F013FF63681B6813B106212046CB +:105DD00098470623D7E7000010B590F870300446C6 +:105DE000142B29D017D8062B05D001D81BB110BD14 +:105DF000093B022BFBD80021204601F003FF0021C4 +:105E0000204601F0F3FE63681B6813B106212046AB +:105E10009847062319E0152BE9D10B2380F8703041 +:105E2000302383F3118800231A461946FFF7D6FD65 +:105E3000002383F31188DAE7C3689B695B68002B52 +:105E4000D5D1C36F03B19847002384F87030CEE7F3 +:105E50000023826880F8243083691B689968914226 +:105E6000FBD25A68036042601060586070470000BF +:105E70000023826880F8243083691B689968914206 +:105E8000FBD85A6803604260106058607047000099 +:105E900008B50846302383F3118891F82430032B8A +:105EA00005D0042B0DD02BB983F3118808BD8B6A64 +:105EB00000221A604FF0FF338362FFF7C9FF00230F +:105EC000F2E7D1E9003213605A60F3E7034610B5F8 +:105ED0001B68984203D09C688A689442F8D25A683A +:105EE0000B604A601160596010BD0000FFF7B0BF41 +:105EF000064BD96881F824001868026853601A605C +:105F00000122D86080F82420FAF77CBA40460020AD +:105F10000C4B30B5DD684B1C87B004460FD02B46C8 +:105F2000094A684600F0B6F92046FFF7E1FF009BFA +:105F300013B1684600F0B8F9A86A07B030BDFFF7A2 +:105F4000D7FFF9E740460020915E0008044B1A682D +:105F5000DB6890689B68984294BF002001207047DE +:105F600040460020094B10B51C68D8682268536071 +:105F70001A600122DC6084F82420FFF779FF0146D3 +:105F80002046BDE81040FAF73DBA00BF4046002069 +:105F9000044B1A68DB6892689B689A4201D9FFF744 +:105FA000E1BF70474046002038B50123084C00256A +:105FB0002370656002F046FB02F06CFB0549064861 +:105FC00002F042FC0223237085F3118838BD00BF24 +:105FD000E8480020109300084046002000F09AB9DD +:105FE000EFF3118020B9EFF30583302282F311889B +:105FF0007047000010B530B9EFF30584C4F308040E +:1060000014B180F3118810BDFFF7C2FF84F311882B +:10601000F9E70000034A516853685B1A9842FBD8BD +:10602000704700BF001000E08B604B630023CA6123 +:1060300000F128020B6302230A618B84012388612B +:1060400081F8263001F11003C26A4A611360C3620D +:1060500001F12C030846CB6270470000D0E9013102 +:10606000026841F8183CA1F19C033839CB60036900 +:1060700041F8243C436941F8203C034B41F8043C7F +:10608000C3680248FFF7D0BF1D0400084046002047 +:1060900008B5FFF7E3FFBDE80840FFF727BF0000A2 +:1060A00038B50E4BDC6804F12C05A062E06AA8420A +:1060B0000FD194F826303BB994F825309B0702BFE6 +:1060C000D4E9043213605A600F20BDE83840FFF76E +:1060D0000FBF0368E362FFF709FFE7E740460020D0 +:1060E000302383F31188FFF7DBBF000008B50146BA +:1060F000302383F311880820FFF70AFF002383F37E +:10610000118808BD054BDB6821B10360986203204C +:10611000FFF7FEBE4FF0FF30704700BF4046002043 +:1061200003682BB10022026018469962FFF7DEBEB9 +:1061300070470000064BDB6839B1426818605A604E +:10614000136043600420FFF7E3BE4FF0FF30704759 +:10615000404600200368984206D01A6802605060EA +:1061600018469962FFF7C2BE7047000038B5044672 +:106170000D462068844200D138BD036823605C600E +:106180008562FFF7B3FEF4E7036810B59C68A2428E +:106190000CD85C688A600B604C602160596099681B +:1061A0008A1A9A604FF0FF33836010BD121B1B6880 +:1061B000ECE700000A2938BF0A2170B504460D46F5 +:1061C0000A26601902F038FA02F020FA041BA542F0 +:1061D00003D8751C04462E46F3E70A2E04D9012085 +:1061E000BDE8704002F0F8BB70BD0000F8B5144B7C +:1061F0000D460A2A4FF00A07D96103F110018260A7 +:1062000038BF0A224160196914460160486018616C +:10621000A81802F001FA02F0F9F9431B0646A3425E +:1062200006D37C1C28192746354602F005FAF2E70A +:106230000A2F04D90120BDE8F84002F0CDBBF8BD1B +:1062400040460020F8B506460D4602F0DFF90F4A39 +:10625000134653F8107F9F4206D12A460146304626 +:10626000BDE8F840FFF7C2BFD169BB68441A2C19DA +:1062700028BF2C46A34202D92946FFF79BFF22469E +:1062800031460348BDE8F840FFF77EBF4046002096 +:1062900050460020C0E90323002310B45DF8044BEE +:1062A0004361FFF7CFBF000010B5194C2369984236 +:1062B0000DD08168D0E9003213605A609A680A44B0 +:1062C0009A60002303604FF0FF33A36110BD0268A2 +:1062D000234643F8102F53600022026022699A423D +:1062E00003D1BDE8104002F0A1B9936881680B4466 +:1062F000936002F08BF92269E1699268441AA24224 +:10630000E4D91144BDE81040091AFFF753BF00BF9C +:10631000404600202DE9F047DFF8BC8008F1100767 +:106320002C4ED8F8105002F071F9D8F81C40AA6829 +:10633000031B9A423ED814444FF00009D5E90032BD +:10634000C8F81C4013605A60C5F80090D8F81030A7 +:10635000B34201D102F06AF989F31188D5E903311A +:1063600028469847302383F311886B69002BD8D0D7 +:1063700002F04CF96A69A0EB040982464A450DD245 +:10638000022002F029FB0022D8F81030B34208D1D5 +:1063900051462846BDE8F047FFF728BF121A2244AD +:1063A000F2E712EB09092946384638BF4A46FFF79B +:1063B000EBFEB5E7D8F81030B34208D01444C8F863 +:1063C0001C00211AA960BDE8F047FFF7F3BEBDE845 +:1063D000F08700BF504600204046002010B560B94D +:1063E000074804790368053C9B6818BF0124984757 +:1063F00008B144F00404204610BD0124FBE700BFAF +:10640000A4360020FFF7EABF2DE9F047884617467B +:106410009A460446B0B90D4E3579052D05D00324B2 +:106420000DE0013D15F0FF050ED0326853463946A8 +:106430003046D2F814904246C8470028F1D1204691 +:10644000BDE8F0870424FAE70124F8E7A436002029 +:106450002DE9F047884617469A460446B0B90D4ED6 +:106460003579052D05D003240DE0013D15F0FF051C +:106470000ED03268534639463046D2F8189042461C +:10648000C8470028F1D12046BDE8F0870424FAE788 +:106490000124F8E7A436002037B50C46154670B93C +:1064A00051B101290BD10748694603681B6A984717 +:1064B00010B9019B04462B60204603B030BD042474 +:1064C000FAE700BFA436002000207047FEE7000076 +:1064D000704700004FF0FF30704700004B6843608A +:1064E0008B688360CB68C3600B6943614B6903624F +:1064F0008B6943620B6803607047000008B53A4B34 +:1065000040F2FF713948D3F888200A43C3F8882045 +:10651000D3F8882022F4FF6222F00702C3F8882013 +:10652000D3F88830324B1A6C0A431A649A6E0A43C5 +:106530009A66304A9B6E1146FFF7D0FF00F58060E7 +:1065400002F11C01FFF7CAFF00F5806002F138017B +:10655000FFF7C4FF00F5806002F15401FFF7BEFFB2 +:1065600000F5806002F17001FFF7B8FF00F5806070 +:1065700002F18C01FFF7B2FF00F5806002F1A80183 +:10658000FFF7ACFF00F5806002F1C401FFF7A6FF42 +:1065900000F5806002F1E001FFF7A0FF00F58060E8 +:1065A00002F1FC01FFF79AFF02F58C7100F58060A3 +:1065B000FFF794FF01F0CEFB0F4BD3F8902242F08F +:1065C0000102C3F89022D3F8942242F00102C3F8EA +:1065D00094220522C3F898204FF06052C3F89C2003 +:1065E000064AC3F8A02008BD004402580000025823 +:1065F000004502582493000800ED00E01F00080346 +:1066000008B501F0C5FDFFF7CFFC0D4BDA6B42F08A +:106610004002DA635A6E22F040025A665B6E094B02 +:106620001A6842F008021A601A6842F004021A60FE +:1066300000F032FD00F032FBBDE8084000F0B4B8D5 +:10664000004502580018024801207047002070479A +:106650007047000002290CD0032904D00129074803 +:1066600018BF00207047032A05D8054800EBC20078 +:106670007047044870470020704700BF2895000805 +:1066800054220020DC94000870B59AB005460846F4 +:10669000144601A900F0C2F801A8FBF73BFB431C1C +:1066A0000022C6B25B001046C5E900342370032304 +:1066B000023404F8013C01ABD1B202348E4201D85D +:1066C0001AB070BD13F8011B013204F8010C04F874 +:1066D000021CF1E708B5302383F311880348FFF764 +:1066E00099F8002383F3118808BD00BFF04800200B +:1066F00090F8803003F01F02012A07D190F8812022 +:106700000B2A03D10023C0E91D3315E003F0600319 +:10671000202B08D1B0F884302BB990F88120212AA1 +:1067200003D81F2A04D8FFF757B8222AEBD0FAE77C +:10673000034A426707228267C3670120704700BF90 +:106740004B22002007B5052917D8DFE801F01916FC +:1067500003191920302383F31188104A0121019075 +:10676000FFF700F9019802210D4AFFF7FBF80D48E9 +:10677000FFF71CF8002383F3118803B05DF804FBD6 +:10678000302383F311880748FEF7E6FFF2E7302352 +:1067900083F311880348FEF7FDFFEBE77C940008C4 +:1067A000A0940008F048002038B50C4D0C4C2A4647 +:1067B0000C4904F10800FFF767FF05F1CA0204F174 +:1067C00010000949FFF760FF05F5CA7204F11800CF +:1067D0000649BDE83840FFF757BF00BFC861002039 +:1067E0005422002058940008629400087194000814 +:1067F00070B5044608460D46FBF78CFAC6B2204633 +:10680000013403780BB9184670BD32462946FBF7B0 +:106810006DFA0028F3D10120F6E700002DE9F047DA +:1068200005460C46FBF776FA2B49C6B22846FFF719 +:10683000DFFF08B10736F6B228492846FFF7D8FF30 +:1068400008B11036F6B2632E0BD8DFF88C80DFF873 +:106850008C90234FDFF894A02E7846B92670BDE8BF +:10686000F08729462046BDE8F04702F02DBA252ED4 +:106870002ED1072241462846FBF738FA70B9194B4A +:10688000224603F10C0153F8040B8B4242F8040B2F +:10689000F9D11B8807350E341380DDE708224946FD +:1068A0002846FBF723FA98B9A21C0F4B197802323D +:1068B0000909C95D02F8041C13F8011B01F00F015E +:1068C0005345C95D02F8031CF0D118340835C3E7FD +:1068D000013504F8016BBFE7489500087194000882 +:1068E0005F9500085095000800E8F11F0CE8F11FC3 +:1068F000BFF34F8F044B1A695107FCD1D3F8102115 +:106900005207F8D1704700BF0020005208B50D4B68 +:106910001B78ABB9FFF7ECFF0B4BDA68D10704D556 +:106920000A4A5A6002F188325A60D3F80C21D20721 +:1069300006D5064AC3F8042102F18832C3F80421BF +:1069400008BD00BF266400200020005223016745D7 +:1069500008B5114B1B78F3B9104B1A69510703D5D1 +:10696000DA6842F04002DA60D3F81021520705D508 +:10697000D3F80C2142F04002C3F80C21FFF7B8FF16 +:10698000064BDA6842F00102DA60D3F80C2142F0DB +:106990000102C3F80C2108BD26640020002000522B +:1069A0000F289ABF00F58060400400207047000067 +:1069B0004FF4003070470000102070470F2808B5D2 +:1069C0000BD8FFF7EDFF00F500330268013204D168 +:1069D00004308342F9D1012008BD0020FCE700000B +:1069E0000F2838B505463FD8FFF782FF1F4CFFF749 +:1069F0008DFF4FF0FF3307286361C4F814311DD8B1 +:106A00002361FFF775FF030243F02403E360E368AB +:106A100043F08003E36023695A07FCD42846FFF75C +:106A200067FFFFF7BDFF4FF4003100F08FFA2846F3 +:106A3000FFF78EFFBDE83840FFF7C0BFC4F8103144 +:106A4000FFF756FFA0F108031B0243F02403C4F82C +:106A50000C31D4F80C3143F08003C4F80C31D4F875 +:106A600010315B07FBD4D9E7002038BD002000526D +:106A70002DE9F84F05460C46104645EA0203DE06AE +:106A800002D00020BDE8F88F20F01F00DFF8BCB076 +:106A9000DFF8BCA0FFF73AFF04EB0008444503D140 +:106AA0000120FFF755FFEDE720222946204602F09E +:106AB0008FF810B920352034F0E72B4605F120027D +:106AC0001F68791CDDD104339A42F9D105F178436E +:106AD0001B481C4EB3F5801F1B4B38BF184603F1F3 +:106AE000F80332BFD946D1461E46FFF701FF0760C3 +:106AF000A5EB040C336804F11C0143F0020333607E +:106B0000231FD9F8007017F00507FAD153F8042FA6 +:106B10008B424CF80320F4D1BFF34F8FFFF7E8FE10 +:106B20004FF0FF332022214603602846336823F0CC +:106B30000203336002F04CF80028BBD03846B0E7BF +:106B4000142100520C200052142000521020005238 +:106B50001021005210B5084C237828B11BB9FFF75B +:106B6000D5FE0123237010BD002BFCD02070BDE8A2 +:106B70001040FFF7EDBE00BF266400202DE9F04F66 +:106B80000D4685B0814658B111F00D0614BF202284 +:106B9000082211F00803019304D0431E034269D078 +:106BA000002435E0002E37D009F11F0121F01F0924 +:106BB0004FF00108314F05F00403DFF8CCA005EADF +:106BC000080BBBF1000F32D07869C0072FD408F151 +:106BD00001080C37B8F1060FF3D19EB9284D49468C +:106BE000A819019201F078FD0446002839D1203619 +:106BF000019AA02EF3D1494601F06EFD044600280B +:106C00002FD1019A49461F4801F066FD044660BB3A +:106C1000204605B0BDE8F08F0029C9D101462846BD +:106C2000029201F059FD0446D8B9029AC0E713B1A7 +:106C300078694107CBD5AC0702D578698007C6D5FE +:106C4000019911B178690107C1D549460AEB48108D +:106C5000CDE9022301F040FD0446DDE902230028CE +:106C6000B5D04A460021204601E04A460021FBF704 +:106C700059F8CDE70246002E96D199E770950008A5 +:106C80006864002028640020486400200021FFF789 +:106C900075BF00000121FFF771BF000070B5144DF2 +:106CA0000124144E40F2FF3200210120FBF73AF894 +:106CB00006EB441001342A6955F80C1F01F0F8FC6A +:106CC000062CF5D137254FF4C0542046FFF7E2FFDC +:106CD000014628B122460848BDE8704001F0E8BCF2 +:106CE000C4EBC404013D4FEAD404EED170BD00BF33 +:106CF0007095000848640020286400200421FFF7F4 +:106D00003DBF00004843FFF7C1BF000008B101F0DC +:106D100055BD7047B0F5805F10B5044607D8FFF742 +:106D2000EDFF28B92046BDE81040FFF7AFBF0020B7 +:106D300010BD0000FFF7EABF08B501F055FE034A99 +:106D4000D2E90032C01842EB010108BD08650020FD +:106D5000434BD3E900232DE9F34113437CD0FFF7E4 +:106D6000EBFF404A00230027F9F766FB06460D4675 +:106D70003D4A0023F9F760FB0023144630462946BC +:106D8000394AF9F759FB4FF461613C23ADF80170C2 +:106D9000B4FBF1F5B4FBF3F601FB154103FB16461A +:106DA0004624B1FBF3F1314BF6B28DF80040984226 +:106DB0003CD84FF0640C4FF4C87EA30704F26C7209 +:106DC00025D1B2FBFCF30CFB132313BBB2FBFEF388 +:106DD0000EFB1322B2FA82F35B0903F26D18621CF8 +:106DE0008045D2B217D90FB18DF800400022204C57 +:106DF0004FF00C0C17460CFB0343D4B2013213F8CE +:106E000004C084450CD8A0EB0C000127F5E7002353 +:106E1000E3E70123E1E7A0EB080014460127CCE7F4 +:106E20000FB18DF80140431C8DF802309DF8010030 +:106E3000431C9DF800005038400640EA43509DF83E +:106E4000023040EA034040EA560040EAC52040EAEA +:106E5000411002B0BDE8F0814FF40410F9E700BF23 +:106E60000865002040420F008051010090230B0074 +:106E7000B89500080244074BD2B210B5904200D139 +:106E800010BD441C00B253F8200041F8040BE0B2DE +:106E9000F4E700BF504000580E4B30B51C6F24047F +:106EA00005D41C6F1C671C6F44F400441C670A4C1B +:106EB00002442368D2B243F480732360074B9042AC +:106EC00000D130BD441C51F8045B00B243F820509F +:106ED000E0B2F4E70044025800480258504000581D +:106EE00007B5012201A90020FFF7C4FF019803B0F4 +:106EF0005DF804FB13B50446FFF7F2FFA04205D08E +:106F0000012201A900200194FFF7C6FF02B010BDC5 +:106F100010B56424013C4FF47A70FFF7E7F814F0E1 +:106F2000FF04F7D1084B4FF0807214249A6103F5E7 +:106F3000805308229A61013C4FF47A70FFF7D6F82B +:106F400014F0FF04F7D110BD000002580144BFF354 +:106F50004F8F064B884204D3BFF34F8FBFF36F8F21 +:106F60007047C3F85C022030F4E700BF00ED00E09A +:106F70000144BFF34F8F064B884204D3BFF34F8FBA +:106F8000BFF36F8F7047C3F870022030F4E700BF83 +:106F900000ED00E070B5054616460C4601201021B4 +:106FA000FFF7B0FE286046733CB1204636B1FFF7CC +:106FB000A5FE2B68186000B19C6070BDFFF76AFEEB +:106FC000F7E7000070B50E461546044600B30B689F +:106FD00043608368934210D213B10068FFF796FEB6 +:106FE000637B28462BB1FFF789FE206020B9A060A3 +:106FF00070BDFFF74FFEF8E7A560206805F11F019F +:10700000306021F01F01FFF7A1FF01202073EFE79F +:107010000120EDE710B5044640B10068884205D173 +:10702000606808B1FAF758FE0023237310BD000012 +:1070300070B50E461546044620B383689A4210D9AF +:1070400013B10068FFF762FE637B28462BB1FFF7A0 +:1070500055FE206020B9A06070BDFFF71BFEF8E769 +:10706000A560316819B12A462068FAF735FE206814 +:1070700005F11F01306021F01F01FFF779FF0120AA +:107080002073E9E70120E7E720B103688B4204BFE2 +:107090000023037370470000034B1A681AB9034AB0 +:1070A000D2F8D0241A6070471065002000400258C2 +:1070B00008B5FFF7F1FF024B1868C0F3806008BD08 +:1070C0001065002070B5BFF34F8FBFF36F8F1A4A62 +:1070D0000021C2F85012BFF34F8FBFF36F8F536977 +:1070E00043F400335361BFF34F8FBFF36F8FC2F888 +:1070F0008410BFF34F8FD2F8803043F6E074C3F3AF +:10710000C900C3F34E335B0103EA0406014646EAB5 +:1071100081750139C2F86052F9D2203B13F1200F7A +:10712000F2D1BFF34F8F536943F480335361BFF300 +:107130004F8FBFF36F8F70BD00ED00E0FEE70000E2 +:10714000214B2248224A70B5904237D3214BC11EB1 +:10715000DA1C121A22F003028B4238BF00220021EF +:10716000FAF7E0FD1C4A0023C2F88430BFF34F8FCA +:10717000D2F8803043F6E074C3F3C900C3F34E3352 +:107180005B0103EA0406014646EA81750139C2F84B +:107190006C52F9D2203B13F1200FF2D1BFF34F8F85 +:1071A000BFF36F8FBFF34F8FBFF36F8F0023C2F812 +:1071B0005032BFF34F8FBFF36F8F70BD53F8041B76 +:1071C00040F8041BC0E700BF20970008206700209C +:1071D000206700202067002000ED00E0054B996B40 +:1071E00021EA000199631A6E22EA00021A661B6EF8 +:1071F000704700BF0045025870B5D0E92443002213 +:107200004FF0FF359E6804EB42135101D3F800099B +:10721000002805DAD3F8000940F08040C3F80009DF +:10722000D3F8000B002805DAD3F8000B40F08040BB +:10723000C3F8000B013263189642C3F80859C3F82B +:10724000085BE0D24FF00113C4F81C3870BD000099 +:10725000890141F02001016103699B06FCD41220E1 +:10726000FEF7D8BE10B50A4C2046FEF759FB094B75 +:10727000C4F89030084BC4F89430084C2046FEF710 +:107280004FFB074BC4F89030064BC4F8943010BD48 +:107290001465002000000840F4950008B065002047 +:1072A000000004400096000870B503780546012BE5 +:1072B00058D13F4BD0F89040984254D13D4B0E21CD +:1072C00065209A6B42F000629A631A6E42F0006287 +:1072D0001A661B6E384BD3F8802042F00062C3F868 +:1072E0008020D3F8802022F00062C3F88020D3F8F9 +:1072F000803000F037FF314BE360314BC4F8003889 +:107300000023D5F89060C4F8003EC02323604FF4FA +:107310000413A3633369002BFCDA01230C203361CF +:10732000FEF778FE3369DB07FCD41220FEF772FE0D +:107330003369002BFCDA00262846A660FFF75CFFC5 +:107340006B68C4F81068DB68C4F81468C4F81C687B +:1073500063BB1C4BA3614FF0FF336361A36843F031 +:107360000103A36070BD184B9842C9D1114B4FF077 +:1073700080609A6B42F000729A631A6E42F000725B +:107380001A661B6E0C4BD3F8802042F00072C3F8D3 +:107390008020D3F8802022F00072C3F88020D3F838 +:1073A0008030FFF71BFF0E214D20A2E7074BD1E7EE +:1073B0001465002000450258004402584014004063 +:1073C00003002002003C30C0B0650020083C30C003 +:1073D000F8B5D0F89040054600214FF000662046F1 +:1073E000FFF736FFD5F8941000234FF001128F6895 +:1073F0004FF0FF30C4F83438C4F81C2804EB4312B3 +:1074000001339F42C2F80069C2F8006BC2F8080954 +:10741000C2F8080BF2D20B68D5F89020C5F8983066 +:10742000636210231361166916F01006FBD1122057 +:10743000FEF7F0FDD4F8003823F4FE63C4F80038FA +:10744000A36943F4402343F01003A3610923C4F864 +:107450001038C4F814380B4BEB604FF0C043C4F83D +:10746000103B094BC4F8003BC4F81069C4F800395C +:10747000D5F8983003F1100243F48013C5F8982032 +:10748000A362F8BDD095000840800010D0F890208D +:1074900090F88A10D2F8003823F4FE6343EA01130F +:1074A000C2F80038704700002DE9F84300EB810373 +:1074B000D0F890500C468046DA680FFA81F94801FE +:1074C000166806F00306731E022B05EB41134FF0FE +:1074D000000194BFB604384EC3F8101B4FF00101F1 +:1074E00004F1100398BF06F1805601FA03F3916985 +:1074F00098BF06F5004600293AD0578A04F1580192 +:10750000374349016F50D5F81C180B430021C5F8CB +:107510001C382B180127C3F81019A7405369611EA6 +:107520009BB3138A928B9B08012A88BF5343D8F8D8 +:107530009820981842EA034301F140022146C8F816 +:107540009800284605EB82025360FFF781FE08EBA6 +:107550008900C3681B8A43EA845348341E4364018C +:107560002E51D5F81C381F43C5F81C78BDE8F883A8 +:1075700005EB4917D7F8001B21F40041C7F8001BA1 +:10758000D5F81C1821EA0303C0E704F13F030B4AB6 +:107590002846214605EB83035A60FFF759FE05EBA9 +:1075A0004910D0F8003923F40043C0F80039D5F869 +:1075B0001C3823EA0707D7E7008000100004000208 +:1075C000D0F894201268C0F89820FFF715BE00008C +:1075D0005831D0F8903049015B5813F4004004D082 +:1075E00013F4001F0CBF0220012070474831D0F86F +:1075F000903049015B5813F4004004D013F4001F8D +:107600000CBF02200120704700EB8101CB68196A92 +:107610000B6813604B6853607047000000EB8103F8 +:1076200030B5DD68AA691368D36019B9402B84BFEF +:10763000402313606B8A1468D0F890201C4402EB3E +:107640004110013C09B2B4FBF3F46343033323F06C +:10765000030343EAC44343F0C043C0F8103B2B6824 +:1076600003F00303012B0ED1D2F8083802EB4110CE +:1076700013F4807FD0F8003B14BF43F0805343F0F5 +:107680000053C0F8003B02EB4112D2F8003B43F03C +:107690000443C2F8003B30BD2DE9F041D0F89060C2 +:1076A00005460C4606EB4113D3F8087B3A07C3F8AE +:1076B000087B08D5D6F814381B0704D500EB8103E6 +:1076C000DB685B689847FA071FD5D6F81438DB07E4 +:1076D0001BD505EB8403D968CCB98B69488A5A68F5 +:1076E000B2FBF0F600FB16228AB91868DA689042FD +:1076F0000DD2121AC3E90024302383F311882146E6 +:107700002846FFF78BFF84F31188BDE8F081012341 +:1077100003FA04F26B8923EA02036B81CB68002B26 +:10772000F3D021462846BDE8F041184700EB81031D +:107730004A0170B5DD68D0F890306C692668E66063 +:1077400056BB1A444FF40020C2F810092A6802F010 +:107750000302012A0AB20ED1D3F8080803EB42143F +:1077600010F4807FD4F8000914BF40F0805040F03E +:107770000050C4F8000903EB4212D2F8000940F0AF +:107780000440C2F800090122D3F8340802FA01F1DA +:107790000143C3F8341870BD19B9402E84BF40208E +:1077A000206020681A442E8A8419013CB4FBF6F448 +:1077B00040EAC44040F00050C6E700002DE9F8431D +:1077C000D0F8906005460C464F0106EB4113D3F804 +:1077D000088918F0010FC3F808891CD0D6F81038B2 +:1077E000DB0718D500EB8103D3F80CC0DCF81430AC +:1077F000D3F800E0DA68964530D2A2EB0E024FF0E3 +:1078000000091A60C3F80490302383F31188FFF74E +:107810008DFF89F3118818F0800F1DD0D6F8343809 +:107820000126A640334217D005EB84030134D5F876 +:107830009050D3F80CC0E4B22F44DCF8142005EBD0 +:107840000434D2F800E05168714514D3D5F83438C7 +:1078500023EA0606C5F83468BDE8F883012303FA75 +:1078600001F2038923EA02030381DCF80830002BCC +:10787000D1D09847CFE7AEEB0103BCF810008342AC +:1078800028BF0346D7F8180980B2B3EB800FE3D8BE +:107890009068A0F1040959F8048FC4F80080A0EBA7 +:1078A00009089844B8F1040FF5D818440B449060C7 +:1078B0005360C8E72DE9F84FD0F8905004466E6940 +:1078C000AB691E4016F480586E6103D0BDE8F84FD6 +:1078D000FEF796B8002E12DAD5F8003E9B0705D0C9 +:1078E000D5F8003E23F00303C5F8003ED5F8043870 +:1078F000204623F00103C5F80438FEF7AFF837053A +:1079000005D52046FFF778FC2046FEF795F8B00431 +:107910000CD5D5F8083813F0060FEB6823F4705334 +:107920000CBF43F4105343F4A053EB6031071BD555 +:107930006368DB681BB9AB6923F00803AB6123788C +:10794000052B0CD1D5F8003E9A0705D0D5F8003E9E +:1079500023F00303C5F8003E2046FEF77FF8636876 +:10796000DB680BB120469847F30200F1BA80B702FA +:1079700026D5D4F8909000274FF0010A09EB471262 +:10798000D2F8003B03F44023B3F5802F11D1D2F895 +:10799000003B002B0DDA62890AFA07F322EA03039F +:1079A000638104EB8703DB68DB6813B1394620464B +:1079B00098470137D4F89430FFB29B689F42DDD9D5 +:1079C000F00619D5D4F89000026AC2F30A1702F043 +:1079D0000F0302F4F012B2F5802F00F0CA80B2F566 +:1079E000402F09D104EB8303002200F58050DB68AF +:1079F0001B6A974240F0B0803003D5F8185835D54F +:107A0000E90303D500212046FFF746FEAA0303D56C +:107A100001212046FFF740FE6B0303D502212046DB +:107A2000FFF73AFE2F0303D503212046FFF734FE6C +:107A3000E80203D504212046FFF72EFEA90203D554 +:107A400005212046FFF728FE6A0203D506212046BD +:107A5000FFF722FE2B0203D507212046FFF71CFE6D +:107A6000EF0103D508212046FFF716FE700340F111 +:107A7000A780E90703D500212046FFF79FFEAA074C +:107A800003D501212046FFF799FE6B0703D502219C +:107A90002046FFF793FE2F0703D503212046FFF76B +:107AA0008DFEEE0603D504212046FFF787FEA806CB +:107AB00003D505212046FFF781FE690603D506217F +:107AC0002046FFF77BFE2A0603D507212046FFF755 +:107AD00075FEEB0574D520460821BDE8F84FFFF789 +:107AE0006DBED4F890904FF0000B4FF0010AD4F81F +:107AF00094305FFA8BF79B689F423FF638AF09EBF3 +:107B00004713D3F8002902F44022B2F5802F20D188 +:107B1000D3F80029002A1CDAD3F8002942F0904259 +:107B2000C3F80029D3F80029002AFBDB3946D4F832 +:107B30009000FFF78DFB22890AFA07F322EA03037C +:107B4000238104EB8703DB689B6813B13946204629 +:107B500098470BF1010BCAE7910701D1D0F80080DB +:107B6000072A02F101029CBF03F8018B4FEA182893 +:107B70003FE704EB830300F58050DA68D2F818C0C1 +:107B8000DCF80820DCE9001CA1EB0C0C00218F4282 +:107B900008D1DB689B699A683A449A605A683A440B +:107BA0005A6029E711F0030F01D1D0F800808C450D +:107BB00001F1010184BF02F8018B4FEA1828E6E7C2 +:107BC000BDE8F88F08B50348FFF774FEBDE808402C +:107BD00000F068BF1465002008B50348FFF76AFE8F +:107BE000BDE8084000F05EBFB0650020D0F89030DE +:107BF00003EB4111D1F8003B43F40013C1F8003B03 +:107C000070470000D0F8903003EB4111D1F80039F3 +:107C100043F40013C1F8003970470000D0F89030E9 +:107C200003EB4111D1F8003B23F40013C1F8003BF2 +:107C300070470000D0F8903003EB4111D1F80039C3 +:107C400023F40013C1F8003970470000044BDA6BCD +:107C50000243DA635A6E104358665B6E704700BF8A +:107C6000004502583A4B4FF0FF31D3F8802062F0C4 +:107C70000042C3F88020D3F8802002F00042C3F80D +:107C80008020D3F88020D3F88420C3F88410D3F860 +:107C900084200022C3F88420D3F88400D86F40F0F9 +:107CA000FF4040F4FF0040F4DF4040F07F00D86721 +:107CB000D86F20F0FF4020F4FF0020F4DF4020F0D8 +:107CC0007F00D867D86FD3F888006FEA40506FEA1A +:107CD0005050C3F88800D3F88800C0F30A00C3F8F6 +:107CE0008800D3F88800D3F89000C3F89010D3F838 +:107CF0009000C3F89020D3F89000D3F89400C3F814 +:107D00009410D3F89400C3F89420D3F89400D3F8D7 +:107D10009800C3F89810D3F89800C3F89820D3F8C7 +:107D20009800D3F88C00C3F88C10D3F88C00C3F8FB +:107D30008C20D3F88C00D3F89C00C3F89C10D3F8A7 +:107D40009C10C3F89C20D3F89C3000F0D3B900BF3E +:107D50000044025808B50122504BC3F80821504B8B +:107D60005A6D42F002025A65DA6F42F00202DA6797 +:107D70000422DB6F4B4BDA605A689104FCD54A4A07 +:107D80001A6001229A60494ADA6000221A614FF4AF +:107D900040429A61434B9A699204FCD51A6842F4B6 +:107DA00080721A60424B1A6F12F4407F04D04FF475 +:107DB00080321A6700221A671A6842F001021A60BC +:107DC0003B4B1A685007FCD500221A611A6912F061 +:107DD0003802FBD1012119604FF0804159605A6788 +:107DE000344ADA62344A1A611A6842F480321A60FC +:107DF0002F4B1A689103FCD51A6842F480521A601E +:107E00001A689204FCD52D4A2D499A6200225A63C1 +:107E1000196301F57C01DA6301F5E77199635A642E +:107E2000284A1A64284ADA621A6842F0A8521A608C +:107E30001F4B1A6802F02852B2F1285FF9D148228C +:107E40009A614FF48862DA6140221A621F4ADA644A +:107E50001F4A1A651F4A5A651F4A9A6532231F4AEC +:107E60001360136803F00F03022BFAD1104A136951 +:107E700043F003031361136903F03803182BFAD19D +:107E80004FF00050FFF7E2FE4FF08040FFF7DEFEBC +:107E90004FF00040BDE80840FFF7D8BE0080005119 +:107EA000004502580048025800C000F004000001DC +:107EB000004402580000FF01008890083220600052 +:107EC00063020901470E0508DD0BBF0120000020F9 +:107ED000000001100910E000000101100020005214 +:107EE0004FF0B04208B5D2F8883003F00103C2F871 +:107EF000883023B1044A13680BB150689847BDE835 +:107F0000084000F0CFBD00BF986600204FF0B0429F +:107F100008B5D2F8883003F00203C2F8883023B1E4 +:107F2000044A93680BB1D0689847BDE8084000F058 +:107F3000B9BD00BF986600204FF0B04208B5D2F836 +:107F4000883003F00403C2F8883023B1044A13696F +:107F50000BB150699847BDE8084000F0A3BD00BFD1 +:107F6000986600204FF0B04208B5D2F8883003F090 +:107F70000803C2F8883023B1044A93690BB1D06971 +:107F80009847BDE8084000F08DBD00BF986600200E +:107F90004FF0B04208B5D2F8883003F01003C2F8B1 +:107FA000883023B1044A136A0BB1506A9847BDE880 +:107FB000084000F077BD00BF986600204FF0B04346 +:107FC00010B5D3F8884004F47872C3F88820A3066B +:107FD00004D5124A936A0BB1D06A9847600604D55B +:107FE0000E4A136B0BB1506B9847210604D50B4A10 +:107FF000936B0BB1D06B9847E20504D5074A136C1D +:108000000BB1506C9847A30504D5044A936C0BB18F +:10801000D06C9847BDE8104000F044BD9866002041 +:108020004FF0B04310B5D3F8884004F47C42C3F855 +:108030008820620504D5164A136D0BB1506D984720 +:10804000230504D5124A936D0BB1D06D9847E00417 +:1080500004D50F4A136E0BB1506E9847A10404D596 +:108060000B4A936E0BB1D06E9847620404D5084A50 +:10807000136F0BB1506F9847230404D5044A936FD4 +:108080000BB1D06F9847BDE8104000F00BBD00BFAA +:108090009866002008B50348FCF72CFDBDE80840B1 +:1080A00000F000BDA436002008B50348FCF722FE0E +:1080B000BDE8084000F0F6BCFC38002008B50348D5 +:1080C000FCF718FEBDE8084000F0ECBC6839002061 +:1080D00008B50348FCF70EFEBDE8084000F0E2BC1E +:1080E000D439002008B500F039FDBDE8084000F0A3 +:1080F000D9BC0000062108B5084600F033F8062177 +:10810000072000F02FF80621082000F02BF80621A8 +:10811000092000F027F806210A2000F023F80621A4 +:10812000172000F01FF80621282000F01BF8092175 +:108130007A2000F017F80921312000F013F8072108 +:10814000322000F00FF80C21262000F00BF80C2153 +:10815000272000F007F80C215220BDE8084000F06D +:1081600001B80000090100F16043012203F56143F9 +:10817000C9B283F8001300F01F039A4043099B0023 +:1081800003F1604303F56143C3F880211A6070472F +:1081900008B5FFF767FD00F0AFFCFDF7E5F9FDF767 +:1081A00083F9FDF7BBFBFDF78DFAFEF751FABDE849 +:1081B000084000F029BA000030B50433039C017276 +:1081C000002104FB0325C160C0E90653049B03633F +:1081D000059BC0E90000C0E90422C0E90842C0E9EB +:1081E0000A11436330BD00000022416AC260C0E949 +:1081F0000411C0E90A226FF00101FDF7B7BF0000CA +:10820000D0E90432934201D1C2680AB9181D7047FF +:1082100000207047036919600021C2680132C26002 +:10822000C269134482699342036124BF436A0361B4 +:10823000FDF790BF38B504460D46E3683BB162696F +:108240000020131D1268A3621344E36207E0237A3F +:1082500033B929462046FDF76DFF0028EDDA38BD19 +:108260006FF00100FBE70000C368C269013BC36017 +:108270004369134482699342436124BF436A436163 +:1082800000238362036B03B11847704770B5302336 +:10829000044683F31188866A3EB9FFF7CBFF054693 +:1082A00018B186F31188284670BDA36AE26A13F8F4 +:1082B000015B9342A36202D32046FFF7D5FF002360 +:1082C00083F31188EFE700002DE9F84F04460E46CE +:1082D000174698464FF0300989F311880025AA46C1 +:1082E000D4F828B0BBF1000F09D141462046FFF772 +:1082F000A1FF20B18BF311882846BDE8F88FD4E99F +:108300000A12A7EB050B521A934528BF9346BBF1FF +:10831000400F1BD9334601F1400251F8040B914242 +:1083200043F8040BF9D1A36A403640354033A362C9 +:10833000D4E90A239A4202D32046FFF795FF8AF335 +:108340001188BD42D8D289F31188C9E730465A4610 +:10835000F9F7C2FCA36A5E445D445B44A362E7E7AD +:1083600010B5029C0433017203FB0421C460C0E910 +:1083700006130023C0E90A33039B0363049BC0E98F +:108380000000C0E90422C0E90842436310BD0000B8 +:10839000026A6FF00101C260426AC0E90422002251 +:1083A000C0E90A22FDF7E2BED0E904239A4201D1D6 +:1083B000C26822B9184650F8043B0B60704700238E +:1083C0001846FAE7C3680021C2690133C3604369F4 +:1083D000134482699342436124BF436A4361FDF7BA +:1083E000B9BE000038B504460D46E3683BB12369C9 +:1083F00000201A1DA262E2691344E36207E0237AB7 +:1084000033B929462046FDF795FE0028EDDA38BD40 +:108410006FF00100FBE7000003691960C268013AD0 +:10842000C260C269134482699342036124BF436AF4 +:10843000036100238362036B03B118477047000098 +:1084400070B530230D460446114683F31188866AC1 +:108450002EB9FFF7C7FF10B186F3118870BDA36A6C +:108460001D70A36AE26A01339342A36204D3E169F7 +:1084700020460439FFF7D0FF002080F31188EDE794 +:108480002DE9F84F04460D46904699464FF0300AC4 +:108490008AF311880026B346A76A4FB94946204699 +:1084A000FFF7A0FF20B187F311883046BDE8F88FB1 +:1084B000D4E90A073A1AA8EB0607974228BF1746DD +:1084C000402F1BD905F1400355F8042B9D4240F87D +:1084D000042BF9D1A36A40364033A362D4E90A23BE +:1084E0009A4204D3E16920460439FFF795FF8BF3E4 +:1084F00011884645D9D28AF31188CDE729463A46F4 +:10850000F9F7EAFBA36A3D443E443B44A362E5E736 +:10851000D0E904239A4217D1C3689BB1836A8BB117 +:10852000043B9B1A0ED01360C368013BC360C36950 +:108530001A4483699A42026124BF436A036100239B +:1085400083620123184670470023FBE701F01F03F5 +:10855000F0B502F01F0456095A1C0123B6EB511F57 +:1085600050F8265003FA02F34FEA511703F1FF3394 +:108570003DBF50F82720C4F12000134003EA050056 +:108580003BBF03FA00F225FA04F0E0401043F0BDCF +:1085900070B57E227F210546FFF7D8FF18B101286C +:1085A00019D0002070BD3E2249212846FFF7CEFF9A +:1085B0002F22044631212846FFF7C8FF0646013422 +:1085C0005022023653212846B440FFF7BFFF093836 +:1085D00004FA00F0E6E7302245212846FFF7B6FF0F +:1085E00001308002DEE7000090F8D63090F8D72006 +:1085F0001B0403EB026390F8D42090F8D5001344D9 +:1086000003EB00207047000000F084BA014B586A69 +:10861000704700BF000C0040034B002258631A61F2 +:108620000222DA60704700BF000C0040014B0022BC +:10863000DA607047000C0040014B5863704700BF80 +:10864000000C0040024B034A1A60034A5A6070470C +:10865000646600202067002000000220074B49428A +:1086600010B55C68201A08401968821A8A4203D340 +:10867000A24201D85A6010BD0020FCE764660020C9 +:1086800008B5302383F31188FFF7E8FF002383F355 +:10869000118808BD0448054B03600023C0E901337D +:1086A0000C3000F017B900BF6C660020818600080E +:1086B000CB1D083A23F00703591A521A10B4D208F6 +:1086C0000024C0E9004384600C301C605A605DF8EF +:1086D000044B00F0FFB800002DE9F74F364FCD1DD9 +:1086E0008846002818BF0746082A4FEAD50538BF34 +:1086F000082207F10C003C1D9146019000F02CF976 +:10870000019809F10701C9F1000E2246246864B9F5 +:1087100000F02CF93B68CBB308224946E8009847A3 +:10872000044698B340E9027830E004EB010CD4F839 +:1087300004A00CEA0E0C0AF10106ACF1080304EBEC +:10874000C6069E42E1D9A6EB0C0CB5EBEC0F4FEA46 +:10875000EC0BDAD89C421DD204F10802AB45A3EB26 +:1087600002024FEAE202626009D9691CED4303EBA1 +:10877000C1025D445560256843F8315022601C46B3 +:10878000C3F8048044F8087B00F0F0F8204603B0FA +:10879000BDE8F08FAA45216802D111602346EEE7BB +:1087A000013504EBC50344F8351003F10801761ACE +:1087B000F6105E601360F1E76C66002073B5044646 +:1087C000A0F1080550F8080C54F8043C061D0C30C4 +:1087D00007330190DB0844F8043C00F0BDF8334651 +:1087E00001989E421A6801D0AB4228D20AB1954244 +:1087F00025D244F8082C54F8042C1D60013254F89A +:10880000081C05EBC206B14206D14E68324444F85A +:10881000042C0A6844F8082C5E68711C03EBC10143 +:108820008D4207D154F8042C013232445A6054F876 +:10883000082C1A6002B0BDE8704000F097B81346EB +:10884000CFE70000FEE7000070B51E4B0025044690 +:1088500086B058600E460563816300F0FBF804F1B2 +:108860002803A5606563C4E90A3304F11003C4E971 +:1088700004334FF0FF33C4E90044C4E90635FFF781 +:10888000C5FE2B46024604F13C012046C4E90823FC +:1088900080230D4A6567FDF7C7FB7368E0600B4AEC +:1088A00003620123009280F824306846F268019246 +:1088B0003269CDE90223064BCDE90435FDF7E8FB2B +:1088C00006B070BDE8480020149600080C96000819 +:1088D000458800080023C0E90000836003617047F9 +:1088E00070B51C4B05468468DE685CB3B44213D196 +:1088F00003690133036170BDA36094F8243083B130 +:10890000062B15D1A06A2146D4E9003213605A60C3 +:10891000FDF7DCFAA36A9C68B368A2689A42EBD3BD +:1089200006E0D4E90032204613605A60FDF7DEFA13 +:1089300028463146FDF7CAFAB5620620BDE8704008 +:10894000FDF7D6BA0369866001330361336BC360F8 +:108950003063D0E74046002008B5302383F3118808 +:10896000FFF7BEFF002383F3118808BD194BD968B8 +:1089700083688B4210B520D1302383F311880269BC +:10898000013A0261B2B90468C368A0420B631ED009 +:108990004A6B9BB901238A60036103681A6802600D +:1089A00050601A6B8360C26018631846FDF79EFA28 +:1089B000FDF7EEFA002383F3118810BD1C68A34273 +:1089C00003D0A468A24238BF2246DB68E1E7826098 +:1089D000F0E700BF40460020024A536B1843506343 +:1089E000704700BF4046002070B5104E82B0FDF7C2 +:1089F000F7FA0546FFF70AFE3268034690423360F5 +:108A000037BF0B4A0A495168146836BF0131D1E9B2 +:108A1000004151600419284641F100010191FDF720 +:108A2000E9FA2046019902B070BD00BF8C660020B3 +:108A300090660020EFF30983054968334A6B22F002 +:108A400001024A6383F30988002383F31188704786 +:108A500000EF00E0302080F3118862B60D4B0E4A23 +:108A6000D96821F4E0610904090C0A430B49DA6072 +:108A7000D3F8FC2042F08072C3F8FC20084AC2F808 +:108A8000B01F116841F0010111602022DA7783F8EC +:108A90002200704700ED00E00003FA0555CEACC59A +:108AA000001000E0302310B583F311880E4B5B6893 +:108AB00013F4006314D0F1EE103AEFF309844FF091 +:108AC0008073683CE361094BDB6B236684F30988A0 +:108AD000FDF73CFA10B1064BA36110BD054BFBE757 +:108AE00083F31188F9E700BF00ED00E000EF00E03C +:108AF0002F040008320400080023054A19460133F8 +:108B0000102BC2E9001102F10802F8D1704700BF32 +:108B1000986600200E4B9A6C42F008029A641A6F15 +:108B200042F008021A670B4A1B6FD36B43F008032D +:108B3000D363C722084B9A624FF0FF32DA620022F9 +:108B40009A615A63DA605A6001225A611A6070476A +:108B5000004502580010005C000C0040094A08B5AE +:108B60001169D3680B40D9B29B076FEA010111610B +:108B700007D5302383F31188FDF730FA002383F300 +:108B8000118808BD000C0040FEF7C0B8012838BFAE +:108B9000012010B504462046FEF778F830B900F001 +:108BA00007F808B900F00CF88047F4E710BD0000A2 +:108BB000024B1868BFF35B8F704700BF1867002037 +:108BC00008B5062000F056F80120FDF77FFC0000F4 +:108BD00010B501390244904201D1002005E003782C +:108BE00011F8014FA34201D0181B10BD0130F2E76C +:108BF000884210B501EB020402D98442234607D80B +:108C0000431EA14208D011F8012B03F8012FF8E709 +:108C1000024401468A4200D110BD13F8014D02F80A +:108C2000014DF7E71F2938B504460D4604D9162330 +:108C300003604FF0FF3038BD426C12B152F8213062 +:108C40004BB9204600F030F82A4601462046BDE8E0 +:108C5000384000F017B8012B0AD0591C03D1162355 +:108C600003600120E7E7002442F8254028469847A2 +:108C70000020E0E7024B01461868FFF7D3BF00BFB2 +:108C80007422002038B5074D0023044608461146DB +:108C90002B60FDF71FFC431C02D12B6803B123603E +:108CA00038BD00BF1C670020FDF70EBCC9B20346EB +:108CB00010F8012B1AB18A42F9D1184670470029E1 +:108CC00018BF0023F9E70000034611F8012B03F851 +:108CD000012B002AF9D1704710B50139034632B192 +:108CE00011F8014F03F8014B013A002CF7D11A4457 +:108CF0000021934200D110BD03F8011BF9E70000E9 +:108D00004D4435002D2D0A002F6172647570696C19 +:108D10006F742E6162696E002F6172647570696C88 +:108D20006F742D7665726966792E6162696E002FA7 +:108D30006172647570696C6F742D666C6173682EF6 +:108D40006162696E002F6172647570696C6F742D59 +:108D5000666C61736865642E6162696E0000000074 +:108D60000000000000000000F10E00088D0F000858 +:108D70003D110008C50F0008850F00080000000025 +:108D800000000000ED0E0008990F000875110008A2 +:108D9000E90E0008F50E000853544D333248373FB2 +:108DA0003F3F0053544D3332483733782F373278B2 +:108DB0000053544D3332483734332F3735332F3740 +:108DC0003530000001105A000310590001205800EE +:108DD000032056002F0000005375636365737366AC +:108DE000756C6C79206D6F756E74656420534443A7 +:108DF0006172642028736C6F77646F776E3D2575A0 +:108E0000290A0000EB769045584641542020200066 +:108E10004641543332202020000000002A3A3C3ED4 +:108E20007C223F7F002B2C3B3D5B5D004355454141 +:108E30004141414345454549494941414592924F48 +:108E40004F4F5555594F554F9C4F9E9F41494F5538 +:108E5000A5A5A6A7A8A9AAABACADAEAFB0B1B2B359 +:108E6000B4414141B8B9BABBBCBDBEBFC0C1C2C3A9 +:108E7000C4C54141C8C9CACBCCCDCECFD1D145455F +:108E80004549494949D9DADBDCDD49DF4FE14F4F3C +:108E90004F4FE6E8E85555555959EEEFF0F1F2F32A +:108EA000F4F5F6F7F8F9FAFBFCFDFEFF0103050700 +:108EB000090E10121416181C1E00000061001A037F +:108EC000E0001703F8000703FF000100780100012C +:108ED000300132010601390110014A012E017901E8 +:108EE000060180014D00430281018201820184015B +:108EF000840186018701870189018A018B018B0129 +:108F00008D018E018F0190019101910193019401D6 +:108F1000F60196019701980198013D029B019C0181 +:108F20009D0120029F01A001A001A201A201A401B4 +:108F3000A401A601A701A701A901AA01AB01AC01E7 +:108F4000AC01AE01AF01AF01B101B201B301B30198 +:108F5000B501B501B701B801B801BA01BB01BC0147 +:108F6000BC01BE01F701C001C101C201C301C401BE +:108F7000C501C401C701C801C701CA01CB01CA01AB +:108F8000CD011001DD0101008E01DE011201F301AE +:108F90000300F101F401F401F80128012202120199 +:108FA0003A020900652C3B023B023D02662C3F025F +:108FB00040024102410246020A015302400081017F +:108FC0008601550289018A0158028F015A029001D7 +:108FD0005C025D025E025F02930161026202940123 +:108FE0006402650266026702970196016A02622CBA +:108FF0006C026D026E029C01700271029D0173028F +:1090000074029F0176027702780279027A027B026B +:109010007C02642C7E027F02A60181028202A901E9 +:109020008402850286028702AE014402B101B201C8 +:1090300045028D028E028F0290029102B7017B03DE +:109040000300FD03FE03FF03AC0304008603880353 +:1090500089038A03B1031103C2030200A303A3031C +:10906000C4030803CC0303008C038E038F03D803CF +:109070001801F2030A00F903F303F403F503F603FE +:10908000F703F703F903FA03FA033004200350044B +:109090001007600422018A043601C1040E01CF04C6 +:1090A0000100C004D0044401610526040000000052 +:1090B0007D1D0100632C001E9601A01E5A01001F99 +:1090C0000806101F0606201F0806301F0806401F4E +:1090D0000606511F0700591F521F5B1F541F5D1FBB +:1090E000561F5F1F601F0806701F0E00BA1FBB1FB0 +:1090F000C81FC91FCA1FCB1FDA1FDB1FF81FF91FAC +:10910000EA1FEB1FFA1FFB1F801F0806901F0806AF +:10911000A01F0806B01F0400B81FB91FB21FBC1F54 +:10912000CC1F0100C31FD01F0206E01F0206E51F6F +:109130000100EC1FF31F0100FC1F4E210100322132 +:1091400070211002842101008321D0241A05302CC3 +:109150002F04602C0201672C0601752C0201802C63 +:109160006401002D260841FF1A030000C700FC001F +:10917000E900E200E400E000E500E700EA00EB00BF +:10918000E800EF00EE00EC00C400C500C900E600F6 +:10919000C600F400F600F200FB00F900FF00D60064 +:1091A000DC00F800A300D800D7009201E100ED0038 +:1091B000F300FA00F100D100AA00BA00BF00AE002F +:1091C000AC00BD00BC00A100AB00BB009125922506 +:1091D000932502252425C100C200C000A9006325F3 +:1091E000512557255D25A200A500102514253425FD +:1091F0002C251C2500253C25E300C3005A255425B9 +:1092000069256625602550256C25A400F000D00056 +:10921000CA00CB00C8003101CD00CE00CF00182518 +:109220000C2588258425A600CC008025D300DF00EE +:10923000D400D200F500D500B500FE00DE00DA0053 +:10924000DB00D900FD00DD00AF00B400AD00B100CF +:109250001720BE00B600A700F700B800B000A800B5 +:10926000B700B900B300B200A025A00001000000C3 +:109270000000000000960000000000000000000058 +:1092800000000000000000000000000000000000DE +:10929000496600084D6600083D51000875540008F5 +:1092A000D1500008F950000821510008B9500008B9 +:1092B0000000000029550008155500085155000808 +:1092C0003D5500084955000835550008215500084E +:1092D0000D5500085D5500080000000041560008CB +:1092E0002D560008695600085556000861560008BA +:1092F0004D560008395600082556000875560008D6 +:1093000000000000010000000000000063300000C9 +:109310000C9300080000000000000000B846002088 +:10932000E84800200000812A00000000AAAAAAAA9A +:1093300000000024FFFE00000000000000A00A0062 +:109340000001000000000000AAAAAAAA0000000074 +:10935000FFFF000000000000000000001400AA56FB +:1093600000000000AAAAAAAA14005554FFFF00009A +:1093700000000000CCCC0C0020681A0000000000A7 +:10938000AAAA8AAA10541500FFFF0000000C70075B +:10939000770000004081020100100000AAAAAAAADA +:1093A00000410100F7FF000000000070070000000E +:1093B0000000000000000000AAAAAAAA0000000005 +:1093C000FFFF00000000000000000000000000009F +:1093D00000000000AAAAAAAA00000000FFFF0000E7 +:1093E000000000000000000000000000000000007D +:1093F000AAAAAAAA00000000FFFF000000000000C7 +:10940000000000000000000000000000AAAAAAAAB4 +:1094100000000000FFFF000000000000000000004E +:109420000000000000000000AAAAAAAA0000000094 +:10943000FFFF00000000000000000000000000002E +:1094400000000000AAAAAAAA00000000FFFF000076 +:1094500000000000000000004375626550696C6FF9 +:109460007400437562654F72616E67652B2D424CC7 +:10947000002553455249414C2500000002000000E0 +:109480000000000061580008D1580008400040006A +:1094900098610020A8610020020000000000000088 +:1094A000030000000000000019590008000000003F +:1094B00010000000B8610020000000000100000062 +:1094C000000000001465002001010200456700084B +:1094D00055660008F1660008D566000843000000E4 +:1094E000E494000809024300020100C032090400AC +:1094F0000001020201000524001001052401000101 +:10950000042402020524060001070582030800FF67 +:1095100009040100020A00000007050102400000E2 +:10952000070581024000000012000000309500088D +:109530001201100102000040AE2D5810000201027D +:10954000030100000403090425424F415244250051 +:10955000437562654F72616E6765506C757300305C +:109560003132333435363738394142434445460089 +:109570000000002000000200020000000000003097 +:1095800000000400080000000000002400000800A3 +:10959000040000000004000000FC000002000000C5 +:1095A00000000430008000000800000000000038C7 +:1095B00000000100010000001F1C1F1E1F1E1F1FB6 +:1095C0001E1F1E1F1F1D1F1E1F1E1F1F1E1F1E1FB3 +:1095D00000000000755A00082D5D0008D95D0008E4 +:1095E000400040004C6600204C6600200100000056 +:1095F0005C660020800000004001000008000000C0 +:1096000000010000001000000800000069646C65A3 +:10961000000000006D61696E002C043804043808F5 +:109620000C10141C202425260000000000006404F7 +:109630000100040000000000000C0010283034007D +:10964000286EFF7F010000002704000000000000DA +:1096500000001E0000000000FF000000F048002095 +:10966000FC38002068390020D439002000000000B8 +:10967000988D000883040000A38D000850040000AA +:10968000B18D0008010000000000000000960000FD +:109690000000080096000000000800000400000020 +:1096A00044950008000000000000000000000000D9 +:1096B00000000000000000000000000078220020F0 +:1096C000000000000000000000000000000000009A +:1096D000000000000000000000000000000000008A +:1096E000000000000000000000000000000000007A +:1096F000000000000000000000000000000000006A +:109700000000000000000000000000000000000059 +:109710000000000000000000000000000000000049 :00000001FF diff --git a/Tools/bootloaders/CubeOrange_bl.bin b/Tools/bootloaders/CubeOrange_bl.bin index 243033814f0152..cd5b57818bff26 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 376200bb94e6a4..f8477f312eaf59 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 d9b147151e1e9d..aea4d36ed1a818 100644 --- a/Tools/bootloaders/CubeOrange_bl.hex +++ b/Tools/bootloaders/CubeOrange_bl.hex @@ -1,1117 +1,2427 @@ :020000040800F2 -:1000000000060020A102000869100008E90F00089E -:1000100041100008E90F000815100008A3020008AD -:10002000A3020008A3020008A3020008A12A0008F6 -:10003000A3020008A3020008A3020008A30200080C -:10004000A3020008A3020008A3020008A3020008FC -:10005000A3020008A3020008293F0008553F00083A -:10006000813F0008AD3F0008D93F0008A302000807 -:10007000A3020008A3020008A3020008A3020008CC -:10008000A3020008A3020008A3020008A3020008BC -:10009000A3020008A3020008A3020008054000080C -:1000A000A3020008A3020008A3020008A30200089C -:1000B000A3020008A3020008A3020008A30200088C -:1000C000A3020008A3020008A3020008A30200087C -:1000D000A3020008A3020008DD400008F140000868 -:1000E00069400008A3020008A3020008A302000858 -:1000F000A3020008A3020008A3020008A30200084C -:10010000A3020008A302000819410008A302000886 -:10011000A3020008A3020008A3020008A30200082B -:10012000A3020008A3020008A3020008A30200081B -:10013000A3020008A3020008A3020008A30200080B -:10014000A3020008A3020008A3020008A3020008FB -:10015000A3020008A3020008A3020008A3020008EB -:10016000A3020008A3020008A3020008A3020008DB -:10017000A30200080D360008A3020008A30200082D -:10018000A3020008A302000805410008A30200081A -:10019000A3020008A3020008A3020008A3020008AB -:1001A000A3020008A3020008A3020008A30200089B -:1001B000A3020008A3020008A3020008A30200088B -:1001C000A3020008A3020008A3020008A30200087B -:1001D000A3020008F9350008A3020008A3020008E2 -:1001E000A3020008A3020008A3020008A30200085B -:1001F000A3020008A3020008A3020008A30200084B -:10020000A3020008A3020008A3020008A30200083A -:10021000A3020008A3020008A3020008A30200082A -:10022000A3020008A3020008A3020008A30200081A -:10023000A3020008A3020008A3020008A30200080A -:10024000A3020008A3020008A3020008A3020008FA -:10025000A3020008A3020008A3020008A3020008EA -:10026000A3020008A3020008A3020008A3020008DA -:10027000A3020008A3020008A3020008A3020008CA -:10028000A3020008A3020008A3020008A3020008BA -:10029000A3020008A3020008A3020008A3020008AA -:1002A00002E000F000F8FEE73B48804772B63B48AA -:1002B00080F308883A4880F309883A484EF6085196 -:1002C000CEF20001086040F20000CCF200004EF6D1 -:1002D0003471CEF200010860BFF34F8FBFF36F8F10 -:1002E00040F20000C0F2F0004EF68851CEF200015C -:1002F0000860BFF34F8FBFF36F8F4FF00000E1EE48 -:10030000100A4EF63C71CEF200010860062080F320 -:100310001488BFF36F8F02F081FC02F023FC03F01E -:10032000BDFB4FF0553020491C4A91423CBF41F87B -:10033000040BFAE71D491A4A91423CBF41F8040BED -:10034000FAE71B491B4A1C4B9A423EBF51F8040B6B -:1003500042F8040BF8E700201849194A91423CBFC3 -:1003600041F8040BFAE702F03BFC03F01BFC154CD0 -:10037000154DAC4203DA54F8041B8847F9E700F046 -:1003800043F8124C124DAC4203DA54F8041B884770 -:10039000F9E702F023BC00006D1000080006002001 -:1003A00000220020000000080000002000060020BD -:1003B00050450008002200205C220020602200201E -:1003C000D44F0020A0020008A0020008A0020008EC -:1003D000A00200082DE9F04F2DED108AC1F80CD0D5 -:1003E000D0F80CD0BDEC108ABDE8F08F002383F369 -:1003F00011882846A047002001F02AFFFEE701F0FF -:10040000A5FE00DFFEE7000038B500F0F1FC30B1DA -:10041000164B00220E211A725A729972DA7202F089 -:10042000F3FA054602F026FB0446D0B9104B9D4274 -:1004300019D001339D4241F2883512BF0446002590 -:100440000124002002F0EAFA0CB100F079F800F083 -:100450006BFD00F013FC284600F020F900F070F866 -:10046000F9E70025EDE70546EBE700BF0022002095 -:10047000010007B008B500F0CDFBA0F12003584201 -:10048000584108BD07B541F21203022101A8ADF899 -:10049000043000F0DDFB03B05DF804FB38B5202329 -:1004A00083F311881748C3680BB101F057FF00238D -:1004B000154A4FF47A71134801F014FF002383F3B7 -:1004C0001188124C236813B12368013B23606368D1 -:1004D00013B16368013B63600D4D2B7833B96368DA -:1004E0007BB9022000F09AFC322363602B78032B47 -:1004F00007D163682BB9022000F090FC4FF47A73A7 -:10050000636038BD602200209D0400087C23002029 -:1005100074220020084B187003280CD8DFE800F084 -:1005200008050208022000F06FBC022000F062BC47 -:10053000024B00225A607047742200207C23002066 -:10054000F8B5504B504A1C461968013100F09980AB -:1005500004339342F8D162684C4B9A4240F2918046 -:100560004B4B9B6803F1006303F500339A4280F024 -:100570008880002000F09CFB0220FFF7CBFF454B5A -:100580000021D3F8E820C3F8E810D3F81021C3F80D -:100590001011D3F81021D3F8EC20C3F8EC10D3F8E5 -:1005A0001421C3F81411D3F81421D3F8F020C3F8A0 -:1005B000F010D3F81821C3F81811D3F81821D3F884 -:1005C000802042F00062C3F88020D3F8802022F01F -:1005D0000062C3F88020D3F88020D3F8802042F056 -:1005E0000072C3F88020D3F8802022F00072C3F894 -:1005F0008020D3F8803072B64FF0E023C3F8084D66 -:10060000D4E90004BFF34F8FBFF36F8F224AC2F8C3 -:100610008410BFF34F8F536923F480335361BFF3CA -:100620004F8FD2F8803043F6E076C3F3C905C3F3A9 -:100630004E335B0103EA060C29464CEA8177013907 -:10064000C2F87472F9D2203B13F1200FF2D1BFF33C -:100650004F8FBFF36F8FBFF34F8FBFF36F8F536910 -:1006600023F4003353610023C2F85032BFF34F8F9D -:10067000BFF36F8F202383F31188854680F30888AA -:100680002047F8BD0000020820000208FFFF010813 -:10069000002200200044025800ED00E02DE9F04F58 -:1006A00093B0A84B2022FF2100900AA89D6800F07B -:1006B000E5FBA54A1378A3B90121A4481170C360D2 -:1006C000202383F31188C3680BB101F047FE002398 -:1006D0009F4A4FF47A719D4801F004FE002383F392 -:1006E0001188009B13B19B4B009A1A609A4A1378A9 -:1006F000032B03D000231370964A53604FF0000A77 -:10070000009CD3465646D146012000F07DFB24B123 -:10071000904B1B68002B00F00E82002000F07AFA4C -:100720000390039B002BF2DB012000F063FB039B93 -:10073000213B162BE8D801A252F823F099070008B4 -:10074000C107000855080008090700080907000844 -:1007500009070008DD080008AB0A0008C509000801 -:10076000270A00084F0A0008750A00080907000850 -:10077000870A000809070008F90A00083908000874 -:10078000090700083D0B0008A50700083908000804 -:1007900009070008270A00080220FFF76BFE00285F -:1007A00040F0F381009B022105A8BAF1000F08BFB9 -:1007B0001C4641F21233ADF8143000F049FAA3E7B9 -:1007C0004FF47A7000F026FA071EEBDB0220FFF7E9 -:1007D00051FE0028E6D0013F052F00F2D881DFE866 -:1007E00007F0030A0D1013360523042105A805930D -:1007F00000F02EFA17E004215248F9E70421574887 -:10080000F6E704215648F3E74FF01C08404608F18C -:10081000040800F04FFA0421059005A800F018FA2A -:10082000B8F12C0FF2D101204FF0000900FA07F7C0 -:1008300047EA0B0B5FFA8BFB00F06CFB26B10BF069 -:100840000B030B2B08BF0024FFF71CFE5CE7042101 -:100850004448CDE7002EA5D00BF00B030B2BA1D104 -:100860000220FFF707FE074600289BD00120002644 -:1008700000F01EFA0220FFF74DFE5FFA86F84046B0 -:1008800000F026FA044688B14046013600F030FAFE -:100890000028F2D1BA46044641F21213022105A8FB -:1008A0003E46ADF8143000F0D3F92DE7254601207F -:1008B000FFF730FE234B9B68AB4207D9284600F078 -:1008C000F9F9013040F066810435F3E70025224B49 -:1008D000BA463E461D701F4B5D60ADE7002E3FF4EB -:1008E00061AF0BF00B030B2B7FF45CAF0220FFF723 -:1008F00011FE322000F08EF9B0F10008FFF652AF81 -:1009000018F003077FF44EAF0E4A08EB0503926818 -:1009100093423FF647AFB8F5807F3FF743AF124BA6 -:10092000B845019322DD4FF47A7000F073F903901B -:10093000039A002AFFF636AF039A0137019B03F8AA -:10094000012BEDE700220020782300206022002008 -:100950009D0400087C230020742200200422002033 -:10096000082200200C22002078220020C820FFF757 -:1009700081FD074600283FF415AF1F2D11D8C5F1A2 -:1009800020020AAB25F0030084494245184428BFE1 -:100990004246019200F04CFA019AFF217F4800F094 -:1009A0006DFA4FEAA803C8F387027C4928460193F1 -:1009B00000F06CFA064600283FF46EAF019B05EB91 -:1009C000830539E70220FFF755FD00283FF4EAAE22 -:1009D00000F0AAF900283FF4E5AE0027B846704BB6 -:1009E0009B68BB4218D91F2F11D80A9B01330ED028 -:1009F00027F0030312AA134453F8203C0593404602 -:100A0000042205A9043700F04FFB8046E7E738468B -:100A100000F050F90590F2E7CDF81480042105A804 -:100A200000F016F908E70023642104A8049300F0FD -:100A300005F900287FF4B6AE0220FFF71BFD002861 -:100A40003FF4B0AE049800F065F90590E6E70023A6 -:100A5000642104A8049300F0F1F800287FF4A2AE0A -:100A60000220FFF707FD00283FF49CAE049800F039 -:100A700053F9EAE70220FFF7FDFC00283FF492AEAD -:100A800000F062F9E1E70220FFF7F4FC00283FF4F0 -:100A900089AE05A9142000F05DF9074604210490F1 -:100AA00004A800F0D5F83946B9E7322000F0B2F8D2 -:100AB000071EFFF677AEBB077FF474AE384A07EB2C -:100AC0000903926893423FF66DAE0220FFF7D2FC15 -:100AD00000283FF467AE27F003074F44B9453FF4C1 -:100AE000ABAE484609F1040900F0E4F80421059092 -:100AF00005A800F0ADF8F1E74FF47A70FFF7BAFC03 -:100B000000283FF44FAE00F00FF9002844D00A9BB4 -:100B100001330BD008220AA9002000F0B7F9002801 -:100B20003AD02022FF210AA800F0A8F9FFF7AAFC7A -:100B30001C4801F093FB13B0BDE8F08F002E3FF48A -:100B400031AE0BF00B030B2B7FF42CAE0023642192 -:100B500005A8059300F072F8074600287FF422AE3E -:100B60000220FFF787FC804600283FF41BAEFFF70A -:100B700089FC41F2883001F071FB059800F014FA0D -:100B800046463C4600F0C6F9BEE5064654E64FF040 -:100B9000000907E6BA467FE637467DE67822002060 -:100BA00000220020A08601002DE9F84F4FF47A734F -:100BB00006460D46002402FB03F7DFF85080DFF8FD -:100BC000509098F900305FFA84FA5A1C01D0A34281 -:100BD00010D159F824002A4631460368D3F820B0D2 -:100BE0003B46D847854205D1074B012083F800A03A -:100BF000BDE8F88F0134042CE3D14FF4FA7001F012 -:100C00002DFB0020F4E700BFC823002010220020A5 -:100C10001C420008002307B5024601210DF1070020 -:100C20008DF80730FFF7C0FF20B19DF8070003B033 -:100C30005DF804FB4FF0FF30F9E700000A4604219D -:100C400008B5FFF7B1FF80F00100C0B2404208BD17 -:100C5000074B0A4630B41978064B53F82140014639 -:100C600023682046DD69044BAC4630BC604700BFBA -:100C7000C82300201C420008A086010070B50A4E5F -:100C800000240A4D01F098FD3080286833888342A3 -:100C900008D901F08DFD2B6804440133B4F5003F01 -:100CA0002B60F2D370BD00BFCA2300208423002034 -:100CB00001F060BE00F1006000F500300068704790 -:100CC00000F10060920000F5003001F0D7BD000097 -:100CD000054B1A68054B1B889B1A834202D91044A6 -:100CE00001F066BD0020704784230020CA23002045 -:100CF00038B5074D04462868204401F05FFD28B947 -:100D000028682044BDE8384001F06ABD38BD00BF06 -:100D1000842300200020704700F1FF5000F58F1061 -:100D2000D0F8000870470000064991F8243033B12C -:100D300000230822086A81F82430FFF7C1BF012090 -:100D4000704700BF88230020014B1868704700BF20 -:100D50000010005C244BF0B51A680446234BC2F324 -:100D60000B06120C1F885868BE4293F9085028D011 -:100D70009F89BE4206D101200C2505FB003358682F -:100D800093F9085041F201039A421CD041F2030347 -:100D90009A421AD042F201039A4218D042F2030357 -:100DA0009A4208BF5625621E0B46441E0A449342CF -:100DB0000FD214F9016F581C6EB1034600F8016C94 -:100DC000F5E70020D8E75A25EDE75925EBE7582548 -:100DD000E9E7184605E02C2482421C7001D9981CD2 -:100DE0005D70401AF0BD00BF0010005C14220020AE -:100DF00000207047022803D1024B4FF080529A61C5 -:100E0000704700BF00100258022803D1024B4FF474 -:100E100080529A61704700BF00100258022804D126 -:100E2000024A536983F4805353617047001002589B -:100E3000002310B5934203D0CC5CC4540133F9E7CE -:100E400010BD0000013810B510F9013F3BB191F918 -:100E500000409C4203D11AB10131013AF4E71AB1C2 -:100E600091F90020981A10BD1046FCE7034602468F -:100E7000D01A12F9011B0029FAD170470244034627 -:100E8000934202D003F8011BFAE770472DE9F843BB -:100E90001F4D14460746884695F8242052BBDFF8BC -:100EA00070909CB395F824302BB92022FF2148463E -:100EB0002F62FFF7E3FF95F824004146C0F10802D6 -:100EC00005EB8000A24228BF2246D6B29200FFF76F -:100ED000AFFF95F82430A41B17441E449044E4B29D -:100EE000F6B2082E85F82460DBD1FFF71DFF00283D -:100EF000D7D108E02B6A03EB82038342CFD0FFF700 -:100F000013FF0028CBD10020BDE8F8830120FBE7C8 -:100F100088230020024B1A78024B1A70704700BFDA -:100F2000C823002010220020F8B5194C194800F001 -:100F300097FC2146174800F0BFFC24681648D4F8F7 -:100F40009020164ED2F80438154D43F00203114F8D -:100F5000C2F8043801F082F92046124900F0BAFDC7 -:100F6000D4F890200424D2F8043823F00203C2F805 -:100F700004384FF4E133336055F8040BB84202D023 -:100F8000314600F0CBFB013C14F0FF04F4D1F8BD76 -:100F900034430008C832002040420F00B023002034 -:100FA0001C4200083C43000838B50B4B04461A7835 -:100FB0000A4B53F822500A4B9D420CD0094B00219A -:100FC00018221846FFF75AFF046001462846BDE87C -:100FD000384000F0A3BB38BDC82300201C420008E5 -:100FE000C8320020B023002000B59BB0EFF3098188 -:100FF00068226846FFF71CFFEFF30583044B9A6BEA -:10100000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE79E -:1010100000ED00E000B59BB0EFF30981682268465F -:10102000FFF706FFEFF30583044B9A6B9A6A9A6AFF -:101030009A6A9A6A9A6A9B6AFEE700BF00ED00E02E -:1010400000B59BB0EFF3098168226846FFF7F0FE18 -:10105000EFF30583034B5A6B9A6A9A6A9A6A9A6A03 -:101060009B6AFEE700ED00E0FEE7000000B595B0EA -:10107000132101A801F00EFD9DF84F307BB1002334 -:10108000132101A88DF84F3001F0FEFC054BD3F879 -:10109000002882F30888D3F804389847FEE715B093 -:1010A0005DF804FB0090F01F30B50A44084D9142F2 -:1010B0000DD011F8013B5840082340F30004013BD8 -:1010C0002C4013F0FF0384EA5000F6D1EFE730BD67 -:1010D0002083B8ED026843681143016003B11847EB -:1010E00070470000024A136843F0C0031360704762 -:1010F00000440040024A136843F0C0031360704785 -:1011000000480040024A136843F0C0031360704770 -:101110000078004037B5274C274D204600F0F2FA02 -:1011200004F11400009400234FF40072234900F0EE -:10113000B3F94FF40072224904F138000094214BB6 -:1011400000F02CFA204BC4E91735204C204600F063 -:10115000D9FA04F11400009400234FF400721C49E2 -:1011600000F09AF94FF400721A4904F13800009423 -:10117000194B00F013FA194BC4E91735184C2046E7 -:1011800000F0C0FA04F1140000234FF40072154976 -:10119000009400F081F9144B4FF40072134904F1EC -:1011A0003800009400F0FAF9114BC4E9173503B088 -:1011B00030BD00BFCC23002000E1F5051025002044 -:1011C000102B0020E51000080044004038240020C7 -:1011D00010270020102D0020F510000800480040C6 -:1011E000A42400201029002005110008102F002041 -:1011F00000780040037C30B5334C002918BF0C4602 -:10120000012B18D1314B98420FD1314BD3F8E82044 -:1012100042F40032C3F8E820D3F8102142F400323F -:10122000C3F81021D3F8103105E02A4B98422FD093 -:10123000294B984238D02268036EC16D03EB5203EC -:101240008466B3FBF2F36268150442BF23F007051E -:1012500003F0070343EA4503CB60A36843F0400370 -:101260004B60E36843F001038B6042F4967343F0F4 -:1012700001030B604FF0FF330B62510505D512F0EF -:1012800010221DD0B2F1805F1CD080F8643030BDD8 -:101290000F4BD3F8E82042F48022C3F8E820D3F8BB -:1012A000102142F48022BBE7094BD3F8E82042F03A -:1012B0008042C3F8E820D3F8102142F08042AFE723 -:1012C0007F23E2E73F23E0E72C420008CC23002005 -:1012D0000044025838240020A42400202DE9F047BF -:1012E000C66D05463768F4692107346219D014F0D9 -:1012F000080118BF8021E20748BF41F02001A30781 -:101300004FF0200348BF41F04001600748BF41F45F -:10131000807183F31188281DFFF7DCFE002383F31F -:101320001188E2050AD5202383F311884FF4007158 -:10133000281DFFF7CFFE002383F311884FF020090B -:101340004FF0000A14F0200838D13B0616D54FF0B4 -:10135000200905F1380A200610D589F31188504676 -:1013600000F050F9002836DA0821281DFFF7B2FEF8 -:1013700027F080033360002383F31188790614D5A6 -:10138000620612D5202383F31188D5E913239A42EC -:1013900008D12B6C33B127F040071021281DFFF72F -:1013A00099FE3760002383F31188E30618D5AA6EEF -:1013B0001369ABB15069BDE8F047184789F311884C -:1013C000736A284695F86410194000F0B5F98AF35D -:1013D0001188F469B6E7B06288F31188F469BAE756 -:1013E000BDE8F087F8B51546826804460B46AA4268 -:1013F00000D28568A1692669761AB5420BD21846D3 -:101400002A46FFF715FDA3692B44A3612846A3686C -:101410005B1BA360F8BD0CD9AF1B18463246FFF723 -:1014200007FD3A46E1683044FFF702FDE3683B44BC -:10143000EBE718462A46FFF7FBFCE368E5E7000008 -:1014400083689342F7B50446154600D28568D4E90F -:101450000460361AB5420BD22A46FFF7E9FC6369ED -:101460002B4463612846A3685B1BA36003B0F0BDF7 -:101470000DD93246AF1B0191FFF7DAFC01993A46CC -:10148000E0683144FFF7D4FCE3683B44E9E72A46CF -:10149000FFF7CEFCE368E4E710B50A440024C3611B -:1014A000029B8460C16002610362C0E90000C0E980 -:1014B000051110BD08B5D0E90532934201D182680B -:1014C00082B98268013282605A1C4261197000211F -:1014D000D0E904329A4224BFC368436100F0DAFEC7 -:1014E000002008BD4FF0FF30FBE7000070B520235F -:1014F00004460E4683F31188A568A5B1A368A269C6 -:10150000013BA360531CA36115782269934224BF59 -:10151000E368A361E3690BB120469847002383F396 -:101520001188284607E03146204600F0A3FE002837 -:10153000E2DA85F3118870BD2DE9F74F04460E46B7 -:1015400017469846D0F81C904FF0200A8AF311886D -:101550004FF0000B154665B12A4631462046FFF78D -:1015600041FF034660B94146204600F083FE002853 -:10157000F1D0002383F31188781B03B0BDE8F08F0E -:10158000B9F1000F03D001902046C847019B8BF3AF -:101590001188ED1A1E448AF31188DCE7C160C3612B -:1015A000009B82600362C0E905111144C0E900009C -:1015B00001617047F8B504460D461646202383F3B3 -:1015C0001188A768A7B1A368013BA36063695A1C8F -:1015D00062611D70D4E904329A4224BFE3686361FA -:1015E000E3690BB120469847002080F3118807E09B -:1015F0003146204600F03EFE0028E2DA87F31188EB -:10160000F8BD0000D0E9052310B59A4201D18268E7 -:101610007AB982680021013282605A1C82611C788A -:1016200003699A4224BFC368836100F033FE2046F9 -:1016300010BD4FF0FF30FBE72DE9F74F04460E4693 -:1016400017469846D0F81C904FF0200A8AF311886C -:101650004FF0000B154665B12A4631462046FFF78C -:10166000EFFE034660B94146204600F003FE002825 -:10167000F1D0002383F31188781B03B0BDE8F08F0D -:10168000B9F1000F03D001902046C847019B8BF3AE -:101690001188ED1A1E448AF31188DCE7026843685A -:1016A0001143016003B11847704700001430FFF781 -:1016B00043BF00004FF0FF331430FFF73DBF000081 -:1016C0003830FFF7B9BF00004FF0FF333830FFF775 -:1016D000B3BF00001430FFF709BF00004FF0FF3127 -:1016E0001430FFF703BF00003830FFF763BF00007E -:1016F0004FF0FF323830FFF75DBF00000020704729 -:10170000FFF708BD044B036000234360C0E90233C8 -:1017100001230374704700BF4442000810B5202322 -:10172000044683F31188FFF765FD02232374002329 -:1017300083F3118810BD000038B5C36904460D4617 -:101740001BB904210844FFF7A9FF294604F114003E -:10175000FFF7B0FE002806DA201D4FF48061BDE8D7 -:101760003840FFF79BBF38BD0268436811430160F2 -:1017700003B118477047000013B5406B00F5805463 -:10178000D4F8A4381A681178042914D1017C0229EC -:1017900011D11979012312898B4013420BD101A970 -:1017A0004C3002F07BF8D4F8A4480246019B217922 -:1017B000206800F0DFF902B010BD0000143001F025 -:1017C000FDBF00004FF0FF33143001F0F7BF000001 -:1017D0004C3002F0CFB800004FF0FF334C3002F035 -:1017E000C9B80000143001F0CBBF00004FF0FF314A -:1017F000143001F0C5BF00004C3002F09BB800006F -:101800004FF0FF324C3002F095B8000000207047D6 -:1018100010B500F58054D4F8A4381A68117804295A -:1018200017D1017C022914D15979012352898B40A7 -:1018300013420ED1143001F05DFF024648B1D4F8D6 -:10184000A4484FF4407361792068BDE8104000F06F -:101850007FB910BD406BFFF7DBBF00007047000091 -:101860007FB5124B0125042604460360002305744E -:1018700000F1840243602946C0E902330C4B029018 -:10188000143001934FF44073009601F00FFF094BA1 -:1018900004F69442294604F14C000294CDE9006319 -:1018A0004FF4407301F0D6FF04B070BD6C420008E5 -:1018B00055180008791700080A68202383F3118857 -:1018C0000B790B3342F823004B79133342F8230092 -:1018D0008B7913B10B3342F8230000F58053C3F822 -:1018E000A41802230374002383F3118870470000B7 -:1018F00038B5037F044613B190F85430ABB90125D5 -:10190000201D0221FFF730FF04F114006FF00101E8 -:10191000257700F0CBFC04F14C0084F854506FF0B4 -:101920000101BDE8384000F0C1BC38BD10B501214F -:1019300004460430FFF718FF0023237784F854305F -:1019400010BD000038B504460025143001F0C6FE75 -:1019500004F14C00257701F095FF201D84F85450C8 -:101960000121FFF701FF2046BDE83840FFF750BFD7 -:1019700090F8803003F06003202B06D190F881208E -:101980000023212A03D81F2A06D800207047222AC4 -:10199000FBD1C0E91D3303E0034A42670722826797 -:1019A000C3670120704700BF2C22002037B500F527 -:1019B0008055D5F8A4381A68117804291AD1017C09 -:1019C000022917D11979012312898B40134211D1B1 -:1019D00000F14C04204602F015F858B101A9204648 -:1019E00001F05CFFD5F8A4480246019B21792068EC -:1019F00000F0C0F803B030BD01F10B03F0B550F8B2 -:101A0000236085B004460D46FEB1202383F3118880 -:101A100004EB8507301D0821FFF7A6FEFB6806F1E1 -:101A20004C005B691B681BB1019001F045FF0198F8 -:101A300003A901F033FF024648B1039B2946204623 -:101A400000F098F8002383F3118805B0F0BDFB681F -:101A50005A691268002AF5D01B8A013B1340F1D164 -:101A600004F18002EAE70000133138B550F8214054 -:101A7000ECB1202383F3118804F58053D3F8A42814 -:101A80001368527903EB8203DB689B695D6845B19B -:101A900004216018FFF768FE294604F1140001F0E4 -:101AA00033FE2046FFF7B4FE002383F3118838BDD0 -:101AB0007047000001F026B901234022002110B533 -:101AC000044600F8303BFFF7D9F90023C4E901339D -:101AD00010BD000010B52023044683F31188242292 -:101AE000416000210C30FFF7C9F9204601F02CF9C4 -:101AF00002232370002383F3118810BD70B500EB1F -:101B00008103054650690E461446DA6018B110226A -:101B10000021FFF7B3F9A06918B110220021FFF7E7 -:101B2000ADF931462846BDE8704001F01FBA00000B -:101B300083682022002103F0011310B5044683605E -:101B40001030FFF79BF92046BDE8104001F09ABA2B -:101B5000F0B4012500EB810447898D40E4683D43E2 -:101B6000A469458123600023A2606360F0BC01F09A -:101B7000B7BA0000F0B4012500EB810407898D405D -:101B8000E4683D436469058123600023A2606360CB -:101B9000F0BC01F02DBB000070B502230025044607 -:101BA000242203702946C0F888500C3040F8045CA9 -:101BB000FFF764F9204684F8705001F06BF9636810 -:101BC0001B6823B129462046BDE87040184770BD08 -:101BD000037880F88C300523037043681B6810B5C8 -:101BE00004460BB1042198470023A36010BD0000F8 -:101BF00090F88C20436802701B680BB105211847D0 -:101C00007047000070B590F87030044613B100239F -:101C100080F8703004F18002204601F057FA6368C2 -:101C20009B68B3B994F8803013F0600535D000217B -:101C3000204601F001FD0021204601F0F1FC63681F -:101C40001B6813B1062120469847062384F870309C -:101C500070BD204698470028E4D0B4F88630A26FC3 -:101C60009A4288BFA36794F98030A56F002B4FF08C -:101C7000200380F20381002D00F0F280092284F815 -:101C8000702083F3118800212046D4E91D23FFF73B -:101C900071FF002383F31188DAE794F8812003F0C1 -:101CA0007F0343EA022340F20232934200F0C580F0 -:101CB00021D8B3F5807F48D00DD8012B3FD0022B1F -:101CC00000F09380002BB2D104F1880262670222F7 -:101CD000A267E367C1E7B3F5817F00F09B80B3F5AE -:101CE000407FA4D194F88230012BA0D1B4F8883081 -:101CF00043F0020332E0B3F5006F4DD017D8B3F5CF -:101D0000A06F31D0A3F5C063012B90D86368204643 -:101D100094F882205E6894F88310B4F88430B04759 -:101D2000002884D0436863670368A3671AE0B3F5AB -:101D3000106F36D040F6024293427FF478AF5C4B8E -:101D400063670223A3670023C3E794F88230012B63 -:101D50007FF46DAFB4F8883023F00203A4F8883024 -:101D6000C4E91D55E56778E7B4F88030B3F5A06F96 -:101D70000ED194F88230204684F88A3001F0E8F8D9 -:101D800063681B6813B10121204698470323237021 -:101D90000023C4E91D339CE704F18B03636701232F -:101DA000C3E72378042B10D1202383F31188204626 -:101DB000FFF7BEFE85F311880321636884F88B501A -:101DC00021701B680BB12046984794F88230002B95 -:101DD000DED084F88B300423237063681B68002BEB -:101DE000D6D0022120469847D2E794F88430204686 -:101DF0001D0603F00F010AD501F05AF9012804D09D -:101E000002287FF414AF2B4B9AE72B4B98E701F095 -:101E100041F9F3E794F88230002B7FF408AF94F88F -:101E2000843013F00F01B3D01A06204602D501F01A -:101E30001BFCADE701F00CFCAAE794F88230002B04 -:101E40007FF4F5AE94F8843013F00F01A0D01B0698 -:101E5000204602D501F0F0FB9AE701F0E1FB97E79D -:101E6000142284F8702083F311882B462A462946D1 -:101E70002046FFF76DFE85F31188E9E65DB1152276 -:101E800084F8702083F3118800212046D4E91D23B3 -:101E9000FFF75EFEFDE60B2284F8702083F31188C5 -:101EA0002B462A4629462046FFF764FEE3E700BF9B -:101EB0009C420008944200089842000838B590F807 -:101EC00070300446002B3ED0063BDAB20F2A34D8DD -:101ED0000F2B32D8DFE803F03731310822323131AD -:101EE0003131313131313737856FB0F886309D422D -:101EF00014D2C3681B8AB5FBF3F203FB12556DB90C -:101F0000202383F311882B462A462946FFF732FE09 -:101F100085F311880A2384F870300EE0142384F8C6 -:101F20007030202383F31188002320461A46194677 -:101F3000FFF70EFE002383F3118838BDC36F03B192 -:101F400098470023E7E70021204601F075FB0021B8 -:101F5000204601F065FB63681B6813B1062120462B -:101F600098470623D7E7000010B590F87030044674 -:101F7000142B29D017D8062B05D001D81BB110BDC2 -:101F8000093B022BFBD80021204601F055FB002124 -:101F9000204601F045FB63681B6813B1062120460B -:101FA0009847062319E0152BE9D10B2380F87030F0 -:101FB000202383F3118800231A461946FFF7DAFD20 -:101FC000002383F31188DAE7C3689B695B68002B01 -:101FD000D5D1C36F03B19847002384F87030CEE7A2 -:101FE000024B0022C3E900339A6070471031002091 -:101FF000002382680374054B1B6899689142FBD2E9 -:102000005A680360426010605860704710310020C9 -:1020100008B5202383F31188037C032B05D0042B00 -:102020000DD02BB983F3118808BD436900221A60D3 -:102030004FF0FF334361FFF7DBFF0023F2E7D0E906 -:10204000003213605A60F3E7002382680374054B83 -:102050001B6899689142FBD85A680360426010601F -:102060005860704710310020054B196908741868D2 -:10207000026853601A60186101230374FEF7AAB95D -:10208000103100204B1C30B5044687B00A4D10D0EB -:102090002B6901A8094A00F025F92046FFF7E4FF63 -:1020A000049B13B101A800F059F92B69586907B0D6 -:1020B00030BDFFF7D9FFF8E71031002011200008EC -:1020C00038B50C4D044641612B6981689A6891428C -:1020D00003D8BDE83840FFF78BBF1846FFF7B4FFC1 -:1020E00001232C61014623742046BDE83840FEF7E9 -:1020F00071B900BF10310020044B1A681B69906849 -:102100009B68984294BF0020012070471031002046 -:1021100010B5084C236820691A68546022600122B7 -:1021200023611A74FFF790FF01462069BDE8104053 -:10213000FEF750B91031002008B5FFF7DDFF18B1E8 -:10214000BDE80840FFF7E4BF08BD0000FFF7E0BFAF -:10215000FEE7000010B50C4CFFF742FF00F0B4F8AA -:1021600080220A49204600F03BF8012344F8180C6D -:10217000037400F0A5FC002383F3118862B60448C1 -:10218000BDE8104000F04CB838310020A0420008F3 -:10219000B042000800F01CB9EFF3118020B9EFF352 -:1021A0000583202282F311887047000010B530B9F2 -:1021B000EFF30584C4F3080414B180F3118810BD53 -:1021C000FFF7BAFF84F31188F9E70000034A51686A -:1021D00053685B1A9842FBD8704700BF001000E0BC -:1021E00082600222028270478368A3F17C0243F876 -:1021F0000C2C026943F83C2C426943F8382C074AFE -:1022000043F81C2CC268A3F1180043F8102C0222DA -:1022100003F8082C002203F8072C7047ED03000890 -:1022200010B5202383F31188FFF7DEFF0021044659 -:10223000FFF746FF002383F31188204610BD0000FE -:10224000024B1B6958610F20FFF70EBF10310020B1 -:10225000202383F31188FFF7F3BF000008B5014680 -:10226000202383F311880820FFF70CFF002383F35A -:10227000118808BD49B1064B42681B6918605A6055 -:10228000136043600420FFF7FDBE4FF0FF3070473E -:10229000103100200368984206D01A68026050602E -:1022A00018465961FFF7A4BE7047000038B50446D0 -:1022B0000D462068844200D138BD036823605C600D -:1022C0004561FFF795FEF4E7054B4FF0FF3103F151 -:1022D0001402C3E905220022C3E90712704700BFB8 -:1022E0001031002070B51C4E05460C46C0E9032392 -:1022F00001F0BEFB334653F8142F9A420DD13062E1 -:102300000A2C2CBF00190A302A60C5E90124C6E94D -:102310000555BDE8704001F095BB316A431AE318DA -:1023200038BF1C469368A34202D9081901F09AFBF2 -:1023300073699A6894420CD85A68AC602B606A60E2 -:1023400015609A685D60121B9A604FF0FF33F3616D -:1023500070BDA41A1B68ECE71031002038B51B4C87 -:10236000636998420DD08168D0E9003213605A60E9 -:102370000022C2609A680A449A604FF0FF33E3611A -:1023800038BD03682246002142F8143F93425A6048 -:10239000C16003D1BDE8384001F05EBB9A68816836 -:1023A000256A0A449A6001F063FB6369411B9A68DD -:1023B0008A42E5D9AB181D1A206A092D98BF01F190 -:1023C0000A02BDE83840104401F04CBB1031002037 -:1023D0002DE9F041184C002704F11406656901F05D -:1023E00047FB236AAA68C11A8A4215D81344D5F854 -:1023F0000C802362D5E9003213605A606369EF6094 -:10240000B34201D101F028FB87F311882869C04746 -:10241000202383F31188E1E76169B14209D01344B5 -:102420001B1ABDE8F0410A2B2CBFC0180A3001F07E -:1024300019BBBDE8F08100BF1031002000207047BB -:10244000FEE70000704700004FF0FF3070470000CB -:1024500002290CD0032904D00129074818BF002005 -:102460007047032A05D8054800EBC20070470448AE -:1024700070470020704700BF984300083C220020AE -:102480004C43000870B59AB005460846144601A9A9 -:1024900000F0C2F801A8FEF7E9FC431C0022C6B216 -:1024A0005B001046C5E9003423700323023404F8AE -:1024B000013C01ABD1B202348E4201D81AB070BDDA -:1024C00013F8011B013204F8010C04F8021CF1E7B7 -:1024D00008B5202383F311880348FFF767FA002328 -:1024E00083F3118808BD00BFC832002090F8803007 -:1024F00003F01F02012A07D190F881200B2A03D193 -:102500000023C0E91D3315E003F06003202B08D140 -:10251000B0F884302BB990F88120212A03D81F2AE3 -:1025200004D8FFF725BA222AEBD0FAE7034A42671C -:1025300007228267C3670120704700BF3322002053 -:1025400007B5052917D8DFE801F019160319192076 -:10255000202383F31188104A01210190FFF7CEFA5E -:10256000019802210D4AFFF7C9FA0D48FFF7EAF971 -:10257000002383F3118803B05DF804FB202383F369 -:1025800011880748FFF7B4F9F2E7202383F3118895 -:102590000348FFF7CBF9EBE7EC42000810430008D3 -:1025A000C832002038B50C4D0C4C2A460C4904F1B9 -:1025B0000800FFF767FF05F1CA0204F1100009499E -:1025C000FFF760FF05F5CA7204F118000649BDE87F -:1025D0003840FFF757BF00BFA04B00203C2200202F -:1025E000C8420008D5420008E042000870B5044621 -:1025F00008460D46FEF73AFCC6B220460134037881 -:102600000BB9184670BD32462946FEF71BFC002860 -:10261000F3D10120F6E700002DE9F84F05460C46FE -:10262000FEF724FC2C49C6B22846FFF7DFFF08B1AD -:102630000336F6B229492846FFF7D8FF08B110360D -:10264000F6B2632E0DD8DFF89080DFF89090244F1B -:10265000DFF894A0DFF894B02E7846B92670BDE874 -:10266000F88F29462046BDE8F84F01F0C1BD252E60 -:102670002ED1072241462846FEF7E4FB70B9DBF86D -:10268000003007350A3444F80A3CDBF8043044F8DB -:10269000063CBBF8083024F8023CDDE70822494636 -:1026A0002846FEF7CFFB98B9A21C0E4B19780232D0 -:1026B0000909C95D02F8041C13F8011B01F00F01A0 -:1026C0005345C95D02F8031CF0D118340835C3E73F -:1026D000013504F8016BBFE7B8430008E042000889 -:1026E000CB43000800E8F11F0CE8F11FC0430008CD -:1026F000BFF34F8F044B1A695107FCD1D3F8102157 -:102700005207F8D1704700BF0020005208B50D4BAA -:102710001B78ABB9FFF7ECFF0B4BDA68D10704D598 -:102720000A4A5A6002F188325A60D3F80C21D20763 -:1027300006D5064AC3F8042102F18832C3F8042101 -:1027400008BD00BFFE4D0020002000522301674558 -:1027500008B5114B1B78F3B9104B1A69510703D513 -:10276000DA6842F04002DA60D3F81021520705D54A -:10277000D3F80C2142F04002C3F80C21FFF7B8FF58 -:10278000064BDA6842F00102DA60D3F80C2142F01D -:102790000102C3F80C2108BDFE4D002000200052AC -:1027A0000F289ABF00F580604004002070470000A9 -:1027B0004FF4003070470000102070470F2808B514 -:1027C0000BD8FFF7EDFF00F500330268013204D1AA -:1027D00004308342F9D1012008BD0020FCE700004D -:1027E0000F2870B5054645D8FFF7D6FC224CFFF7F9 -:1027F0007FFF0646FFF78AFF4FF0FF33072D636127 -:10280000C4F8143120D82361FFF772FF2B0243F084 -:102810002403E360E36843F08003E36023695A071D -:10282000FCD42846FFF764FF4FF40031FFF7B8FFF0 -:1028300000F002F93046FFF78BFFFFF7B7FC2846A0 -:10284000BDE87040FFF7BABFC4F81031FFF750FF82 -:10285000A5F108031B0243F02403C4F80C31D4F89B -:102860000C3143F08003C4F80C31D4F810315B070D -:10287000FBD4D6E7002070BD002000522DE9F84FB0 -:1028800040EA020305460C461746D80602D000204F -:10289000BDE8F88F27F01F07DFF8D4B0FFF736FF49 -:1028A0002744BC4203D10120FFF752FFF0E720226A -:1028B0002946204601F08CFC10B920352034F0E781 -:1028C0002B4605F120021E68711CE0D104339A42A8 -:1028D000F9D1FFF761FC05F17843234AB3F5801F76 -:1028E000224B28BF9A4603F1040338BF9046A2F159 -:1028F000080228BF9846A3F108033ABF9146DA467A -:102900009946FFF7F5FEC8F80060A5EB040CD9F86E -:10291000002004F11C0142F00202C9F80020221F2D -:10292000DAF8006016F00506FAD152F8043F8A4240 -:102930004CF80230F4D1BFF34F8FFFF7D9FE4FF0C0 -:10294000FF32C8F80020D9F8002022F00202C9F8AE -:102950000020FFF72BFC20222146284601F038FCFE -:102960000028AAD030469FE71420005210210052C0 -:102970001020005210B5084C237828B11BB9FFF77E -:10298000C5FE0123237010BD002BFCD02070BDE8D4 -:102990001040FFF7DDBE00BFFE4D00200244074B94 -:1029A000D2B210B5904200D110BD441C00B253F811 -:1029B000200041F8040BE0B2F4E700BF504000589B -:1029C0000E4B30B51C6F240405D41C6F1C671C6FA4 -:1029D00044F400441C670A4C02442368D2B243F416 -:1029E00080732360074B904200D130BD441C51F8E6 -:1029F000045B00B243F82050E0B2F4E70044025810 -:102A0000004802585040005807B5012201A9002093 -:102A1000FFF7C4FF019803B05DF804FB13B504464B -:102A2000FFF7F2FFA04205D0012201A90020019486 -:102A3000FFF7C6FF02B010BD0144BFF34F8F064B36 -:102A4000884204D3BFF34F8FBFF36F8F7047C3F833 -:102A50005C022030F4E700BF00ED00E0034B1A6891 -:102A60001AB9034AD2F8D0241A607047004E0020E9 -:102A70000040025808B5FFF7F1FF024B1868C0F399 -:102A8000806008BD004E0020CAB201460120FFF759 -:102A900097BF0000CAB201460120FFF77FBF0000C8 -:102AA000EFF30983054968334A6B22F001024A6358 -:102AB00083F30988002383F31188704700EF00E057 -:102AC000202080F3118862B60D4B0E4AD96821F49C -:102AD000E0610904090C0A430B49DA60D3F8FC20D1 -:102AE00042F08072C3F8FC20084AC2F8B01F116897 -:102AF00041F0010111601022DA7783F8220070475B -:102B000000ED00E00003FA0555CEACC5001000E072 -:102B1000202310B583F311880E4B5B6813F4006318 -:102B200014D0F1EE103AEFF309844FF08073683C53 -:102B3000E361094BDB6B236684F30988FFF7DCFA5A -:102B400010B1064BA36110BD054BFBE783F3118861 -:102B5000F9E700BF00ED00E000EF00E0FF03000830 -:102B60000204000870B5BFF34F8FBFF36F8F1A4A8E -:102B70000021C2F85012BFF34F8FBFF36F8F53691C -:102B800043F400335361BFF34F8FBFF36F8FC2F82D -:102B90008410BFF34F8FD2F8803043F6E074C3F354 -:102BA000C900C3F34E335B0103EA0406014646EA5B -:102BB00081750139C2F86052F9D2203B13F1200F20 -:102BC000F2D1BFF34F8F536943F480335361BFF3A6 -:102BD0004F8FBFF36F8F70BD00ED00E0FEE7000088 -:102BE0000A4B0B480B4A90420BD30B4BC11EDA1C0D -:102BF000121A22F003028B4238BF00220021FEF796 -:102C00003DB953F8041B40F8041BECE7AC45000841 -:102C1000D44F0020D44F0020D44F00207047000034 -:102C200070B5D0E9244300224FF0FF359E6804EBD5 -:102C300042135101D3F80009002805DAD3F800093E -:102C400040F08040C3F80009D3F8000B002805DAF3 -:102C5000D3F8000B40F08040C3F8000B013263183A -:102C60009642C3F80859C3F8085BE0D24FF001134D -:102C7000C4F81C3870BD000000EB8103D3F80CC011 -:102C80002DE9F043DCF814204E1CD0F89050D2F817 -:102C900000E005EB063605EB4118506870450AD395 -:102CA0000122D5F8343802FA01F123EA0101C5F80E -:102CB0003418BDE8F083AEEB0003BCF81040A3422B -:102CC00028BF2346D8F81849A4B2B3EB840FF0D834 -:102CD0009468A4F1040959F8047F3760A4EB09074C -:102CE0001F44042FF7D81C44034494605360D4E776 -:102CF000890141F02001016103699B06FCD4122087 -:102D0000FFF764BA10B50A4C2046FEF7D5FE094B12 -:102D1000C4F89030084BC4F89430084C2046FEF7B5 -:102D2000CBFE074BC4F89030064BC4F8943010BD6E -:102D3000044E00200000084000440008A04E00207F -:102D4000000004400C44000870B503780546012BD0 -:102D50005DD1494BD0F89040984259D1474B0E2154 -:102D60006520D3F8D82042F00062C3F8D820D3F809 -:102D7000002142F00062C3F80021D3F80021D3F80B -:102D8000802042F00062C3F88020D3F8802022F037 -:102D90000062C3F88020D3F8803000F071FC384B1B -:102DA000E360384BC4F800380023D5F89060C4F8CD -:102DB000003EC02323604FF40413A3633369002B48 -:102DC000FCDA01230C203361FFF700FA3369DB07DB -:102DD000FCD41220FFF7FAF93369002BFCDA002645 -:102DE0002846A660FFF71CFF6B68C4F81068DB6814 -:102DF000C4F81468C4F81C68002B3AD1224BA361B4 -:102E00004FF0FF336361A36843F00103A36070BD1B -:102E10001E4B9842C8D1194B0E214D20D3F8D82013 -:102E200042F00072C3F8D820D3F8002142F00072BB -:102E3000C3F80021D3F80021D3F8802042F00072BB -:102E4000C3F88020D3F8802022F00072C3F88020DD -:102E5000D3F88020D3F8D82022F08062C3F8D8209D -:102E6000D3F8002122F08062C3F80021D3F80031AA -:102E700093E7074BC3E700BF044E0020004402580D -:102E80004014004003002002003C30C0A04E00204F -:102E9000083C30C0F8B5D0F89040054600214FF00E -:102EA00000662046FFF724FFD5F8941000234FF06A -:102EB00001128F684FF0FF30C4F83438C4F81C2872 -:102EC00004EB431201339F42C2F80069C2F8006B61 -:102ED000C2F80809C2F8080BF2D20B68D5F89020A6 -:102EE000C5F89830636210231361166916F0100656 -:102EF000FBD11220FFF76AF9D4F8003823F4FE63FF -:102F0000C4F80038A36943F4402343F01003A361DD -:102F10000923C4F81038C4F814380B4BEB604FF099 -:102F2000C043C4F8103B094BC4F8003BC4F8106917 -:102F3000C4F80039D5F8983003F1100243F4801337 -:102F4000C5F89820A362F8BDDC430008408000105B -:102F5000D0F8902090F88A10D2F8003823F4FE635D -:102F600043EA0113C2F80038704700002DE9F84326 -:102F700000EB8103D0F890500C468046DA680FFAD7 -:102F800081F94801166806F00306731E022B05EB53 -:102F900041134FF0000194BFB604384EC3F8101B24 -:102FA0004FF0010104F1100398BF06F1805601FAB9 -:102FB00003F3916998BF06F5004600293AD0578A75 -:102FC00004F15801374349016F50D5F81C180B43E1 -:102FD0000021C5F81C382B180127C3F81019A74089 -:102FE0005369611E9BB3138A928B9B08012A88BF89 -:102FF0005343D8F89820981842EA034301F140025D -:103000002146C8F89800284605EB82025360FFF776 -:103010006FFE08EB8900C3681B8A43EA8453483477 -:103020001E4364012E51D5F81C381F43C5F81C7887 -:10303000BDE8F88305EB4917D7F8001B21F40041E0 -:10304000C7F8001BD5F81C1821EA0303C0E704F1F8 -:103050003F030B4A2846214605EB83035A60FFF7DE -:1030600047FE05EB4910D0F8003923F40043C0F8BF -:103070000039D5F81C3823EA0707D7E7008000108D -:1030800000040002D0F894201268C0F89820FFF7DE -:10309000C7BD00005831D0F8903049015B5813F497 -:1030A000004004D013F4001F0CBF02200120704721 -:1030B0004831D0F8903049015B5813F4004004D0F7 -:1030C00013F4001F0CBF02200120704700EB8101A8 -:1030D000CB68196A0B6813604B6853607047000037 -:1030E00000EB810330B5DD68AA691368D36019B9B4 -:1030F000402B84BF402313606B8A1468D0F8902063 -:103100001C4402EB4110013C09B2B4FBF3F46343ED -:10311000033323F0030343EAC44343F0C043C0F83E -:10312000103B2B6803F00303012B0ED1D2F80838B3 -:1031300002EB411013F4807FD0F8003B14BF43F042 -:10314000805343F00053C0F8003B02EB4112D2F829 -:10315000003B43F00443C2F8003B30BD2DE9F04191 -:10316000D0F8906005460C4606EB4113D3F8087B77 -:103170003A07C3F8087B08D5D6F814381B0704D5DE -:1031800000EB8103DB685B689847FA071FD5D6F828 -:103190001438DB071BD505EB8403D968CCB98B69E0 -:1031A000488A5A68B2FBF0F600FB16228AB9186802 -:1031B000DA6890420DD2121AC3E90024202383F367 -:1031C000118821462846FFF78BFF84F31188BDE85C -:1031D000F081012303FA04F26B8923EA02036B8175 -:1031E000CB68002BF3D021462846BDE8F0411847B4 -:1031F00000EB81034A0170B5DD68D0F890306C694E -:103200002668E66056BB1A444FF40020C2F8100945 -:103210002A6802F00302012A0AB20ED1D3F8080884 -:1032200003EB421410F4807FD4F8000914BF40F07F -:10323000805040F00050C4F8000903EB4212D2F86D -:10324000000940F00440C2F800090122D3F8340814 -:1032500002FA01F10143C3F8341870BD19B9402EC8 -:1032600084BF4020206020681A442E8A8419013CC3 -:10327000B4FBF6F440EAC44040F00050C6E700005A -:103280002DE9F041D0F8906004460D4606EB41135D -:10329000D3F80879C3F80879FB071CD5D6F810389D -:1032A000DA0718D500EB8103D3F80CC0DCF8143032 -:1032B000D3F800E0DA6896451BD2A2EB0E024FF07D -:1032C00000081A60C3F80480202383F31188FFF7F5 -:1032D0008FFF88F311883B0618D50123D6F83428D0 -:1032E000AB40134212D029462046BDE8F041FFF71B -:1032F000C3BC012303FA01F2038923EA0203038119 -:10330000DCF80830002BE6D09847E4E7BDE8F08110 -:103310002DE9F84FD0F8905004466E69AB691E4015 -:1033200016F480586E6103D0BDE8F84FFEF734BC48 -:10333000002E12DAD5F8003E9F0705D0D5F8003EE2 -:1033400023F00303C5F8003ED5F80438204623F0E7 -:103350000103C5F80438FEF74BFC300505D52046BF -:10336000FFF75EFC2046FEF733FCB1040CD5D5F820 -:10337000083813F0060FEB6823F470530CBF43F4C6 -:10338000105343F4A053EB60320704D56368DB6845 -:103390000BB120469847F30200F1BA80B70226D558 -:1033A000D4F8909000274FF0010A09EB4712D2F8A9 -:1033B000003B03F44023B3F5802F11D1D2F8003B3A -:1033C000002B0DDA62890AFA07F322EA030363810C -:1033D00004EB8703DB68DB6813B139462046984766 -:1033E0000137D4F89430FFB29B689F42DDD9F006D4 -:1033F00019D5D4F89000026AC2F30A1702F00F033D -:1034000002F4F012B2F5802F00F0CC80B2F5402F1C -:1034100009D104EB8303002200F58050DB681B6AAE -:10342000974240F0B2803003D5F8185835D5E903FB -:1034300003D500212046FFF791FEAA0303D5012101 -:103440002046FFF78BFE6B0303D502212046FFF7D2 -:1034500085FE2F0303D503212046FFF77FFEE802F8 -:1034600003D504212046FFF779FEA90203D50521E3 -:103470002046FFF773FE6A0203D506212046FFF7B8 -:103480006DFE2B0203D507212046FFF767FEEF01F3 -:1034900003D508212046FFF761FE700340F1A980A3 -:1034A000E90703D500212046FFF7EAFEAA0703D566 -:1034B00001212046FFF7E4FE6B0703D502212046D9 -:1034C000FFF7DEFE2F0703D503212046FFF7D8FEC6 -:1034D000EE0603D504212046FFF7D2FEA80603D549 -:1034E00005212046FFF7CCFE690603D506212046BC -:1034F000FFF7C6FE2A0603D507212046FFF7C0FEC8 -:10350000EB0576D520460821BDE8F84FFFF7B8BE99 -:10351000D4F8909000274FF0010AD4F894305FFA65 -:1035200087FB9B689B453FF639AF09EB4B13D3F8FC -:10353000002902F44022B2F5802F24D1D3F80029CB -:10354000002A20DAD3F8002942F09042C3F800297B -:10355000D3F80029002AFBDB5946D4F89000FFF786 -:10356000C7FB22890AFA0BF322EA0303238104EB47 -:103570008B03DB689B6813B1594620469847594630 -:103580002046FFF779FB0137C7E7910701D1D0F853 -:103590000080072A02F101029CBF03F8018B4FEA69 -:1035A00018283DE704EB830300F58050DA68D2F871 -:1035B00018C0DCF80820DCE9001CA1EB0C0C002191 -:1035C0008F4208D1DB689B699A683A449A605A68CE -:1035D0003A445A6027E711F0030F01D1D0F8008078 -:1035E0008C4501F1010184BF02F8018B4FEA1828D4 -:1035F000E6E7BDE8F88F000008B50348FFF788FE4E -:10360000BDE80840FFF784BA044E002008B503481F -:10361000FFF77EFEBDE80840FFF77ABAA04E002013 -:10362000D0F8903003EB4111D1F8003B43F4001384 -:10363000C1F8003B70470000D0F8903003EB411117 -:10364000D1F8003943F40013C1F800397047000085 -:10365000D0F8903003EB4111D1F8003B23F4001374 -:10366000C1F8003B70470000D0F8903003EB4111E7 -:10367000D1F8003923F40013C1F800397047000075 -:10368000090100F16043012203F56143C9B283F8E7 -:10369000001300F01F039A4043099B0003F16043AD -:1036A00003F56143C3F880211A60704730B50433D5 -:1036B000039C0172002104FB0325C160C0E906538D -:1036C000049B0363059BC0E90000C0E90422C0E934 -:1036D0000842C0E90A11436330BD00000022416A7C -:1036E000C260C0E90411C0E90A226FF00101FEF7CF -:1036F000DDBD0000D0E90432934201D1C2680AB9AD -:10370000181D704700207047036919600021C268C6 -:103710000132C260C269134482699342036124BFCB -:10372000436A0361FEF7B6BD38B504460D46E3684B -:103730003BB162690020131D1268A3621344E36267 -:1037400007E0237A33B929462046FEF793FD002887 -:10375000EDDA38BD6FF00100FBE70000C368C26915 -:10376000013BC3604369134482699342436124BFB0 -:10377000436A436100238362036B03B118477047B8 -:1037800070B52023044683F31188866A3EB9FFF79B -:10379000CBFF054618B186F31188284670BDA36A91 -:1037A000E26A13F8015B9342A36202D32046FFF75B -:1037B000D5FF002383F31188EFE700002DE9F84FD0 -:1037C00004460E46174698464FF0200989F31188A3 -:1037D0000025AA46D4F828B0BBF1000F09D1414614 -:1037E0002046FFF7A1FF20B18BF311882846BDE8E2 -:1037F000F88FD4E90A12A7EB050B521A934528BF9C -:103800009346BBF1400F1BD9334601F1400251F8FA -:10381000040B914243F8040BF9D1A36A40364035BA -:103820004033A362D4E90A239A4202D32046FFF729 -:1038300095FF8AF31188BD42D8D289F31188C9E770 -:1038400030465A46FDF7F4FAA36A5E445D445B4491 -:10385000A362E7E710B5029C0433017204FB032165 -:10386000C460C0E906130023C0E90A33039B036365 -:10387000049BC0E90000C0E90422C0E90842436398 -:1038800010BD0000026A6FF00101C260426AC0E927 -:1038900004220022C0E90A22FEF708BDD0E9042371 -:1038A0009A4201D1C26822B9184650F8043B0B6015 -:1038B0007047002070470000C3680021C2690133CF -:1038C000C3604369134482699342436124BF436ADE -:1038D0004361FEF7DFBC000038B504460D46E368DF -:1038E0003BB1236900201A1DA262E2691344E3621E -:1038F00007E0237A33B929462046FEF7BBFC0028AF -:10390000EDDA38BD6FF00100FBE7000003691960D4 -:10391000C268013AC260C26913448269934203617A -:1039200024BF436A036100238362036B03B118471A -:103930007047000070B520230D460446114683F3FE -:103940001188866A2EB9FFF7C7FF10B186F3118878 -:1039500070BDA36A1D70A36AE26A01339342A36239 -:1039600004D3E16920460439FFF7D0FF002080F33B -:103970001188EDE72DE9F84F04460D46904699462B -:103980004FF0200A8AF311880026B346A76A4FB980 -:1039900049462046FFF7A0FF20B187F31188304643 -:1039A000BDE8F88FD4E90A073A1AA8EB0607974250 -:1039B00028BF1746402F1BD905F1400355F8042BAB -:1039C0009D4240F8042BF9D1A36A40364033A362EC -:1039D000D4E90A239A4204D3E16920460439FFF767 -:1039E00095FF8BF311884645D9D28AF31188CDE72C -:1039F00029463A46FDF71CFAA36A3D443E443B443F -:103A0000A362E5E7D0E904239A4217D1C3689BB1CA -:103A1000836A8BB1043B9B1A0ED01360C368013BD1 -:103A2000C360C3691A4483699A42026124BF436A2E -:103A30000361002383620123184670470023FBE7DC -:103A400000F0DAB8034B002258631A610222DA60F0 -:103A5000704700BF000C0040014B0022DA60704745 -:103A6000000C0040014B5863704700BF000C004041 -:103A7000014B586A704700BF000C00404B68436020 -:103A80008B688360CB68C3600B6943614B690362D9 -:103A90008B6943620B6803607047000008B53C4BBC -:103AA00040F2FF713B48D3F888200A43C3F88820CE -:103AB000D3F8882022F4FF6222F00702C3F888209E -:103AC000D3F88820D3F8E0200A43C3F8E020D3F8E5 -:103AD00008210A43C3F808212F4AD3F808311146B8 -:103AE000FFF7CCFF00F5806002F11C01FFF7C6FF75 -:103AF00000F5806002F13801FFF7C0FF00F580603B -:103B000002F15401FFF7BAFF00F5806002F1700185 -:103B1000FFF7B4FF00F5806002F18C01FFF7AEFF04 -:103B200000F5806002F1A801FFF7A8FF00F58060B2 -:103B300002F1C401FFF7A2FF00F5806002F1E0018D -:103B4000FFF79CFF00F5806002F1FC01FFF796FF94 -:103B500002F58C7100F58060FFF790FF00F000F92E -:103B60000E4BD3F8902242F00102C3F89022D3F812 -:103B7000942242F00102C3F894220522C3F898204F -:103B80004FF06052C3F89C20054AC3F8A02008BD3E -:103B900000440258000002581844000800ED00E0FC -:103BA0001F00080308B500F0F3FAFEF7D3FA0F4B35 -:103BB000D3F8DC2042F04002C3F8DC20D3F8042123 -:103BC00022F04002C3F80421D3F80431084B1A68EC -:103BD00042F008021A601A6842F004021A60FEF706 -:103BE0003DFFBDE80840FEF7DDBC00BF00440258C1 -:103BF0000018024870470000114BD3F8E82042F04B -:103C00000802C3F8E820D3F8102142F00802C3F8F4 -:103C100010210C4AD3F81031D36B43F00803D3635F -:103C2000C722094B9A624FF0FF32DA6200229A6192 -:103C30005A63DA605A6001225A611A60704700BF05 -:103C4000004402580010005C000C0040094A08B50E -:103C50001169D3680B40D9B29B076FEA010111616A -:103C600007D5202383F31188FEF794FA002383F30A -:103C7000118808BD000C0040384B4FF0FF31D3F8DD -:103C80008020C3F88010D3F880200022C3F8802061 -:103C9000D3F88000D3F88400C3F88410D3F88400EC -:103CA000C3F88420D3F88400D86F40F0FF4040F47C -:103CB000FF0040F43F5040F03F00D867D86F20F03D -:103CC000FF4020F4FF0020F43F5020F03F00D86771 -:103CD000D86FD3F888006FEA40506FEA5050C3F8AD -:103CE0008800D3F88800C0F30A00C3F88800D3F82E -:103CF0008800D3F89000C3F89010D3F89000C3F870 -:103D00009020D3F89000D3F89400C3F89410D3F81F -:103D10009400C3F89420D3F89400D3F89800C3F823 -:103D20009810D3F89800C3F89820D3F89800D3F8E7 -:103D30008C00C3F88C10D3F88C00C3F88C20D3F817 -:103D40008C00D3F89C00C3F89C10D3F89C10C3F8E7 -:103D50009C20D3F89C3000F0E7B900BF0044025823 -:103D6000614B0122C3F80821604BD3F8F42042F0E4 -:103D70000202C3F8F420D3F81C2142F00202C3F877 -:103D80001C210222D3F81C31594BDA605A68910485 -:103D9000FCD5584A1A6001229A60574ADA6000221C -:103DA0001A614FF440429A61514B9A699204FCD5D2 -:103DB0001A6842F480721A604C4B1A6F12F4407FFA -:103DC00004D04FF480321A6700221A671A6842F052 -:103DD00001021A60454B1A685007FCD500221A618F -:103DE0001A6912F03802FBD1012119604FF08041AD -:103DF00059605A67414ADA62414A1A611A6842F4C4 -:103E000080321A60394B1A689103FCD51A6842F463 -:103E100080521A601A689204FCD53A4A3A499A626A -:103E200000225A6319633949DA6399635A64384A3C -:103E30001A64384ADA621A6842F0A8521A602B4BA8 -:103E40001A6802F02852B2F1285FF9D148229A612B -:103E50004FF48862DA6140221A622F4ADA644FF026 -:103E600080521A652D4A5A652D4A9A6532232D4A89 -:103E70001360136803F00F03022BFAD11B4B1A696E -:103E800042F003021A611A6902F03802182AFAD1C4 -:103E9000D3F8DC2042F00052C3F8DC20D3F8042130 -:103EA00042F00052C3F80421D3F80421D3F8DC20F7 -:103EB00042F08042C3F8DC20D3F8042142F0804273 -:103EC000C3F80421D3F80421D3F8DC2042F00042E7 -:103ED000C3F8DC20D3F8042142F00042C3F80421E7 -:103EE000D3F80431704700BF0080005100440258ED -:103EF0000048025800C000F0020000010000FF016D -:103F00000088900832206000630209011D0204004D -:103F100047040508FD0BFF01200000200010E00011 -:103F200000010100002000524FF0B04208B5D2F865 -:103F3000883003F00103C2F8883023B1044A1368C3 -:103F40000BB150689847BDE80840FEF7E1BD00BFDF -:103F5000544F00204FF0B04208B5D2F8883003F03B -:103F60000203C2F8883023B1044A93680BB1D068C9 -:103F70009847BDE80840FEF7CBBD00BF544F002076 -:103F80004FF0B04208B5D2F8883003F00403C2F80D -:103F9000883023B1044A13690BB150699847BDE8D2 -:103FA0000840FEF7B5BD00BF544F00204FF0B042AF -:103FB00008B5D2F8883003F00803C2F8883023B17E -:103FC000044A93690BB1D0699847BDE80840FEF7F1 -:103FD0009FBD00BF544F00204FF0B04208B5D2F84B -:103FE000883003F01003C2F8883023B1044A136A02 -:103FF0000BB1506A9847BDE80840FEF789BD00BF85 -:10400000544F00204FF0B04310B5D3F8884004F46B -:104010007872C3F88820A30604D5124A936A0BB1BC -:10402000D06A9847600604D50E4A136B0BB1506BEB -:104030009847210604D50B4A936B0BB1D06B984778 -:10404000E20504D5074A136C0BB1506C9847A305E1 -:1040500004D5044A936C0BB1D06C9847BDE810406E -:10406000FEF756BD544F00204FF0B04310B5D3F8C3 -:10407000884004F47C42C3F88820620504D5164ABF -:10408000136D0BB1506D9847230504D5124A936DFB -:104090000BB1D06D9847E00404D50F4A136E0BB1F5 -:1040A000506E9847A10404D50B4A936E0BB1D06EA5 -:1040B0009847620404D5084A136F0BB1506F9847B4 -:1040C000230404D5044A936F0BB1D06F9847BDE821 -:1040D0001040FEF71DBD00BF544F002008B5034837 -:1040E000FDF7FCF8BDE80840FEF712BDCC23002028 -:1040F00008B50348FDF7F2F8BDE80840FEF708BD33 -:104100003824002008B50348FDF7E8F8BDE808406A -:10411000FEF7FEBCA424002008B5FFF797FDBDE81C -:104120000840FEF7F5BC0000062108B50846FFF779 -:10413000A7FA06210720FFF7A3FA06210820FFF7B8 -:104140009FFA06210920FFF79BFA06210A20FFF7B4 -:1041500097FA06211720FFF793FA06212820FFF788 -:104160008FFA09217A20FFF78BFA07213220FFF717 -:1041700087FA0C212620FFF783FA0C212720FFF76E -:104180007FFA0C215220BDE80840FFF779BA000001 -:1041900008B5FFF771FD00F00DF8FDF7B1FAFDF776 -:1041A00089FCFDF75BFBFFF725FDBDE80840FFF745 -:1041B00047BC00000023054A19460133102BC2E911 -:1041C000001102F10802F8D1704700BF544F0020DF -:1041D00010B501390244904201D1002005E0037876 -:1041E00011F8014FA34201D0181B10BD0130F2E7B6 -:1041F000034611F8012B03F8012B002AF9D170476F -:1042000053544D333248373F3F3F0053544D3332C0 -:10421000483734332F37353300000000C8320020D0 -:10422000CC23002038240020A42400200096000085 -:10423000000000000000000000000000000000007E -:104240000000000000000000C9160008B5160008B4 -:10425000F1160008DD160008E9160008D51600085A -:10426000C1160008AD160008FD1600080000000089 -:10427000D9170008C517000801180008ED17000835 -:10428000F9170008E5170008D1170008BD17000846 -:104290000D180008000000000100000000000000F0 -:1042A0006D61696E0000000069646C6500000000CB -:1042B000A842000850310020C83200200100000050 -:1042C00051210008000000004865782F50726F6689 -:1042D00069434E430025424F415244252D424C0034 -:1042E0002553455249414C250000000002000000C2 -:1042F00000000000F9190008691A00084000400099 -:10430000704B0020804B00200200000000000000E5 -:104310000300000000000000B11A000800000000C7 -:1043200010000000904B0020000000000100000081 -:1043300000000000044E0020010102004125000899 -:1043400051240008ED240008D12400084300000097 -:104350005443000809024300020100C0320904006E -:1043600000010202010005240010010524010001E2 -:10437000042402020524060001070582030800FF49 -:1043800009040100020A00000007050102400000C4 -:10439000070581024000000012000000A043000851 -:1043A0001201100102000040AE2D161000020102A1 -:1043B000030100000403090425424F415244250033 -:1043C000437562654F72616E676500303132333418 -:1043D0003536373839414243444546000000000035 -:1043E000051C0008BD1E0008691F000840004000B1 -:1043F0003C4F00203C4F0020010000004C4F0020AB -:1044000080000000400100000800000000010000E2 -:1044100000040000080000000000812A00000000E5 -:10442000AAAAAAAA00000024FFFE000000000000C3 -:1044300000A00A000001000000000000AAAAAAAA29 -:1044400000000000FFFF000000000000000000006E -:104450001400005400000000AAAAAAAA14000054E4 -:10446000FFFF0000000000000000000000681A00CC -:1044700000000000AAAA8AAA00541500FFFF00004D -:10448000000070077700000040810201001000006A -:10449000AAAAAAAA00410100F7FF000000000070CC -:1044A000070000000000000000000000AAAAAAAA5D -:1044B00000000000FFFF00000000000000000000FE -:1044C0000000000000000000AAAAAAAA0000000044 -:1044D000FFFF0000000000000000000000000000DE -:1044E00000000000AAAAAAAA00000000FFFF000026 -:1044F00000000000000000000000000000000000BC -:10450000AAAAAAAA00000000FFFF00000000000005 -:10451000000000000000000000000000AAAAAAAAF3 -:1045200000000000FFFF000000000000000000008D -:104530000000000000000000AAAAAAAA00000000D3 -:10454000FFFF00000000000000000000000000006D -:104550008C0000000000000000001E0000000000B1 -:10456000FF00000000000000004200083F000000C3 -:10457000500400000B4200083F00000000960000BD -:104580000000080096000000000800000400000081 -:10459000B44300080000000000000000000000001C -:0C45A0000000000000000000000000000F +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E30200089D8A0008DA +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008497F0008757F0008FA +:10006000A17F0008CD7F0008F97F0008E3020008A7 +:10007000E3020008E3020008E3020008E3020008CC +:10008000E3020008E3020008E3020008E3020008BC +:10009000E3020008E3020008E302000825800008EC +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E30200081181000825810008FE +:1000E00089800008E3020008E3020008E302000838 +:1000F000E3020008E3020008E3020008E30200084C +:10010000E3020008FD8000084D810008E3020008BA +:10011000E3020008E3020008E3020008E30200082B +:10012000E3020008E3020008E3020008E30200081B +:10013000E3020008E3020008E3020008E30200080B +:10014000E3020008E3020008E3020008E3020008FB +:10015000E3020008E3020008E3020008E3020008EB +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008317C0008E3020008E302000803 +:10018000E3020008E302000839810008E3020008E6 +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E30200081D7C0008E3020008E3020008B7 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F06F0DCFE90 +:1003500006F0ECF84FF055301F491B4A91423CBF64 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE706F0F4FE06F04AF918 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F0C4F9114C124DAC4203DA54F8041B9E +:1003C0008847F9E706F0DCBE000600200022002086 +:1003D0000000000808ED00E00000002000060020FA +:1003E000B896000800220020D8220020D822002041 +:1003F00020670020E0020008E0020008E002000898 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002005F072FEFEE705F07F +:10043000B1FD00DFFEE7000053B94AB9002908BF4B +: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 +:1007300009E76444023842E7704700BF38B500F06B +:10074000DDFB06F0EFFB054606F0D4FC0446E0B9FD +:10075000104B9D421BD001339D4241F2883504BFAE +:1007600001240025002006F0E7FB0CB100F07AF828 +:1007700001F03AFB01F0F6F900F028FD08B100F0B5 +:1007800071F8284600F01CF9F9E70025EAE705466C +:10079000E8E700BF010007B008B501F0AFF9A0F12C +:1007A00020035842584108BD07B541F21203022107 +:1007B00001A8ADF8043001F0BFF903B05DF804FB07 +:1007C00038B5302383F31188174803680BB105F05F +:1007D00083FD0023154A4FF47A71134805F072FD2A +:1007E000002383F31188124C236813B12368013B63 +:1007F0002360636813B16368013B63600D4D2B7820 +:1008000033B963687BB9022001F068FA3223636070 +:100810002B78032B07D163682BB9022001F05EFA15 +:100820004FF47A73636038BDD8220020C1070008F6 +:10083000F8230020F0220020084B187003280CD861 +:10084000DFE800F008050208022001F03DBA0220AE +:1008500001F030BA024B00225A607047F0220020AB +:10086000F8230020F8B5504B504A1C461968013156 +:1008700000F0998004339342F8D162684C4B9A425D +:1008800040F291804B4B9B6803F1006303F500330A +:100890009A4280F08880002001F07EF90220FFF764 +:1008A000CBFF454B0021D3F8E820C3F8E810D3F87C +:1008B0001021C3F81011D3F81021D3F8EC20C3F89D +:1008C000EC10D3F81421C3F81411D3F81421D3F881 +:1008D000F020C3F8F010D3F81821C3F81811D3F89A +:1008E0001821D3F8802042F00062C3F88020D3F8AA +:1008F000802022F00062C3F88020D3F88020D3F853 +:10090000802042F00072C3F88020D3F8802022F0CB +:100910000072C3F88020D3F8803072B64FF0E02325 +:10092000C3F8084DD4E90004BFF34F8FBFF36F8FB6 +:10093000224AC2F88410BFF34F8F536923F48033E7 +:100940005361BFF34F8FD2F8803043F6E076C3F3A4 +:10095000C905C3F34E335B0103EA060C29464CEA92 +:1009600081770139C2F87472F9D2203B13F1200F5C +:10097000F2D1BFF34F8FBFF36F8FBFF34F8FBFF332 +:100980006F8F536923F4003353610023C2F8503250 +:10099000BFF34F8FBFF36F8F302383F311888546EA +:1009A00080F308882047F8BD0000020820000208F4 +:1009B000FFFF0108002200200044025800ED00E083 +:1009C0002DE9F04F93B0B44B2022FF2100900AA8EC +:1009D0009D6801F0B3F9B14A1378A3B90121B04879 +:1009E00011700360302383F3118803680BB105F0A5 +:1009F00073FC0023AB4A4FF47A71A94805F062FCFE +:100A0000002383F31188009B13B1A74B009A1A604F +:100A1000A64A1378032B03D000231370A24A536015 +:100A20004FF0000A009CD3465646D146012001F003 +:100A30004BF924B19C4B1B68002B00F02682002050 +:100A400001F05CF80390039B002BF2DB012001F026 +:100A500031F9039B213B1F2BE8D801A252F823F068 +:100A6000E10A0008090B00089D0B00082D0A000888 +:100A70002D0A00082D0A00082F0C0008FF0D0008A1 +:100A8000190D00087B0D0008A30D0008C90D000812 +:100A90002D0A0008DB0D00082D0A00084D0E000885 +:100AA000810B00082D0A0008910E0008ED0A0008CD +:100AB000810B00082D0A00087B0D00082D0A000894 +:100AC0002D0A00082D0A00082D0A00082D0A00082A +:100AD0002D0A00082D0A00082D0A00089D0B0008A9 +:100AE0000220FFF759FE002840F0F981009B022107 +:100AF00005A8BAF1000F08BF1C4641F21233ADF849 +:100B0000143001F019F891E74FF47A7000F0F6FF15 +:100B1000071EEBDB0220FFF73FFE0028E6D0013F77 +:100B2000052F00F2DE81DFE807F0030A0D1013360F +:100B30000523042105A8059300F0FEFF17E004211A +:100B40005548F9E704215A48F6E704215948F3E7E4 +:100B50004FF01C08404608F1040801F01FF804217A +:100B6000059005A800F0E8FFB8F12C0FF2D10120A4 +:100B70004FF0000900FA07F747EA0B0B5FFA8BFB0F +:100B800001F028F926B10BF00B030B2B08BF002452 +:100B9000FFF70AFE4AE704214748CDE7002EA5D01B +:100BA0000BF00B030B2BA1D10220FFF7F5FD07463D +:100BB00000289BD00120002600F0EEFF0220FFF766 +:100BC0003BFE1FFA86F8404600F0F6FF0446B0B13F +:100BD000039940460136A1F140025142514100F0D3 +:100BE000FBFF0028EDD1BA46044641F21213022160 +:100BF00005A83E46ADF8143000F09EFF16E72546E6 +:100C00000120FFF719FE244B9B68AB4207D9284609 +:100C100000F0C4FF013040F067810435F3E70025A0 +:100C2000224BBA463E461D701F4B5D60A8E7002E62 +:100C30003FF45CAF0BF00B030B2B7FF457AF02209C +:100C4000FFF7FAFD322000F059FFB0F10008FFF67F +:100C50004DAF18F003077FF449AF0F4A08EB0503C7 +:100C6000926893423FF642AFB8F5807F3FF73EAFC0 +:100C7000124BB845019323DD4FF47A7000F03EFF2C +:100C80000390039A002AFFF631AF039A0137019BC4 +:100C900003F8012BEDE700BF00220020F423002021 +:100CA000D8220020C1070008F8230020F0220020ED +:100CB00004220020082200200C220020F422002020 +:100CC000C820FFF769FD074600283FF40FAF1F2D2E +:100CD00011D8C5F120020AAB25F003008449424532 +:100CE000184428BF4246019201F002F8019AFF2100 +:100CF0007F4801F023F84FEAA803C8F387027C4934 +:100D00002846019301F022F8064600283FF46DAF13 +:100D1000019B05EB830533E70220FFF73DFD00282B +:100D20003FF4E4AE00F076FF00283FF4DFAE00278A +:100D3000B846704B9B68BB4218D91F2F11D80A9B2D +:100D400001330ED027F0030312AA134453F8203CBA +:100D500005934046042205A9043701F0A5F8804612 +:100D6000E7E7384600F01AFF0590F2E7CDF8148067 +:100D7000042105A800F0E0FE02E70023642104A896 +:100D8000049300F0CFFE00287FF4B0AE0220FFF7FE +:100D900003FD00283FF4AAAE049800F031FF05904F +:100DA000E6E70023642104A8049300F0BBFE0028BA +:100DB0007FF49CAE0220FFF7EFFC00283FF496AED4 +:100DC000049800F01FFFEAE70220FFF7E5FC002887 +:100DD0003FF48CAE00F02EFFE1E70220FFF7DCFCD1 +:100DE00000283FF483AE05A9142000F029FF074630 +:100DF0000421049004A800F09FFE3946B9E7322090 +:100E000000F07CFE071EFFF671AEBB077FF46EAEEE +:100E1000384A07EB0903926893423FF667AE022017 +:100E2000FFF7BAFC00283FF461AE27F003074F44F8 +:100E3000B9453FF4A5AE484609F1040900F0AEFEFD +:100E40000421059005A800F077FEF1E74FF47A70D1 +:100E5000FFF7A2FC00283FF449AE00F0DBFE0028BB +:100E600044D00A9B01330BD008220AA9002000F0CD +:100E70006DFF00283AD02022FF210AA800F05EFF73 +:100E8000FFF792FC1C4805F049F913B0BDE8F08F5C +:100E9000002E3FF42BAE0BF00B030B2B7FF426AE92 +:100EA0000023642105A8059300F03CFE07460028B6 +:100EB0007FF41CAE0220FFF76FFC804600283FF451 +:100EC00015AEFFF771FC41F2883005F027F905985F +:100ED00000F0C8FF46463C4600F07CFFA6E506460B +: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 :00000001FF diff --git a/Tools/bootloaders/CubePilot-CANMod_bl.bin b/Tools/bootloaders/CubePilot-CANMod_bl.bin new file mode 100755 index 00000000000000..8530e9ba2f9d57 Binary files /dev/null and b/Tools/bootloaders/CubePilot-CANMod_bl.bin differ diff --git a/Tools/bootloaders/CubePilot-CANMod_bl.hex b/Tools/bootloaders/CubePilot-CANMod_bl.hex new file mode 100644 index 00000000000000..e8bf2bd2d4d8ea --- /dev/null +++ b/Tools/bootloaders/CubePilot-CANMod_bl.hex @@ -0,0 +1,1996 @@ +:020000040800F2 +:1000000000060020F5050008B53400086D3400082E +:10001000953400086D3400088D340008F705000899 +:10002000F7050008F7050008F705000899440008DF +:10003000F7050008F7050008F7050008F7050008B0 +:10004000F7050008F7050008F7050008F7050008A0 +:10005000F7050008F70500086974000895740008A2 +:10006000C1740008ED74000819750008F705000850 +:10007000F7050008F7050008F7050008F705000870 +:10008000F7050008F7050008F70500084D340008DB +:10009000F70500085D340008F705000845750008FD +:1000A000F7050008F7050008F7050008F705000840 +:1000B000F7050008F7050008F7050008F705000830 +:1000C000F7050008F7050008F7050008F705000820 +:1000D000F7050008F7050008F7050008F705000810 +:1000E000A9750008F7050008F7050008F7050008DE +:1000F000F7050008F7050008F7050008F7050008F0 +:10010000F7050008F705000831760008F705000834 +:10011000F7050008F7050008F7050008F7050008CF +:10012000F7050008F7050008F7050008F7050008BF +:10013000F7050008F7050008F7050008F7050008AF +:10014000F7050008F7050008F7050008F70500089F +:10015000F7050008F7050008F7050008F70500088F +:10016000F7050008F7050008F7050008F70500087F +:10017000F70500081D6B0008F7050008F7050008E3 +:10018000F7050008F70500081D760008F7050008C8 +:10019000F7050008F7050008F7050008F70500084F +:1001A000F7050008F7050008F7050008F70500083F +:1001B000F7050008F7050008F7050008F70500082F +:1001C000F7050008F7050008F7050008F70500081F +:1001D000F7050008096B0008F7050008F705000897 +:1001E000F7050008F7050008F7050008F7050008FF +:1001F000F7050008F7050008F7050008F7050008EF +:10020000F7050008F7050008F7050008F7050008DE +:10021000F7050008F7050008F7050008F7050008CE +:10022000F7050008F7050008F7050008F7050008BE +:10023000F7050008F7050008F7050008F7050008AE +:10024000F7050008F7050008F7050008F70500089E +:10025000F7050008F7050008F7050008F70500088E +:10026000F7050008F7050008F7050008F70500087E +:10027000F7050008F7050008F7050008F70500086E +:10028000F7050008F7050008F7050008F70500085E +:10029000F7050008F7050008F7050008F70500084E +:1002A000F7050008F7050008F7050008F70500083E +:1002B000F7050008F7050008F7050008F70500082E +:1002C000F7050008F7050008F7050008F70500081E +:1002D000F7050008F7050008F7050008F70500080E +:1002E000BD19000800000000000000000000000030 +: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 +:1006600005F0D2FC06F0D6FC4FF055301F491B4A6E +:1006700091423CBF41F8040BFAE71D49184A9142E8 +:100680003CBF41F8040BFAE71A491B4A1B4B9A423C +:100690003EBF51F8040B42F8040BF8E7002018495C +:1006A000184A91423CBF41F8040BFAE705F0EAFC16 +:1006B00006F032FD144C154DAC4203DA54F8041B1D +:1006C0008847F9E700F042F8114C124DAC4203DACA +:1006D00054F8041B8847F9E705F0D2BC0006002057 +:1006E000002200200000000808ED00E000000020CB +:1006F00000060020D07B000800220020D02200202D +:10070000D022002080720020E0020008E4020008ED +:10071000E4020008E40200082DE9F04F2DED108AF4 +:10072000C1F80CD0D0F80CD0BDEC108ABDE8F08F29 +:10073000002383F311882846A047002004F04EFFD1 +:10074000FEE704F0A7FE00DFFEE70000F8B501F0C9 +:1007500047F905F0DDFB074605F04CFC0546B8BB44 +:10076000204B9F4234D001339F4234D027F0FF0208 +:100770001D4B9A4232D12E4642F21074F8B200F06C +:100780006DFF00F071FF08B10024264601F02AFD3C +:1007900020B10024032000F07BF8264635B1134B2E +:1007A0009F4203D0002405F01DFC2646002005F0E2 +:1007B000B9FB0EB100F082F801F0C0FA00F088FF3A +:1007C00001F08AF9204600F01DF900F077F8F9E70A +:1007D0002E460024D5E704460126D2E7064641F21C +:1007E0008834CEE7010007B0000008B0263A09B00F +:1007F00008B501F03DF9A0F120035842584108BD69 +:1008000007B541F21203022101A8ADF8043001F04E +:100810004DF903B05DF804FB38B5302383F311883C +:10082000174803680BB104F0A5FF0023154A4FF4E5 +:100830007A71134804F094FF002383F31188124C5B +:10084000236813B12368013B2360636813B16368B5 +:10085000013B63600D4D2B7833B963687BB902208F +:1008600001F0EEF9322363602B78032B07D1636824 +:100870002BB9022001F0E4F94FF47A73636038BDBC +:10088000D022002019080008F0230020E8220020D0 +:10089000084B187003280CD8DFE800F008050208A0 +:1008A000022001F0CBB9022001F0C6B9024B0022B0 +:1008B0005A607047E8220020F0230020F8B501F0CC +:1008C00091FC30B1464B03221A700022454B5A600E +:1008D000F8BD454B454A1C4619680131F8D0043330 +:1008E0009342F9D16268424B9A42F1D9414B9B68DD +:1008F00003F1006303F580239A42E9D205F046FB39 +:1009000005F058FB002001F00DF90220FFF7C0FFB1 +:10091000394B00219A6C99641A6F19671A6FDA6C57 +:10092000D9645A6F59675A6F1A6D19659A6F99672A +:100930009B6F324BD3F8802042F00072C3F88020C6 +:10094000D3F8802022F00072C3F88020D3F88030E2 +:1009500072B64FF0E023C3F8084DD4E90004BFF3AA +:100960004F8FBFF36F8F264AC2F88410BFF34F8FAB +:10097000536923F480335361BFF34F8FD2F8803033 +:1009800043F6E076C3F3C905C3F34E335B0103EAD4 +:10099000060C29464CEA81770139C2F87472F9D203 +:1009A000203B13F1200FF2D1BFF34F8FBFF36F8FB6 +:1009B000BFF34F8FBFF36F8F536923F4003353613D +:1009C0000023C2F85032BFF34F8FBFF36F8F302335 +:1009D00083F31188854680F30888204778E700BFB5 +:1009E000E8220020F0230020000004082000040872 +:1009F000FFFF03080022002000450258004402586F +:100A000000ED00E02DE9F04F93B0B74B2022FF211D +:100A100000900AA89D6801F03BF9B44A1378A3B985 +:100A20000121B34811700360302383F311880368F8 +:100A30000BB104F09FFE0023AE4A4FF47A71AC482C +:100A400004F08EFE002383F31188009B13B1AA4BA0 +:100A5000009A1A60A94A1378032B03D0002313705D +:100A6000A54A53604FF0000A009CD3465646D14633 +:100A7000012001F0E3F824B19F4B1B68002B00F02C +:100A80002C82002000F0F4FF0390039B002B01DA7E +:100A900000F066FE039B002BEDDB012001F0CCF89B +:100AA000039B213B1F2BE3D801A252F823F000BF88 +:100AB000310B0008590B0008ED0B0008710A000803 +:100AC000710A0008710A00087F0C00084F0E000828 +:100AD000690D0008CB0D0008F30D0008190E000881 +:100AE000710A00082B0E0008710A00089D0E00080C +:100AF000D10B0008710A0008E10E00083D0B000848 +:100B0000D10B0008710A0008CB0D0008710A00081B +:100B1000710A0008710A0008710A0008710A0008C9 +:100B2000710A0008710A0008710A0008ED0B00083C +:100B30000220FFF75DFE002840F0F981009B0221B2 +:100B400005A8BAF1000F08BF1C4641F21233ADF8F8 +:100B5000143000F0ABFF8BE74FF47A7000F088FFA1 +:100B6000071EEBDB0220FFF743FE0028E6D0013F23 +:100B7000052F00F2DE81DFE807F0030A0D101336BF +:100B80000523042105A8059300F090FF17E0042138 +:100B90005548F9E704215A48F6E704215948F3E794 +:100BA0004FF01C08404608F1040800F0BDFF042186 +:100BB000059005A800F07AFFB8F12C0FF2D10120C2 +:100BC0004FF0000900FA07F747EA0B0B5FFA8BFBBF +:100BD00001F0AAF826B10BF00B030B2B08BF002481 +:100BE000FFF70EFE44E704214748CDE7002EA5D0CD +:100BF0000BF00B030B2BA1D10220FFF7F9FD0746E9 +:100C000000289BD00120002600F08CFF0220FFF777 +:100C10003FFE1FFA86F8404600F094FF0446B0B14C +:100C2000039940460136A1F140025142514100F082 +:100C3000A1FF0028EDD1BA46044641F21213022169 +:100C400005A83E46ADF8143000F030FF10E7254609 +:100C50000120FFF71DFE244B9B68AB4207D92846B5 +:100C600000F062FF013040F067810435F3E70025B2 +:100C7000224BBA463E461D701F4B5D60A8E7002E12 +:100C80003FF45CAF0BF00B030B2B7FF457AF02204C +:100C9000FFF7FEFD322000F0EBFEB0F10008FFF69A +:100CA0004DAF18F003077FF449AF0F4A08EB050377 +:100CB000926893423FF642AFB8F5807F3FF73EAF70 +:100CC000124BB845019323DD4FF47A7000F0D0FE4B +:100CD0000390039A002AFFF631AF039A0137019B74 +:100CE00003F8012BEDE700BF00220020EC230020D9 +:100CF000D022002019080008F0230020E82200205C +:100D000004220020082200200C220020EC220020D7 +:100D1000C820FFF76DFD074600283FF40FAF1F2DD9 +:100D200011D8C5F120020AAB25F0030084494245E1 +:100D3000184428BF4246019200F084FF019AFF2127 +:100D40007F4800F0A5FF4FEAA803C8F387027C495B +:100D50002846019300F0A4FF064600283FF46DAF3B +:100D6000019B05EB830533E70220FFF741FD0028D7 +:100D70003FF4E4AE00F010FF00283FF4DFAE0027A0 +:100D8000B846704B9B68BB4218D91F2F11D80A9BDD +:100D900001330ED027F0030312AA134453F8203C6A +:100DA00005934046042205A9043701F005FA804660 +:100DB000E7E7384600F0B8FE0590F2E7CDF814807A +:100DC000042105A800F072FE02E70023642104A8B4 +:100DD000049300F061FE00287FF4B0AE0220FFF71C +:100DE00007FD00283FF4AAAE049800F0CBFE059062 +:100DF000E6E70023642104A8049300F04DFE0028D8 +:100E00007FF49CAE0220FFF7F3FC00283FF496AE7F +:100E1000049800F0B9FEEAE70220FFF7E9FC002899 +:100E20003FF48CAE00F0C8FEE1E70220FFF7E0FCE3 +:100E300000283FF483AE05A9142000F0C3FE074646 +:100E40000421049004A800F031FE3946B9E73220AD +:100E500000F00EFE071EFFF671AEBB077FF46EAE0C +:100E6000384A07EB0903926893423FF667AE0220C7 +:100E7000FFF7BEFC00283FF461AE27F003074F44A4 +:100E8000B9453FF4A5AE484609F1040900F04CFE0F +:100E90000421059005A800F009FEF1E74FF47A70EF +:100EA000FFF7A6FC00283FF449AE00F075FE0028CD +:100EB00044D00A9B01330BD008220AA9002000F07D +:100EC000EFFE00283AD02022FF210AA800F0E0FE21 +:100ED000FFF796FC1C4804F087FB13B0BDE8F08FC9 +:100EE000002E3FF42BAE0BF00B030B2B7FF426AE42 +:100EF0000023642105A8059300F0CEFD07460028D5 +:100F00007FF41CAE0220FFF773FC804600283FF4FC +:100F100015AEFFF775FC41F2883004F065FB0598CB +:100F200000F04CFF46463C4600F0FEFEA0E50646BB +:100F30004EE64FF0000901E6BA467EE637467CE60B +:100F4000EC22002000220020A0860100094A49F27C +:100F50006900136899B21B0C00FB013344F2506125 +:100F60001360054B186882B2000C01FB0200186088 +:100F700080B270471422002010220020002110228D +:100F800010B5044600F084FE034B03CB2060616083 +:100F90001868A06010BD00BF00E8F11F2DE9F04106 +:100FA000ADF5507D0D46002140F275126EAC07463E +:100FB00010A80F9100F06CFE4FF4C472002120467F +:100FC00000F066FE0DF13C0802F07CFA4FF47A72F4 +:100FD000264BB0FBF2F0186093E80700022384E888 +:100FE00007000DF5ED702382FFF7C8FF43F204738D +:100FF0001F4907A8238406F0BFFB1E230DF2EB2236 +:101000000DF1340C84F8323107AB1E46083203CEA2 +:10101000664542F8080C42F8041C3346F5D13068A6 +:10102000414610602046B3889380012200F0E8FE1C +:10103000002380B2E97E0393AB7E029305F119038E +:1010400001930123009307A3D3E90023CDE9048092 +:10105000384602F0F5FD0DF5507DBDE8F08100BF8A +:10106000AFF300809E6AC421818A46EEF8230020F7 +:10107000887700082DE9F0412C4CDAB080460D4607 +:10108000237A5BBB27A9284600F0C8FF0746002843 +:1010900042D19DF89D60C82E3ED801464FF4A6620D +:1010A000204600F0F5FD4FF4807332460DF19E01AD +:1010B000C4F8F8314FF4007304F109002644C4F871 +:1010C0000C334FF44073C4F8203400F0BBFD9DF89E +:1010D0009C30777223720BB9EB7E237206AC8122AF +:1010E000002127A800F0D4FD0122214627A800F006 +:1010F000D1FF002380B2E97E0393AB7E029305F11A +:10110000190301932823CDE904400093404605A329 +:10111000D3E9002302F094FD5AB0BDE8F08100BF8E +:10112000AFF3008026417272DF25D7B7F048002068 +:10113000F0B5254E4FF48A75F1B0002405FB00652B +:1011400096F8D830D822214685F8DC303AA885F8C0 +:10115000E84006AF00F09CFD06F1090000F090FDAC +:10116000D5F8E430C2B206F109018DF8F0000DF1B6 +:10117000F100CDE93A3400F065FD394601223AA884 +:1011800000F0B4FF082380B2317ACDE90470012762 +:101190000E48CDE9023706F1D803019330230093BE +:1011A00007A3D3E9002302F04BFDA04206DD02F0C5 +:1011B00089F9C5F8E000384671B0F0BD2046FBE77C +:1011C00078F6339F93CACD8DF0480020103400206C +:1011D0002DE9F0411D4D86B01D4E1E4F284602F0F0 +:1011E0005BFD034658B30024DFF86C80ADF8144073 +:1011F0000294CDE90344027B8DF8142003AA996878 +:10120000406803C21B6843F00043029302F05CF99C +:1012100082190094384641F1000302A901F0E4F973 +:10122000A04205DD284602F03BFD88F80040D5E7E6 +:1012300098F80030072B05D8013388F8003006B045 +:10124000BDE8F081014802F02BFDF8E710340020E2 +:1012500040420F0040340020254E002070B50D465E +:1012600014461E4602F048FC50B9022E10D1012C43 +:101270000ED112A3D3E900230120C5E9002307E022 +:10128000282C10D005D8012C09D0052C0FD0002017 +:1012900070BD302CFBD10BA3D3E90023ECE70BA3EB +:1012A000D3E90023E8E70BA3D3E90023E4E70BA38A +:1012B000D3E90023E0E700BFAFF30080401DA12089 +:1012C00026812A0B78F6339F93CACD8D9E6AC4215E +:1012D000818A46EE26417272DF25D7B7F017304A71 +:1012E00039059E5638B505460E4C0021013500F0F3 +:1012F00041FCA4F82C55B4F82C0500F023FC78B17F +:10130000B4F82C0500F02EFC014648B9B4F82C05C1 +:1013100000F030FCB4F82C350133A4F82C35EAE7A2 +:1013200038BD00BFF04800200A4B0B4A10B51A60C8 +:1013300003F5805393F848203AB95C6C2CB12046F1 +:1013400000F0CEFF204606F0CDF90448BDE810407D +:1013500000F0C6BF403400203878000870440020F8 +:101360002DE9F04F8FB005460C4600AF02F0C4FBEC +:10137000002849D1237E022B1BD1E38A012B18D1EF +:1013800002F0A0F80646FFF7E1FD03464FF4C870EF +:1013900006F51676DFF8C082B3FBF0F202FB1033DD +:1013A00016FA83F3C8F80030E37E33B9A34B00226A +:1013B0001A703C37BD46BDE8F08F07F12401204686 +:1013C00000F0EAFD0028F4D107F11400FFF7D6FD84 +:1013D00097F8264007F1140107F12700224606F08E +:1013E00099F90028E2D10F2C08D8944B1C70D8F83A +:1013F0000030A3F51673C8F80030DAE797F8241028 +:10140000284602F071FBD4E7E38A282B2BD010D8B2 +:10141000012B23D0052BCCD1BFF34F8F8849894BAB +:10142000CA6802F4E0621343CB60BFF34F8F00BF82 +:10143000FDE7302BBDD1844EE17E327A9142B8D1A6 +:10144000607E3146002291F8DC50854200F0A58094 +:10145000013201F58A71042AF5D1AAE7214628460E +:10146000FFF79CFDA5E721462846FFF703FEA0E70E +:10147000B2F8EC507B6005F103094FEA99094FEA95 +:101480008902D11DC908A8EBC10300219D46EB4686 +:10149000584600F0FDFB04F1EE012A46584631445F +:1014A00000F0D0FB7B6813B9012000F03BFB96F8FD +:1014B000D20000F047FB044630B9307200F06CFBFC +:1014C000204600F02FFBB1E0D6F8D4203AB996F8C8 +:1014D000D200B6F82C25824201D8FFF703FFD6F8D8 +:1014E000D4202A44944208D296F8D200B6F82C258B +:1014F0000130824201D8FFF7F5FE5FFA89F25946C2 +:10150000706800F0CDFB08B9C54679E0726896F8BE +:10151000D2002A447260D6F8D42005EB0209C6F83E +:10152000D49000F00FFB814509D396F8D220D6F86D +:10153000D4000132001B86F8D220C6F8D400FF2D5B +:101540000FD80024347200F027FB204600F0EAFA9E +:1015500000F048FE3D4B188108B9FFF7AFF9C546CA +:1015600027E7BB6896F8D9000AFB0362FB68D2F84C +:10157000E41082F8E83001F58061C2F8E030C2F88A +:10158000E410FFF7D5FDFFF723FE96F8D9200132CE +:1015900002F0030286F8D920B6E74FF48A7A204693 +:1015A0000AFB02F505F1EA01314400F0CBFDF860D9 +:1015B00000287FF4FEAE0122354485F8E82001F0D2 +:1015C00081FFD5F8E020D6ED007A801A40F6B832D7 +:1015D000B8EE677ADFED1E6A192838BF19209042ED +:1015E00028BF104607EE900AF8EEE77A67EEA67A73 +:1015F000DFED186AE7EE267AFCEEE77AC6ED007AB0 +:1016000096F8D930BB60BA6873680AFB02F43219E5 +:1016100092F8E81059B1D2F8E410E8468B423FF452 +:1016200027AF002182F8E810C2F8E010C5467368C1 +:10163000064A9B0A01331381BBE600BF0934002030 +:1016400000ED00E00400FA05F0480020F823002037 +:10165000CDCCCC3D6666663F0C340020014B187043 +:10166000704700BF0424002038B54FF04054144B9D +:1016700022689A4221D1627D0025124B12481A70CD +:10168000C922237D0930114900F8013C4FF48073D1 +:10169000C0F8DB50C0F8EF314FF40073C0F80333EB +:1016A0004FF44073C0F8173400F0CCFAE02229461A +:1016B000204600F0EDFA012038BD0020FCE700BF15 +:1016C0009AAD44C504240020F048002016000030E4 +:1016D00037B500F087FD194D0223002218492881F3 +:1016E0006B710123174801F0D9FA002316494FF412 +:1016F00080520193154B16480093164B02F0CCF91B +:10170000154B197811B1124802F0EEF901F0DAFE2A +:101710000446FFF71BFC4FF4C873B0FBF3F202FB67 +:10172000130304F5167010FA83F00C4B186004F0E4 +:1017300061FC08B10F232B8103B030BDF8230020DA +:1017400040420F0040340020082400205D120008B1 +:101750001034002061130008042400200C34002001 +:101760002DE9F04F8C4C2DED028B85A7D7E9006752 +:1017700095B00FF21429D9E900899FED858BFFF709 +:1017800027FD0DAD0023DFF824B20C93ADF83C30FB +:101790000D936B6000234FF0010A0DF1250209A99A +:1017A00058468DF825308DF824A08DED008B01F082 +:1017B000F1FD9DF824200023002A40F0AE80204651 +:1017C00002F09AF90546002847D1DFF8E4B101F0AC +:1017D00079FEDBF8003098423FD301F073FE0790AA +:1017E000FFF7B4FB4FF4C873079AB0FBF3F101FBAA +:1017F000130302F5167010FA83F0CBF8000010A85E +:10180000DFF8B0B19BF80010002914BF2B465346F7 +:1018100007918DF83030FFF7B1FB079910AB0DF150 +:101820003100C1F110021944D2B2062A28BF0622A3 +:10183000079200F007FA079A0CAB20460393013297 +:101840001823D2B20293554B04923246CDE900A33D +:101850003B4602F097F98BF8005001F033FE504AF6 +:10186000504D1368C31AB3F57A7F32D3106001F07C +:101870002BFE02460B46204602F01CFA204602F0E0 +:101880003BF930B32B7A0DF1400BDFF82CA1002B84 +:1018900014BF032302238AF8053001F013FE4FF42E +:1018A0007A7301225946B0FBF3F0CAF800005046A3 +:1018B00000F04AFB182380B2424602933A4B019350 +:1018C00040F25513CDE903B0009320464B4602F099 +:1018D00059F92B7AABB101F0F5FD4FF0000A8346C0 +:1018E0004FF48A7295F8D900504400F0030002FBCF +:1018F000005393F8E81071B30AF1010ABAF1040F2A +:10190000F0D1C82003F070FE2B7A002B7FF435AFA6 +:1019100015B0BDEC028BBDE8F08F1946102210A85F +:1019200000F0B6F90DF126030AAA0CA9584601F0F9 +:1019300063F811AB95E8030083E803009DF83C30A1 +:1019400010A920468DF84C300C9B1093DDE90A233A +:1019500002F084FB1EE7D3F8E01049B12B68ABEB33 +:101960000101FA2B38BFFA230533B1EB430FC3D380 +:10197000FFF7DEFB4FF48A720028BDD1C1E700BF3C +:10198000401DA12026812A0BF1C6A7C1D068080FEF +:101990000000000000000000103400200834002087 +:1019A000204E0020F0480020244E0020403400202B +:1019B0000C34002009340020F823002008B5054825 +:1019C00001F0C0F8044A05490020BDE8084005F0D0 +:1019D00083BE00BF403400207C4E00202913000845 +:1019E000704700002DE9F84F4FF47A7306460D4614 +:1019F000002402FB03F7DFF85080DFF8509098F9DD +:101A000000305FFA84FA5A1C01D0A34212D159F86F +:101A100024002A4631460368D3F820B03B46D84715 +:101A2000854207D1074B012083F800A0BDE8F88F5D +:101A30000124E4E7002CFBD04FF4FA7003F0D4FD4E +:101A40000020F3E76C4E0020182200201C2200200A +:101A500070B504464FF47A76412C254628BF4125BF +:101A600006FB05F003F0C0FD641BF5D170BD00005E +:101A7000002307B5024601210DF107008DF807305C +:101A8000FFF7B0FF20B19DF8070003B05DF804FB3D +:101A90004FF0FF30F9E700000A46042108B5FFF7D0 +:101AA000A1FF80F00100C0B2404208BD074B0A46CA +:101AB00030B41978064B53F821400146236820467C +:101AC000DD69044BAC4630BC604700BF6C4E002063 +:101AD0001C220020A086010070B5104C0025104E7D +:101AE00004F09CF820803068238883420CD80025BD +:101AF0002088013804F08EF823880544013BB5F5B1 +:101B0000802F2380F4D370BD04F084F8336805443B +:101B10000133B5F5802F3360E5D3E8E76E4E002042 +:101B2000284E002004F048B900F1006000F5802044 +:101B30000068704700F10060920000F5802004F01A +:101B4000C9B80000054B1A68054B1B889B1A8342D5 +:101B500002D9104404F05EB800207047284E0020DF +:101B60006E4E0020024B1B68184404F059B800BFA9 +:101B7000284E0020024B1B68184404F063B800BFD5 +:101B8000284E00200020704700F1FF5000F58F1014 +:101B9000D0F8000870470000064991F8243033B1AE +:101BA00000230822086A81F82430FFF7C3BF012010 +:101BB000704700BF2C4E0020014B1868704700BFD3 +:101BC0000010005C194B01380322084470B51D68F1 +:101BD000174BC5F30B042D0C1E88A6420BD15C6875 +:101BE0000A46013C824213460FD214F9016F4EB1EE +:101BF00002F8016BF6E7013A03F10803ECD18142E8 +:101C00000B4602D22C2203F8012B0424094A168821 +:101C1000AE4204D1984284BF967803F8016B013C30 +:101C200002F10402F3D1581A70BD00BF0010005C2D +:101C300024220020D477000870470000704700007D +:101C400070470000002310B5934203D0CC5CC4540D +:101C50000133F9E710BD0000013810B510F9013F5C +:101C60003BB191F900409C4203D11AB10131013AD4 +:101C7000F4E71AB191F90020981A10BD1046FCE75C +:101C800003460246D01A12F9011B0029FAD1704707 +:101C900002440346934202D003F8011BFAE770475F +:101CA0002DE9F8431F4D14460746884695F8242031 +:101CB00052BBDFF870909CB395F824302BB92022EA +:101CC000FF2148462F62FFF7E3FF95F824004146C5 +:101CD000C0F1080205EB8000A24228BF2246D6B21E +:101CE0009200FFF7AFFF95F82430A41B17441E4461 +:101CF0009044E4B2F6B2082E85F82460DBD1FFF7F9 +:101D00004BFF0028D7D108E02B6A03EB8203834204 +:101D1000CFD0FFF741FF0028CBD10020BDE8F883EA +:101D20000120FBE72C4E0020024B1A78024B1A7060 +:101D3000704700BF6C4E00201822002038B51A4CA6 +:101D40001A4D204602F06EFF2946204602F096FF0B +:101D50002D684FF47A70D5F89020D2F8043843F00B +:101D60000203C2F80438FFF773FE1149284603F056 +:101D700093F8D5F890200F4DD2F80438286823F056 +:101D800002030D49A042C2F804384FF4E1330B605E +:101D900001D002F0A5FE6868A04204D00649BDE863 +:101DA000384002F09DBE38BD6055002064790008BF +:101DB0006C7900081C220020544E00200C4B70B59A +:101DC0000C4D04461E780C4B55F826209A420DD037 +:101DD0000A4B002118221846FFF75AFF04600146FB +:101DE00055F82600BDE8704002F07ABE70BD00BF15 +:101DF0006C4E00201C22002060550020544E002014 +:101E00002DE9F0470D46044600219046284640F251 +:101E10007912FFF73DFF234620220021284604F1D6 +:101E2000220702F0BDF8231D022220212846C026E9 +:101E300002F0B6F8631D03222221284602F0B0F812 +:101E4000A31D03222521284602F0AAF804F1080365 +:101E500010222821284602F0A3F804F110030822DA +:101E60003821284602F09CF804F111030822402191 +:101E7000284602F095F804F112030822482128466A +:101E800002F08EF804F1140320225021284602F0BB +:101E900087F804F1180340227021284602F080F8E8 +:101EA00004F120030822B021284602F079F804F159 +:101EB00021030822B821284602F072F8314608367C +:101EC0003B4608222846013702F06AF8B6F5A07FA3 +:101ED000F4D1002704F1330A04F132030822314619 +:101EE000284602F05DF894F832304FEAC7099F4265 +:101EF00009F5A47615D3B8F1000F08D1314609F2DF +:101F00004F1604F599730722284602F049F8274630 +:101F10003B1B94F8322193420CD3F01DC008BDE85E +:101F2000F0870AEB0703082231462846013702F002 +:101F300037F8D8E707F23313314608222846083627 +:101F4000013702F02DF8E3E713B5044608460021F7 +:101F50002022234601900160C0F8031002F020F80F +:101F6000231D01980222202102F01AF8631D019816 +:101F70000322222102F014F8A31D01980322252137 +:101F800002F00EF8019804F108031022282102F053 +:101F900007F8072002B010BD0023F7B50E46047FF6 +:101FA000072200911946054601F0BEFE731C01226E +:101FB000072100932846002301F0B6FEC4B9B31CE4 +:101FC000052208212846009323460D2401F0ACFE8B +:101FD0003746BB1BB278934211D307342B7FA88AB4 +:101FE000E408BBB9844294BF0020012003B0F0BDD7 +:101FF000AB8A0824DB00083BDB08B370E8E7FB1C76 +:10200000214608222846009300230834013701F0B6 +:102010008BFEDEE7201A18BF0120E7E70023F7B5A3 +:102020000E46047F082200911946054601F07CFE09 +:10203000731CC4B908220093234610241146284675 +:1020400001F072FE01235F1C7278013B934211D3B1 +:1020500007342B7FA88AE408BBB9844294BF0020D0 +:10206000012003B0F0BDAB8A0824DB00083BDB088D +:102070007370E7E7F31921460822284600930023EE +:1020800001F052FE08343B46DDE7201A18BF01205C +:10209000E7E70000F8B50E46054614460021812208 +:1020A0003046FFF7F5FD2B4608220021304601F0AF +:1020B00077FF7CB90F246B1C07220821304601F002 +:1020C0006FFF01235F1C6A78013B934204D3E01D3C +:1020D000C008F8BD0824F4E7EB1921460822304671 +:1020E00001F05EFF08343B46ECE70000F8B50E4611 +:1020F000054614460021CE223046FFF7C9FD2B4687 +:1021000028220021304601F04BFF7CB9302405F134 +:10211000080308222821304601F042FF2F467B1B8E +:102120002A7A934204D3E01DC008F8BD2824F5E7BD +:1021300007F109032146082230460834013701F02F +:102140002FFFECE7F7B5047F0E4600910123102224 +:102150000021054601F0E8FDC4B9B31C0922102195 +:10216000284600932346192401F0DEFD3746728885 +:10217000BB1B9A4211D807342B7FA88AE408BBB94D +:10218000844294BF0020012003B0F0BDAB8A10242C +:10219000DB00103BDB087380E8E73B1D214608228B +:1021A0002846009300230834013701F0BDFDDEE727 +:1021B000201A18BF0120E7E730B50A44084D9142C4 +:1021C0000DD011F8013B5840082340F30004013BB7 +:1021D0002C4013F0FF0384EA5000F6D1EFE730BD46 +:1021E0002083B8EDF7B5384A6B46106851686A46E7 +:1021F00003C308233549364805F09CFA04460028F5 +:1022000033D10A25334A6B46106851686A4603C3C6 +:10221000082331492E4805F08DFA0446002849D09C +:102220000369B3F5E01F45D8B0F8661040F23742B5 +:1022300091423FD1294A024402F15C018B4239D3D9 +:102240005C3B234900209E1AFFF7B6FF04F16401AE +:10225000074632460020FFF7AFFFA3689F4229D10F +:10226000E368984208BF002524E00369B3F5E01F46 +:1022700027D8418B40F23742914220D1174A02447D +:1022800002F110018B4218D3103B114900209D1A16 +:10229000FFF792FF04F1180106462A460020FFF7D7 +:1022A0008BFFA3689E4202D1E368984201D00D25BE +:1022B000A8E70025284603B0F0BD1025A2E70C25AD +:1022C000A0E70B259EE700BFE4770008DCFF1B00BA +:1022D00000000408ED77000890FF1B000800FCF7E1 +:1022E00010B5037C044613B9006805F00BFA2046CC +:1022F00010BD00000023BFF35B8FC360BFF35B8F93 +:10230000BFF35B8F8360BFF35B8F7047BFF35B8F5F +:102310000068BFF35B8F704770B505460C30FFF760 +:10232000F5FF044605F108063046FFF7EFFFA0422F +:1023300006D96D683046FFF7E9FF2544281A70BDBD +:102340003046FFF7E3FF201AF9E7000070B50546B5 +:102350004068A0B105F10C0605F10800FFF7D6FFB3 +:1023600004463046FFF7D2FF844204F1FF34304682 +:1023700094BF6D680025FFF7C9FF2C44201A70BD7B +:1023800038B50C460546FFF7C7FFA04210D305F14C +:102390000800FFF7BBFF04446868BFF35B8FB4FB22 +:1023A000F0F100FB11440120AC60BFF35B8F38BD3E +:1023B0000020FCE72DE9F041144607460D46FFF7E3 +:1023C000C5FF844228BF0446D4B1B84658F80C6B08 +:1023D0004046FFF79BFF3044286040467E68FFF789 +:1023E00095FF331A9C4203D801206C60BDE8F08150 +:1023F000A41B6B603B682044AB60E8600220F5E7FB +:102400002046F3E738B50C460546FFF79FFFA0428C +:1024100010D305F10C00FFF779FF04446868BFF39F +:102420005B8FB4FBF0F100FB11440120EC60BFF3C3 +:102430005B8F38BD0020FCE72DE9FF4188466946E7 +:1024400007466C46FFF7B6FF002506B204EBC6064A +:10245000B4420AD0626808EB050120680834FFF72F +:10246000F1FB54F8043C1D44F2E729463846FFF7D7 +:10247000C9FF284604B0BDE8F0810000F8B5054664 +:102480000C300F46FFF742FF05F1080604463046C0 +:10249000FFF73CFFA042304688BF6C68FFF736FF6D +:1024A000201A386020B12C683046FFF72FFF2044F7 +:1024B000F8BD000073B5144606460D46FFF72CFF25 +:1024C0008442019028BF0446DCB101A93046FFF7E1 +:1024D000D5FF019B33B93268C5E90233C5E9002451 +:1024E00001200CE09C42286038BF0194019884428E +:1024F0006860F5D93368241A0220AB60EC6002B042 +:1025000070BD2046FBE700002DE9FF410F466946FC +:102510006C46FFF7CFFF00B2002604EBC005AC42CB +:1025200009D0D4F80480B81954F8081B4246464430 +:10253000FFF788FBF3E7304604B0BDE8F081000008 +:1025400038B50546FFF7E0FF044601462846FFF789 +:1025500017FF204638BD0000302383F3118862B690 +:1025600070470000002383F3118862B670470000B3 +:10257000012070477047000010B4134602681468C9 +:102580000022A4465DF8044B6047000000F580502F +:1025900090F859047047000000F5805090F85204FC +:1025A0007047000000F5805090F958047047000013 +:1025B0004E20704700F5805208B5FFF7CDFFD2F8E6 +:1025C0009834D2F894041844D2F890341844D2F8CD +:1025D00078341844D2F888341844D2F88434184433 +:1025E000FFF7C0FF08BD00002DE9F04F0C4600F5D5 +:1025F000805185B01F4691F8523405469046BDF88B +:1026000038909BB1D1F874340133C1F87434236825 +:102610009A0006D4237B082B0BD9627B0AB10F2BBF +:1026200007D9D1F878340133C1F878344FF0FF304E +:102630000FE0FFF791FFEB6AD3F8C42012F4001A01 +:102640000AD0D1F87C3400200133C1F87C34FFF784 +:1026500089FF05B0BDE8F08F22684FF0480BD3F832 +:10266000C460002A6B6AC6F30446B4BF42F08042DD +:1026700092041BFB063BCBF8002023685B004FEA6B +:10268000066344BF42F00052CBF80020227B43EAAD +:1026900002437201CBF80430607B18B343F440135B +:1026A000CBF80430D1F8A4340133C1F8A434AB180A +:1026B00003F58353197B41F020011973207B0392AA +:1026C00000F05CFF0330039A80105FFA8AF30AF18E +:1026D000010A83420DDA04EB83010BEB83034968A3 +:1026E0009960F2E7AB1803F58353197B60F345114A +:1026F000E3E70121EB6A04F10C00B140C3F8D0100C +:10270000AB18214603F58253C3E9048705EB461352 +:1027100003F58253183351F804CB814243F804CBBC +:10272000F9D109882A442846198041F26803D65015 +:1027300002F5805209F0030392F86C1043F0100385 +:1027400021F01F010B43214682F86C304246FFF70F +:1027500009FF3B46CDF8009000F0D6FE012078E757 +:102760002DE9F04700F58056044696F85254002DA6 +:1027700040F00181037C032B40F092802B462846D9 +:102780002F465FFA83FC944510DA01EBCC0E51F82A +:102790003CC0BCF1000F04DBDEF804C0BCF1000F4C +:1027A00002DB01370133ECE70130FBE7FFF7D4FE32 +:1027B000E36AF0B9D3F8800040F00200C3F880006B +:1027C0004E23E06A002F6ED1D0F8803043F0010331 +:1027D000C0F88030694B6A4A1B6803F1805303F5E7 +:1027E0002C539B009342A36240F2AF80654800F0F7 +:1027F00063FE4D2842D8DFF884814FEA004EDFF8AF +:102800008891D8F800C04EEA8C0EC3F884E00CF131 +:10281000805303F52C539B00636100EB0C03D4F849 +:102820002CC0C8F80030C0F14E03DCF8800040F046 +:102830003000CCF880004FF0000CD4F81480E6464D +:102840005FFA8CF08242BCDD01EBC00A51F8300027 +:10285000002810DBDAF804A0BAF1000F0BDA09EA5D +:1028600000400AF07F0A40EA0A0040F0084048F8B9 +:102870002E000EF1010E0CF1010CE1E79A6922F035 +:1028800001029A6100F01EFE0646E36A9B69D907C1 +:1028900004D500F017FE831BFA2BF6D9FFF762FE72 +:1028A0002846BDE8F087B7EB530F3DD2DFF8CCE008 +:1028B0004FEA074CDEF800304CEA830CC0F888C0C1 +:1028C00003F1805003EB4703002700F52C50CEF8AE +:1028D0000030BC468000A061E06AD0F8803043F050 +:1028E0000C03C0F88030D4F818E0FBB29A427FF7AE +:1028F00071AF51F8330001EBC3080028D8F8043059 +:1029000001DB002B0EDB20F0604023F0604340F041 +:10291000005043F000434EF83C000EEBCC000CF1AD +:10292000010C43600137E0E7836923F00103836111 +:1029300000F0C8FD0646E36A9B69DA07AED500F0F1 +:10294000C1FD831BFA2BF6D9A8E7E26A936923F04D +:102950000103936100F0B6FD0746E36A9B69DB075C +:1029600005D500F0AFFDC31BFA2BF6D996E701257C +:1029700086F8525492E7002592E700BF784E002077 +:10298000FCB50040F87700080000FF0713B500F51C +:1029900080540191606CFFF7D9FC1F280AD92022CE +:1029A0000199606CFFF748FDA0F12003584258419F +:1029B00002B010BD0020FBE700F5805008B5FFF71E +:1029C000CBFD406CFFF796FCBDE80840FFF7CABDA1 +:1029D00000220260828142608260704700220023F0 +:1029E00010B5C0E90023002304460C3020F8043C55 +:1029F000FFF7EEFF204610BD2DE9F047074688B0EF +:102A00009A46884607F5805468469146FFF7A4FD2C +:102A1000FFF7E4FF606CFFF77FFC1F282DD9202211 +:102A20006946606CFFF78CFD202826D194F852345B +:102A30001BB303AD444605AB2E46083403CE9E427D +:102A400044F8080C44F8041C3546F5D1306841467A +:102A500020603846B388A380DDE90023C9E900235C +:102A6000BDF808304A46AAF80030FFF77BFD534610 +:102A700008B0BDE8F04700F035BD0020FFF772FD5B +:102A800008B0BDE8F08700002DE9F84F00230646A6 +:102A900000F58154054688461034C0E90133264BC1 +:102AA00046F8303B374638462037FFF797FFA742B6 +:102AB000F9D105F580544FF4805305F5A3594FF033 +:102AC000000A26630026676405F5835709F110099B +:102AD0004FF0000B1037E663C4E90D36012384F88C +:102AE000403084F84830A7F11800203747E910AB90 +:102AF000FFF76EFF47F8286C4F45F4D184F85884EF +:102B0000A4F85A64A4F85C64A4F85E6484F8606471 +:102B1000A4F86264A4F86464A4F8666484F8686441 +:102B2000B8F1000F02D0054800F0C6FC044B28465F +:102B3000EB62BDE8F88F00BF387800081C78000809 +:102B400000A00040044B10B5197804464A1C1A70C6 +:102B5000FFF79AFF204610BD754E00202DE9F04783 +:102B600000295FD0304F3148B7FBF1F581428CBF6F +:102B70000A201120431EB5FBF0FC00FB1C50DCB208 +:102B800020B1022B1846F5D8002037E00CF1FF35B4 +:102B9000B5F5806F32D2C4EBC4094FF47A7009F1F5 +:102BA00003034FEAE308C3F3C70308F1010AA4EBE8 +:102BB000030E08FB00085FFA8EF65AFA8EFEB8FB89 +:102BC000FEFEBEF5617F1BDC1FFA8EF4581C56FA20 +:102BD00080F00CFB00FCB7FBFCFC6145D4D1013B51 +:102BE000DBB20F2BD0D8711E0020C9B2072905D83F +:102BF000107101201480558053719171BDE8F087E8 +:102C000009F1FF334FEAE30EC3F3C7030EF10108E6 +:102C1000E41A0EFB0000E6B258FA84F4B0FBF4F4B8 +:102C2000A4B2D3E70846E9E700B4C4043F420F006A +:102C300038B540F27772C36A154CC3F8BC2007223E +:102C4000C36AC3F8C8202268C16A930043F4C02352 +:102C5000C1F8A03002F1805302F16C01C56A03F59E +:102C60002C53EA3289009B00226041F0E061094A5E +:102C7000C361C5F8C01003F5D87103F56A734162EA +:102C80009342836202D9044800F016FC38BD00BFAD +:102C9000784E0020FCB50040F87700082DE9F04F91 +:102CA00000F58055994689B0044695F858348A460F +:102CB0009046012B04D90027384609B0BDE8F08FB3 +:102CC000934A52F8231009B942F823009149C4F8F5 +:102CD0000CA00B7884F81090C3B9FFF73DFC8E4B25 +:102CE000D3F8EC2042F48072C3F8EC20D3F894209F +:102CF00042F48072C3F89420D3F8942022F48072B6 +:102D0000C3F8942001230B70FFF72CFC95F8513485 +:102D100073B903211320FFF71FFC01F02BFD0321E2 +:102D2000152001F027FD012385F85134FFF71AFC27 +:102D3000FFF712FCE26A936923F01003936100F03D +:102D4000C1FB0746E36A9E6916F0080607D000F04B +:102D5000B9FBC31BFA2BF5D9FFF704FCABE79A6963 +:102D600042F001029A6100F0ADFB0746E36A9A69FE +:102D7000D00705D400F0A6FBC31BFA2BF6D9EBE76E +:102D80009A69002704F5825B42F002020BF1100BF6 +:102D90009A61E36A5F65FFF7E5FB686CFFF7AAFAE3 +:102DA000202200216846FEF773FF02A8FFF710FEFD +:102DB0006A460BEB06030DF1180E0697944608338E +:102DC000BCE80300F44543F8080C43F8041C6246D1 +:102DD000F4D1DCF8000020361860B6F5806F9CF85E +:102DE00004201A71DCD1002304F5A252514620467A +:102DF0001A3285F8503485F85334FFF7AFFE074692 +:102E000090B9E26A936923F00103936100F05AFBE1 +:102E10000546E36A9B69D9077FF54DAF00F052FB89 +:102E2000431BFA2BF5D946E795F85F6495F85E24C5 +:102E30003602C5F86CA4E36A46EA426695F8602457 +:102E40001643B5F85C2446EA0246DE61B8F1000F8D +:102E500029D004F5A352414620460232FFF77EFEF8 +:102E600090B9E26A936923F00103936100F02AFBB1 +:102E70000546E36A9B69DA077FF51DAF00F022FB88 +:102E8000431BFA2BF5D916E795F8683495F86714C3 +:102E90001B01C5F87084E26A43EA0123B5F86414A3 +:102EA00043EA0143D360E36A00262046C3F8BC60CE +:102EB000FFF7BEFE85F859646FF04042E36A1A6579 +:102EC000164AE36A5A654FF00222E36A9A654FF0A8 +:102ED000FF32E36AC3F8E0200322E36A9145DA6532 +:102EE0003FF4EAAEE26A936923F00103936100F0D4 +:102EF000E9FA0646E36A9B69DB0705D500F0E2FACA +:102F0000831BFA2BF6D9D6E6012385F85234D3E693 +:102F1000704E0020744E00200044025855020002FA +:102F20002DE9F04F054689B090469946002741F2B9 +:102F3000680A00F58056EB6AD3F8D830FB40D80712 +:102F40004AD505EB47124FEA471B5244137919073C +:102F500042D4D6F880340133C6F8803413799A0607 +:102F600005EB0B0248BFD6F8A834524444BF0133E6 +:102F7000C6F8A834137943F008031371DB0723D58F +:102F800096F8533403B305F582546846FFF726FDDF +:102F900003AB18345C4404F1080C2068083454F87E +:102FA000041C1A46644503C21346F6D120686946DC +:102FB00010602846A2889A800123ADF808302B685B +:102FC000CDE90089DB6B9847D6F8543423B1D6F8A5 +:102FD0009C340133C6F89C340137202FABD109B0A3 +:102FE000BDE8F08F2DE9F04F0F468DB0044600F09C +:102FF0006BFA82468946002F5BD1E36AD3F8A020A2 +:1030000012F4FE0F03D100200DB0BDE8F08FD3F80D +:10301000A420920141BF04F58051D1F894240132DB +:10302000C1F89424D3F8A4205606ECD0D3F8A450C9 +:10303000E669C5F305254823E8464FF0000B03FB7E +:1030400005664046FFF7C4FC326851004ABF22F0D3 +:103050006043C2F38A4343F00043920048BF43F009 +:1030600080430093736813F400131BBF012304F51E +:1030700080528DF80D308DF80D301EBFD2F8AC3473 +:103080000133C2F8AC34F38803F00F038DF80C3031 +:103090009DF80C0000F072FA5FFA8BF3984225D984 +:1030A000F2180CA90BF1010B127A0B4403F82C2C2B +:1030B000EEE7012FA7D1E36AD3F8B02012F4FE0F98 +:1030C000A1D0D3F8B420950141BF04F58051D1F8C7 +:1030D00094240132C1F89424D3F8B420500692D03D +:1030E000D3F8B450266AC5F30525A4E7EFB9E36A1F +:1030F000C3F8A85004A807ADFFF770FC98E80F00CC +:1031000007C52B800023204604A9ADF8183023689A +:1031100004F58054DB6BCDE904A9984758B1D4F885 +:103120008C340133C4F88C346EE7012FE2D1E36AAA +:10313000C3F8B850DEE7D4F8903401200133C4F866 +:10314000903461E7F8B505460F4600F58054012636 +:1031500039462846FFF746FF10B184F85364F7E775 +:10316000D4F8543423B1D4F89C340133C4F89C34DB +:10317000F8BD0000C36AF0B51A6C12F47F0F2BD0B3 +:103180001B6C00F5805441F268054FF0010CC4F847 +:10319000A0340023471900EB43125E012A44117941 +:1031A00011F0020F15D0490713D4B959C66A0CFAA9 +:1031B00001F1D6F8CCE011EA0E0F0AD0C6F8D4100F +:1031C000117941F004011171D4F888240132C4F856 +:1031D00088240133202BDED1F0BD000010B5264C31 +:1031E000264B22680AB340B31A6D92050FD54FF4EF +:1031F00000721A6500F068F950EA01020B4602D02D +:10320000013861F1000302462068FFF789FE1B4A7E +:10321000136D9B012AD523684FF0007103F580538D +:103220001165012283F8592420E001221A65102239 +:103230001A654FF480521A6510BD196DC80702D483 +:10324000196D490705D50521104619650021FFF7BD +:1032500079FF0A4B1A6DD00602D41A6D510605D5B6 +:10326000502201211A652068FFF76CFF2068BDE835 +:103270001040FFF77FBF00BF704E002000A000404D +:1032800008B5FFF769F9FFF775FFBDE80840FFF7DC +:1032900069B90000C36AD3F8C00010F07C5005D0B3 +:1032A000D3F8C40080F40010C0F340507047000011 +:1032B00000F5805008B5FFF74FF9406CFFF72CF888 +:1032C000FFF750F943090CBF0120002008BD0000A2 +:1032D00000F5805393F8592462B1C16A8A6922F0DB +:1032E00001028A61D3F898240132C3F8982400229D +:1032F00083F85924704700002DE9F74300F5825107 +:1033000098460025FFF728F9103141F2680E4FF07A +:10331000010900F5805C00EB4514744423795E07D5 +:103320001CD4DB061AD58E69C36A09FA06F6D3F8EF +:10333000CC703E4212D04F6801970F689742019FB0 +:1033400077EB08070AD2C3F8D460237943F004036B +:103350002371DCF884340133CCF884340135203116 +:10336000202DD8D103B0BDE8F043FFF7FBB8000033 +:10337000F8B51E4600230F46054613701446FFF7A6 +:1033800097FF80F0010038701EB12846FFF782FFDA +:103390002070F8BD2DE9F04F85B099460D46804666 +:1033A000164691F800B0DDE90EA30293137801935D +:1033B00000F08AF82B7804460F4613B93378002BB7 +:1033C00042D022463B464046FFF796FFFFF758FFA4 +:1033D000FFF77EFF4B4632462946FFF7C9FF2B78A1 +:1033E00033B1BBF1000F03D0012005B0BDE8F08F71 +:1033F000337813B1019B002BF6D108F5805303936A +:103400005445029B77EB03031ED2039BD3F854046D +:10341000D0B10368AAEB0401DB6889B298474B4638 +:10342000324629464046FFF7A3FF2B7813B1BBF184 +:10343000000FD9D1337813B1019B002BD4D100F008 +:1034400043F804460F46DBE70020CEE708B500202E +:10345000FFF7C4FEBDE8084001F056B808B50120EA +:10346000FFF7BCFEBDE8084001F04EB800B59BB0C8 +:10347000EFF3098168226846FEF7E4FBEFF305836A +:10348000014B9B6BFEE700BF00ED00E008B5FFF7C6 +:10349000EDFF000000B59BB0EFF30981682268469C +:1034A000FEF7D0FBEFF30583014B5B6BFEE700BF3C +:1034B00000ED00E0FEE700000FB408B5029802F04E +:1034C0001FF8FEE702F0C4BC02F09CBC13B56C46CA +:1034D000031D84E8060094E8030083E8050001204A +:1034E00002B010BD73B58568019155B11B885B07AB +:1034F00007D4D0E900369B6B9847019AC1B2304699 +:10350000A847012002B070BDF0B5866889B00546B5 +:103510000C465EB1BDF838305B070AD4D0E90037FD +:103520009B6B98472246C1B23846B047012009B08C +:10353000F0BD0022002301F10806CDE9002300239D +:103540000A46ADF8083003AB1068083252F8041C84 +:103550001C46B24203C42346F6D11068206092880C +:10356000A280FFF7B1FF0423ADF808302B68CDE946 +:103570000001DB6B694628469847D7E7082817D92A +:1035800009280CD00A280CD00B280CD00C280CD001 +:103590000D280CD00E2814BF4020302070470C207E +:1035A0007047102070471420704718207047202063 +:1035B000704700002DE9F041456A15B94162BDE848 +:1035C000F0814B68AC4623F06047C3F38A464FEA6C +:1035D000D37EC3F3807816EA230638BF3E462B46D7 +:1035E0005A68BEEBD27F22F060440AD0002A18DA73 +:1035F000A40CB44217D19D420FD10D60DEE71346F3 +:10360000EEE7A74207D102F08044C2F38072424540 +:103610000BD054B1EFE708D2EDE7CCF800100B6007 +:10362000CDE7B44201D0B442E5D81A689C46002ADE +:10363000E5D11960C3E700002DE9F047089D01F0CE +:10364000070400EBD1004FF47F494FEAD50822442C +:1036500005F00705944201D1BDE8F08704F00707A3 +:1036600005F0070A111B08EBD50E57453E4613F827 +:103670000EC038BF5646C6F108068E4228BF0E4619 +:10368000E108415C34443544B94029FA06F721FA8F +:103690000AF1FFB28CEA010147FA0AF739408CEAD5 +:1036A000010C03F80EC0D5E780EA0120082341F29F +:1036B000210201B2013B4000002980B2B8BF504056 +:1036C00013F0FF03F5D1704738B50C468D18A542AD +:1036D00000D138BD14F8011BFFF7E6FFF7E7000043 +:1036E00042684AB1136881894360438901339BB2C0 +:1036F0009942438138BF83811046704770B588B0C6 +:10370000044620220D4668460021FEF7C1FA2046F5 +:103710000495FFF7E5FF024660B16B46054608AE2B +:103720001C46083503CCB44245F8080C45F8041C87 +:103730002346F5D1104608B070BD0000082817D9FF +:1037400009280CD00A280CD00B280CD00C280CD03F +:103750000D280CD00E2814BF4020302070470C20BC +:1037600070471020704714207047182070472020A1 +:1037700070470000082817D90C280CD910280CD93C +:1037800014280CD918280CD920280CD930288CBF23 +:103790000F200E207047092070470A2070470B2029 +:1037A00070470C2070470D20704700002DE9F8434A +:1037B000078C0446072F1ED900254FF6FF73D0E96A +:1037C0000298C5F12006A5F1200029FA05F1083577 +:1037D00008FA06F628FA00F0314301431846C9B248 +:1037E000FFF762FF402D0346EBD13A46E169BDE8A1 +:1037F000F843FFF769BF4FF6FF70BDE8F88300009C +:1038000010B54B6823B9CA8A63F30902CA8210BD96 +:1038100004691A681C600361C38A013BC3824A6061 +:10382000EFE700002DE9F84F1D46CB8A0F46814691 +:10383000C3F30901924605290B4630D00020AAB2F5 +:1038400007F11A049EB21FFA80F8042E0FD8904593 +:1038500003F1010306D30A44FB8A62F30903012042 +:10386000FB821AE01AF800600130E654EAE790455E +:10387000F1D2A1F1050B1C237C68BBFBF3F203FB27 +:1038800012BB1FFA8BF6002C45D14846FFF728FFE4 +:10389000044638B978606FF00200BDE8F88F4FF049 +:1038A0000008E6E7002606607860ADB24FF0000B36 +:1038B000454510D90AEB0803221D13F8011B08F136 +:1038C00001089155B1B21FFA88F81B292BD0454544 +:1038D00006F10106F1D8FB8AC3F30902154465F32A +:1038E0000903BCE701321C4692B22368002BF9D1D0 +:1038F0006B1F0B441C21B3FBF1F301339BB29A42C3 +:10390000D3D2BBF1000FD0D14846FFF7E9FE20B972 +:10391000C4F800B0BFE70122E7E7C0F800B05E4698 +:1039200020600446C1E74545D5D94846FFF7D8FE93 +:1039300008B92060AFE7C0F800B000262060044658 +:10394000B6E700002DE9F04F1C46074688462DEDEE +:10395000028B83B05B690192002B00F09A80238C6C +:103960002BB1E269002A00F09480072B35D807F1CB +:103970000C00FFF7B5FE054638B96FF00205284682 +:1039800003B0BDEC028BBDE8F08F14220021FEF7DE +:103990007FF9228CE16905F10800FEF753F9208CCC +:1039A00048F00041013080B2FFF7E4FEFFF7C6FEA9 +:1039B000013880B220840130287438466369228C33 +:1039C0001B782A4403F01F0363F03F0313726960FE +:1039D0002946FFF7EFFD0125D1E74FF0000900F17F +:1039E0000C034FF0800A4E464D4608EE103A18EE92 +:1039F000100AFFF775FE83460028BED0142200216E +:103A0000FEF746F9002E3AD1019B0222ABF80830AE +:103A10000BF1080E1FFA82FC218C0CF10100BCF1A5 +:103A2000060F80B201D88E422BD3FFF7A3FE8E4241 +:103A300008BF4FF0400AFFF781FE62690138013587 +:103A400012781BFA80F1013002F01F022DB242EA17 +:103A5000491289F001094AEA020A48F0004281F855 +:103A600008A059468BF810003846CBF804204FF0D8 +:103A7000000AFFF79FFD238CB342B8D17FE70022F5 +:103A8000C6E7E169895D01360EF80210B6B201326F +:103A9000C0E76FF0010572E7F8B515460E46302213 +:103AA000002104461F46FEF7F3F8069BB5F5001FFC +:103AB000A760636004F11000079B34BF6A094FF6EA +:103AC000FF72E661A362002397B29A4206D80023F0 +:103AD0000360A782E3822383E360F8BD06600133BD +:103AE00030462036F1E7000003781BB94BB2002BBB +:103AF000C8BF01707047000000787047F8B50C46E9 +:103B0000C969074611B9238C002B37D1257E1F2D9B +:103B100034D8387828BB228C072A2CD8268A36F04D +:103B200003032BD14FF6FF70FFF7CEFD20F001000D +:103B300031024FF6FF72400441EA0561400C41EA50 +:103B40004025234629463846FFF7FCFE002807DDBE +:103B5000626913780133DBB21F2B88BF0023137017 +:103B6000F8BD218A2D0645EA012505432046FFF7C9 +:103B70001DFE0246E5E76FF00300F1E76FF001007C +:103B8000EEE7000070B58AB00446164600212822F0 +:103B900068461D46FEF77CF8BDF838306946204679 +:103BA000ADF810300F9B05939DF840308DF818301C +:103BB000119B0793BDF84830CDE90265ADF8203080 +:103BC000FFF79CFF0AB070BD2DE9F041D3690546AF +:103BD0000C4616460BB9138C5BBB377E1F2F28D8BB +:103BE00095F80080B8F1000F26D03046FFF7DEFDD3 +:103BF000337821020246284641EAC331338A41EA3A +:103C0000080141EA076141EA0341334641F080017E +:103C1000FFF798FE00280ADD3378012B07D172697F +:103C200013780133DBB21F2B88BF00231370BDE86C +:103C3000F0816FF00100FAE76FF00300F7E7000092 +:103C4000F0B58BB004460D46174600212822684681 +:103C50001E46FEF71DF89DF84C30294620465A1E98 +:103C6000534253416A468DF800309DF84030ADF81C +:103C70001030119B05939DF848308DF81830149B37 +:103C80000793BDF85430CDE90276ADF82030FFF748 +:103C90009BFF0BB0F0BD0000406A00B104307047DC +:103CA000436A1A68426202691A600361C38A013B6F +:103CB000C38270472DE9F041D0F8208014461D469C +:103CC000184E4146002709B9BDE8F081D1E9022329 +:103CD000A21A65EB0303964277EB03031ED2036A35 +:103CE0008B420DD1FFF78CFD036A1B6803620369E9 +:103CF0000B60C38A0161013B016AC3828846E2E727 +:103D0000FFF77EFD0B68C8F8003003690B60C38ABB +:103D10000161013BC382D8F80010D4E788460968E6 +:103D2000D1E700BF80841E002DE9F04F8BB00D4617 +:103D300014469B46DDF850908046002800F018811C +:103D4000B9F1000F00F01481531E3F2B00F21081D7 +:103D5000012A03D1BBF1000F40F00A810023CDE915 +:103D60000833B8F81430B5EBC30F4FEAC30703D3D9 +:103D700000200BB0BDE8F08F2B199F42D8F80C3013 +:103D800036BF7F1B2746FFB21BB9D8F81030002B77 +:103D90007AD0272D4DD8C5F1280600232946B742F1 +:103DA000009308ABD8F808002CBFF6B23E46A7EB4C +:103DB000060A354432465FFA8AFAFFF73DFCB8F846 +:103DC0001430282103F10053053BDB000493D8F89D +:103DD0000C300393039B13B1BAF1000F2CD1D8F828 +:103DE000100040B1BAF1000F05D008AB5246691A75 +:103DF0000096FFF721FC38B2002FB9D066070AD031 +:103E00000AAB624203EBD40102F0070211F8083C4E +:103E1000134101F8083C082C3DD9102C40F2B58024 +:103E2000202C40F2B780BBF1000F00F09C800823EB +:103E300035E0BA460026C2E7049BE02B28BFE0230A +:103E400006930B44AB42059315D95A1B0398691A84 +:103E50000096924508AB00F1040034BF5246D2B23E +:103E60000792FFF7E9FB079A1644AAEB020A1544EA +:103E7000F6B25FFA8AFA049B069A05999B1A049394 +:103E8000039B1B680393A5E700933A4608AB2946BA +:103E9000D8F80800ADE7BBF1000F13D00123B4EB55 +:103EA000C30F6BD0082C12D89DF82030621E23FA65 +:103EB00002F2D50706D54FF0FF3202FA04F423438D +:103EC0008DF820309DF8203089F8003051E7102C13 +:103ED00012D8BDF82030621E23FA02F2D10706D5AF +:103EE0004FF0FF3202FA04F42343ADF82030BDF85E +:103EF0002030A9F800303CE7202C0FD80899631E29 +:103F000021FA03F3DA0705D54FF0FF3202FA04F481 +:103F10000C430894089BC9F800302AE7402C2AD0AB +:103F2000611EC4F12102A4F12103DDE9086526FA2E +:103F300001F105FA02F225FA03F311431943CB0705 +:103F400011D50122A4F12003C4F1200102FA03F3E8 +:103F500022FA01F1A2400B43524263EB4303324386 +:103F60002B43CDE90823DDE90823C9E9002300E755 +:103F70006FF00100FDE66FF00800FAE6082CA1D909 +:103F8000102CB4D9202CEED8C4E7BBF1000FAED072 +:103F9000022384E7BBF1000FBCD004237FE70000BD +:103FA000012A30B5144638BF012485B00025402CC5 +:103FB00028BF4024012ACDE9025518D81B788DF876 +:103FC000083063070AD004AB624203EBD40502F069 +:103FD000070215F8083C934005F8083C0346009199 +:103FE0002246002102A8FFF727FB05B030BD082AB2 +:103FF000E4D9102A03D81B88ADF80830E1E7202A5D +:1040000095BF1B68D3E900230293CDE90223D8E7CB +:1040100010B5CB681BB98B600B618B8210BD046936 +:104020001A681C600361C38A013BC382CA60F0E75F +:1040300003064CBFC0F3C0300220704708B50246EB +:10404000FFF7F6FF022806D15306C2F30F2001D175 +:1040500000F0030008BDC2F30740FBE72DE9F04F75 +:1040600093B004460D46CDE903230A681046FFF7D6 +:10407000DFFF0228824614BFC2F306260026002A6C +:1040800080F2F38112F0C04940F0EF81097B0029F2 +:1040900000F0EB81022803D02378B34240F0E8819E +:1040A000C2F3046310462944069302F07F0305938C +:1040B000FFF7C4FF059B002283464FEA8348002395 +:1040C00048EA0A4848EA4668CE78CDE90823F30969 +:1040D00048EA0008029368D0059B024608A92046DA +:1040E000009353466768B847002800F0C481276AE8 +:1040F0004FB9414604F10C00FFF700FB074690B9A9 +:104100006FF0020055E03B6998450DD03F68002FE5 +:10411000F9D1414604F10C00FFF7F0FA07460028F8 +:10412000EED0236A3B60276297F817C006F01F089D +:10413000CCF3840CACEB0800A8EB0C031FFA80FE58 +:104140000028B8BF0EF120001FFA83FEB8BF00B2EE +:10415000002B0793B8BF0EF12003D7E90221BCBFA3 +:104160001BB2079352EA010338D0039B4FF0000CB7 +:10417000DFF820E39A1A049B63EB010196457CEB80 +:1041800001032BD36B7B97F81AE0734519D1029B7F +:10419000002B78D0012821DC7868F8B9DFF8F0C26C +:1041A000944570EB010316D337E0276A27B96FF007 +:1041B0000C0013B0BDE8F08F3B699845B4D03F6860 +:1041C000F4E7B34890427CEB010301D30020F0E711 +:1041D000029B002BFAD0079B0F2B17DCFA7DB30054 +:1041E0003946204602F0030203F07C031343FB75BB +:1041F000FFF706FB6B7BBB76029B3BB9FB7DC3F3F2 +:104200008402013262F38603FB75D0E76A7BBB7ED2 +:104210009A42DBD1029B002B35D0B309022B32D05E +:10422000039B142200210DA8BB60049BFB60FDF7DB +:104230002FFD039B0AA920460A93049BADF83EB0CC +:104240000B932B1D8DF840A00C932B7B8DF8418098 +:10425000013BDBB2ADF83C30069B8DF84230059B4C +:104260008DF8433094F82C3083F001038DF84430FE +:10427000A3689847FB7DC3F38403013303F01F0356 +:104280009B02FB82A2E7FB7DC6F34012B2EBD31F79 +:1042900040F0F480C3F38403434540F0F280029A77 +:1042A000B6092B7B002A4DD0F2075DD4032B40F2D8 +:1042B000EB80039BAE1D394604F10C00BB60324617 +:1042C000049BFB602B7B033BDBB2FFF7ABFA0028C0 +:1042D0000CDA39462046FFF793FAFB7DC3F38403DB +:1042E000013303F01F039B02FB8209E7AB88DDE982 +:1042F00008843B834FF6FF73C9F12000A9F1200227 +:1043000028FA09F109F1080904FA00F024FA02F286 +:10431000014318461143C9B2FFF7C6F9B9F1400F7E +:104320000346E9D1B88231462A7B033AD2B2FFF77D +:10433000CBF9FB7DB882DA43C2F3C01262F3C71334 +:10434000FB7543E786B92E1D013B394604F10C008D +:10435000DBB23246FFF766FA0028BADB2A7B314629 +:10436000B88A013AD2B2E2E7F98A013BC1F3090106 +:10437000DAB204295BD8281D002307F11B069A42F4 +:1043800008D910F801CB013306F801C00131DBB2C6 +:104390000529F4D1039993420A9138BF0433049953 +:1043A0002CBF002355FA83F30B9107F11B010C91ED +:1043B00079680E930D91291DFB8AADF83EB0C3F3C9 +:1043C00009038DF840A08DF841801A44069B8DF8B2 +:1043D0004230059BADF83C208DF8433094F82C30EA +:1043E00083F001038DF844300023B88A7B602A7B78 +:1043F000013AFFF769F93B8BB882834203D1A36886 +:104400000AA92046984720460AA9FFF701FEFB7D2E +:10441000BA8AC3F38403013303F01F039B02FB82B8 +:104420003B8B9A420CBF00206FF01000C1E67B6806 +:10443000002BAFD0052001E01C3033461E68002E53 +:10444000FAD1091A2E1D081D184401EB090C5FFA58 +:1044500089F3BCF11B0F9DD89A429BD916F8013BFA +:1044600009F1010900F8013BEFE76FF00900A0E650 +:104470006FF00A009DE66FF00B009AE66FF00D00FA +:1044800097E66FF00E0094E66FF00F0091E600BF24 +:1044900040420F0080841E00EFF309830549683312 +:1044A0004A6B22F001024A6383F30988002383F3F5 +:1044B0001188704700EF00E0302080F3118862B669 +:1044C0000D4B0E4AD96821F4E0610904090C0A4336 +:1044D0000B49DA60D3F8FC2042F08072C3F8FC206C +:1044E000084AC2F8B01F116841F001011160202292 +:1044F000DA7783F82200704700ED00E00003FA0548 +:1045000055CEACC5001000E0302310B583F3118800 +:104510000E4B5B6813F4006314D0F1EE103AEFF326 +:1045200009844FF08073683CE361094BDB6B2366C1 +:1045300084F3098800F0A2FF10B1064BA36110BDFF +:10454000054BFBE783F31188F9E700BF00ED00E0BE +:1045500000EF00E0430700084607000802684368D0 +:104560001143016003B1184770470000024A136805 +:1045700043F0C003136070470078004013B50E4C41 +:10458000204600F0A1FA04F1140000234FF4007259 +:104590000A49009400F05EF9094B4FF40072094992 +:1045A00004F13800009400F0D7F9074A074BC4E93A +:1045B000172302B010BD00BF804E0020EC4E00203B +:1045C0006D450008EC5000200078004000E1F50542 +:1045D000037C30B5214C002918BF0C46012B0CD1AF +:1045E0001F4B984209D11F4B9A6C42F080429A644B +:1045F0001A6F42F080421A671B6F2268036EC16D0A +:1046000003EB52038466B3FBF2F36268150442BF06 +:1046100023F0070503F0070343EA4503CB60A368D3 +:1046200043F040034B60E36843F001038B6042F4C6 +:10463000967343F001030B604FF0FF330B6251059B +:1046400005D512F0102205D0B2F1805F04D080F8B9 +:10465000643030BD7F23FAE73F23F8E7787800081D +:10466000804E0020004502582DE9F047C66D0546F2 +:104670003768F469210734621AD014F0080118BFB2 +:104680004FF48071E20748BF41F02001A3074FF0CB +:10469000300348BF41F04001600748BF41F080014E +:1046A00083F31188281DFFF759FF002383F3118836 +:1046B000E2050AD5302383F311884FF48061281D69 +:1046C000FFF74CFF002383F311884FF030094FF0C0 +:1046D000000A14F0200838D13B0616D54FF03009F7 +:1046E00005F1380A200610D589F31188504600F0EC +:1046F00067F9002836DA0821281DFFF72FFF27F079 +:1047000080033360002383F31188790614D5620691 +:1047100012D5302383F31188D5E913239A4208D1A7 +:104720002B6C33B127F040071021281DFFF716FF2F +:104730003760002383F31188E30618D5AA6E136946 +:10474000ABB15069BDE8F047184789F31188736A27 +:10475000284695F86410194000F0D0F98AF31188C2 +:10476000F469B6E7B06288F31188F469BAE7BDE886 +:10477000F0870000090100F16043012203F5614365 +:10478000C9B283F8001300F01F039A4043099B004D +:1047900003F1604303F56143C3F880211A60704759 +:1047A000F8B51546826804460B46AA4200D28568D1 +:1047B000A1692669761AB5420BD218462A46FDF73A +:1047C00041FAA3692B44A3612846A3685B1BA3603D +:1047D000F8BD0CD9AF1B18463246FDF733FA3A46FE +:1047E000E1683044FDF72EFAE3683B44EBE71846F6 +:1047F0002A46FDF727FAE368E5E70000836893425D +:10480000F7B50446154600D28568D4E90460361A27 +:10481000B5420BD22A46FDF715FA63692B44636152 +:104820002846A3685B1BA36003B0F0BD0DD93246D8 +:10483000AF1B0191FDF706FA01993A46E068314451 +:10484000FDF700FAE3683B44E9E72A46FDF7FAF989 +:10485000E368E4E710B50A440024C361029B846066 +:10486000C16002610362C0E90000C0E9051110BD2A +:1048700008B5D0E90532934201D1826882B98268D5 +:10488000013282605A1C426119700021D0E9043261 +:104890009A4224BFC368436100F0C2FE002008BDF5 +:1048A0004FF0FF30FBE7000070B5302304460E46A2 +:1048B00083F31188A568A5B1A368A269013BA36031 +:1048C000531CA36115782269934224BFE368A36156 +:1048D000E3690BB120469847002383F311882846EB +:1048E00007E03146204600F08BFE0028E2DA85F32F +:1048F000118870BD2DE9F74F04460E4617469846BD +:10490000D0F81C904FF0300A8AF311884FF0000B5A +:10491000154665B12A4631462046FFF741FF03465A +:1049200060B94146204600F06BFE0028F1D000231C +:1049300083F31188781B03B0BDE8F08FB9F1000F45 +:1049400003D001902046C847019B8BF31188ED1AD4 +:104950001E448AF31188DCE7C160C361009B82605A +:104960000362C0E905111144C0E90000016170470C +:10497000F8B504460D461646302383F31188A76820 +:10498000A7B1A368013BA36063695A1C62611D70F3 +:10499000D4E904329A4224BFE3686361E3690BB14E +:1049A00020469847002080F3118807E031462046D2 +:1049B00000F026FE0028E2DA87F31188F8BD000037 +:1049C000D0E9052310B59A4201D182687AB982688C +:1049D0000021013282605A1C82611C7803699A426C +:1049E00024BFC368836100F01BFE204610BD4FF05A +:1049F000FF30FBE72DE9F74F04460E461746984671 +:104A0000D0F81C904FF0300A8AF311884FF0000B59 +:104A1000154665B12A4631462046FFF7EFFE0346AC +:104A200060B94146204600F0EBFD0028F1D000239C +:104A300083F31188781B03B0BDE8F08FB9F1000F44 +:104A400003D001902046C847019B8BF31188ED1AD3 +:104A50001E448AF31188DCE7026843681143016051 +:104A600003B11847704700001430FFF743BF000040 +:104A70004FF0FF331430FFF73DBF00003830FFF731 +:104A8000B9BF00004FF0FF333830FFF7B3BF00006D +:104A90001430FFF709BF00004FF0FF311430FFF76B +:104AA00003BF00003830FFF763BF00004FF0FF3254 +:104AB0003830FFF75DBF0000012914BF6FF013000D +:104AC00000207047FFF75ABD044B0360002343608A +:104AD000C0E9023301230374704700BF90780008D7 +:104AE00010B53023044683F31188FFF771FD0223CC +:104AF0000020237480F3118810BD000038B5C3690D +:104B000004460D461BB904210844FFF7A5FF2946BA +:104B100004F11400FFF7ACFE002806DA201D4FF464 +:104B20000061BDE83840FFF797BF38BD02684368B1 +:104B30001143016003B118477047000013B5406B83 +:104B400000F58054D4F8A4381A681178042914D1D7 +:104B5000017C022911D11979012312898B4013425A +:104B60000BD101A94C3002F00BF9D4F8A44802464D +:104B7000019B2179206800F0DFF902B010BD000030 +:104B8000143002F08DB800004FF0FF33143002F003 +:104B900087B800004C3002F05FB900004FF0FF33DF +:104BA0004C3002F059B90000143002F05BB800003C +:104BB0004FF0FF31143002F055B800004C3002F0D5 +:104BC0002BB900004FF0FF324C3002F025B9000045 +:104BD0000020704710B500F58054D4F8A4381A6846 +:104BE0001178042917D1017C022914D159790123A4 +:104BF00052898B4013420ED1143001F0EDFF024672 +:104C000048B1D4F8A4484FF4407361792068BDE8F6 +:104C1000104000F07FB910BD406BFFF7DBBF000014 +:104C2000704700007FB5124B01250426044603603F +:104C30000023057400F1840243602946C0E9023371 +:104C40000C4B0290143001934FF44073009601F026 +:104C50009FFF094B04F69442294604F14C0002944C +:104C6000CDE900634FF4407302F066F804B070BD04 +:104C7000B8780008194C00083D4B00080A6830233A +:104C800083F311880B790B3342F823004B791333EC +:104C900042F823008B7913B10B3342F8230000F55F +:104CA0008053C3F8A41802230374002080F31188F2 +:104CB0007047000038B5037F044613B190F85430B4 +:104CC000ABB90125201D0221FFF730FF04F11400CC +:104CD0006FF00101257700F0AFFC04F14C0084F87F +:104CE00054506FF00101BDE8384000F0A5BC38BD5C +:104CF00010B5012104460430FFF718FF0023237785 +:104D000084F8543010BD000038B504460025143036 +:104D100001F056FF04F14C00257702F025F8201D24 +:104D200084F854500121FFF701FF2046BDE83840C8 +:104D3000FFF750BF90F8803003F06003202B06D1BE +:104D400090F881200023212A03D81F2A06D80020AA +:104D50007047222AFBD1C0E91D3303E0034A4267B2 +:104D600007228267C3670120704700BF3C220020F2 +:104D700037B500F58055D5F8A4381A68117804299C +:104D80001AD1017C022917D11979012312898B408C +:104D9000134211D100F14C04204602F0A5F858B19D +:104DA00001A9204601F0ECFFD5F8A4480246019B7A +:104DB0002179206800F0C0F803B030BD01F10B0389 +:104DC000F0B550F8236085B004460D46FEB130239F +:104DD00083F3118804EB8507301D0821FFF7A6FE39 +:104DE000FB6806F14C005B691B681BB1019001F088 +:104DF000D5FF019803A901F0C3FF024648B1039B08 +:104E00002946204600F098F8002383F3118805B066 +:104E1000F0BDFB685A691268002AF5D01B8A013B75 +:104E20001340F1D104F18002EAE70000133138B5F4 +:104E300050F82140ECB1302383F3118804F58053FE +:104E4000D3F8A4281368527903EB8203DB689B69CB +:104E50005D6845B104216018FFF768FE294604F13A +:104E6000140001F0C3FE2046FFF7B4FE002383F3D5 +:104E7000118838BD7047000001F096B90123402227 +:104E8000002110B5044600F8303BFCF701FF002379 +:104E9000C4E9013310BD000010B53023044683F38C +:104EA00011882422416000210C30FCF7F1FE2046DD +:104EB00001F09CF902230020237080F3118810BDBB +:104EC00070B500EB8103054650690E461446DA6062 +:104ED00018B110220021FCF7DBFEA06918B11022E6 +:104EE0000021FCF7D5FE31462846BDE8704001F0B0 +:104EF0007DBA000083682022002103F0011310B561 +:104F0000044683601030FCF7C3FE2046BDE8104025 +:104F100001F0F8BAF0B4012500EB810447898D4017 +:104F2000E4683D43A469458123600023A260636077 +:104F3000F0BC01F015BB0000F0B4012500EB8104CA +:104F400007898D40E4683D4364690581236000233F +:104F5000A2606360F0BC01F08BBB000070B502235F +:104F600000250446242203702946C0F888500C30DE +:104F700040F8045CFCF78CFE204684F8705001F089 +:104F8000C9F963681B6823B129462046BDE8704013 +:104F9000184770BD0378052B10B504460AD080F879 +:104FA0008C300523037043681B680BB104219847BC +:104FB0000023A36010BD00000178052906D190F8F8 +:104FC0008C20436802701B6803B1184770470000CB +:104FD00070B590F87030044613B1002380F870303B +:104FE00004F18002204601F0B1FA63689B68B3B90E +:104FF00094F8803013F0600535D00021204601F090 +:10500000A3FD0021204601F093FD63681B6813B1E6 +:10501000062120469847062384F8703070BD20464C +:1050200098470028E4D0B4F88630A26F9A4288BF2F +:10503000A36794F98030A56F002B4FF0300380F206 +:105040000381002D00F0F280092284F8702083F3A0 +:10505000118800212046D4E91D23FFF76DFF0023AE +:1050600083F31188DAE794F8812003F07F0343EAA1 +:10507000022340F20232934200F0C58021D8B3F5FA +:10508000807F48D00DD8012B3FD0022B00F09380B9 +:10509000002BB2D104F1880262670222A267E367A3 +:1050A000C1E7B3F5817F00F09B80B3F5407FA4D1C9 +:1050B00094F88230012BA0D1B4F8883043F0020379 +:1050C00032E0B3F5006F4DD017D8B3F5A06F31D0F3 +:1050D000A3F5C063012B90D86368204694F8822022 +:1050E0005E6894F88310B4F88430B047002884D008 +:1050F000436863670368A3671AE0B3F5106F36D09F +:1051000040F6024293427FF478AF5C4B6367022320 +:10511000A3670023C3E794F88230012B7FF46DAFBF +:10512000B4F8883023F00203A4F88830C4E91D5590 +:10513000E56778E7B4F88030B3F5A06F0ED194F846 +:105140008230204684F88A3001F042F963681B6897 +:1051500013B1012120469847032323700023C4E99B +:105160001D339CE704F18B0363670123C3E72378B6 +:10517000042B10D1302383F311882046FFF7BAFEA9 +:1051800085F311880321636884F88B5021701B68B4 +:105190000BB12046984794F88230002BDED084F87B +:1051A0008B300423237063681B68002BD6D0022148 +:1051B00020469847D2E794F8843020461D0603F035 +:1051C0000F010AD501F0B4F9012804D002287FF4B8 +:1051D00014AF2B4B9AE72B4B98E701F09BF9F3E7C1 +:1051E00094F88230002B7FF408AF94F8843013F0E9 +:1051F0000F01B3D01A06204602D501F0BDFCADE781 +:1052000001F0AEFCAAE794F88230002B7FF4F5AEF3 +:1052100094F8843013F00F01A0D01B06204602D56D +:1052200001F092FC9AE701F083FC97E7142284F8DE +:10523000702083F311882B462A4629462046FFF723 +:1052400069FE85F31188E9E65DB1152284F87020C6 +:1052500083F3118800212046D4E91D23FFF75AFE6D +:10526000FDE60B2284F8702083F311882B462A4632 +:1052700029462046FFF760FEE3E700BFE878000814 +:10528000E0780008E478000838B590F870300446FB +:10529000002B3ED0063BDAB20F2A34D80F2B32D87F +:1052A000DFE803F037313108223231313131313129 +:1052B00031313737856FB0F886309D4214D2C368DC +:1052C0001B8AB5FBF3F203FB12556DB9302383F350 +:1052D00011882B462A462946FFF72EFE85F31188B2 +:1052E0000A2384F870300EE0142384F870303023E1 +:1052F00083F31188002320461A461946FFF70AFE59 +:10530000002383F3118838BDC36F03B1984700238E +:10531000E7E70021204601F017FC0021204601F0BC +:1053200007FC63681B6813B10621204698470623D3 +:10533000D7E7000010B590F870300446142B29D040 +:1053400017D8062B05D001D81BB110BD093B022B85 +:10535000FBD80021204601F0F7FB0021204601F098 +:10536000E7FB63681B6813B10621204698470623B4 +:1053700019E0152BE9D10B2380F87030302383F32B +:10538000118800231A461946FFF7D6FD002383F340 +:105390001188DAE7C3689B695B68002BD5D1C36FBE +:1053A00003B19847002384F87030CEE70023826869 +:1053B000037503691B6899689142FBD25A680360C0 +:1053C000426010605860704700238268037503696B +:1053D0001B6899689142FBD85A680360426010606C +:1053E0005860704708B50846302383F311880B7D59 +:1053F000032B05D0042B0DD02BB983F3118808BDE6 +:105400008B6900221A604FF0FF338361FFF7CEFFF4 +:105410000023F2E7D1E9003213605A60F3E700009D +:10542000FFF7C4BF054BD968087518680268536058 +:105430001A600122D8600275FBF76EB9F0520020A5 +:105440000C4B30B5DD684B1C87B004460FD02B46A3 +:10545000094A684600F084F92046FFF7E3FF009B05 +:1054600013B1684600F086F9A86907B030BDFFF7B0 +:10547000D9FFF9E7F0520020E5530008044B1A6801 +:10548000DB6890689B68984294BF002001207047B9 +:10549000F0520020084B10B51C68D8682268536091 +:1054A0001A600122DC602275FFF78EFF014620465C +:1054B000BDE81040FBF730B9F0520020044B1A68E9 +:1054C000DB6892689B689A4201D9FFF7E3BF704797 +:1054D000F052002038B5074C012300250649074843 +:1054E0002370656001F03EFD0223237085F311886F +:1054F00038BD00BF58550020F0780008F052002059 +:1055000008B572B6044B186500F06AFC00F03CFD6B +:10551000024B03221A70FEE7F0520020585500207B +:1055200000F05EB9EFF3118020B9EFF3058330226C +:1055300082F311887047000010B530B9EFF305848D +:10554000C4F3080414B180F3118810BDFFF7B6FF4F +:1055500084F31188F9E70000034A516853685B1A25 +:105560009842FBD8704700BF001000E08B60022318 +:10557000086108468B8270478368A3F1840243F870 +:10558000142C026943F8442C426943F8402C094A20 +:1055900043F8242CC268A3F1200043F8182C0222FF +:1055A00003F80C2C002203F80B2C034A43F8102CB0 +:1055B000704700BF31070008F052002008B5FFF720 +:1055C000DBFFBDE80840FFF72BBF0000024BDB68A4 +:1055D00098610F20FFF726BFF0520020302383F39D +:1055E0001188FFF7F3BF000008B50146302383F3AD +:1055F00011880820FFF724FF002383F3118808BDDA +:10560000064BDB6839B1426818605A60136043602A +:105610000420FFF715BF4FF0FF307047F052002015 +:105620000368984206D01A68026050601846996173 +:10563000FFF7F6BE7047000038B504460D462068F7 +:10564000844200D138BD036823605C608561FFF748 +:10565000E7FEF4E7036810B59C68A2420CD85C68CA +:105660008A600B604C602160596099688A1A9A6060 +:105670004FF0FF33836010BD121B1B68ECE7000086 +:105680000A2938BF0A2170B504460D460A2660195A +:1056900001F060FC01F048FC041BA54203D8751C16 +:1056A00004462E46F3E70A2E04D90120BDE87040D7 +:1056B00001F098BC70BD0000F8B5144B0D460A2AE5 +:1056C0004FF00A07D96103F11001826038BF0A2246 +:1056D000416019691446016048601861A81801F01A +:1056E00029FC01F021FC431B0646A34206D37C1C87 +:1056F00028192746354601F02DFCF2E70A2F04D978 +:105700000120BDE8F84001F06DBCF8BDF05200206A +:10571000F8B506460D4601F007FC0F4A134653F84C +:10572000107F9F4206D12A4601463046BDE8F84028 +:10573000FFF7C2BFD169BB68441A2C1928BF2C4699 +:10574000A34202D92946FFF79BFF22463146034870 +:10575000BDE8F840FFF77EBFF05200200053002064 +:10576000C0E90323002310B45DF8044B4361FFF745 +:10577000CFBF000010B5194C236998420DD0816845 +:10578000D0E9003213605A609A680A449A60002394 +:1057900003604FF0FF33A36110BD0268234643F856 +:1057A000102F53600022026022699A4203D1BDE8A3 +:1057B000104001F0C9BB936881680B44936001F00D +:1057C000B3FB2269E1699268441AA242E4D9114408 +:1057D000BDE81040091AFFF753BF00BFF052002088 +:1057E0002DE9F047DFF8BC8008F110072C4ED8F8FF +:1057F000105001F099FBD8F81C40AA68031B9A428C +:105800003ED814444FF00009D5E90032C8F81C40D6 +:1058100013605A60C5F80090D8F81030B34201D137 +:1058200001F092FB89F31188D5E9033128469847A6 +:10583000302383F311886B69002BD8D001F074FBFF +:105840006A69A0EB040982464A450DD2022001F0A4 +:10585000C9FB0022D8F81030B34208D1514628467F +:10586000BDE8F047FFF728BF121A2244F2E712EB17 +:1058700009092946384638BF4A46FFF7EBFEB5E727 +:10588000D8F81030B34208D01444C8F81C00211ACC +:10589000A960BDE8F047FFF7F3BEBDE8F08700BFA1 +:1058A00000530020F052002000207047FEE7000067 +:1058B000704700004FF0FF307047000002290CD005 +:1058C000032904D00129074818BF00207047032A84 +:1058D00005D8054800EBC200704704487047002017 +:1058E000704700BFC87900084C2200207C7900086E +:1058F00070B59AB005460846144601A900F0C2F8F2 +:1059000001A8FCF7BDF9431C0022C6B25B0010469B +:10591000C5E9003423700323023404F8013C01ABD1 +:10592000D1B202348E4201D81AB070BD13F8011BF7 +:10593000013204F8010C04F8021CF1E708B5302329 +:1059400083F311880348FFF713FA002383F31188C8 +:1059500008BD00BF6055002090F8803003F01F02A2 +:10596000012A07D190F881200B2A03D10023C0E936 +:105970001D3315E003F06003202B08D1B0F884300C +:105980002BB990F88120212A03D81F2A04D8FFF7C9 +:10599000D1B9222AEBD0FAE7034A4267072282678D +:1059A000C3670120704700BF4322002007B50529C7 +:1059B00017D8DFE801F0191603191920302383F3F3 +:1059C0001188104A01210190FFF77AFA019802210B +:1059D0000D4AFFF775FA0D48FFF796F9002383F398 +:1059E000118803B05DF804FB302383F31188074866 +:1059F000FFF760F9F2E7302383F311880348FFF7DC +:105A000077F9EBE71C790008407900086055002021 +:105A100038B50C4D0C4C2A460C4904F10800FFF730 +:105A200067FF05F1CA0204F110000949FFF760FFA2 +:105A300005F5CA7204F118000649BDE83840FFF7C1 +:105A400057BF00BF386E00204C220020FC780008B1 +:105A5000067900081179000870B5044608460D461D +:105A6000FCF70EF9C6B22046013403780BB918468C +:105A700070BD32462946FCF7EFF80028F3D101202B +:105A8000F6E700002DE9F04705460C46FCF7F8F86C +:105A90002A49C6B22846FFF7DFFF08B10936F6B239 +:105AA00027492846FFF7D8FF08B11036F6B2632E13 +:105AB0000BD8DFF88880DFF88890224FDFF890A0BD +:105AC0002E7846B92670BDE8F08729462046BDE805 +:105AD000F04701F051BE252E2CD107224146284621 +:105AE000FCF7BAF860B9184B224603F1100153F8DD +:105AF000040B8B4242F8040BF9D107351034DFE771 +:105B0000082249462846FCF7A7F898B9A21C0F4B73 +:105B1000197802320909C95D02F8041C13F8011B47 +:105B200001F00F015345C95D02F8031CF0D1183490 +:105B30000835C5E7013504F8016BC1E7E8790008CD +:105B400011790008F07900089677000800E8F11F45 +:105B50000CE8F11FBFF34F8F044B1A695107FCD1BA +:105B6000D3F810215207F8D1704700BF002000522F +:105B700008B50D4B1B78ABB9FFF7ECFF0B4BDA68A0 +:105B8000D10704D50A4A5A6002F188325A60D3F824 +:105B90000C21D20706D5064AC3F8042102F1883247 +:105BA000C3F8042108BD00BF9670002000200052F9 +:105BB0002301674508B5114B1B78F3B9104B1A69DF +:105BC000510703D5DA6842F04002DA60D3F81021B9 +:105BD000520705D5D3F80C2142F04002C3F80C213E +:105BE000FFF7B8FF064BDA6842F00102DA60D3F83B +:105BF0000C2142F00102C3F80C2108BD9670002070 +:105C0000002000520F289ABF00F580604004002059 +:105C1000704700004FF400307047000010207047BC +:105C20000F2808B50BD8FFF7EDFF00F50033026829 +:105C3000013204D104308342F9D1012008BD002093 +:105C4000FCE700000F2838B505463FD8FFF782FF74 +:105C50001F4CFFF78DFF4FF0FF3307286361C4F837 +:105C600014311DD82361FFF775FF030243F02403AD +:105C7000E360E36843F08003E36023695A07FCD4E0 +:105C80002846FFF767FFFFF7BDFF4FF4003100F034 +:105C900057F92846FFF78EFFBDE83840FFF7C0BF31 +:105CA000C4F81031FFF756FFA0F108031B0243F0C0 +:105CB0002403C4F80C31D4F80C3143F08003C4F849 +:105CC0000C31D4F810315B07FBD4D9E7002038BD84 +:105CD000002000522DE9F84F05460C46104645EAD3 +:105CE0000203DE0602D00020BDE8F88F20F01F007E +:105CF000DFF8BCB0DFF8BCA0FFF73AFF04EB000808 +:105D0000444503D10120FFF755FFEDE72022294646 +:105D1000204601F0FFFC10B920352034F0E72B4677 +:105D200005F120021F68791CDDD104339A42F9D1B4 +:105D300005F178431B481C4EB3F5801F1B4B38BF41 +:105D4000184603F1F80332BFD946D1461E46FFF785 +:105D500001FF0760A5EB040C336804F11C0143F05C +:105D600002033360231FD9F8007017F00507FAD13A +:105D700053F8042F8B424CF80320F4D1BFF34F8F1C +:105D8000FFF7E8FE4FF0FF3320222146036028464C +:105D9000336823F00203336001F0BCFC0028BBD061 +:105DA0003846B0E7142100520C2000521420005253 +:105DB000102000521021005210B5084C237828B151 +:105DC0001BB9FFF7D5FE0123237010BD002BFCD0BB +:105DD0002070BDE81040FFF7EDBE00BF96700020B8 +:105DE00038B5054D00240334696855F80C0B00F0F4 +:105DF000B9F8122CF7D138BD047A0008084601F032 +:105E000081BC000070B5104E82B0FFF78BFB0546D9 +:105E100001F08AF8326803469042336037BF0B4A7C +:105E20000A495168146836BF0131D1E90041516017 +:105E30000419284641F100010191FFF77DFB20463E +:105E4000019902B070BD00BF98700020A0700020C2 +:105E500070B5124E82B0FFF765FB054601F064F89D +:105E6000326803469042336037BF0D4A0C4951688F +:105E7000146836BF0131D1E9004151600419284648 +:105E800041F100010191FFF757FB4FF47A720023B3 +:105E900020460199FAF72CFA02B070BD98700020E4 +:105EA000A07000200244074BD2B210B5904200D13E +:105EB00010BD441C00B253F8200041F8040BE0B2BE +:105EC000F4E700BF504000580E4B30B51C6F24045F +:105ED00005D41C6F1C671C6F44F400441C670A4CFB +:105EE00002442368D2B243F480732360074B90428C +:105EF00000D130BD441C51F8045B00B243F820507F +:105F0000E0B2F4E7004402580048025850400058FC +:105F100007B5012201A90020FFF7C4FF019803B0D3 +:105F20005DF804FB13B50446FFF7F2FFA04205D06D +:105F3000012201A900200194FFF7C6FF02B010BDA5 +:105F40000144BFF34F8F064B884204D3BFF34F8FFA +:105F5000BFF36F8F7047C3F85C022030F4E700BFD7 +:105F600000ED00E00144BFF34F8F064B884204D39D +:105F7000BFF34F8FBFF36F8F7047C3F870022030AD +:105F8000F4E700BF00ED00E070470000074B45F26A +:105F900055521A6002225A6040F6FF729A604CF61F +:105FA000CC421A600122024B1A7070470048005818 +:105FB000AC700020034B1B781BB1034B4AF6AA229E +:105FC0001A607047AC70002000480058034B1A68F4 +:105FD0001AB9034AD2F8D0241A607047A87000207A +:105FE00000400258024B4FF48032C3F8D02470476F +:105FF0000040025808B5FFF7E9FF024B1868C0F3EC +:10600000806008BDA870002070B5BFF34F8FBFF34C +:106010006F8F1A4A0021C2F85012BFF34F8FBFF39F +:106020006F8F536943F400335361BFF34F8FBFF356 +:106030006F8FC2F88410BFF34F8FD2F8803043F6D1 +:10604000E074C3F3C900C3F34E335B0103EA0406F3 +:10605000014646EA81750139C2F86052F9D2203B07 +:1060600013F1200FF2D1BFF34F8F536943F4803304 +:106070005361BFF34F8FBFF36F8F70BD00ED00E032 +:10608000FEE70000214B2248224A70B5904237D3E8 +:10609000214BC11EDA1C121A22F003028B4238BFB8 +:1060A00000220021FBF7F4FD1C4A0023C2F88430D3 +:1060B000BFF34F8FD2F8803043F6E074C3F3C900CA +:1060C000C3F34E335B0103EA0406014646EA8175D9 +:1060D0000139C2F86C52F9D2203B13F1200FF2D1F2 +:1060E000BFF34F8FBFF36F8FBFF34F8FBFF36F8F30 +:1060F0000023C2F85032BFF34F8FBFF36F8F70BDD4 +:1061000053F8041B40F8041BC0E700BFA07C000844 +:1061100080720020807200208072002000ED00E07C +:10612000054B996B21EA000199631A6E22EA00027D +:106130001A661B6E704700BF0045025870B5D0E963 +:10614000244300224FF0FF359E6804EB42135101B7 +:10615000D3F80009002805DAD3F8000940F08040A0 +:10616000C3F80009D3F8000B002805DAD3F8000BB8 +:1061700040F08040C3F8000B013263189642C3F828 +:106180000859C3F8085BE0D24FF00113C4F81C387B +:1061900070BD0000890141F02001016103699B0687 +:1061A000FCD41220FFF7D8B910B50A4C2046FEF7F0 +:1061B00065FE094BC4F89030084BC4F89430084C85 +:1061C0002046FEF75BFE074BC4F89030064BC4F840 +:1061D000943010BDB070002000000840707A0008B4 +:1061E0004C710020000004407C7A000870B50378F0 +:1061F0000546012B58D13F4BD0F89040984254D1DE +:106200003D4B0E2165209A6B42F000629A631A6E34 +:1062100042F000621A661B6E384BD3F8802042F0C1 +:106220000062C3F88020D3F8802022F00062C3F817 +:106230008020D3F88030FEF79DFA314BE360314B7C +:10624000C4F800380023D5F89060C4F8003EC0239D +:1062500023604FF40413A3633369002BFCDA01239A +:106260000C203361FFF778F93369DB07FCD4122087 +:10627000FFF772F93369002BFCDA00262846A66086 +:10628000FFF75CFF6B68C4F81068DB68C4F814683B +:10629000C4F81C6863BB1C4BA3614FF0FF33636100 +:1062A000A36843F00103A36070BD184B9842C9D1A5 +:1062B000114B4FF080609A6B42F000729A631A6E35 +:1062C00042F000721A661B6E0C4BD3F8802042F02D +:1062D0000072C3F88020D3F8802022F00072C3F847 +:1062E0008020D3F88030FFF71BFF0E214D20A2E75E +:1062F000074BD1E7B0700020004502580044025817 +:106300004014004003002002003C30C04C710020CB +:10631000083C30C0F8B5D0F89040054600214FF059 +:1063200000662046FFF736FFD5F8941000234FF0A3 +:1063300001128F684FF0FF30C4F83438C4F81C28BD +:1063400004EB431201339F42C2F80069C2F8006BAC +:10635000C2F80809C2F8080BF2D20B68D5F89020F1 +:10636000C5F89830636210231361166916F01006A1 +:10637000FBD11220FFF7F0F8D4F8003823F4FE63C5 +:10638000C4F80038A36943F4402343F01003A36129 +:106390000923C4F81038C4F814380B4BEB604FF0E5 +:1063A000C043C4F8103B094BC4F8003BC4F8106963 +:1063B000C4F80039D5F8983003F1100243F4801383 +:1063C000C5F89820A362F8BD4C7A00084080001000 +:1063D000D0F8902090F88A10D2F8003823F4FE63A9 +:1063E00043EA0113C2F80038704700002DE9F84372 +:1063F00000EB8103D0F890500C468046DA680FFA23 +:1064000081F94801166806F00306731E022B05EB9E +:1064100041134FF0000194BFB604384EC3F8101B6F +:106420004FF0010104F1100398BF06F1805601FA04 +:1064300003F3916998BF06F5004600293AD0578AC0 +:1064400004F15801374349016F50D5F81C180B432C +:106450000021C5F81C382B180127C3F81019A740D4 +:106460005369611E9BB3138A928B9B08012A88BFD4 +:106470005343D8F89820981842EA034301F14002A8 +:106480002146C8F89800284605EB82025360FFF7C2 +:1064900081FE08EB8900C3681B8A43EA84534834B1 +:1064A0001E4364012E51D5F81C381F43C5F81C78D3 +:1064B000BDE8F88305EB4917D7F8001B21F400412C +:1064C000C7F8001BD5F81C1821EA0303C0E704F144 +:1064D0003F030B4A2846214605EB83035A60FFF72A +:1064E00059FE05EB4910D0F8003923F40043C0F8F9 +:1064F0000039D5F81C3823EA0707D7E700800010D9 +:1065000000040002D0F894201268C0F89820FFF729 +:1065100015BE00005831D0F8903049015B5813F493 +:10652000004004D013F4001F0CBF0220012070476C +:106530004831D0F8903049015B5813F4004004D042 +:1065400013F4001F0CBF02200120704700EB8101F3 +:10655000CB68196A0B6813604B6853607047000082 +:1065600000EB810330B5DD68AA691368D36019B9FF +:10657000402B84BF402313606B8A1468D0F89020AE +:106580001C4402EB4110013C09B2B4FBF3F4634339 +:10659000033323F0030343EAC44343F0C043C0F88A +:1065A000103B2B6803F00303012B0ED1D2F80838FF +:1065B00002EB411013F4807FD0F8003B14BF43F08E +:1065C000805343F00053C0F8003B02EB4112D2F875 +:1065D000003B43F00443C2F8003B30BD2DE9F041DD +:1065E000D0F8906005460C4606EB4113D3F8087BC3 +:1065F0003A07C3F8087B08D5D6F814381B0704D52A +:1066000000EB8103DB685B689847FA071FD5D6F873 +:106610001438DB071BD505EB8403D968CCB98B692B +:10662000488A5A68B2FBF0F600FB16228AB918684D +:10663000DA6890420DD2121AC3E90024302383F3A2 +:10664000118821462846FFF78BFF84F31188BDE8A7 +:10665000F081012303FA04F26B8923EA02036B81C0 +:10666000CB68002BF3D021462846BDE8F0411847FF +:1066700000EB81034A0170B5DD68D0F890306C6999 +:106680002668E66056BB1A444FF40020C2F8100991 +:106690002A6802F00302012A0AB20ED1D3F80808D0 +:1066A00003EB421410F4807FD4F8000914BF40F0CB +:1066B000805040F00050C4F8000903EB4212D2F8B9 +:1066C000000940F00440C2F800090122D3F8340860 +:1066D00002FA01F10143C3F8341870BD19B9402E14 +:1066E00084BF4020206020681A442E8A8419013C0F +:1066F000B4FBF6F440EAC44040F00050C6E70000A6 +:106700002DE9F843D0F8906005460C464F0106EBA2 +:106710004113D3F8088918F0010FC3F808891CD079 +:10672000D6F81038DB0718D500EB8103D3F80CC07E +:10673000DCF81430D3F800E0DA68964530D2A2EBEA +:106740000E024FF000091A60C3F80490302383F35F +:106750001188FFF78DFF89F3118818F0800F1DD085 +:10676000D6F834380126A640334217D005EB84030F +:106770000134D5F89050D3F80CC0E4B22F44DCF8C3 +:10678000142005EB0434D2F800E05168714514D3AD +:10679000D5F8343823EA0606C5F83468BDE8F8832E +:1067A000012303FA01F2038923EA02030381DCF8DF +:1067B0000830002BD1D09847CFE7AEEB0103BCF8EF +:1067C0001000834228BF0346D7F8180980B2B3EB04 +:1067D000800FE3D89068A0F1040959F8048FC4F839 +:1067E0000080A0EB09089844B8F1040FF5D81844CC +:1067F0000B4490605360C8E72DE9F84FD0F89050F3 +:1068000004466E69AB691E4016F480586E6103D071 +:10681000BDE8F84FFEF7A2BB002E12DAD5F8003E15 +:106820009B0705D0D5F8003E23F00303C5F8003ED2 +:10683000D5F80438204623F00103C5F80438FEF7E4 +:10684000BBFB370505D52046FFF778FC2046FEF751 +:10685000A1FBB0040CD5D5F8083813F0060FEB688F +:1068600023F470530CBF43F4105343F4A053EB6074 +:1068700031071BD56368DB681BB9AB6923F00803DC +:10688000AB612378052B0CD1D5F8003E9A0705D0D3 +:10689000D5F8003E23F00303C5F8003E2046FEF77E +:1068A0008BFB6368DB680BB120469847F30200F16D +:1068B000BA80B70226D5D4F8909000274FF0010A8D +:1068C00009EB4712D2F8003B03F44023B3F5802FC5 +:1068D00011D1D2F8003B002B0DDA62890AFA07F3D6 +:1068E00022EA0303638104EB8703DB68DB6813B1EF +:1068F0003946204698470137D4F89430FFB29B6858 +:106900009F42DDD9F00619D5D4F89000026AC2F38F +:106910000A1702F00F0302F4F012B2F5802F00F014 +:10692000CA80B2F5402F09D104EB8303002200F5A1 +:106930008050DB681B6A974240F0B0803003D5F886 +:10694000185835D5E90303D500212046FFF746FE48 +:10695000AA0303D501212046FFF740FE6B0303D5B0 +:1069600002212046FFF73AFE2F0303D503212046DC +:10697000FFF734FEE80203D504212046FFF72EFE80 +:10698000A90203D505212046FFF728FE6A0203D598 +:1069900006212046FFF722FE2B0203D507212046C1 +:1069A000FFF71CFEEF0103D508212046FFF716FE76 +:1069B000700340F1A780E90703D500212046FFF7C7 +:1069C0009FFEAA0703D501212046FFF799FE6B071A +:1069D00003D502212046FFF793FE2F0703D503219D +:1069E0002046FFF78DFEEE0603D504212046FFF773 +:1069F00087FEA80603D505212046FFF781FE69061C +:106A000003D506212046FFF77BFE2A0603D5072182 +:106A10002046FFF775FEEB0574D520460821BDE83A +:106A2000F84FFFF76DBED4F890904FF0000B4FF089 +:106A3000010AD4F894305FFA8BF79B689F423FF6C7 +:106A400038AF09EB4713D3F8002902F44022B2F51E +:106A5000802F20D1D3F80029002A1CDAD3F800298E +:106A600042F09042C3F80029D3F80029002AFBDB4A +:106A70003946D4F89000FFF78DFB22890AFA07F314 +:106A800022EA0303238104EB8703DB689B6813B1CD +:106A90003946204698470BF1010BCAE7910701D10F +:106AA000D0F80080072A02F101029CBF03F8018B95 +:106AB0004FEA18283FE704EB830300F58050DA68BB +:106AC000D2F818C0DCF80820DCE9001CA1EB0C0CA3 +:106AD00000218F4208D1DB689B699A683A449A602A +:106AE0005A683A445A6029E711F0030F01D1D0F8EF +:106AF00000808C4501F1010184BF02F8018B4FEA4F +:106B00001828E6E7BDE8F88F08B50348FFF774FEDC +:106B1000BDE80840FDF7F8BCB070002008B5034898 +:106B2000FFF76AFEBDE80840FDF7EEBC4C7100209F +:106B3000D0F8903003EB4111D1F8003B43F400133F +:106B4000C1F8003B70470000D0F8903003EB4111D2 +:106B5000D1F8003943F40013C1F800397047000040 +:106B6000D0F8903003EB4111D1F8003B23F400132F +:106B7000C1F8003B70470000D0F8903003EB4111A2 +:106B8000D1F8003923F40013C1F800397047000030 +:106B900030B50433039C0172002104FB0325C1605E +:106BA000C0E90653049B0363059BC0E90000C0E9EC +:106BB0000422C0E90842C0E90A11436330BD000065 +:106BC0000022416AC260C0E90411C0E90A226FF0E4 +:106BD0000101FEF731BD0000D0E90432934201D13A +:106BE000C2680AB9181D7047002070470369196010 +:106BF0000021C2680132C260C269134482699342B3 +:106C0000036124BF436A0361FEF70ABD38B5044639 +:106C10000D46E3683BB162690020131D1268A36250 +:106C20001344E36207E0237A33B929462046FEF78E +:106C3000E7FC0028EDDA38BD6FF00100FBE700004B +:106C4000C368C269013BC3604369134482699342CC +:106C5000436124BF436A436100238362036B03B132 +:106C60001847704770B53023044683F31188866A4D +:106C70003EB9FFF7CBFF054618B186F311882846C9 +:106C800070BDA36AE26A13F8015B9342A36202D368 +:106C90002046FFF7D5FF002383F31188EFE70000BC +:106CA0002DE9F84F04460E46174698464FF0300936 +:106CB00089F311880025AA46D4F828B0BBF1000F4B +:106CC00009D141462046FFF7A1FF20B18BF311887F +:106CD0002846BDE8F88FD4E90A12A7EB050B521A33 +:106CE000934528BF9346BBF1400F1BD9334601F1B2 +:106CF000400251F8040B914243F8040BF9D1A36A06 +:106D0000403640354033A362D4E90A239A4202D385 +:106D10002046FFF795FF8AF31188BD42D8D289F348 +:106D20001188C9E730465A46FAF78CFFA36A5E44D9 +:106D30005D445B44A362E7E710B5029C0433017233 +:106D400003FB0421C460C0E906130023C0E90A3331 +:106D5000039B0363049BC0E90000C0E90422C0E96F +:106D60000842436310BD0000026A6FF00101C26077 +:106D7000426AC0E904220022C0E90A22FEF75CBC94 +:106D8000D0E904239A4201D1C26822B9184650F8CA +:106D9000043B0B60704700231846FAE7C3680021E4 +:106DA000C2690133C36043691344826993424361FA +:106DB00024BF436A4361FEF733BC000038B5044684 +:106DC0000D46E3683BB1236900201A1DA262E26907 +:106DD0001344E36207E0237A33B929462046FEF7DD +:106DE0000FFC0028EDDA38BD6FF00100FBE7000072 +:106DF00003691960C268013AC260C26913448269BA +:106E00009342036124BF436A036100238362036BDF +:106E100003B118477047000070B530230D46044693 +:106E2000114683F31188866A2EB9FFF7C7FF10B1A8 +:106E300086F3118870BDA36A1D70A36AE26A0133EC +:106E40009342A36204D3E16920460439FFF7D0FFDF +:106E5000002080F31188EDE72DE9F84F04460D4638 +:106E6000904699464FF0300A8AF311880026B346BF +:106E7000A76A4FB949462046FFF7A0FF20B187F324 +:106E800011883046BDE8F88FD4E90A073A1AA8EB12 +:106E90000607974228BF1746402F1BD905F140032C +:106EA00055F8042B9D4240F8042BF9D1A36A4036D3 +:106EB0004033A362D4E90A239A4204D3E16920460D +:106EC0000439FFF795FF8BF311884645D9D28AF331 +:106ED0001188CDE729463A46FAF7B4FEA36A3D4445 +:106EE0003E443B44A362E5E7D0E904239A4217D12C +:106EF000C3689BB1836A8BB1043B9B1A0ED01360AD +:106F0000C368013BC360C3691A4483699A42026142 +:106F100024BF436A0361002383620123184670473C +:106F20000023FBE700F01CB9014B586A704700BF13 +:106F3000000C0040034B002258631A610222DA6001 +:106F4000704700BF000C0040014B0022DA60704720 +:106F5000000C0040014B5863704700BF000C00401C +:106F6000FEE7000070B51B4B0025044686B0586054 +:106F70000E4685620163FDF79FFA04F11003A560D8 +:106F8000E562C4E904334FF0FF33C4E90044C4E9C7 +:106F90000635FFF7C9FF2B46024604F134012046AF +:106FA000C4E9082380230C4A2565FEF7DFFA012394 +:106FB0000A4AE06000920375684672680192B268FE +:106FC000CDE90223064BCDE90435FEF7F7FA06B00A +:106FD00070BD00BF58550020887A00088D7A0008DF +:106FE000616F0008024AD36A1843D062704700BF3D +:106FF000F05200204B6843608B688360CB68C360AD +:107000000B6943614B6903628B6943620B680360E0 +:107010007047000008B53A4B40F2FF713948D3F889 +:1070200088200A43C3F88820D3F8882022F4FF621E +:1070300022F00702C3F88820D3F88830324B1A6C4C +:107040000A431A649A6E0A439A66304A9B6E114646 +:10705000FFF7D0FF00F5806002F11C01FFF7CAFFC7 +:1070600000F5806002F13801FFF7C4FF00F5806091 +:1070700002F15401FFF7BEFF00F5806002F17001DC +:10708000FFF7B8FF00F5806002F18C01FFF7B2FF57 +:1070900000F5806002F1A801FFF7ACFF00F5806009 +:1070A00002F1C401FFF7A6FF00F5806002F1E001E4 +:1070B000FFF7A0FF00F5806002F1FC01FFF79AFFE7 +:1070C00002F58C7100F58060FFF794FF00F006F97F +:1070D0000F4BD3F8902242F00102C3F89022D3F86C +:1070E000942242F00102C3F894220522C3F89820AA +:1070F0004FF06052C3F89C20064AC3F8A02008BD98 +:10710000004402580000025800450258947A0008D2 +:1071100000ED00E01F00080308B500F0BDFAFEF71F +:10712000D9F90C4BDA6B42F04002DA635A6E22F066 +:1071300040025A665B6E084B1A6842F008021A60F9 +:107140001A6842F004021A60FEF740FFBDE80840EA +:10715000FEF75EBC00450258001802487047000068 +:107160000E4B9A6C42F008029A641A6F42F00802C1 +:107170001A670B4A1B6FD36B43F00803D363C72214 +:10718000084B9A624FF0FF32DA6200229A615A632A +:10719000DA605A6001225A611A607047004502584D +:1071A0000010005C000C0040094A08B51169D36862 +:1071B0000B40D9B29B076FEA0101116107D530235B +:1071C00083F31188FEF7ACF9002383F3118808BD1F +:1071D000000C0040044BDA6B0243DA635A6E104332 +:1071E00058665B6E704700BF004502583A4B4FF03F +:1071F000FF31D3F8802062F00042C3F88020D3F83A +:10720000802002F00042C3F88020D3F88020D3F819 +:107210008420C3F88410D3F884200022C3F884208B +:10722000D3F88400D86F40F0FF4040F4FF0040F4F2 +:10723000DF4040F07F00D867D86F20F0FF4020F497 +:10724000FF0020F4DF4020F07F00D867D86FD3F82C +:1072500088006FEA40506FEA5050C3F88800D3F8B6 +:107260008800C0F30A00C3F88800D3F88800D3F878 +:107270009000C3F89010D3F89000C3F89020D3F892 +:107280009000D3F89400C3F89410D3F89400C3F896 +:107290009420D3F89400D3F89800C3F89810D3F84A +:1072A0009800C3F89820D3F89800D3F88C00C3F85E +:1072B0008C10D3F88C00C3F88C20D3F88C00D3F852 +:1072C0009C00C3F89C10D3F89C10C3F89C20D3F802 +:1072D0009C3000F0B5B900BF0044025808B5012247 +:1072E000504BC3F80821504B5A6D42F002025A65C8 +:1072F000DA6F42F00202DA670422DB6F4B4BDA608E +:107300005A689104FCD54A4A1A6001229A60494A97 +:10731000DA6000221A614FF440429A61434B9A6945 +:107320009204FCD51A6842F480721A60424B1A6FBC +:1073300012F4407F04D04FF480321A6700221A679B +:107340001A6842F001021A603B4B1A685007FCD5DC +:1073500000221A611A6912F03802FBD1012119606A +:107360004FF0804159605A67344ADA62344A1A61F0 +:107370001A6842F480321A602F4B1A689103FCD5C8 +:107380001A6842F480521A601A689204FCD52D4A99 +:107390002D499A6200225A63196301F57C01DA6370 +:1073A00001F5E77199635A64284A1A64284ADA6237 +:1073B0001A6842F0A8521A601F4B1A6802F028524D +:1073C000B2F1285FF9D148229A614FF48862DA61FC +:1073D00040221A621F4ADA641F4A1A651F4A5A6518 +:1073E0001F4A9A6532231F4A1360136803F00F0384 +:1073F000022BFAD1104A136943F003031361136996 +:1074000003F03803182BFAD14FF00050FFF7E2FEDB +:107410004FF08040FFF7DEFE4FF00040BDE808402F +:10742000FFF7D8BE008000510045025800480258BE +:1074300000C000F004000001004402580000FF01F9 +:10744000008890083220600063020901470E050899 +:10745000DD0BBF0120000020000001100910E0003A +:1074600000010110002000524FF0B04208B5D2F8E0 +:10747000883003F00103C2F8883023B1044A13684E +:107480000BB150689847BDE80840FDF73DB800BF14 +:10749000007200204FF0B04208B5D2F8883003F0F7 +:1074A0000203C2F8883023B1044A93680BB1D06854 +:1074B0009847BDE80840FDF727B800BF00720020DC +:1074C0004FF0B04208B5D2F8883003F00403C2F898 +:1074D000883023B1044A13690BB150699847BDE85D +:1074E0000840FDF711B800BF007200204FF0B04215 +:1074F00008B5D2F8883003F00803C2F8883023B109 +:10750000044A93690BB1D0699847BDE80840FCF77D +:10751000FBBF00BF007200204FF0B04208B5D2F8A8 +:10752000883003F01003C2F8883023B1044A136A8C +:107530000BB1506A9847BDE80840FCF7E5BF00BFB3 +:10754000007200204FF0B04310B5D3F8884004F427 +:107550007872C3F88820A30604D5124A936A0BB147 +:10756000D06A9847600604D50E4A136B0BB1506B76 +:107570009847210604D50B4A936B0BB1D06B984703 +:10758000E20504D5074A136C0BB1506C9847A3056C +:1075900004D5044A936C0BB1D06C9847BDE81040F9 +:1075A000FCF7B2BF007200204FF0B04310B5D3F823 +:1075B000884004F47C42C3F88820620504D5164A4A +:1075C000136D0BB1506D9847230504D5124A936D86 +:1075D0000BB1D06D9847E00404D50F4A136E0BB180 +:1075E000506E9847A10404D50B4A936E0BB1D06E30 +:1075F0009847620404D5084A136F0BB1506F98473F +:10760000230404D5044A936F0BB1D06F9847BDE8AB +:107610001040FCF779BF00BF0072002008B5034896 +:10762000FDF722F8BDE80840FCF76EBF804E002051 +:1076300008B5FFF7B9FDBDE80840FCF765BF0000DD +:10764000062108B50846FDF795F806210720FDF745 +:1076500091F806210820FDF78DF806210920FDF795 +:1076600089F806210A20FDF785F806211720FDF785 +:1076700081F806212820FDF77DF809217A20FDF701 +:1076800079F807213220FDF775F80C215220BDE86A +:107690000840FDF76FB8000008B5FFF7A7FD00F040 +:1076A0000DF8FDF70FFAFDF7E7FBFDF7B9FAFFF765 +:1076B00055FDBDE80840FFF735BC00000023054A32 +:1076C00019460133102BC2E9001102F10802F8D16A +:1076D000704700BF007200200B460146184600F0BC +:1076E00003B8000000F00EB810B5054C13462CB1DD +:1076F0000A4601460220AFF3008010BD2046FCE799 +:1077000000000000024B01461868FEF777BB00BF7F +:107710006C22002010B501390244904201D10020B2 +:1077200005E0037811F8014FA34201D0181B10BDEA +:107730000130F2E72DE9F041A3B1C91A17780144ED +:10774000044603F1FF3C8C42204601D9002009E0A9 +:107750000578BD4204F10104F5D10CEB0405D618FF +:10776000A54201D1BDE8F08115F8018D16F801EDB3 +:10777000F045F5D0E7E70000034611F8012B03F8C8 +:10778000012B002AF9D170476F72672E6172647500 +:1077900070696C6F742E4375626550696C6F742DDF +:1077A00043414E4D6F64000053544D333248373FD0 +:1077B0003F3F0053544D3332483733782F373278B8 +:1077C0000053544D3332483734332F3735332F3746 +:1077D0003530000001105A000310590001205800F4 +:1077E0000320560040A2E4F1646891060041A3E53D +:1077F000F26569920700000043414E4644496661C4 +:1078000063653A204D6573736167652052414D2071 +:107810004F766572666C6F772100000042616420CC +:1078200043414E496661636520696E6465782E0048 +:1078300000000000000000009D2C000879250008D1 +:107840009533000871250008E9250008F92900088A +:1078500061270008B1250008B52500088D2500081E +:1078600075250008B929000899250008CD340008BD +:10787000A52500088D2900080096000000000000E2 +:1078800000000000000000000000000000000000F8 +:1078900000000000854A0008714A0008AD4A00084F +:1078A000994A0008A54A0008914A00087D4A000844 +:1078B000694A0008B94A0008000000009D4B000812 +:1078C000894B0008C54B0008B14B0008BD4B0008B0 +:1078D000A94B0008954B0008814B0008D14B0008CC +:1078E0000000000001000000000000006330000004 +:1078F000EC78000848530020585500204172647508 +:1079000050696C6F740025424F415244252D424C02 +:10791000002553455249414C25000000020000005B +:1079200000000000BD4D00082D4E00084000400042 +:10793000086E0020186E0020020000000000000009 +:107940000300000000000000754E00080000000069 +:1079500010000000286E0020000000000100000060 +:1079600000000000B070002001010200AD590008C5 +:10797000BD580008595900083D590008430000004F +:107980008479000809024300020100C032090400A2 +:10799000000102020100052400100105240100017C +:1079A000042402020524060001070582030800FFE3 +:1079B00009040100020A000000070501024000005E +:1079C000070581024000000012000000D079000885 +:1079D0001201100102000040091241570002010289 +:1079E000030100000403090425424F4152442500CD +:1079F00030313233343536373839414243444546E5 +:107A00000000000000000020000002000200000052 +:107A10000001003000000000080000000000002409 +:107A200000000800040000000004000000FC00004A +:107A30000200000000000430008000000800000088 +:107A400000000038000001000100000000000000FC +:107A5000D14F00088952000835530008400040000B +:107A6000E8710020E871002001000000F87100209A +:107A7000800000004001000008000000000100003C +:107A800000100000080000006D61696E0069646C00 +:107A9000650000000000802A00000000AAAAAAAA2F +:107AA00000000024FFFF00000000000000A00A000A +:107AB0000000000000000000AAAAAAAA000000001E +:107AC000FFFF0000000000000000000000000000B8 +:107AD00000000000AAAAAAAA00000000FFFF000000 +:107AE00000000000000000000A000000000000008C +:107AF000AAAAAAAA00000000FFFF00009900000047 +:107B0000000000000080020000000000AAAAAAAA4B +:107B100000400100FFFF00000000007007000000AF +:107B20000000000000000000AAAAAAAA00000000AD +:107B3000FFFF000000000000000000000500000042 +:107B400000000000A5AAAAAA00000000FCFF000097 +:107B50000000000000000000000000000000000025 +:107B6000AAAAAAAA00000000FFFF0000000000006F +:107B7000000000000000000000000000AAAAAAAA5D +:107B800000000000FFFF00000000000000000000F7 +:107B90000000000000000000AAAAAAAA000000003D +:107BA000FFFF0000000000000000000000000000D7 +:107BB00000000000AAAAAAAA00000000FFFF00001F +:107BC00000000000000000005887FF7F0100000057 +:107BD0003704000000000000000018000000000052 +:107BE000FE2A0100D2040000FF00000060550020C2 +:107BF000804E002000000000A877000883040000E9 +:107C0000B377000850040000C17700080096000018 +:107C100000000800960000000008000004000000BA +:107C2000E4790008000000000000000000000000EF +:107C30000000000000000000000000007022002092 +:107C40000000000000000000000000000000000034 +:107C50000000000000000000000000000000000024 +:107C60000000000000000000000000000000000014 +:107C70000000000000000000000000000000000004 +:107C800000000000000000000000000000000000F4 +:107C900000000000000000000000000000000000E4 +:00000001FF diff --git a/Tools/bootloaders/CubeRedPrimary_bl.bin b/Tools/bootloaders/CubeRedPrimary_bl.bin index 021141d534f04d..8070aaf1ad3780 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 08404078bec8f0..5f48f1dbe44db9 100644 --- a/Tools/bootloaders/CubeRedPrimary_bl.hex +++ b/Tools/bootloaders/CubeRedPrimary_bl.hex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diff --git a/Tools/bootloaders/CubeRedSecondary_bl.bin b/Tools/bootloaders/CubeRedSecondary_bl.bin index fc2c4f2751ca50..403e7e859e420b 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 c22d8e2ebe7774..6f4adbe5be9c81 100644 --- a/Tools/bootloaders/CubeRedSecondary_bl.hex +++ b/Tools/bootloaders/CubeRedSecondary_bl.hex @@ -1,21 +1,21 @@ :020000040800F2 :1000000000060020E1020008E3020008E302000805 :10001000E3020008E3020008E3020008E30200082C -:10002000E3020008E3020008E30200089920000848 +:10002000E3020008E3020008E3020008F1200008F0 :10003000E3020008E3020008E3020008E30200080C :10004000E3020008E3020008E3020008E3020008FC -:10005000E3020008E3020008652400089124000878 -:10006000BD240008E924000815250008E302000863 +:10005000E3020008E3020008BD240008E9240008C8 +:1000600015250008412500086D250008E302000859 :10007000E3020008E3020008E3020008E3020008CC :10008000E3020008E3020008E3020008E3020008BC -:10009000E3020008E3020008E3020008412500082B +:10009000E3020008E3020008E302000899250008D3 :1000A000E3020008E3020008E3020008E30200089C :1000B000E3020008E3020008E3020008E30200088C :1000C000E3020008E3020008E3020008E30200087C :1000D000E3020008E3020008E3020008E30200086C -:1000E000A5250008E3020008E3020008E302000877 +:1000E000FD250008E3020008E3020008E30200081F :1000F000E3020008E3020008E3020008E30200084C -:10010000E3020008E302000841260008E3020008B9 +:10010000E3020008E302000899260008E302000861 :10011000E3020008E3020008E3020008E30200082B :10012000E3020008E3020008E3020008E30200081B :10013000E3020008E3020008E3020008E30200080B @@ -23,7 +23,7 @@ :10015000E3020008E3020008E3020008E3020008EB :10016000E3020008E3020008E3020008E3020008DB :10017000E3020008E3020008E3020008E3020008CB -:10018000E3020008E3020008192600082D260008F3 +:10018000E3020008E3020008712600088526000843 :10019000E3020008E3020008E3020008E3020008AB :1001A000E3020008E3020008E3020008E30200089B :1001B000E3020008E3020008E3020008E30200088B @@ -45,49 +45,49 @@ :1002B000E3020008E3020008E3020008E30200088A :1002C000E3020008E3020008E3020008E30200087A :1002D000E3020008E3020008E3020008E30200086A -:1002E00002E000F000F8FEE772B6384880F30888B4 -:1002F000374880F3098837483749086040F20000E2 +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 :10030000CCF200004EF63471CEF200010860BFF36B :100310004F8FBFF36F8F40F20000C0F2F0004EF637 :100320008851CEF200010860BFF34F8FBFF36F8F8B :100330004FF00000E1EE100A4EF63C71CEF20001E3 -:100340000860062080F31488BFF36F8F01F086FDEC -:1003500001F028FD01F0FCFD4FF055301F491B4A0C -:1003600091423CBF41F8040BFAE71D49184A9142FB -:100370003CBF41F8040BFAE71A491B4A1B4B9A424F -:100380003EBF51F8040B42F8040BF8E7002018496F -:10039000184A91423CBF41F8040BFAE701F040FDD6 -:1003A00001F058FE144C154DAC4203DA54F8041B0E -:1003B0008847F9E700F042F8114C124DAC4203DADD -:1003C00054F8041B8847F9E701F028BD0006002017 -:1003D000002200200000000808ED00E000000020DE -:1003E00000060020F0280008002200203022002013 -:1003F00030220020702F0020E0020008E0020008F8 -:10040000E0020008E00200082DE9F04F2DED108A0F -:10041000C1F80CD0D0F80CD0BDEC108ABDE8F08F3C -:10042000002383F311882846A047002001F08CF9AF -:10043000FEE701F0FFF800DFFEE7000038B501F04D -:1004400071FC054601F0A4FC0446D0B90F4B9D4257 +:100340000860062080F31488BFF36F8F01F028FD4A +:1003500001F02AFE4FF055301F491B4A91423CBF25 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE701F040FD01F086FE96 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E701F028BD000600200022002040 +:1003D0000000000808ED00E00000002000060020FA +:1003E000582900080022002030220020302200205E +:1003F000702F0020E0020008E0020008E002000880 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F08CF9FEE701F072 +:10043000FFF800DFFEE7000038B500F0ADFB01F08B +:100440006FFC054601F0A2FC0446D0B90F4B9D425B :1004500019D001339D4242F2107512BF04460025A7 -:100460000124002001F068FC0CB100F077F800F0E6 -:1004700025FD00F0EDFB284600F0F0F800F06EF8E6 +:100460000124002001F066FC0CB100F077F800F0E8 +:1004700023FD00F0EFFB284600F0F0F800F06EF8E6 :10048000F9E70025EDE70546EBE700BF010007B0FF -:1004900008B500F0A9FBA0F120035842584108BD5F +:1004900008B500F0ABFBA0F120035842584108BD5D :1004A00007B541F21203022101A8ADF8043000F0B3 -:1004B000B9FB03B05DF804FB38B5302383F3118832 -:1004C000174803680BB101F0FDF90023154A4FF4FA -:1004D0007A71134801F0ECF9002383F31188124C70 +:1004B000BBFB03B05DF804FB38B5302383F3118830 +:1004C000174803680BB101F0FBF90023154A4FF4FC +:1004D0007A71134801F0EAF9002383F31188124C72 :1004E000236813B12368013B2360636813B1636819 :1004F000013B63600D4D2B7833B963687BB90220F3 -:1005000000F072FC322363602B78032B07D1636801 -:100510002BB9022000F068FC4FF47A73636038BD99 +:1005000000F070FC322363602B78032B07D1636803 +:100510002BB9022000F066FC4FF47A73636038BD9B :1005200030220020B9040008502300204822002077 :10053000084B187003280CD8DFE800F00805020803 -:10054000022000F047BC022000F03ABC024B00221F +:10054000022000F045BC022000F038BC024B002223 :100550005A6070474822002050230020F8B5394BDC :10056000394A1C46196801316BD004339342F9D1E2 :100570006268364B9A4264D9354B9B6803F100633D -:1005800003F500339A425CD2002000F087FB022082 +:1005800003F500339A425CD2002000F089FB022080 :10059000FFF7CEFF2F4B00219A6C99641A6F1967F1 :1005A0001A6FDA6CD9645A6F59675A6F1A6D1965E8 :1005B0009A6F99679B6F72B64FF0E023C3F8084DAE @@ -102,14 +102,14 @@ :100640002047F8BD0000020820000208FFFF010853 :10065000002200200045025800ED00E02DE9F04F97 :1006600093B0B44B2022FF2100900AA89D6800F0AF -:10067000CFFBB14A1378A3B90121B04811700360D0 -:10068000302383F3118803680BB101F01BF90023B9 -:10069000AB4A4FF47A71A94801F00AF9002383F3B9 +:10067000CDFBB14A1378A3B90121B04811700360D2 +:10068000302383F3118803680BB101F019F90023BB +:10069000AB4A4FF47A71A94801F008F9002383F3BB :1006A0001188009B13B1A74B009A1A60A64A1378D1 :1006B000032B03D000231370A24A53604FF0000AAB -:1006C000009CD3465646D146012000F083FB24B15E -:1006D0009C4B1B68002B00F02682002000F084FA5F -:1006E0000390039B002BF2DB012000F069FB039BCE +:1006C000009CD3465646D146012000F081FB24B160 +:1006D0009C4B1B68002B00F02682002000F086FA5D +:1006E0000390039B002BF2DB012000F067FB039BD0 :1006F000213B1F2BE8D801A252F823F07D07000808 :10070000A507000839080008C9060008C90600083E :10071000C9060008CB0800089B0A0008B5090008B4 @@ -121,540 +121,547 @@ :10077000C9060008C9060008390800080220FFF76A :1007800087FE002840F0F981009B022105A8BAF1FC :10079000000F08BF1C4641F21233ADF8143000F0D0 -:1007A00041FA91E74FF47A7000F01EFA071EEBDB76 +:1007A00043FA91E74FF47A7000F020FA071EEBDB72 :1007B0000220FFF76DFE0028E6D0013F052F00F272 :1007C000DE81DFE807F0030A0D101336052304214C -:1007D00005A8059300F026FA17E004215548F9E72B +:1007D00005A8059300F028FA17E004215548F9E729 :1007E00004215A48F6E704215948F3E74FF01C0862 -:1007F000404608F1040800F053FA0421059005A8CA -:1008000000F010FAB8F12C0FF2D101204FF00009DE -:1008100000FA07F747EA0B0B5FFA8BFB00F044FB8B +:1007F000404608F1040800F055FA0421059005A8C8 +:1008000000F012FAB8F12C0FF2D101204FF00009DC +:1008100000FA07F747EA0B0B5FFA8BFB00F042FB8D :1008200026B10BF00B030B2B08BF0024FFF738FE9B :100830004AE704214748CDE7002EA5D00BF00B0373 :100840000B2BA1D10220FFF723FE074600289BD0E7 -:100850000120002600F022FA0220FFF769FE5FFA6D -:1008600086F8404600F02AFA0446B0B103994046A3 -:100870000136A1F140025142514100F02FFA002807 +:100850000120002600F024FA0220FFF769FE5FFA6B +:1008600086F8404600F02CFA0446B0B103994046A1 +:100870000136A1F140025142514100F031FA002805 :10088000EDD1BA46044641F21213022105A83E46B4 -:10089000ADF8143000F0C6F916E725460120FFF741 -:1008A00047FE244B9B68AB4207D9284600F0F8F975 +:10089000ADF8143000F0C8F916E725460120FFF73F +:1008A00047FE244B9B68AB4207D9284600F0FAF973 :1008B000013040F067810435F3E70025224BBA464A :1008C0003E461D701F4B5D60A8E7002E3FF45CAFF5 :1008D0000BF00B030B2B7FF457AF0220FFF728FE22 -:1008E000322000F081F9B0F10008FFF64DAF18F0AA +:1008E000322000F083F9B0F10008FFF64DAF18F0A8 :1008F00003077FF449AF0F4A08EB05039268934260 :100900003FF642AFB8F5807F3FF73EAF124BB84598 -:10091000019323DD4FF47A7000F066F90390039A97 +:10091000019323DD4FF47A7000F068F90390039A95 :10092000002AFFF631AF039A0137019B03F8012B30 :10093000EDE700BF002200204C23002030220020E1 :10094000B90400085023002048220020042200207F :10095000082200200C2200204C220020C820FFF793 :1009600097FD074600283FF40FAF1F2D11D8C5F1A2 :1009700020020AAB25F0030084494245184428BFF1 -:100980004246019200F03AFA019AFF217F4800F0B6 -:100990003FFA4FEAA803C8F387027C49284601932F -:1009A00000F03EFA064600283FF46DAF019B05EBD0 +:100980004246019200F038FA019AFF217F4800F0B8 +:100990003DFA4FEAA803C8F387027C492846019331 +:1009A00000F03CFA064600283FF46DAF019B05EBD2 :1009B000830533E70220FFF76BFD00283FF4E4AE28 -:1009C00000F0AAF900283FF4DFAE0027B846704BCC +:1009C00000F0ACF900283FF4DFAE0027B846704BCA :1009D0009B68BB4218D91F2F11D80A9B01330ED038 :1009E00027F0030312AA134453F8203C0593404612 -:1009F000042205A9043700F089FA8046E7E7384663 -:100A000000F04EF90590F2E7CDF81480042105A816 -:100A100000F008F902E70023642104A8049300F021 -:100A2000F7F800287FF4B0AE0220FFF731FD002870 -:100A30003FF4AAAE049800F065F90590E6E70023BC -:100A4000642104A8049300F0E3F800287FF49CAE2E +:1009F000042205A9043700F087FA8046E7E7384665 +:100A000000F050F90590F2E7CDF81480042105A814 +:100A100000F00AF902E70023642104A8049300F01F +:100A2000F9F800287FF4B0AE0220FFF731FD00286E +:100A30003FF4AAAE049800F067F90590E6E70023BA +:100A4000642104A8049300F0E5F800287FF49CAE2C :100A50000220FFF71DFD00283FF496AE049800F039 -:100A600053F9EAE70220FFF713FD00283FF48CAEAC -:100A700000F062F9E1E70220FFF70AFD00283FF4E9 -:100A800083AE05A9142000F05DF907460421049007 -:100A900004A800F0C7F83946B9E7322000F0A4F8FE +:100A600055F9EAE70220FFF713FD00283FF48CAEAA +:100A700000F064F9E1E70220FFF70AFD00283FF4E7 +:100A800083AE05A9142000F05FF907460421049005 +:100A900004A800F0C9F83946B9E7322000F0A6F8FA :100AA000071EFFF671AEBB077FF46EAE384A07EB48 :100AB0000903926893423FF667AE0220FFF7E8FC15 :100AC00000283FF461AE27F003074F44B9453FF4D7 -:100AD000A5AE484609F1040900F0E2F804210590AA -:100AE00005A800F09FF8F1E74FF47A70FFF7D0FC0B -:100AF00000283FF449AE00F00FF9002844D00A9BCB -:100B000001330BD008220AA9002000F089F900283F -:100B10003AD02022FF210AA800F07AF9FFF7C0FCA2 -:100B20001C4800F017FE13B0BDE8F08F002E3FF414 +:100AD000A5AE484609F1040900F0E4F804210590A8 +:100AE00005A800F0A1F8F1E74FF47A70FFF7D0FC09 +:100AF00000283FF449AE00F011F9002844D00A9BC9 +:100B000001330BD008220AA9002000F087F9002841 +:100B10003AD02022FF210AA800F078F9FFF7C0FCA4 +:100B20001C4800F015FE13B0BDE8F08F002E3FF416 :100B30002BAE0BF00B030B2B7FF426AE00236421AE -:100B400005A8059300F064F8074600287FF41CAE62 +:100B400005A8059300F066F8074600287FF41CAE60 :100B50000220FFF79DFC804600283FF415AEFFF70A -:100B60009FFC41F2883000F0F5FD059800F0B4F9E3 -:100B700046463C4600F098F9A6E506464EE64FF09C +:100B60009FFC41F2883000F0F3FD059800F0B2F9E7 +:100B700046463C4600F096F9A6E506464EE64FF09E :100B8000000901E6BA467EE637467CE64C220020A4 -:100B900000220020A0860100104B70B51B780C4687 -:100BA0000133DBB2012B12D80D4B1D684FF47A7361 -:100BB0002968A2FB033222460E6A01462846B04746 -:100BC000844204D1074B002201201A7070BD4FF4FB -:100BD000FA7000F0BFFD0020F8E700BF10220020EF -:100BE000142200209C230020002307B50246012187 -:100BF0000DF107008DF80730FFF7CEFF20B19DF80B -:100C0000070003B05DF804FB4FF0FF30F9E7000088 -:100C10000A46042108B5FFF7BFFF80F00100C0B20B -:100C2000404208BD074B0A4630B41978064B53F8CA -:100C30002140014623682046DD69044BAC4630BCA8 -:100C4000604700BF9C23002014220020A0860100E2 -:100C500070B5104C0025104E00F03CFF208030682D -:100C6000238883420CD800252088013800F02EFF0D -:100C700023880544013BB5F5802F2380F4D370BD54 -:100C800000F024FF336805440133B5F5003F3360BD -:100C9000E5D3E8E79E2300205823002000F0F8BFAA -:100CA00000F1006000F500300068704700F100605E -:100CB000920000F5003000F06FBF0000054B1A688D -:100CC000054B1B889B1A834202D9104400F0FEBEDC -:100CD00000207047582300209E23002038B504468A -:100CE000074D29B128682044BDE8384000F006BF10 -:100CF0002868204400F0F0FE0028F3D038BD00BF83 -:100D0000582300200020704700F1FF5000F58F109D -:100D1000D0F8000870470000064991F8243033B13C -:100D200000230822086A81F82430FFF7BFBF0120A2 -:100D3000704700BF5C230020014B1868704700BF5C -:100D40000010005C1B4B0246F0B518681A4BC0F34C -:100D50000B06000C1F885C68BE4293F9085003D054 -:100D60009F89BE4203D10C335C6893F90850042676 -:100D7000124B1F880433874208BF13F9025C013EFF -:100D8000F7D1013A013C0B460A44934207D214F9C9 -:100D9000016F581C2EB1034600F8016CF5E71846A8 -:100DA00005E02C2482421C7001D9981C5D70401A09 -:100DB000F0BD00BF0010005C182200205027000882 -:100DC000022803D1024B4FF080629A61704700BF46 -:100DD000000C0258022803D1024B4FF480629A6142 -:100DE000704700BF000C0258022804D1024A536920 -:100DF00083F4806353617047000C0258002310B5E0 -:100E0000934203D0CC5CC4540133F9E710BD000019 -:100E100002440346934202D003F8011BFAE77047ED -:100E20002DE9F8431F4D14460746884695F82420BF -:100E300052BBDFF870909CB395F824302BB9202278 -:100E4000FF2148462F62FFF7E3FF95F82400414653 -:100E5000C0F1080205EB8000A24228BF2246D6B2AC -:100E60009200FFF7CBFF95F82430A41B17441E44D3 -:100E70009044E4B2F6B2082E85F82460DBD1FFF787 -:100E80004BFF0028D7D108E02B6A03EB8203834293 -:100E9000CFD0FFF741FF0028CBD10020BDE8F88379 -:100EA0000120FBE75C230020024B1A78024B1A70EA -:100EB000704700BF9C23002010220020034B0449F0 -:100EC0000B60044B186800F01BBB00BF80841E0041 -:100ED0008423002014220020094B1822002110B581 -:100EE00004461846FFF794FF064A074B014612785E -:100EF000046053F82200BDE8104000F001BB00BFC1 -:100F0000842300209C2300201422002030B50A44B2 -:100F1000084D91420DD011F8013B5840082340F391 -:100F20000004013B2C4013F0FF0384EA5000F6D18B -:100F3000EFE730BD2083B8ED0268436811430160DC -:100F400003B1184770470000024A136843F0C0031A -:100F50001360704700780040024A136843F0C003F2 -:100F600013607047007C004037B51A4C1A4D20467C -:100F700000F0BAFA04F11400009400234FF4007258 -:100F8000164900F077F94FF40072154904F1380062 -:100F90000094144B00F0F0F9134BC4E91735134CCF -:100FA000204600F0A1FA04F1140000234FF400726F -:100FB0000F49009400F05EF90E4B4FF400720E4999 -:100FC00004F13800009400F0D7F90C4BC4E9173550 -:100FD00003B030BDA023002000E1F50578240020F7 -:100FE00078280020490F0008007800400C240020D9 -:100FF00078260020590F0008782A0020007C004045 -:10100000037C30B5274C002918BF0C46012B0CD1AE -:10101000254B984236D1254B9A6C42F080429A6417 -:101020001A6F42F080421A671B6F2268036EC16D0F -:1010300003EB52038466B3FBF2F36268150442BF0C -:1010400023F0070503F0070343EA4503CB60A368D9 -:1010500043F040034B60E36843F001038B6042F4CC -:10106000967343F001030B604FF0FF330B625105A1 -:1010700005D512F0102211D0B2F1805F10D080F8A7 -:10108000643030BD0A4B9842CFD1084B9A6C42F085 -:1010900000429A641A6F42F00042C4E77F23EEE7F1 -:1010A0003F23ECE760270008A023002000450258FA -:1010B0000C2400202DE9F047C66D05463768F46919 -:1010C000210734621AD014F0080118BF4FF4807160 -:1010D000E20748BF41F02001A3074FF0300348BFAB -:1010E00041F04001600748BF41F0800183F311885F -:1010F000281DFFF721FF002383F31188E2050AD59D -:10110000302383F311884FF48061281DFFF714FF0B -:10111000002383F311884FF030094FF0000A14F0D8 -:10112000200838D13B0616D54FF0300905F1380AB2 -:10113000200610D589F31188504600F051F9002897 -:1011400036DA0821281DFFF7F7FE27F08003336009 -:10115000002383F31188790614D5620612D5302353 -:1011600083F31188D5E913239A4208D12B6C33B14C -:1011700027F040071021281DFFF7DEFE376000230F -:1011800083F31188E30618D5AA6E1369ABB15069D1 -:10119000BDE8F047184789F31188736A284695F827 -:1011A0006410194000F0BAF98AF31188F469B6E7BF -:1011B000B06288F31188F469BAE7BDE8F0870000EF -:1011C000F8B51546826804460B46AA4200D28568E7 -:1011D000A1692669761AB5420BD218462A46FFF74E -:1011E0000DFEA3692B44A3612846A3685B1BA36083 -:1011F000F8BD0CD9AF1B18463246FFF7FFFD3A4643 -:10120000E1683044FFF7FAFDE3683B44EBE718463A -:101210002A46FFF7F3FDE368E5E7000083689342A1 -:10122000F7B50446154600D28568D4E90460361A3D -:10123000B5420BD22A46FFF7E1FD63692B44636197 -:101240002846A3685B1BA36003B0F0BD0DD93246EE -:10125000AF1B0191FFF7D2FD01993A46E068314496 -:10126000FFF7CCFDE3683B44E9E72A46FFF7C6FDFC -:10127000E368E4E710B50A440024C361029B84607C -:10128000C16002610362C0E90000C0E9051110BD40 -:1012900008B5D0E90532934201D1826882B98268EB -:1012A000013282605A1C426119700021D0E9043277 -:1012B0009A4224BFC368436100F068FA002008BD69 -:1012C0004FF0FF30FBE7000070B5302304460E46B8 -:1012D00083F31188A568A5B1A368A269013BA36047 -:1012E000531CA36115782269934224BFE368A3616C -:1012F000E3690BB120469847002383F31188284601 -:1013000007E03146204600F031FA0028E2DA85F3A2 -:10131000118870BD2DE9F74F04460E4617469846D2 -:10132000D0F81C904FF0300A8AF311884FF0000B70 -:10133000154665B12A4631462046FFF741FF034670 -:1013400060B94146204600F011FA0028F1D0002390 -:1013500083F31188781B03B0BDE8F08FB9F1000F5B -:1013600003D001902046C847019B8BF31188ED1AEA -:101370001E448AF31188DCE7C160C361009B826070 -:101380000362C0E905111144C0E900000161704722 -:10139000F8B504460D461646302383F31188A76836 -:1013A000A7B1A368013BA36063695A1C62611D7009 -:1013B000D4E904329A4224BFE3686361E3690BB164 -:1013C00020469847002080F3118807E031462046E8 -:1013D00000F0CCF90028E2DA87F31188F8BD0000AC -:1013E000D0E9052310B59A4201D182687AB98268A2 -:1013F0000021013282605A1C82611C7803699A4282 -:1014000024BFC368836100F0C1F9204610BD4FF0CE -:10141000FF30FBE72DE9F74F04460E461746984686 -:10142000D0F81C904FF0300A8AF311884FF0000B6F -:10143000154665B12A4631462046FFF7EFFE0346C2 -:1014400060B94146204600F091F90028F1D0002310 -:1014500083F31188781B03B0BDE8F08FB9F1000F5A -:1014600003D001902046C847019B8BF31188ED1AE9 -:101470001E448AF31188DCE7026843681143016067 -:1014800003B11847704700001430FFF743BF000056 -:101490004FF0FF331430FFF73DBF00003830FFF747 -:1014A000B9BF00004FF0FF333830FFF7B3BF000083 -:1014B0001430FFF709BF00004FF0FF311430FFF781 -:1014C00003BF00003830FFF763BF00004FF0FF326A -:1014D0003830FFF75DBF0000012914BF6FF0130023 -:1014E00000207047FFF740BD044B036000234360BA -:1014F000C0E9023301230374704700BF7827000856 -:1015000010B53023044683F31188FFF779FD0223D9 -:101510000020237480F3118810BD000038B5C36922 -:1015200004460D461BB904210844FFF7A5FF2946D0 -:1015300004F11400FFF7ACFE002806DA201D4FF47A -:101540000061BDE83840FFF797BF38BD00238268CF -:10155000037503691B6899689142FBD25A6803605E -:101560004260106058607047002382680375036909 -:101570001B6899689142FBD85A680360426010600A -:101580005860704708B50846302383F311880B7DF7 -:10159000032B05D0042B0DD02BB983F3118808BD84 -:1015A0008B6900221A604FF0FF338361FFF7CEFF93 -:1015B0000023F2E7D1E9003213605A60F3E700003C -:1015C000FFF7C4BF054BD9680875186802685360F7 -:1015D0001A600122D8600275FEF716BF782C002031 -:1015E0000C4B30B5DD684B1C87B004460FD02B4642 -:1015F000094A684600F05CF92046FFF7E3FF009BCC -:1016000013B1684600F05EF9A86907B030BDFFF776 -:10161000D9FFF9E7782C002085150008044B1A68DB -:10162000DB6890689B68984294BF00200120704757 -:10163000782C0020084B10B51C68D86822685360CD -:101640001A600122DC602275FFF78EFF01462046FA -:10165000BDE81040FEF7D8BE782C0020044B1A6875 -:10166000DB6892689B689A4201D9FFF7E3BF704735 -:10167000782C002038B5074C01230025064907487F -:101680002370656000F00CFC0223237085F3118841 -:1016900038BD00BFE02E0020A4270008782C0020D1 -:1016A00000F046B9EFF3118020B9EFF30583302243 -:1016B00082F311887047000010B530B9EFF305844C -:1016C000C4F3080414B180F3118810BDFFF7C6FFFE -:1016D00084F31188F9E700008B6002230861084653 -:1016E0008B8270478368A3F1840243F8142C02694B -:1016F00043F8442C426943F8402C094A43F8242C0F -:10170000C268A3F1200043F8182C022203F80C2C25 -:10171000002203F80B2C034A43F8102C704700BF3B -:1017200021040008782C002008B5FFF7DBFFBDE896 -:101730000840FFF745BF0000024BDB6898610F20AF -:10174000FFF740BF782C0020302383F31188FFF788 -:10175000F3BF000008B50146302383F31188082049 -:10176000FFF73EFF002383F3118808BD064BDB68BB -:1017700039B1426818605A60136043600420FFF773 -:101780002FBF4FF0FF307047782C0020036898423D -:1017900006D01A680260506018469961FFF710BFC2 -:1017A00070470000036810B59C68A2420CD85C68C2 -:1017B0008A600B604C602160596099688A1A9A604F -:1017C0004FF0FF33836010BD121B1B68ECE7000075 -:1017D0000A2938BF0A2170B504460D460A26601949 -:1017E00000F056FB00F03EFB041BA54203D8751C1D -:1017F00004462E46F3E70A2E04D90120BDE87040C6 -:1018000000F08EBB70BD0000F8B5144B0D460A2ADF -:101810004FF00A07D96103F11001826038BF0A2234 -:10182000416019691446016048601861A81800F009 -:101830001FFB00F017FB431B0646A34206D37C1C8C -:1018400028192746354600F023FBF2E70A2F04D972 -:101850000120BDE8F84000F063BBF8BD782C002003 -:10186000F8B506460D4600F0FDFA0F4A134653F848 -:10187000107F9F4206D12A4601463046BDE8F84017 -:10188000FFF7C2BFD169BB68441A2C1928BF2C4688 -:10189000A34202D92946FFF79BFF2246314603485F -:1018A000BDE8F840FFF77EBF782C0020882C002090 -:1018B000C0E90323002310B45DF8044B4361FFF734 -:1018C000CFBF000010B5194C236998420DD0816834 -:1018D000D0E9003213605A609A680A449A60002383 -:1018E00003604FF0FF33A36110BD0268234643F845 -:1018F000102F53600022026022699A4203D1BDE892 -:10190000104000F0BFBA936881680B44936000F008 -:10191000A9FA2269E1699268441AA242E4D9114401 -:10192000BDE81040091AFFF753BF00BF782C002014 -:101930002DE9F047DFF8BC8008F110072C4ED8F8ED -:10194000105000F08FFAD8F81C40AA68031B9A4286 -:101950003ED814444FF00009D5E90032C8F81C40C5 -:1019600013605A60C5F80090D8F81030B34201D126 -:1019700000F088FA89F31188D5E9033128469847A1 -:10198000302383F311886B69002BD8D000F06AFAFA -:101990006A69A0EB040982464A450DD2022000F094 -:1019A000BFFA0022D8F81030B34208D15146284679 -:1019B000BDE8F047FFF728BF121A2244F2E712EB06 -:1019C00009092946384638BF4A46FFF7EBFEB5E716 -:1019D000D8F81030B34208D01444C8F81C00211ABB -:1019E000A960BDE8F047FFF7F3BEBDE8F08700BF90 -:1019F000882C0020782C002000207047FEE7000093 -:101A0000704700004FF0FF3070470000BFF34F8F6A -:101A1000044B1A695107FCD1D3F810215207F8D1B1 -:101A2000704700BF0020005208B50D4B1B78ABB9C2 -:101A3000FFF7ECFF0B4BDA68D10704D50A4A5A606E -:101A400002F188325A60D3F80C21D20706D5064A33 -:101A5000C3F8042102F18832C3F8042108BD00BF95 -:101A6000E82E0020002000522301674508B5114BE5 -:101A70001B78F3B9104B1A69510703D5DA6842F0A5 -:101A80004002DA60D3F81021520705D5D3F80C21B3 -:101A900042F04002C3F80C21FFF7B8FF064BDA68AA -:101AA00042F00102DA60D3F80C2142F00102C3F8DF -:101AB0000C2108BDE82E0020002000520F289ABFFC -:101AC00000F5806040040020704700004FF40030B3 -:101AD00070470000102070470F2808B50BD8FFF79B -:101AE000EDFF00F500330268013204D10430834277 -:101AF000F9D1012008BD0020FCE700000F2870B5D7 -:101B0000054645D8FFF7CEFD224CFFF77FFF06467E -:101B1000FFF78AFF4FF0FF33072D6361C4F81431DC -:101B200020D82361FFF772FF2B0243F02403E36008 -:101B3000E36843F08003E36023695A07FCD4284636 -:101B4000FFF764FF4FF40031FFF7B8FF00F002F930 -:101B50003046FFF78BFFFFF7AFFD2846BDE870402A -:101B6000FFF7BABFC4F81031FFF750FFA5F1080323 -:101B70001B0243F02403C4F80C31D4F80C3143F0B9 -:101B80008003C4F80C31D4F810315B07FBD4D6E7DE -:101B9000002070BD002000522DE9F84F40EA0203FA -:101BA00005460C461746D80602D00020BDE8F88F3F -:101BB00027F01F07DFF8D4B0FFF736FF2744BC42F9 -:101BC00003D10120FFF752FFF0E7202229462046EB -:101BD00000F0A0FD10B920352034F0E72B4605F1C8 -:101BE00020021E68711CE0D104339A42F9D1FFF73C -:101BF00059FD05F17843234AB3F5801F224B28BFD6 -:101C00009A4603F1040338BF9046A2F1080228BFA8 -:101C10009846A3F108033ABF9146DA469946FFF782 -:101C2000F5FEC8F80060A5EB040CD9F8002004F11B -:101C30001C0142F00202C9F80020221FDAF80060FD -:101C400016F00506FAD152F8043F8A424CF80230E9 -:101C5000F4D1BFF34F8FFFF7D9FE4FF0FF32C8F832 -:101C60000020D9F8002022F00202C9F80020FFF776 -:101C700023FD20222146284600F04CFD0028AAD052 -:101C800030469FE7142000521021005210200052CD -:101C900010B5084C237828B11BB9FFF7C5FE012306 -:101CA000237010BD002BFCD02070BDE81040FFF762 -:101CB000DDBE00BFE82E00200244074BD2B210B5B3 -:101CC000904200D110BD441C00B253F8200041F8EE -:101CD000040BE0B2F4E700BF504000580E4B30B5A3 -:101CE0001C6F240405D41C6F1C671C6F44F4004453 -:101CF0001C670A4C02442368D2B243F48073236009 -:101D0000074B904200D130BD441C51F8045B00B237 -:101D100043F82050E0B2F4E700440258004802586B -:101D20005040005807B5012201A90020FFF7C4FF69 -:101D3000019803B05DF804FB13B50446FFF7F2FF0A -:101D4000A04205D0012201A900200194FFF7C6FF9F -:101D500002B010BD0144BFF34F8F064B884204D33D -:101D6000BFF34F8FBFF36F8F7047C3F85C02203013 -:101D7000F4E700BF00ED00E0034B1A681AB9034A0C -:101D8000D2F8D0241A607047EC2E00200040025890 -:101D900008B5FFF7F1FF024B1868C0F3806008BD7B -:101DA000EC2E002070B5BFF34F8FBFF36F8F1A4A30 -:101DB0000021C2F85012BFF34F8FBFF36F8F5369EA -:101DC00043F400335361BFF34F8FBFF36F8FC2F8FB -:101DD0008410BFF34F8FD2F8803043F6E074C3F322 -:101DE000C900C3F34E335B0103EA0406014646EA29 -:101DF00081750139C2F86052F9D2203B13F1200FEE -:101E0000F2D1BFF34F8F536943F480335361BFF373 -:101E10004F8FBFF36F8F70BD00ED00E0FEE7000055 -:101E20000A4B0B480B4A90420BD30B4BC11EDA1CDA -:101E3000121A22F003028B4238BF00220021FEF763 -:101E4000E7BF53F8041B40F8041BECE72029000807 -:101E5000702F0020702F0020702F0020704700008E -:101E600000F07CB9014B586A704700BF000C00407D -:101E7000034B002258631A610222DA60704700BFE8 -:101E8000000C0040014B0022DA607047000C00405B -:101E9000014B5863704700BF000C0040FEE7000094 -:101EA00070B51B4B0025044686B058600E4685620F -:101EB000016300F001F904F11003A560E562C4E9D3 -:101EC00004334FF0FF33C4E90044C4E90635FFF79B -:101ED000C9FF2B46024604F134012046C4E9082319 -:101EE00080230C4A2565FFF7F7FB01230A4AE060CF -:101EF00000920375684672680192B268CDE90223C8 -:101F0000064BCDE90435FFF70FFC06B070BD00BFEE -:101F1000E02E0020B0270008B52700089D1E00080D -:101F2000024AD36A1843D062704700BF782C002061 -:101F30004B6843608B688360CB68C3600B69436107 -:101F40004B6903628B6943620B6803607047000052 -:101F500008B53A4B40F2FF713948D3F888200A435C -:101F6000C3F88820D3F8882022F4FF6222F0070209 -:101F7000C3F88820D3F88830324B1A6C0A431A64AD -:101F80009A6E0A439A66304A9B6E1146FFF7D0FF5D -:101F900000F5806002F11C01FFF7CAFF00F58060C8 -:101FA00002F13801FFF7C4FF00F5806002F154012F -:101FB000FFF7BEFF00F5806002F17001FFF7B8FF88 -:101FC00000F5806002F18C01FFF7B2FF00F5806040 -:101FD00002F1A801FFF7ACFF00F5806002F1C40137 -:101FE000FFF7A6FF00F5806002F1E001FFF7A0FF18 -:101FF00000F5806002F1FC01FFF79AFF02F58C7199 -:1020000000F58060FFF794FF00F066F90F4BD3F8FE -:10201000902242F00102C3F89022D3F8942242F0B9 -:102020000102C3F894220522C3F898204FF06052B1 -:10203000C3F89C20064AC3F8A02008BD00440258FB -:102040000000025800450258BC27000800ED00E0DF -:102050001F00080308B500F041FBFFF70BFB0B4B1B -:10206000DA6B42F04002DA635A6E22F040025A669E -:102070005B6E074B1A6842F008021A601A6842F059 -:1020800004021A60BDE80840FFF776BE004502581A -:102090000018024870470000EFF3098305496833D0 -:1020A0004A6B22F001024A6383F30988002383F319 -:1020B0001188704700EF00E0302080F3118862B68D -:1020C0000D4B0E4AD96821F4E0610904090C0A435A -:1020D0000B49DA60D3F8FC2042F08072C3F8FC2090 -:1020E000084AC2F8B01F116841F0010111602022B6 -:1020F000DA7783F82200704700ED00E00003FA056C -:1021000055CEACC5001000E0302310B583F3118824 -:102110000E4B5B6813F4006314D0F1EE103AEFF34A -:1021200009844FF08073683CE361094BDB6B2366E5 -:1021300084F30988FFF772FA10B1064BA36110BD52 -:10214000054BFBE783F31188F9E700BF00ED00E0E2 -:1021500000EF00E033040008360400080E4B9A6CD0 -:1021600042F008029A641A6F42F008021A670B4A9A -:102170001B6FD36B43F00803D363C722084B9A62EB -:102180004FF0FF32DA6200229A615A63DA605A60D5 -:1021900001225A611A607047004502580010005C25 -:1021A000000C0040094A08B51169D3680B40D9B248 -:1021B0009B076FEA0101116107D5302383F3118872 -:1021C000FFF76EFA002383F3118808BD000C00406E -:1021D000044BDA6B0243DA635A6E104358665B6E47 -:1021E000704700BF004502583A4B4FF0FF31D3F81B -:1021F000802062F00042C3F88020D3F8802002F0F3 -:102200000042C3F88020D3F88020D3F88420C3F89C -:102210008410D3F884200022C3F88420D3F88400EB -:10222000D86F40F0FF4040F4FF0040F4DF4040F042 -:102230007F00D867D86F20F0FF4020F4FF0020F423 -:10224000DF4020F07F00D867D86FD3F888006FEAAE -:1022500040506FEA5050C3F88800D3F88800C0F3AC -:102260000A00C3F88800D3F88800D3F89000C3F8B8 -:102270009010D3F89000C3F89020D3F89000D3F8D2 -:102280009400C3F89410D3F89400C3F89420D3F8C2 -:102290009400D3F89800C3F89810D3F89800C3F8C6 -:1022A0009820D3F89800D3F88C00C3F88C10D3F89A -:1022B0008C00C3F88C20D3F88C00D3F89C00C3F8B2 -:1022C0009C10D3F89C10C3F89C20D3F89C3000F0ED -:1022D000BFB900BF0044025808B50122504BC3F8F3 -:1022E0000821504B5A6D42F002025A65DA6F42F0F3 -:1022F0000202DA670422DB6F4B4BDA605A68910402 -:10230000FCD54A4A1A6001229A60494ADA600022E2 -:102310001A614FF440429A61434B9A699204FCD58A -:102320001A6842F480721A60424B1A6F12F4407FAE -:1023300004D04FF480321A6700221A671A6842F0FC -:1023400001021A603B4B1A685007FCD500221A6143 -:102350001A6912F03802FBD1012119604FF0804157 -:1023600059605A67344ADA62344A1A611A6842F488 -:1023700080321A602F4B1A689103FCD51A6842F418 -:1023800080521A601A689204FCD52D4A2D499A622F -:1023900000225A63196301F57C01DA6301F5E771E4 -:1023A00099635A64284A1A64284ADA621A6842F021 -:1023B000A8521A601F4B1A6802F02852B2F1285F27 -:1023C000F9D148229A614FF48862DA6140221A6298 -:1023D0001F4ADA641F4A1A651F4A5A651F4A9A65DE -:1023E00032231F4A1360136803F00F03022BFAD144 -:1023F000104A136943F003031361136903F03803B0 -:10240000182BFAD14FF00050FFF7E2FE4FF080405A -:10241000FFF7DEFE4FF00040BDE80840FFF7D8BEF2 -:1024200000800051004502580048025800C000F0EA -:1024300004000001004402580000FF0100889008D9 -:102440003220600063020901470E0508DD0BBF0161 -:1024500020000020000001100910E0000001011020 -:10246000002000524FF0B04208B5D2F8883003F097 -:102470000103C2F8883023B1044A13680BB15068D5 -:102480009847BDE80840FFF73FBE00BFF02E002090 -:102490004FF0B04208B5D2F8883003F00203C2F81A -:1024A000883023B1044A93680BB1D0689847BDE8DF -:1024B0000840FFF729BE00BFF02E00204FF0B042C9 -:1024C00008B5D2F8883003F00403C2F8883023B18D -:1024D000044A13690BB150699847BDE80840FFF7FB -:1024E00013BE00BFF02E00204FF0B04208B5D2F866 -:1024F000883003F00803C2F8883023B1044A936996 -:102500000BB1D0699847BDE80840FFF7FDBD00BF9B +: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 -:102520001003C2F8883023B1044A136A0BB1506A11 -:102530009847BDE80840FFF7E7BD00BFF02E002038 -:102540004FF0B04310B5D3F8884004F47872C3F864 -:102550008820A30604D5124A936A0BB1D06A984723 -:10256000600604D50E4A136B0BB1506B98472106D9 -:1025700004D50B4A936B0BB1D06B9847E20504D599 -:10258000074A136C0BB1506C9847A30504D5044A55 -:10259000936C0BB1D06C9847BDE81040FFF7B4BD09 -:1025A000F02E00204FF0B04310B5D3F8884004F46B -:1025B0007C42C3F88820620504D5164A136D0BB11E -:1025C000506D9847230504D5124A936D0BB1D06D19 -:1025D0009847E00404D50F4A136E0BB1506E98472C -:1025E000A10404D50B4A936E0BB1D06E98476204D8 -:1025F00004D5084A136F0BB1506F9847230404D5D4 -:10260000044A936F0BB1D06F9847BDE81040FFF7B5 -:102610007BBD00BFF02E002008B50348FEF74AFD41 -:10262000BDE80840FFF770BDA023002008B50348AF -:10263000FEF740FDBDE80840FFF766BD0C24002012 -:1026400008B5FFF7AFFDBDE80840FFF75DBD00002E -:10265000062108B5084600F02BF80621072000F0F7 -:1026600027F80621082000F023F80621092000F0B1 -:102670001FF806210A2000F01BF80621172000F0A1 -:1026800017F80621282000F013F809217A2000F01D -:102690000FF80721322000F00BF80C21522000F037 -:1026A00007F80C215320BDE8084000F001B80000F5 -:1026B000090100F16043012203F56143C9B283F8C7 -:1026C000001300F01F039A4043099B0003F160438D -:1026D00003F56143C3F880211A60704708B5FFF71E -:1026E00083FD00F009F8FEF7FDFEFFF7D3FCBDE81F -:1026F0000840FFF7B5BB00000023054A1946013327 -:10270000102BC2E9001102F10802F8D1704700BF96 -:10271000F02E002010B501390244904201D1002072 -:1027200005E0037811F8014FA34201D0181B10BD3A -:102730000130F2E753544D333248373F3F3F0053A7 -:10274000544D3332483734332F37353300000000CF -:1027500001105A00031059000120580003205600B0 -:1027600000960000000000000000000000000000D3 -:10277000000000000000000000000000A514000898 -:1027800091140008CD140008B9140008C5140008FD -:10279000B11400089D14000889140008D914000819 -:1027A00063300000A0270008D02C0020E02E00207D -:1027B0006D61696E0069646C6500000000000028AE -:1027C00000000000AAAAAAAA00000024FFFF00003F +: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 -:1027E000AAAAAAAA00000000FFFF00000000000043 -:1027F000000000000000000000000000AAAAAAAA31 -:1028000000000000FFFF00000000000000000000CA -:102810000000100000000000AAAAAAAA0000000000 -:10282000FFFF000000000000000000000A8002001E -:1028300000000000AAAAAAAA05400100FFFF0000AC -:102840008800007007000000000000000000000089 -:10285000AAAAAAAA00000000FFFF000000000000D2 -:10286000000000000000000000000000AAAAAAAAC0 -:1028700000000000FFFF000000000000000000005A -:102880000000000000000000AAAAAAAA00000000A0 -:10289000FFFF00000000000000000000000000003A -:1028A00000000000AAAAAAAA00000000FFFF000082 -:1028B0000000000000000000000000000000000018 -:1028C000AAAAAAAA00000000FFFF00000000000062 -:1028D000000000000000000000000000AAAAAAAA50 -:1028E00000000000FFFF00000000000000000000EA -:1028F0002E0400000000000000001A00000000008C -:10290000FF000000A0230020000000003427000882 -:102910003F000000500400003F2700083F00000077 +: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 :00000001FF diff --git a/Tools/bootloaders/FlywooF405Pro_bl.bin b/Tools/bootloaders/FlywooF405Pro_bl.bin new file mode 100644 index 00000000000000..eb3600056e395c Binary files /dev/null and b/Tools/bootloaders/FlywooF405Pro_bl.bin differ diff --git a/Tools/bootloaders/FlywooF405Pro_bl.hex b/Tools/bootloaders/FlywooF405Pro_bl.hex new file mode 100644 index 00000000000000..88324bb106193d --- /dev/null +++ b/Tools/bootloaders/FlywooF405Pro_bl.hex @@ -0,0 +1,898 @@ +:020000040800F2 +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E3010008B92F00081C +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E301000861320008893200086A +:10006000B1320008D932000801330008E30100086A +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E30100082933000838 +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B000FD330008E3010008E3010008E301000844 +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E0008D330008E3010008E3010008E301000884 +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E30100086D2700084F +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F01F056FF1B +:1002500002F050FE4FF055301F491B4A91423CBFFF +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE701F034FF02F07EFEA8 +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E701F01CBF00060020002200204B +:1002D0000000000808ED00E00000002000060020FB +:1002E000C0370008002200204022002040220020C9 +:1002F000602E0020E0010008E0010008E001000895 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F084FAFEE701F07A +:10033000EDF900DFFEE7000038B500F061FB01F0E9 +:10034000ADFE054601F0D0FE0446D8B90F4B9D42E4 +:100350001AD001339D4218BF044641F2883504BFCC +:1003600001240025002001F0A3FE0CB100F076F876 +:1003700000F0ECFC00F09AFB284600F0B7F800F023 +:100380006DF8F9E70025EDE70546EBE7010007B05A +:1003900008B500F05DFBA0F120035842584108BDAC +:1003A00007B541F21203022101A8ADF8043000F0B4 +:1003B0006DFB03B05DF804FB38B5302383F311887F +:1003C000174803680BB101F001FB164A14480023DB +:1003D0004FF47A7101F0F0FA002383F31188124C84 +:1003E000236813B12368013B2360636813B163681A +:1003F000013B63600D4D2B7833B963687BB90220F4 +:1004000000F01EFC322363602B78032B07D1636856 +:100410002BB9022000F014FC4FF47A73636038BDEE +:1004200040220020B9030008602300205822002049 +:10043000084B187003280CD8DFE800F00805020804 +:10044000022000F0F3BB022000F0E6BB024B0022CA +:100450005A60704758220020602300201F4B204A1A +:1004600010B51C461968013136D004339342F9D1D6 +:100470006268A24230D31B4B9B6803F1006303F513 +:1004800040439A4228D2002000F02AFB0220FFF7C6 +:10049000CFFF154B1A6C00221A64196E1A66196E7A +:1004A000596C5A64596E5A665A6E1A6942F0005273 +:1004B0001A611A6922F000521A611B6972B64FF074 +:1004C000E0233021C3F8084DD4E9003281F31188CC +:1004D0009D4683F30888104710BD00BF00C0000888 +:1004E00020C0000800220020003802402DE9F04F13 +:1004F00093B0AA4B00902022FF210AA89D6800F02B +:10050000CFFBA74A1378A3B9A64801210360117055 +:10051000302383F3118803680BB101F057FAA24A24 +:10052000A04800234FF47A7101F046FA002383F3C8 +:100530001188009B13B19D4B009A1A609C4A009C45 +:100540001378032B1EBF00231370984A4FF0000A44 +:1005500018BF5360D3465646D146012000F066FBD3 +:1005600024B1924B1B68002B00F01182002000F098 +:100570006FFA0390039B002BF2DB012000F04CFB91 +:10058000039B213B162BE8D801A252F823F000BFB1 +:10059000ED05000815060008A90600085B0500081F +:1005A0005B0500085B050008330700080309000825 +:1005B0001D0800087F080008A7080008CD080008EB +:1005C0005B050008DF0800085B050008510900080A +:1005D0008D0600085B05000895090008F90500086C +:1005E0008D0600085B0500087F0800080220FFF761 +:1005F000CFFE002840F0F581009B0221BAF1000FE8 +:1006000008BF1C4605A841F21233ADF8143000F0C3 +:100610003DFAA2E74FF47A7000F01AFA071EEBDBFE +:100620000220FFF7B5FE0028E6D0013F052F00F2BB +:10063000DA81DFE807F0030A0D101336052305936E +:10064000042105A800F022FA17E054480421F9E734 +:1006500058480421F6E758480421F3E74FF01C08F6 +:10066000404600F03FFA08F104080590042105A86F +:1006700000F00CFAB8F12C0FF2D1012000FA07F7C4 +:1006800047EA0B0B5FFA8BFB4FF0000900F054FBBD +:1006900026B10BF00B030B2B08BF0024FFF780FEE5 +:1006A0005BE746480421CDE7002EA5D00BF00B03F5 +:1006B0000B2BA1D10220FFF76BFE074600289BD031 +:1006C000012000F00DFA0220FFF7B2FE00261FFA0B +:1006D00086F8404600F014FA044690B100214046E6 +:1006E00000F01EFA01360028F1D1BA46044641F264 +:1006F0001213022105A8ADF814303E4600F0C6F9E9 +:100700002BE70120FFF794FE2546244B9B68AB4264 +:1007100007D9284600F0E6F9013040F0678104353A +:10072000F3E7234B00251D70204BBA465D603E4623 +:10073000ACE7002E3FF460AF0BF00B030B2B7FF404 +:100740005BAF0220FFF774FE322000F081F9B0F1B8 +:100750000008FFF651AF18F003077FF44DAF0F4AC2 +:10076000926808EB050393423FF646AFB8F5807FE9 +:100770003FF742AF124B0193B84523DD4FF47A7037 +:1007800000F066F90390039A002AFFF635AF019B4B +:10079000039A03F8012B0137EDE700BF0022002088 +:1007A0005C23002040220020B903000860230020C1 +:1007B0005822002004220020082200200C220020C1 +:1007C0005C220020C820FFF7E3FD074600283FF425 +:1007D00013AF1F2D11D8C5F1200242450AAB25F0F9 +:1007E000030028BF424683490192184400F032FAC0 +:1007F000019A8048FF2100F053FA4FEAA8037D498F +:100800000193C8F38702284600F052FA06460028F2 +:100810003FF46DAF019B05EB830537E70220FFF73F +:10082000B7FD00283FF4E8AE00F0A6F900283FF439 +:10083000E3AE0027B846704B9B68BB4218D91F2F08 +:1008400011D80A9B01330ED027F0030312AA1344D8 +:1008500053F8203C05934046042205A900F0A0FA75 +:1008600004378046E7E7384600F03CF90590F2E7A8 +:10087000CDF81480042105A800F008F906E700234C +:10088000642104A8049300F0F7F800287FF4B4AEC4 +:100890000220FFF77DFD00283FF4AEAE049800F083 +:1008A00053F90590E6E70023642104A8049300F0BF +:1008B000E3F800287FF4A0AE0220FFF769FD0028CE +:1008C0003FF49AAE049800F04FF9EAE70220FFF7F0 +:1008D0005FFD00283FF490AE00F05EF9E1E70220F2 +:1008E000FFF756FD00283FF487AE05A9142000F05D +:1008F00059F904210746049004A800F0C7F83946C6 +:10090000B9E7322000F0A4F8071EFFF675AEBB076A +:100910007FF472AE384A926807EB090393423FF6C0 +:100920006BAE0220FFF734FD00283FF465AE27F0E0 +:1009300003074F44B9453FF4A9AE484600F0D2F84A +:100940000421059005A800F0A1F809F10409F1E7D8 +:100950004FF47A70FFF71CFD00283FF44DAE00F015 +:100960000BF9002844D00A9B01330BD008220AA9B6 +:10097000002000F09DF900283AD02022FF210AA88B +:1009800000F08EF9FFF70CFD1C4800F059FF13B082 +:10099000BDE8F08F002E3FF42FAE0BF00B030B2BB6 +:1009A0007FF42AAE0023642105A8059300F064F8C3 +:1009B000074600287FF420AE0220FFF7E9FC8046BE +:1009C00000283FF419AEFFF7EBFC41F2883000F04D +:1009D00037FF059800F0E2F9464600F0ADF93C46D5 +:1009E000BBE5064652E64FF0000905E6BA467EE64C +:1009F00037467CE65C22002000220020A086010011 +:100A00007047000070B50F4B1B780133DBB2012B30 +:100A10000C4611D80C4D29684FF47A730E6AA2FB6C +:100A20000332014622462846B047844204D1074B90 +:100A300000221A70012070BD4FF4FA7000F000FF20 +:100A40000020F8E710220020082600209423002030 +:100A500007B50023024601210DF107008DF807308C +:100A6000FFF7D0FF20B19DF8070003B05DF804FB4D +:100A70004FF0FF30F9E700000A4608B50421FFF700 +:100A8000C1FF80F00100C0B2404208BD30B4054C47 +:100A90002368DD69044B0A46AC460146204630BC5B +:100AA000604700BF08260020A086010070B501F055 +:100AB000E7F9094E094D30800024286833888342C5 +:100AC00008D901F0D7F92B6804440133B4F5404F3D +:100AD0002B60F2D370BD00BF962300206823002056 +:100AE00001F090BA00F1006000F5404000687047E6 +:100AF00000F10060920000F5404001F00FBA0000E4 +:100B0000054B1A68054B1B889B1A834202D9104477 +:100B100001F0B0B900207047682300209623002020 +:100B200038B5084D044629B128682044BDE838404E +:100B300001F0C0B92868204401F0A4F90028F3D0DE +:100B400038BD00BF6823002010F003030AD1B0F5C0 +:100B5000047F05D200F10050A0F51040D0F8003815 +:100B6000184670470023FBE700F10050A0F5104045 +:100B7000D0F8100A70470000064991F8243033B1CC +:100B80000023086A81F824300822FFF7B1BF012052 +:100B9000704700BF6C230020014B1868704700BFEE +:100BA000002004E070B5194B1D68194B0138C5F3DE +:100BB0000B0408442D0C04221E88A6420BD15C684D +:100BC0000A46013C824213460FD214F9016F4EB11E +:100BD00002F8016BF6E7013A03F10803ECD1814218 +:100BE0000B4602D22C2203F8012B0A4A0524168850 +:100BF000AE4204D1984284BF967803F8016B013C61 +:100C000002F10402F3D1581A70BD00BF002004E0C5 +:100C1000E0340008CC340008022802BF024B4FF039 +:100C200000729A61704700BF00000240022802BFB4 +:100C3000024B4FF400729A61704700BF00000240FF +:100C4000022801BF024A536983F40073536170475D +:100C50000000024010B50023934203D0CC5CC45482 +:100C60000133F9E710BD000010B5013810F9013F5C +:100C70003BB191F900409C4203D11AB10131013AD4 +:100C8000F4E71AB191F90020981A10BD1046FCE75C +:100C900003460246D01A12F9011B0029FAD1704707 +:100CA00002440346934202D003F8011BFAE770475F +:100CB0002DE9F8431F4D144695F824200746884631 +:100CC00052BBDFF870909CB395F824302BB92022EA +:100CD000FF2148462F62FFF7E3FF95F82400C0F19B +:100CE0000802A24228BF2246D6B24146920005EB36 +:100CF0008000FFF7AFFF95F82430A41B1E44F6B226 +:100D0000082E17449044E4B285F82460DBD1FFF745 +:100D100033FF0028D7D108E02B6A03EB820383421C +:100D2000CFD0FFF729FF0028CBD10020BDE8F88302 +:100D30000120FBE76C230020024B1A78024B1A704B +:100D4000704700BF942300201022002010B50F4CE4 +:100D50000F4800F0B5F821460D4800F0DDF8246892 +:100D60000C48626DD2F8043843F00203C2F804382C +:100D700000F066FD0849204600F0D4F9626DD2F813 +:100D8000043823F00203C2F8043810BDAC35000863 +:100D90000826002040420F00B435000870470000CC +:100DA00030B5094D0A4491420DD011F8013B58402D +:100DB000082340F30004013B2C4013F0FF0384EAB6 +:100DC0005000F6D1EFE730BD2083B8ED02684368EC +:100DD0001143016003B118477047000013B5446B1D +:100DE000D4F894341A681178042915D1217C022989 +:100DF00012D11979128901238B4013420CD101A918 +:100E000004F14C0001F032FFD4F89444019B2179A5 +:100E10000246206800F0D0F902B010BD143001F095 +:100E2000B5BE00004FF0FF33143001F0AFBE00003C +:100E30004C3001F087BF00004FF0FF334C3001F021 +:100E400081BF0000143001F083BE00004FF0FF317D +:100E5000143001F07DBE00004C3001F053BF0000A3 +:100E60004FF0FF324C3001F04DBF000000207047C2 +:100E700010B5D0F894341A6811780429044617D1B3 +:100E8000017C022914D15979528901238B401342E4 +:100E90000ED1143001F016FE024648B1D4F8944445 +:100EA0004FF4807361792068BDE8104000F072B99A +:100EB00010BD0000406BFFF7DBBF00007047000073 +:100EC0007FB5124B036000234360C0E90233012564 +:100ED00002260F4B057404460290019300F1840230 +:100EE000294600964FF48073143001F0C7FD094B7A +:100EF0000294CDE9006304F523724FF48073294610 +:100F000004F14C0001F08EFE04B070BD0035000805 +:100F1000B50E0008DD0D00080B68302282F3118841 +:100F20000A7903EB820290614A79093243F8220080 +:100F30008A7912B103EB820398610223C0F89414FA +:100F40000374002080F311887047000038B5037FD8 +:100F5000044613B190F85430ABB9201D012502218D +:100F6000FFF734FF04F1140025776FF0010100F062 +:100F70008FFC84F8545004F14C006FF00101BDE87F +:100F8000384000F085BC38BD10B50121044604305E +:100F9000FFF71CFF0023237784F8543010BD0000B6 +:100FA00038B504460025143001F080FD04F14C00F2 +:100FB000257701F04FFE201D84F854500121FFF7E2 +:100FC00005FF2046BDE83840FFF752BF90F8443097 +:100FD00003F06003202B07D190F84520212A4FF021 +:100FE000000303D81F2A06D800207047222AFBD10D +:100FF000C0E90E3303E0034A82630722C26303643D +:10100000012070471122002037B5D0F894341A68B7 +:101010001178042904461AD1017C022917D11979C3 +:10102000128901238B40134211D100F14C0528464F +:1010300001F0D0FE58B101A9284601F017FED4F8FE +:101040009444019B21790246206800F0B5F803B072 +:1010500030BD0000F0B500EB810385B09E69044609 +:101060000D46FEB1302383F3118804EB8507301D54 +:101070000821FFF7ABFEFB685B691B6806F14C00BB +:101080001BB1019001F000FE019803A901F0EEFDF3 +:10109000024648B1039B2946204600F08DF8002304 +:1010A00083F3118805B0F0BDFB685A691268002A05 +:1010B000F5D01B8A013B1340F1D104F14402EAE769 +:1010C000093138B550F82140DCB1302383F3118861 +:1010D000D4F894241368527903EB8203DB689B698C +:1010E0005D6845B104216018FFF770FE294604F1E0 +:1010F000140001F0F1FC2046FFF7BAFE002383F351 +:10110000118838BD7047000001F050B8012303700A +:101110000023C0E90133C36183620362C362436297 +:101120000363704738B50446302383F311880025E4 +:10113000C0E90355C0E90555416001F047F80223B5 +:10114000237085F31188284638BD000070B500EB88 +:10115000810305465069DA600E46144618B1102224 +:101160000021FFF79DFDA06918B110220021FFF7B3 +:1011700097FD31462846BDE8704001F0F1B8000007 +:10118000826802F0011282600022C0E904228261BA +:1011900001F072B9F0B400EB81044789E4680125DD +:1011A000A4698D403D43458123600023A2606360B4 +:1011B000F0BC01F08DB90000F0B400EB81040789A8 +:1011C000E468012564698D403D4305812360002367 +:1011D000A2606360F0BC01F007BA000070B50223A2 +:1011E000002504460370C0E90255C0E90455C564F2 +:1011F000856180F8345001F04FF863681B6823B1B3 +:1012000029462046BDE87040184770BD0378052B7D +:1012100010B504460AD080F85030052303704368A7 +:101220001B680BB1042198470023A36010BD000088 +:101230000178052906D190F85020436802701B6898 +:1012400003B118477047000070B590F83430044679 +:1012500013B1002380F8343004F14402204601F039 +:101260002DF963689B68B3B994F8443013F06005B6 +:1012700035D00021204601F0CDFB0021204601F0B1 +:10128000BFFB63681B6813B10621204698470623FD +:1012900084F8343070BD204698470028E4D0B4F874 +:1012A0004A30E26B9A4288BFE36394F94430E56BBD +:1012B000002B4FF0300380F20381002D00F0F2800C +:1012C000092284F8342083F311880021D4E90E2305 +:1012D0002046FFF771FF002383F31188DAE794F8C3 +:1012E000452003F07F0343EA022340F20232934297 +:1012F00000F0C58021D8B3F5807F48D00DD8012BF0 +:101300003FD0022B00F09380002BB2D104F14C02AD +:10131000A2630222E2632364C1E7B3F5817F00F098 +:101320009B80B3F5407FA4D194F84630012BA0D127 +:10133000B4F84C3043F0020332E0B3F5006F4DD007 +:1013400017D8B3F5A06F31D0A3F5C063012B90D8A7 +:10135000636894F846205E6894F84710B4F8483003 +:101360002046B047002884D04368A3630368E36342 +:101370001AE0B3F5106F36D040F6024293427FF484 +:1013800078AF5C4BA3630223E3630023C3E794F8C5 +:101390004630012B7FF46DAFB4F84C3023F00203DC +:1013A000C4E90E55A4F84C30256478E7B4F844300D +:1013B000B3F5A06F0ED194F8463084F84E30204635 +:1013C00000F0C2FF63681B6813B1012120469847F3 +:1013D000032323700023C4E90E339CE704F14F0379 +:1013E000A3630123C3E72378042B10D1302383F3B5 +:1013F00011882046FFF7C4FE85F311880321636836 +:1014000084F84F5021701B680BB12046984794F820 +:101410004630002BDED084F84F30042323706368FD +:101420001B68002BD6D0022120469847D2E794F8BB +:1014300048301D0603F00F0120460AD501F030F8B0 +:10144000012804D002287FF414AF2B4B9AE72B4BD2 +:1014500098E701F017F8F3E794F84630002B7FF493 +:1014600008AF94F8483013F00F01B3D01A062046A5 +:1014700002D501F0E3FAADE701F0D6FAAAE794F855 +:101480004630002B7FF4F5AE94F8483013F00F018E +:10149000A0D01B06204602D501F0BCFA9AE701F065 +:1014A000AFFA97E7142284F8342083F311882B468F +:1014B0002A4629462046FFF76DFE85F31188E9E6A6 +:1014C0005DB1152284F8342083F311880021D4E91A +:1014D0000E232046FFF75EFEFDE60B2284F8342043 +:1014E00083F311882B462A4629462046FFF764FEDF +:1014F000E3E700BF30350008283500082C35000828 +:1015000038B590F834300446002B3ED0063BDAB2B2 +:101510000F2A34D80F2B32D8DFE803F037313108E7 +:10152000223231313131313131313737C56BB0F899 +:101530004A309D4214D2C3681B8AB5FBF3F203FB09 +:1015400012556DB9302383F311882B462A4629465C +:10155000FFF732FE85F311880A2384F834300EE059 +:10156000142384F83430302383F3118800231A467F +:1015700019462046FFF70EFE002383F3118838BD7D +:10158000036C03B198470023E7E70021204601F0F0 +:1015900041FA0021204601F033FA63681B6813B159 +:1015A0000621204698470623D7E7000010B590F89B +:1015B0003430142B044629D017D8062B05D001D877 +:1015C0001BB110BD093B022BFBD80021204601F0C6 +:1015D00021FA0021204601F013FA63681B6813B159 +:1015E000062120469847062319E0152BE9D10B2345 +:1015F00080F83430302383F3118800231A461946CB +:10160000FFF7DAFD002383F31188DAE7C3689B69EB +:101610005B68002BD5D1036C03B19847002384F895 +:101620003430CEE700230375826803691B6899682C +:101630009142FBD25A680360426010605860704764 +:1016400000230375826803691B6899689142FBD87F +:101650005A680360426010605860704708B50846D9 +:10166000302383F311880B7D032B05D0042B0DD081 +:101670002BB983F3118808BD8B6900221A604FF0E3 +:10168000FF338361FFF7CEFF0023F2E7D1E9003299 +:1016900013605A60F3E70000FFF7C4BF054BD96839 +:1016A0000875186802681A60536001220275D860D4 +:1016B000FEF728BE9823002030B50C4BDD684B1C8C +:1016C00087B004460FD02B46094A684600F074F9EB +:1016D0002046FFF7E3FF009B13B1684600F076F960 +:1016E000A86907B030BDFFF7D9FFF9E798230020BC +:1016F0005D160008044B1A68DB6890689B68984286 +:1017000094BF00200120704798230020084B10B59B +:101710001C68D86822681A60536001222275DC6058 +:10172000FFF78EFF01462046BDE81040FEF7EABDF8 +:1017300098230020044B1A68DB6892689B689A42E1 +:1017400001D9FFF7E3BF70479823002038B5074C55 +:1017500007490848012300252370656001F072FBEA +:101760000223237085F3118838BD00BF00260020B6 +:10177000383500089823002000F05EB9EFF311809F +:1017800020B9EFF30583302282F3118870470000FF +:1017900010B530B9EFF30584C4F3080414B180F335 +:1017A000118810BDFFF7C6FF84F31188F9E7000028 +:1017B000034A516853685B1A9842FBD8704700BFD0 +:1017C000001000E08B60022308618B82084670479E +:1017D0008368A3F1840243F8142C026943F8442C73 +:1017E000426943F8402C094A43F8242CC26843F864 +:1017F000182C022203F80C2C002203F80B2C044AAC +:1018000043F8102CA3F12000704700BF1D0300080F +:101810009823002008B5FFF7DBFFBDE80840FFF77D +:101820003BBF0000024BDB6898610F20FFF736BF1B +:1018300098230020302383F31188FFF7F3BF0000C3 +:1018400008B50146302383F311880820FFF734FFE1 +:10185000002383F3118808BD064BDB6839B1426869 +:1018600018605A60136043600420FFF725BF4FF0F3 +:10187000FF307047982300200368984206D01A680A +:101880000260506099611846FFF706BF704700007C +:1018900038B504460D462068844200D138BD03683F +:1018A00023605C608561FFF7F7FEF4E710B503681D +:1018B0009C68A2420CD85C688A600B604C60216016 +:1018C000596099688A1A9A604FF0FF33836010BD9F +:1018D0001B68121BECE700000A2938BF0A2170B50B +:1018E00004460D460A26601901F0A6FA01F092FAA4 +:1018F000041BA54203D8751C2E460446F3E70A2EA6 +:1019000004D9BDE87040012001F0DCBA70BD0000D0 +:10191000F8B5144B0D46D96103F1100141600A2A54 +:101920001969826038BF0A22016048601861A818EE +:10193000144601F073FA0A2701F06CFA431BA34224 +:10194000064606D37C1C281901F076FA2746354650 +:10195000F2E70A2F04D9BDE8F840012001F0B2BA3D +:10196000F8BD00BF98230020F8B506460D4601F0EB +:1019700051FA0F4A134653F8107F9F4206D12A4668 +:1019800001463046BDE8F840FFF7C2BFD169BB68E9 +:10199000441A2C1928BF2C46A34202D92946FFF726 +:1019A0009BFF224631460348BDE8F840FFF77EBF63 +:1019B00098230020A823002010B4C0E903230023AB +:1019C0005DF8044B4361FFF7CFBF000010B5194C21 +:1019D000236998420DD0D0E90032816813605A60C3 +:1019E0009A680A449A60002303604FF0FF33A361B2 +:1019F00010BD2346026843F8102F53600022026096 +:101A000022699A4203D1BDE8104001F00FBA9368F1 +:101A100081680B44936001F0FDF92269E1699268E5 +:101A2000441AA242E4D91144BDE81040091AFFF754 +:101A300053BF00BF982300202DE9F047DFF8BC809A +:101A400008F110072C4ED8F8105001F0E3F9D8F83F +:101A50001C40AA68031B9A423ED81444D5E90032C0 +:101A60004FF00009C8F81C4013605A60C5F8009098 +:101A7000D8F81030B34201D101F0D8F989F31188B8 +:101A8000D5E9033128469847302383F311886B69E1 +:101A9000002BD8D001F0BEF96A69A0EB04094A45D1 +:101AA00082460DD2022001F00DFA0022D8F8103043 +:101AB000B34208D151462846BDE8F047FFF728BF9A +:101AC000121A2244F2E712EB090938BF4A462946A6 +:101AD0003846FFF7EBFEB5E7D8F81030B34208D030 +:101AE0001444211AC8F81C00A960BDE8F047FFF7AC +:101AF000F3BEBDE8F08700BFA82300209823002094 +:101B000000207047FEE70000704700004FF0FF30F4 +:101B10007047000002290CD0032904D0012907488E +:101B200018BF00207047032A05D8054800EBC20003 +:101B30007047044870470020704700BF1036000807 +:101B400020220020C435000870B59AB0054608462A +:101B500001A9144600F0C2F801A8FFF799F8431C48 +:101B60005B00C5E900340022237003236370C6B212 +:101B700001AB02341046D1B28E4204F1020401D806 +:101B80001AB070BD13F8011B04F8021C04F8010C14 +:101B90000132F0E708B5302383F311880348FFF7DB +:101BA00033FA002383F3118808BD00BF0826002004 +:101BB00090F8443003F01F02012A07D190F8452025 +:101BC0000B2A03D10023C0E90E3315E003F06003B4 +:101BD000202B08D1B0F848302BB990F84520212AA5 +:101BE00003D81F2A04D8FFF7F1B9222AEBD0FAE76D +:101BF000034A82630722C26303640120704700BF67 +:101C00001822002007B5052917D8DFE801F01916BA +:101C100003191920302383F31188104A0190012100 +:101C2000FFF794FA01980E4A0221FFF78FFA0D4848 +:101C3000FFF7B6F9002383F3118803B05DF804FBC6 +:101C4000302383F311880748FFF780F9F2E7302348 +:101C500083F311880348FFF797F9EBE76435000831 +:101C6000883500080826002038B50C4D0C4C0D496D +:101C70002A4604F10800FFF767FF05F1CA0204F1E4 +:101C800010000949FFF760FF05F5CA7204F118005A +:101C90000649BDE83840FFF757BF00BFD02A0020F3 +:101CA00020220020443500084E3500085935000830 +:101CB00070B5044608460D46FEF7EAFFC6B2204658 +:101CC000013403780BB9184670BD32462946FEF739 +:101CD000CBFF0028F3D10120F6E700002DE9F04703 +:101CE00005460C46FEF7D4FF2B49C6B22846FFF73F +:101CF000DFFF08B10636F6B228492846FFF7D8FFBD +:101D000008B11036F6B2632E0BD8DFF88C80DFF8FE +:101D10008C90234FDFF894A02E7846B92670BDE84A +:101D2000F08729462046BDE8F04701F0B1BB252EDB +:101D30002ED1072241462846FEF796FF70B9194B6F +:101D4000224603F10C0153F8040B42F8040B8B42BA +:101D5000F9D11B78137007350D34DDE708224946A9 +:101D60002846FEF781FF98B90F4BA21C1978090984 +:101D70000232C95D02F8041C13F8011B01F00F01C7 +:101D80005345C95D02F8031CF0D118340835C3E788 +:101D900004F8016B0135BFE73036000859350008FB +:101DA0004636000838360008107AFF1F1C7AFF1FDD +:101DB000BFF34F8F024AD368DB03FCD4704700BFE8 +:101DC000003C024008B5094B1B7873B9FFF7F0FFE0 +:101DD000074B1A69002ABFBF064A5A6002F18832CF +:101DE0005A601A6822F480621A6008BD2E2D002005 +:101DF000003C02402301674508B50B4B1B7893B9A3 +:101E0000FFF7D6FF094B1A6942F000421A611A68BF +:101E100042F480521A601A6822F480521A601A68DA +:101E200042F480621A6008BD2E2D0020003C024062 +:101E30000B28F0B516D80C4C0C4923787BB90C4D07 +:101E40000E460C234FF0006255F8047B46F8042B35 +:101E5000013B13F0FF033A44F6D10123237051F8FC +:101E60002000F0BD0020FCE7602D0020302D002078 +:101E700058360008014B53F82000704758360008C8 +:101E80000C2070470B2810B5044601D9002010BD66 +:101E9000FFF7CEFF064B53F824301844C21A0BB993 +:101EA0000120F4E712680132F0D1043BF6E700BFED +:101EB000583600080B2838B5044628D8FFF75EFCD2 +:101EC000FFF776FFFFF77EFF124AF323D360E300AC +:101ED000DBB243F4007343F002031361136943F46C +:101EE0008033136105462046FFF762FFFFF7A0FF2E +:101EF000094B53F8241000F0E9F82846FFF77CFF5F +:101F0000FFF746FC2046BDE83840FFF7BBBF002086 +:101F100038BD00BF003C02405836000812F00103F3 +:101F20002DE9F04105460E4614464BD18218B2F118 +:101F3000016F61D8314B1B6813F001035CD0304F47 +:101F4000FFF71CFCFFF73EFFF323FB60FFF730FFBA +:101F5000314640F20128032C18D824F00104284E01 +:101F60000C446D1A40F20118A142336905EB0107D8 +:101F70002AD123F001033361FFF73EFFFFF708FC8E +:101F80000120BDE8F081043C0435E4E7AB07E4D16F +:101F90003B6923F440733B613B6943EA08033B61BF +:101FA00051F8046B2E60BFF34F8FFFF701FF2B68D2 +:101FB0009E42E8D03B6923F001033B61FFF71CFF21 +:101FC000FFF7E6FB0020DCE723F44073336133695D +:101FD00043EA080333610B883B80BFF34F8FFFF761 +:101FE000E7FE3F8831F8023BBFB2BB42BCD0336949 +:101FF00023F001033361E1E71846C2E700380240ED +:10200000003C0240084908B50B7828B11BB9FFF71E +:10201000D9FE01230B7008BD002BFCD0BDE80840A1 +:102020000870FFF7E9BE00BF2E2D002010B5024456 +:10203000064BD2B2904200D110BD441C00B253F8FE +:10204000200041F8040BE0B2F4E700BF5028004044 +:102050000F4B30B51C6F240407D41C6F44F400747C +:102060001C671C6F44F400441C670A4C236843F44B +:10207000807323600244084BD2B2904200D130BD3D +:10208000441C00B251F8045B43F82050E0B2F4E77E +:1020900000380240007000405028004007B501227F +:1020A00001A90020FFF7C2FF019803B05DF804FB0F +:1020B00013B50446FFF7F2FFA04205D0012201A9A3 +:1020C00000200194FFF7C4FF02B010BD704700006C +:1020D000034B1A681AB9034AD2F874281A60704779 +:1020E000642D00200030024008B5FFF7F1FF024BDD +:1020F0001868C0F3407008BD642D002070470000D0 +:10210000FEE700000A4B0B480B4A90420BD30B4BE7 +:10211000DA1C121AC11E22F003028B4238BF0022C1 +:102120000021FEF7BDBD53F8041B40F8041BECE78B +:1021300000380008602E0020602E0020602E002055 +:1021400070B5D0E915439E6800224FF0FF3504EBCF +:1021500042135101D3F800090028BEBFD3F800098B +:1021600040F08040C3F80009D3F8000B0028BEBF40 +:10217000D3F8000B40F08040C3F8000B0132631825 +:102180009642C3F80859C3F8085BE0D24FF0011338 +:10219000C4F81C3870BD0000890141F020010161C4 +:1021A00003699B06FCD41220FFF702BB10B5054C57 +:1021B0002046FEF7ABFF4FF0A0436365024BA365DB +:1021C00010BD00BF682D0020AC36000870B5037844 +:1021D000012B054650D12A4B446D98421BD1294B07 +:1021E0005A6B42F080025A635A6D42F080025A657F +:1021F0005A6D5A6942F080025A615A6922F080028F +:102200005A610E2143205B6900F022FC1E4BE36003 +:102210001E4BC4F800380023C4F8003EC0232360DE +:102220006E6D4FF40413A3633369002BFCDA0123B2 +:1022300033610C20FFF7BCFA3369DB07FCD41220B2 +:10224000FFF7B6FA3369002BFCDA0026A6602846B1 +:10225000FFF776FF6B68C4F81068DB68C4F8146891 +:10226000C4F81C684BB90A4BA3614FF0FF3363619C +:10227000A36843F00103A36070BD064BF4E700BF01 +:10228000682D002000380240401400400300200266 +:10229000003C30C0083C30C0F8B5446D0546002114 +:1022A0002046FFF779FFA96D00234FF001128F68D8 +:1022B000C4F834384FF00066C4F81C284FF0FF30E3 +:1022C00004EB431201339F42C2F80069C2F8006B6D +:1022D000C2F80809C2F8080BF2D20B686A6DEB6508 +:1022E000636210231361166916F01006FBD11220E9 +:1022F000FFF75EFAD4F8003823F4FE63C4F8003820 +:10230000A36943F4402343F01003A3610923C4F8F5 +:102310001038C4F814380A4BEB604FF0C043C4F8CF +:10232000103B084BC4F8003BC4F81069C4F80039EE +:10233000EB6D03F1100243F48013EA65A362F8BD6C +:102340008836000840800010426D90F84E10D2F898 +:10235000003823F4FE6343EA0113C2F800387047E3 +:102360002DE9F84300EB8103456DDA68166806F045 +:102370000306731E022B05EB41130C4680460FFA31 +:1023800081F94FEA41104FF00001C3F8101B4FF0E4 +:10239000010104F1100398BFB60401FA03F3916937 +:1023A0008EBF334E06F1805606F5004600293AD01E +:1023B000578A04F15801490137436F50D5F81C186A +:1023C0000B43C5F81C382B180021C3F810195369AA +:1023D0000127611EA7409BB3138A928B9B08012A99 +:1023E00088BF5343D8F85C20981842EA034301F1B0 +:1023F000400205EB8202C8F85C0021465360284683 +:10240000FFF7CAFE08EB8900C3681B8A43EA8453BE +:10241000483464011E432E51D5F81C381F43C5F8BB +:102420001C78BDE8F88305EB4917D7F8001B21F4A9 +:102430000041C7F8001BD5F81C1821EA0303C0E7C8 +:1024400004F13F0305EB83030A4A5A6028462146FC +:10245000FFF7A2FE05EB4910D0F8003923F4004342 +:10246000C0F80039D5F81C3823EA0707D7E700BFC2 +:102470000080001000040002826D1268C265FFF740 +:102480005FBE00005831436D49015B5813F40040B2 +:1024900004D013F4001F0CBF02200120704700007D +:1024A0004831436D49015B5813F4004004D013F4E4 +:1024B000001F0CBF022001207047000000EB8101CB +:1024C000CB68196A0B6813604B6853607047000053 +:1024D00000EB810330B5DD68AA691368D36019B9D0 +:1024E000402B84BF402313606B8A1468426D1C44E8 +:1024F000013CB4FBF3F46343033323F0030302EB27 +:10250000411043EAC44343F0C043C0F8103B2B687A +:1025100003F00303012B09B20ED1D2F8083802EB05 +:10252000411013F4807FD0F8003B14BF43F0805378 +:1025300043F00053C0F8003B02EB4112D2F8003BDD +:1025400043F00443C2F8003B30BD00002DE9F041E8 +:10255000244D6E6D06EB40130446D3F8087BC3F898 +:10256000087B38070AD5D6F81438190706D505EBC5 +:1025700084032146DB6828465B689847FA071FD525 +:10258000D6F81438DB071BD505EB8403D968CCB922 +:102590008B69488A5A68B2FBF0F600FB16228AB9AA +:1025A0001868DA6890420DD2121AC3E90024302369 +:1025B00083F311880B482146FFF78AFF84F31188C3 +:1025C000BDE8F081012303FA04F26B8923EA0203D8 +:1025D0006B81CB68002BF3D021460248BDE8F04167 +:1025E000184700BF682D002000EB810370B5DD683F +:1025F000436D6C692668E6604A0156BB1A444FF485 +:102600000020C2F810092A6802F00302012A0AB267 +:102610000ED1D3F8080803EB421410F4807FD4F8ED +:10262000000914BF40F0805040F00050C4F8000989 +:1026300003EB4212D2F8000940F00440C2F800094E +:10264000D3F83408012202FA01F10143C3F8341827 +:1026500070BD19B9402E84BF4020206020682E8AAA +:102660008419013CB4FBF6F440EAC44040F0005049 +:102670001A44C6E72DE9F8433B4D6E6D06EB401357 +:102680000446D3F80889C3F8088918F0010F4FEA07 +:1026900040171AD0D6F81038DB0716D505EB8003A3 +:1026A000D9684B691868DA68904230D2121A4FF034 +:1026B00000091A60C3F80490302383F3118821467F +:1026C0002846FFF791FF89F3118818F0800F1CD07E +:1026D000D6F834380126A640334216D005EB8403E1 +:1026E0006D6DD3F80CC0DCF814200134E4B2D2F8DC +:1026F00000E005EB04342F445168714515D3D5F83B +:10270000343823EA0606C5F83468BDE8F8830123A7 +:1027100003FA04F22B8923EA02032B818B68002B36 +:10272000D3D0214628469847CFE7BCF81000AEEB3F +:102730000103834228BF0346D7F8180980B2B3EBE0 +:10274000800FE2D89068A0F1040959F8048FC4F80A +:102750000080A0EB09089844B8F1040FF5D818449C +:102760000B4490605360C7E7682D00202DE9F74FB8 +:10277000A24C656D6E69AB691E4016F480586E619F +:1027800007D02046FEF72AFD03B0BDE8F04F00F069 +:1027900047BC002E12DAD5F8003E98489B071EBFB2 +:1027A000D5F8003E23F00303C5F8003ED5F8043801 +:1027B00023F00103C5F80438FEF73AFD370505D5C7 +:1027C0008E48FFF7BDFC8D48FEF720FDB0040CD508 +:1027D000D5F8083813F0060FEB6823F470530CBFDC +:1027E00043F4105343F4A053EB6031071BD56368E7 +:1027F000DB681BB9AB6923F00803AB612378052BB9 +:102800000CD1D5F8003E7D489A071EBFD5F8003E92 +:1028100023F00303C5F8003EFEF70AFD6368DB689A +:102820000BB176489847F30274D4B70227D5D4F891 +:102830005490DFF8C8B100274FF0010A09EB4712A6 +:10284000D2F8003B03F44023B3F5802F11D1D2F826 +:10285000003B002B0DDA62890AFA07F322EA030330 +:10286000638104EB8703DB68DB6813B139465846A4 +:102870009847A36D01379B68FFB29F42DED9F006EF +:1028800017D5676D3A6AC2F30A1002F00F0302F41B +:10289000F012B2F5802F00F08580B2F5402F08D1FC +:1028A00004EB83030022DB681B6A07F58057904224 +:1028B0006AD13003D5F8184813D5E10302D50020BA +:1028C000FFF744FEA20302D50120FFF73FFE63039A +:1028D00002D50220FFF73AFE270302D50320FFF7B7 +:1028E00035FE75037FF550AFE00702D50020FFF7F6 +:1028F000C1FEA10702D50120FFF7BCFE620702D589 +:102900000220FFF7B7FE23077FF53EAF0320FFF756 +:10291000B1FE39E7636DDFF8E4A0019300274FF0C3 +:102920000109A36D9B685FFA87FB9B453FF67DAF6E +:10293000019B03EB4B13D3F8001901F44021B1F5CF +:10294000802F1FD1D3F8001900291BDAD3F8001902 +:1029500041F09041C3F80019D3F800190029FBDBBE +:102960005946606DFFF718FC218909FA0BF321EA3B +:102970000303238104EB8B03DB689B6813B1594687 +:10298000504698470137CCE7910708BFD7F8008039 +:10299000072A98BF03F8018B02F1010298BF4FEAA2 +:1029A000182884E7023304EB830207F58057526846 +:1029B000D2F818C0DCF80820DCE9001CA1EB0C0CF4 +:1029C000002188420AD104EB830463689B699A68FA +:1029D00002449A605A6802445A606AE711F0030F91 +:1029E00008BFD7F800808C4588BF02F8018B01F141 +:1029F000010188BF4FEA1828E3E700BF682D0020D7 +:102A0000436D03EB4111D1F8003B43F40013C1F8CF +:102A1000003B7047436D03EB4111D1F8003943F49B +:102A20000013C1F800397047436D03EB4111D1F831 +:102A3000003B23F40013C1F8003B7047436D03EBE8 +:102A40004111D1F8003923F40013C1F8003970475F +:102A500000F1604303F561430901C9B283F8001333 +:102A6000012200F01F039A4043099B0003F16043D9 +:102A700003F56143C3F880211A60704730B5039CA9 +:102A80000172043304FB0325C0E90653049B03636E +:102A90000021059BC160C0E90000C0E90422C0E933 +:102AA0000842C0E90A11436330BD0000416A0022B8 +:102AB000C0E90411C0E90A22C2606FF00101FEF70B +:102AC000E7BE0000D0E90432934201D1C2680AB9DE +:102AD000181D70470020704703691960C2680132F1 +:102AE000C260C269134482690361934224BF436A8E +:102AF00003610021FEF7C0BE38B504460D46E36809 +:102B00003BB16269131D1268A3621344E3620020A3 +:102B100007E0237A33B929462046FEF79DFE0028B8 +:102B2000EDDA38BD6FF00100FBE70000C368C26951 +:102B3000013BC3604369134482694361934224BFEC +:102B4000436A436100238362036B03B118477047F4 +:102B500070B53023044683F31188866A3EB9FFF7C7 +:102B6000CBFF054618B186F31188284670BDA36ACD +:102B7000E26A13F8015BA362934202D32046FFF797 +:102B8000D5FF002383F31188EFE700002DE9F84F0C +:102B900004460E46174698464FF0300989F31188CF +:102BA0000025AA46D4F828B0BBF1000F09D1414650 +:102BB0002046FFF7A1FF20B18BF311882846BDE81E +:102BC000F88FD4E90A12A7EB050B521A934528BFD8 +:102BD0009346BBF1400F1BD9334601F1400251F837 +:102BE000040B43F8040B9142F9D1A36A40334036F9 +:102BF000A3624035D4E90A239A4202D32046FFF764 +:102C000095FF8AF31188BD42D8D289F31188C9E7AC +:102C100030465A46FEF71EF8A36A5B445E44A36240 +:102C20005D44E7E710B5029C0172043303FB042105 +:102C3000C0E906130023C0E90A33039B0363049B26 +:102C4000C460C0E90000C0E90422C0E9084243634F +:102C500010BD0000026AC260426AC0E9042200227C +:102C6000C0E90A226FF00101FEF712BED0E9042389 +:102C70009A4201D1C26822B9184650F8043B0B6051 +:102C8000704700231846FAE7C368C2690133C3607E +:102C90004369134482694361934224BF436A436199 +:102CA0000021FEF7E9BD000038B504460D46E36893 +:102CB0003BB123691A1DA262E2691344E36200205A +:102CC00007E0237A33B929462046FEF7C5FD0028E0 +:102CD000EDDA38BD6FF00100FBE700000369196011 +:102CE000C268013AC260C2691344826903619342B7 +:102CF00024BF436A036100238362036B03B1184757 +:102D00007047000070B530230D460446114683F32A +:102D10001188866A2EB9FFF7C7FF10B186F31188B4 +:102D200070BDA36A1D70A36AE26A01339342A36275 +:102D300004D3E16920460439FFF7D0FF002080F377 +:102D40001188EDE72DE9F84F04460D469046994667 +:102D50004FF0300A8AF311880026B346A76A4FB9AC +:102D600049462046FFF7A0FF20B187F3118830467F +:102D7000BDE8F88FD4E90A073A1AA8EB060797428C +:102D800028BF1746402F1BD905F1400355F8042BE7 +:102D900040F8042B9D42F9D1A36A4033A362403628 +:102DA000D4E90A239A4204D3E16920460439FFF7A3 +:102DB00095FF8BF311884645D9D28AF31188CDE768 +:102DC00029463A46FDF746FFA36A3B443D44A362C9 +:102DD0003E44E5E7D0E904239A4217D1C3689BB18A +:102DE000836A8BB1043B9B1A0ED01360C368013B0E +:102DF000C360C3691A44836902619A4224BF436A6B +:102E00000361002383620123184670470023FBE718 +:102E100000F030B94FF08043586A70474FF080435C +:102E2000002258631A610222DA6070474FF0804333 +:102E30000022DA60704700004FF08043586370470B +:102E4000FEE7000070B51B4B01630025044686B009 +:102E5000586085620E4600F0BFF804F11003C4E923 +:102E600004334FF0FF33C4E90635C4E90044A560DC +:102E7000E562FFF7CFFF2B460246C4E9082304F1C1 +:102E800034010D4A256580232046FEF79BFC012373 +:102E9000E0600A4A0375009272680192B268CDE957 +:102EA0000223074B6846CDE90435FEF7B3FC06B0B4 +:102EB00070BD00BF00260020B8360008BD360008EF +:102EC000412E0008024AD36A1843D062704700BFFF +:102ED000982300204B6843608B688360CB68C36095 +:102EE0000B6943614B6903628B6943620B68036042 +:102EF0007047000008B5264B26481A6940F2FF11BA +:102F00000A431A611A6922F4FF7222F001021A615F +:102F10001A691A6B0A431A631A6D0A431A651E4A24 +:102F20001B6D1146FFF7D6FF02F11C0100F5806012 +:102F3000FFF7D0FF02F1380100F58060FFF7CAFF0C +:102F400002F1540100F58060FFF7C4FF02F1700147 +:102F500000F58060FFF7BEFF02F18C0100F5806094 +:102F6000FFF7B8FF02F1A80100F58060FFF7B2FF9C +:102F700002F1C40100F58060FFF7ACFF02F1E0014F +:102F800000F58060FFF7A6FFBDE8084000F0EEB84E +:102F90000038024000000240C436000808B500F0C6 +:102FA00059FAFEF7D3FBFFF793F8BDE80840FEF7A8 +:102FB0005BBE000070470000EFF3098305494A6BD0 +:102FC00022F001024A63683383F30988002383F304 +:102FD0001188704700EF00E0302080F3118862B65E +:102FE0000C4B0D4AD96821F4E0610904090C0A432D +:102FF000DA60D3F8FC20094942F08072C3F8FC2063 +:103000000A6842F001020A602022DA7783F822007F +:10301000704700BF00ED00E00003FA05001000E07B +:1030200010B5302383F311880E4B5B6813F40063F3 +:1030300014D0F1EE103AEFF30984683C4FF080733E +:10304000E361094BDB6B236684F30988FEF752FBCF +:1030500010B1064BA36110BD054BFBE783F311884C +:10306000F9E700BF00ED00E000EF00E02F030008EB +:10307000320300080F4B1A6C42F001021A641A6EF8 +:1030800042F001021A660C4A1B6E936843F001037A +:1030900093604FF0804353229A624FF0FF32DA621E +:1030A00000229A615A63DA605A6001225A611A60FA +:1030B000704700BF00380240002004E04FF080421B +:1030C00008B51169D3680B40D9B2C9439B07116198 +:1030D00007D5302383F31188FEF74EFB002383F3DB +:1030E000118808BD1F4B1A696FEAC2526FEAD252AB +:1030F0001A611A69C2F308021A614FF0FF301A69A7 +:103100005A69586100215A6959615A691A6A62F00C +:1031100080521A621A6A02F080521A621A6A5A6A55 +:1031200058625A6A59625A6A1A6C42F080521A649A +:103130001A6E42F080521A661A6E0B4A106840F4FA +:1031400080701060186F00F44070B0F5007F1EBFF3 +:103150004FF4803018671967536823F40073536085 +:1031600000F054B90038024000700040334B4FF07B +:1031700080521A64324A4FF4404111601A6842F09A +:1031800001021A601A689107FCD59A6822F00302BE +:103190009A602A4B9A6812F00C02FBD1196801F070 +:1031A000F90119609A601A6842F480321A601A684C +:1031B0009203FCD55A6F42F001025A671F4B5A6FB7 +:1031C0009007FCD51F4A5A601A6842F080721A6054 +:1031D0001B4A53685904FCD5184B1A689201FCD558 +:1031E000194A9A60194B1A68194B9A42194B21D106 +:1031F000194A1168194A91421CD140F205121A600D +:10320000144A136803F00F03052BFAD10B4B9A688D +:1032100042F002029A609A6802F00C02082AFAD17F +:103220005A6C42F480425A645A6E42F480425A66A2 +:103230005B6E704740F20572E1E700BF0038024064 +:10324000007000400854400700948838002004E0D3 +:1032500011640020003C024000ED00E041C20F413B +:10326000074A08B5536903F00103536123B1054AC6 +:1032700013680BB150689847BDE80840FFF7D0BE0F +:10328000003C0140E02D0020074A08B5536903F0D7 +:103290000203536123B1054A93680BB1D068984784 +:1032A000BDE80840FFF7BCBE003C0140E02D002017 +:1032B000074A08B5536903F00403536123B1054A73 +:1032C00013690BB150699847BDE80840FFF7A8BEE5 +:1032D000003C0140E02D0020074A08B5536903F087 +:1032E0000803536123B1054A93690BB1D06998472C +:1032F000BDE80840FFF794BE003C0140E02D0020EF +:10330000074A08B5536903F01003536123B1054A16 +:10331000136A0BB1506A9847BDE80840FFF780BEBA +:10332000003C0140E02D0020164B10B55C6904F410 +:1033300078725A61A30604D5134A936A0BB1D06A16 +:103340009847600604D5104A136B0BB1506B984731 +:10335000210604D50C4A936B0BB1D06B9847E2055C +:1033600004D5094A136C0BB1506C9847A30504D5DA +:10337000054A936C0BB1D06C9847BDE81040FFF73D +:103380004FBE00BF003C0140E02D0020194B10B59E +:103390005C6904F47C425A61620504D5164A136DD7 +:1033A0000BB1506D9847230504D5134A936D0BB1AB +:1033B000D06D9847E00404D50F4A136E0BB1506EE0 +:1033C0009847A10404D50C4A936E0BB1D06E984770 +:1033D000620404D5084A136F0BB1506F9847230459 +:1033E00004D5054A936F0BB1D06F9847BDE81040E4 +:1033F000FFF716BE003C0140E02D002008B5FFF7A6 +:103400005DFEBDE80840FFF70BBE0000062108B5D1 +:103410000846FFF71DFB06210720FFF719FB0621D1 +:103420000820FFF715FB06210920FFF711FB0621F5 +:103430000A20FFF70DFB06211720FFF709FB0621E5 +:103440002820FFF705FBBDE8084007211C20FFF7F7 +:10345000FFBA000008B5FFF745FE00F00BF8FDF7D6 +:1034600053FEFDF72BFDFFF7A5FDBDE80840FFF774 +:10347000CFBC00000023054A19460133102BC2E9D6 +:10348000001102F10802F8D1704700BFE02D0020C2 +:10349000034611F8012B03F8012B002AF9D17047DC +:1034A00053544D3332463F3F3F0053544D33324621 +:1034B0003430780053544D3332463432780053540C +:1034C0004D33324634343658580000000120330062 +:1034D0000010410001105A0003105900071031007C +:1034E00000000000A034000813040000AA34000803 +:1034F00019040000B434000821040000BE340008A0 +:1035000000000000390E0008250E0008610E0008BA +:103510004D0E0008590E0008450E0008310E000837 +:103520001D0E00086D0E00080000000001000000E4 +:10353000000000006330000034350008F023002054 +:10354000002600204172647550696C6F740025423A +:103550004F415244252D424C002553455249414C80 +:1035600025000000020000000000000055100008C7 +:10357000C110000840004000A02A0020B02A00200E +:103580000200000000000000030000000000000036 +:10359000051100080000000010000000C02A0020F3 +:1035A000000000000100000000000000682D002065 +:1035B00001010200051C0008151B0008B11B0008D2 +:1035C000951B000843000000CC35000809024300A9 +:1035D000020100C0320904000001020201000524BA +:1035E0000010010524010001042402020524060044 +:1035F00001070582030800FF09040100020A000018 +:10360000000705010240000007058102400000009C +:1036100012000000183600081201100102000040DC +:1036200009124157000201020301000004030904CA +:1036300025424F4152442500466C79776F6F4634DE +:10364000303550726F0030313233343536373839D7 +:103650004142434445460000004000000040000055 +:1036600000400000004000000000010000000200D7 +:103670000000020000000200000002000000020042 +:1036800000000200000002000000000049120008D3 +:1036900001150008AD15000840004000C82D0020AD +:1036A000C82D002001000000D82D0020800000005F +:1036B00040010000030000006D61696E0069646CE8 +:1036C000650000000000842A00000000AAAAAAAA3F +:1036D00000000024FFFD00000000000000A00A0020 +:1036E0004000001100000000AAAAAAAA4000001190 +:1036F000FFFF0000000000000000000000000000CC +:1037000000000000AAAAAAAA00000000FFFF000013 +:1037100000000000000000000000000000000000A9 +:10372000AAAAAAAA00000000FFFF000000000000F3 +:10373000000000000000000000000000AAAAAAAAE1 +:1037400000000000FFFF000000000000000000007B +:103750000000000000000000AAAAAAAA00000000C1 +:10376000FFFF00000000000000000000000000005B +:1037700000000000AAAAAAAA00000000FFFF0000A3 +:103780000000000000000000000000000000000039 +:103790000A0000000000000003000000000000001C +:1037A0000000000000000000000000000000000019 +:1037B0000000000000000000000000000000000009 +:1037C000710400000000000000400F000000000035 +:1037D000FF009600000000080096000000000800AE +:1037E000040000002C36000800000000000000006B +:1037F00000000000000000000000000000000000C9 +:00000001FF diff --git a/Tools/bootloaders/FreeflyRTK_bl.bin b/Tools/bootloaders/FreeflyRTK_bl.bin index 823020ff3c3a83..08144e90fa3ee6 100755 Binary files a/Tools/bootloaders/FreeflyRTK_bl.bin and b/Tools/bootloaders/FreeflyRTK_bl.bin differ diff --git a/Tools/bootloaders/FreeflyRTK_bl.elf b/Tools/bootloaders/FreeflyRTK_bl.elf index 2d04211b44b259..64ba9bdb6458b6 100755 Binary files a/Tools/bootloaders/FreeflyRTK_bl.elf and b/Tools/bootloaders/FreeflyRTK_bl.elf differ diff --git a/Tools/bootloaders/FreeflyRTK_bl.hex b/Tools/bootloaders/FreeflyRTK_bl.hex index 24cd13692fe251..f96d350ee15827 100644 --- a/Tools/bootloaders/FreeflyRTK_bl.hex +++ b/Tools/bootloaders/FreeflyRTK_bl.hex @@ -1,1509 +1,1772 @@ :020000040800F2 -:100000000007002005050008351E0008B51D000882 -:100010000D1E0008B51D0008E11D000807050008B9 -:100020000705000807050008070500084146000805 -:100030000705000807050008070500080705000870 -:100040000705000807050008070500080705000860 -:1000500007050008070500086157000889570008D0 -:10006000B1570008D95700080158000807050008D3 -:100070000705000807050008070500080705000830 -:10008000070500080705000807050008ED2D000812 -:10009000592E0008AD2E0008012F0008295800082D -:1000A0000705000807050008070500080705000800 -:1000B000FD580008070500080705000807050008A7 -:1000C00007050008070500080705000807050008E0 -:1000D00007050008070500080705000807050008D0 -:1000E0008D580008070500080705000807050008E7 -:1000F00007050008070500080705000807050008B0 -:10010000070500080705000807050008070500089F -:10011000070500080705000807050008070500088F -:10012000070500080705000807050008070500087F -:10013000070500080705000807050008070500086F -:10014000070500080705000807050008F54D000829 -:10015000070500080705000807050008070500084F -:10016000070500080705000807050008070500083F -:10017000070500080705000807050008070500082F -:10018000070500080705000807050008070500081F -:10019000070500080705000807050008070500080F -:1001A00007050008070500080705000807050008FF -:1001B00007050008070500080705000807050008EF -:1001C00007050008070500080705000807050008DF -:1001D00007050008070500080705000807050008CF -:1001E00007050008070500080705000807050008BF -:1001F00007050008070500080705000807050008AF -:1002000053B94AB9002908BF00281CBF4FF0FF317D -:100210004FF0FF3000F074B9ADF1080C6DE904CE79 -:1002200000F006F8DDF804E0DDE9022304B07047D1 -:100230002DE9F047089D04468E46002B4DD18A4299 -:10024000944669D9B2FA82F252B101FA02F3C2F1CC -:10025000200120FA01F10CFA02FC41EA030E94405D -:100260004FEA1C48210CBEFBF8F61FFA8CF708FB7E -:1002700016E341EA034306FB07F199420AD91CEB56 -:10028000030306F1FF3080F01F81994240F21C8188 -:10029000023E63445B1AA4B2B3FBF8F008FB1033D0 -:1002A00044EA034400FB07F7A7420AD91CEB040405 -:1002B00000F1FF3380F00A81A74240F207816444D5 -:1002C000023840EA0640E41B00261DB1D44000235A -:1002D000C5E900433146BDE8F0878B4209D9002DBE -:1002E00000F0EF800026C5E9000130463146BDE848 -:1002F000F087B3FA83F6002E4AD18B4202D38242B2 -:1003000000F2F980841A61EB030301209E46002D60 -:10031000E0D0C5E9004EDDE702B9FFDEB2FA82F2B5 -:10032000002A40F09280A1EB0C014FEA1C471FFA13 -:100330008CFE0126200CB1FBF7F307FB131140EAFA -:1003400001410EFB03F0884208D91CEB010103F1C7 -:10035000FF3802D2884200F2CB804346091AA4B289 -:10036000B1FBF7F007FB101144EA01440EFB00FE5D -:10037000A64508D91CEB040400F1FF3102D2A645C2 -:1003800000F2BB800846A4EB0E0440EA03409CE761 -:10039000C6F12007B34022FA07FC4CEA030C20FA0E -:1003A00007F401FA06F31C43F9404FEA1C4900FA2E -:1003B00006F3B1FBF9F8200C1FFA8CFE09FB1811AB -:1003C00040EA014108FB0EF0884202FA06F20BD91E -:1003D0001CEB010108F1FF3A80F08880884240F26E -:1003E0008580A8F102086144091AA4B2B1FBF9F0B2 -:1003F00009FB101144EA014100FB0EFE8E4508D9AD -:100400001CEB010100F1FF346CD28E456AD9023831 -:10041000614440EA0840A0FB0294A1EB0E01A14216 -:10042000C846A64656D353D05DB1B3EB080261EB84 -:100430000E0101FA07F722FA06F3F1401F43C5E95E -:10044000007100263146BDE8F087C2F12003D84094 -:100450000CFA02FC21FA03F3914001434FEA1C47D6 -:100460001FFA8CFEB3FBF7F007FB10360B0C43EAC8 -:10047000064300FB0EF69E4204FA02F408D91CEB78 -:10048000030300F1FF382FD29E422DD90238634476 -:100490009B1B89B2B3FBF7F607FB163341EA034116 -:1004A00006FB0EF38B4208D91CEB010106F1FF3865 -:1004B00016D28B4214D9023E6144C91A46EA00465C -:1004C00038E72E46284605E70646E3E61846F8E6EE -:1004D0004B45A9D2B9EB020864EB0C0E0138A3E737 -:1004E0004646EAE7204694E74046D1E7D0467BE718 -:1004F000023B614432E7304609E76444023842E790 -:10050000704700BF02E000F000F8FEE772B63A481C -:1005100080F30888394880F3098839484EF6085135 -:10052000CEF20001086040F20000CCF200004EF66E -:100530003471CEF200010860BFF34F8FBFF36F8FAD -:1005400040F20000C0F2F0004EF68851CEF20001F9 -:100550000860BFF34F8FBFF36F8F4FF00000E1EEE5 -:10056000100A4EF63C71CEF200010860062080F3BE -:100570001488BFF36F8F04F021F904F0C3F804F07E -:100580009FFF4FF055301F491B4A91423CBF41F835 -:10059000040BFAE71C49194A91423CBF41F8040B8D -:1005A000FAE71A491A4A1B4B9A423EBF51F8040B0C -:1005B00042F8040BF8E700201749184A91423CBF63 -:1005C00041F8040BFAE704F0DBF804F0CDFF144C1B -:1005D000144DAC4203DA54F8041B8847F9E700F0E5 -:1005E00041F8114C114DAC4203DA54F8041B884712 -:1005F000F9E704F0C3B80000000700200023002042 -:10060000000000080001002000070020A85D00088D -:10061000002300207C23002080230020584000205D -:1006200000020008000200080002000800020008A2 -:100630002DE9F04F2DED108AC1F80CD0D0F80CD078 -:10064000BDEC108ABDE8F08F002383F311882846A3 -:10065000A047002003F07CFBFEE703F0F7FA00DF81 -:10066000FEE70000F8B503F079FF074603F0D4FF7A -:100670000546C0BB224B9F4235D001339F4235D047 -:10068000204B27F0FF029A4233D1F8B200F064FD0C -:100690002E4642F2107400F06DFF08B10024264689 -:1006A00000F060FD08B90646044635B1164B9F427E -:1006B00003D003F0A9FF00242646002003F058FFD2 -:1006C000124B1B695B0418D40EB100F067F801F0FF -:1006D00043FB00F0ADFF01F0E7F9204600F0F4F82D -:1006E00000F05CF8F9E72E460024D4E70446012622 -:1006F000D1E706464FF47A74CDE70024E7E700BF60 -:10070000010007B0000008B0263A09B00008024016 -:1007100008B501F09BF9A0F120035842584108BDEB -:1007200007B541F21203022101A8ADF8043001F02F -:10073000ABF903B05DF804FB10B5202383F31188F7 -:100740001248C3680BB103F089FB114A0F4800231C -:100750004FF47A7103F046FB002383F311880D4CAC -:10076000236813B12368013B2360636813B1636896 -:10077000013B6360084B1B7833B9636823B90220DF -:1007800001F064FA3223636010BD00BF80230020B3 -:10079000390700089C24002094230020F8B5434B1F -:1007A000434A1C46196801317ED004339342F9D183 -:1007B0006268404B9A4277D93F4B9B6803F10063D4 -:1007C00003F580339A426FD203F0F2FE03F004FF88 -:1007D000002001F083F9394B0220187001F02EFA45 -:1007E000374B00211A6C19641A6E19661A6E5A6C0E -:1007F00059645A6E59665A6E5A6942F080025A61BB -:100800005A6922F080025A615A691A6942F000520C -:100810001A611A6922F000521A611B6972B64FF010 -:10082000E023C3F8084DD4E90004BFF34F8FBFF3B2 -:100830006F8F244AC2F88410BFF34F8F536923F49B -:1008400080335361BFF34F8FD2F88030C3F3C905B3 -:10085000C3F34E335B0143F6E07603EA060C294608 -:100860004CEA81770139C2F87472F9D2203B13F156 -:10087000200FF2D1BFF34F8FBFF36F8FBFF34F8FB6 -:10088000BFF36F8F536923F4003353610023C2F821 -:100890005032BFF34F8FBFF36F8F202383F3118844 -:1008A000854680F308882047F8BD00BF0000010896 -:1008B00020000108FFFF00080023002094230020EF -:1008C0000038024000ED00E02DE9F04F93B0AC4B52 -:1008D00000902022FF210AA89D6801F0E7F9A94AAB -:1008E0001378A3B9A8480121C3601170202383F3B2 -:1008F0001188C3680BB103F0B1FAA44AA2480023DF -:100900004FF47A7103F06EFA002383F31188009B91 -:100910009F4A03B113609F49009C00230B705360F2 -:1009200098469B461E469A46012001F087F924B15D -:10093000974B1B68002B00F01C82002001F086F80A -:100940000390039B002B01DA00F024FF039B002B94 -:10095000EDDB012001F068F9039B213B162BE3D866 -:1009600001A252F823F000BFC5090008ED090008F4 -:10097000810A000829090008290900082909000836 -:10098000150B0008E70C0008010C0008630C0008B8 -:100990008B0C0008B10C000829090008C30C0008E2 -:1009A00029090008350D0008650A00082909000812 -:1009B000790D0008D1090008650A00082909000816 -:1009C000630C00080220FFF7A3FE002840F0FB8123 -:1009D000009B0221B8F1000F08BF1C4605A841F298 -:1009E0001233ADF8143001F04FF89DE74FF47A70F0 -:1009F00001F02CF8071EEBDB0220FFF789FE002830 -:100A0000E6D0013F052F00F2E081DFE807F0030A9E -:100A10000D10133605230593042105A801F034F8C1 -:100A200017E057480421F9E75B480421F6E75B48E3 -:100A30000421F3E74FF01C09484601F051F809F191 -:100A400004090590042105A801F01EF8B9F12C0F46 -:100A5000F2D1012000FA07F747EA0B0B5FFA8BFB94 -:100A60004FF0000A01F06EF926B10BF00B030B2BCF -:100A700008BF0024FFF754FE56E749480421CDE79C -:100A8000002EA5D00BF00B030B2BA1D10220FFF7FA -:100A90003FFE074600289BD001203E4E01F01EF885 -:100AA0000220307001F0CAF84FF000085FFA88F9B0 -:100AB000484601F023F8044690B1484601F02EF86C -:100AC00008F101080028F1D1B846044641F212139A -:100AD000022105A8ADF814303E4600F0D5FF23E70B -:100AE00001230220337001F09FF82546244B9B68B8 -:100AF000AB4207D9284600F0F3FF013040F068818F -:100B00000435F3E7234B00251D70214BB8465D608B -:100B10003E46A7E7002E3FF45BAF0BF00B030B2B19 -:100B20007FF456AF1B4B0220187001F087F832207B -:100B300000F08CFFB0F10009FFF64AAF19F003078F -:100B40007FF446AF0E4A926809EB050393423FF6E5 -:100B50003FAFB9F5807F3FF73BAF124B0193B945EB -:100B600022DD4FF47A7000F071FF0390039A002A9F -:100B7000FFF62EAF019B039A03F8012B0137EDE737 -:100B8000002300209824002080230020390700083B -:100B90009C2400209423002004230020082300200C -:100BA0000C23002098230020C820FFF7B1FD074642 -:100BB00000283FF40DAF1F2D11D8C5F120024A4582 -:100BC0000AAB25F0030028BF4A4683490192184426 -:100BD00001F046F8019A8048FF2101F067F84FEADA -:100BE000A9037D490193C9F38702284601F066F8FD -:100BF000064600283FF46AAF019B05EB830531E709 -:100C00000220FFF785FD00283FF4E2AE00F0B0FFC0 -:100C100000283FF4DDAE0027B946704B9B68BB420D -:100C200018D91F2F11D80A9B01330ED027F00303C8 -:100C300012AA134453F8203C05934846042205A900 -:100C400001F0FEF804378146E7E7384600F048FF38 -:100C50000590F2E7CDF81490042105A800F014FFE8 -:100C600000E70023642104A8049300F003FF002898 -:100C70007FF4AEAE0220FFF74BFD00283FF4A8AE94 -:100C8000049800F05DFF0590E6E70023642104A8C6 -:100C9000049300F0EFFE00287FF49AAE0220FFF7E5 -:100CA00037FD00283FF494AE049800F059FFEAE7BE -:100CB0000220FFF72DFD00283FF48AAE00F068FF08 -:100CC000E1E70220FFF724FD00283FF481AE05A9EB -:100CD000142000F063FF04210746049004A800F0EC -:100CE000D3FE3946B9E7322000F0B0FE071EFFF60A -:100CF0006FAEBB077FF46CAE384A926807EB0A030D -:100D000093423FF665AE0220FFF702FD00283FF454 -:100D10005FAE27F003075744BA453FF4A3AE5046F1 -:100D200000F0DEFE0421059005A800F0ADFE0AF1FA -:100D3000040AF1E74FF47A70FFF7EAFC00283FF469 -:100D400047AE00F015FF002844D00A9B01330BD0BA -:100D500008220AA9002000F0B1FF00283AD0202282 -:100D6000FF210AA800F0A2FFFFF7DAFC1C4802F0FE -:100D7000F5FF13B0BDE8F08F002E3FF429AE0BF065 -:100D80000B030B2B7FF424AE0023642105A80593ED -:100D900000F070FE074600287FF41AAE0220FFF72D -:100DA000B7FC814600283FF413AEFFF7B9FC41F2CF -:100DB000883002F0D3FF059800F0F6FF4E4600F0B1 -:100DC000C1FF3C46B0E506464CE64FF0000AFFE5A1 -:100DD000B8467BE6374679E69823002000230020BA -:100DE000A0860100094A136849F2690099B21B0CF8 -:100DF00000FB01331360064B186844F2506182B265 -:100E0000000C01FB0200186080B270472023002014 -:100E10001C23002010B500211022044600F046FFDC -:100E2000034B03CB206061601868A06010BD00BF59 -:100E3000107AF01F2DE9F043224DBBB000F0FCFF0B -:100E4000AB6840F2ED22C31A934232D906AFA860D4 -:100E50002B4628220021384601F0FCFC05F10E004B -:100E600000F01CFF002604465FFA80F905F10E0829 -:100E7000F3B2F100994501F1280107D908EB060307 -:100E80000822384601F0E6FC0136F1E7082301228A -:100E9000CDE9023205340C4B0193A4B23023009308 -:100EA000CDE9047405A3D3E90023297B074801F0A9 -:100EB000E9FA3BB0BDE8F083AFF3008078F6339FEA -:100EC00093CACD8DE8340020F5340020BC340020D6 -:100ED00070B50D4614461E4601F06AFA50B9022E4E -:100EE00010D1012C0ED112A3D3E90023C5E90023B0 -:100EF000012007E0282C10D005D8012C09D0052CA2 -:100F00000FD0002070BD302CFBD10BA3D3E9002300 -:100F1000ECE70BA3D3E90023E8E70BA3D3E9002315 -:100F2000E4E70BA3D3E90023E0E700BFAFF30080C1 -:100F3000401DA12026812A0B78F6339F93CACD8DC0 -:100F40009E6AC421818A46EE26417272DF25D7B798 -:100F5000F017304A39059E5613B504462346084615 -:100F600020220021019001F075FC22790198032ACA -:100F7000234628BF032203F8042F2021022201F078 -:100F800069FC62790198072A234628BF072203F8E3 -:100F9000052F2221032201F05DFCA2790198072A86 -:100FA000234628BF072203F8062F2521032201F03C -:100FB00051FC019804F108031022282101F04AFC99 -:100FC000382002B010BD00002DE9F04FADF5017DD5 -:100FD00021AD0EAE40F2751280460F4622A80021C8 -:100FE000296000F063FE48220021304600F05EFEDA -:100FF00000F022FF564B4FF47A72B0FBF2F018600B -:1010000093E80700012386E807000DF15A003382B8 -:10101000FFF700FF40F20443338407AB18464D4905 -:1010200004F0EAFC182230642946304686F83C2059 -:10103000FFF792FF12AB044601460822284601F052 -:1010400009FC0822A1180DF14903284601F002FC11 -:101050000DF14A03082204F11001284601F0FAFBC1 -:1010600013AB202204F11801284601F0F3FB14AB66 -:10107000402204F13801284601F0ECFB16AB0822AF -:1010800004F17801284601F0E5FB0DF1590308222F -:1010900004F18001284601F0DDFB04F1880A0DF11E -:1010A0005A0904F5847B4B465146082228460AF12A -:1010B000080A01F0CFFBD34509F10109F3D11BABBD -:1010C00008225946284601F0C5FB04F588744FF004 -:1010D000000996F834304B450AD9B36B21464B448E -:1010E0000822284601F0B6FB083409F10109F0E7AF -:1010F0004FF0000996F83C304B4504EBC90108D984 -:10110000336C08224B44284601F0A4FB09F1010985 -:10111000F0E700230393BB7E0293073107F1190325 -:101120000193C1F3CF010123CDE904510093F97E6E -:1011300005A3D3E90023404601F0A4F90DF5017D94 -:10114000BDE8F08FAFF300809E6AC421818A46EE2D -:10115000A4240020085A0008014B1870704700BFF3 -:10116000B02400202DE9FF41344B1F7B27B1344BC5 -:101170000E221A81002630E0324A1068516802AB14 -:1011800003C30823304931480DEB030204F012FC7D -:10119000044630B92A4B2E480A221A8100F006FE76 -:1011A000E8E70169B1F5E02F06D9254B29480B2264 -:1011B0001A8100F0FBFDDDE7438B40F20442552B22 -:1011C00018BF93420CBF012600260AD01C490C20F0 -:1011D00008812148194600F0E9FD304604B0BDE819 -:1011E000F0811E4A024402F11003994204D2144BCA -:1011F0001B4810221A81DCE710398D1A3846134932 -:1012000000F01EFE2A46804604F11801384600F020 -:1012100017FEA368984502D1E36898420AD0084BAC -:101220000D221A810090D4E9021243460D4800F0C5 -:10123000BDFD9FE70C4800F0B9FDCEE7E834002083 -:10124000A4240020B55A0008DCFF060000000108B5 -:10125000245A0008305A0008425A00080800FFF7D4 -:10126000605A00087D5A0008A65A00082DE9F04F80 -:10127000ADB006AF80460C4601F09AF8054600284E -:101280005AD1237E022B1BD1E38A012B18D100F007 -:10129000D3FD0646FFF7A6FD03464FF4C870DFF8FE -:1012A000D092B3FBF0F206F5167602FB103316FA75 -:1012B00083F3C9F80030E37E33B9A84B00221A70DB -:1012C0009C37BD46BDE8F08FA38AEEB2013BB34226 -:1012D00005F101050BD93B1D1E44E90000960023D2 -:1012E000082201F0F801204601F078F9ECE707F157 -:1012F0001400FFF78FFD324607F11401381D04F08A -:1013000049FB0028D9D10F2E08D8944B1E70D9F86C -:101310000030A3F51673C9F80030D1E7FB1CF87054 -:101320000146009307220346204601F057F9F97859 -:10133000404601F035F8C3E7E38A282B26D010D8C1 -:10134000012B1ED0052BBBD1BFF34F8F8449854B9A -:10135000CA6802F4E0621343CB60BFF34F8F00BF53 -:10136000FDE7302BACD1637E7F4D01336A7BDBB26E -:101370009342E94603D1E27E2B7B9A4265D0CD466B -:101380009EE721464046FFF71FFE99E7A38A013BEF -:101390009BB2C92B94D8744D2E7B26BB05F10C0350 -:1013A0000093082233463146204601F017F9731C9A -:1013B000F2B2D9001E46A38A013B9A4205DA0E32E8 -:1013C0002A44009200230822EEE700230022C5E908 -:1013D00000230023AB6085F8D730C5F8D8302B7BCD -:1013E0000BB9E37E2B73002507F114093B1D08227E -:1013F00029464846C7E90155FD6001F02BFA3B7AC2 -:1014000005F1010AAB424FEACA0608D9FB68082277 -:101410002B443146484601F01DFA5546EFE7C6F326 -:10142000CF06E17ECDE9049600230393A37E0293C9 -:10143000193428230093019446A3D3E9002340469E -:1014400001F020F8FFF7F6FC3AE74FF0000807F14B -:101450001403A7F81480102200934146012320466C -:1014600001F0BCF8A68A023EB6B2F31C9B109B00AA -:101470000733DB08A9EBC3039D460DF1180A1FFAD9 -:1014800088F34FEAC801B34201F110010AD20AEB16 -:101490000803009308220023204601F09FF808F17A -:1014A0000108ECE795F8D70000F028FBD5F8D83014 -:1014B00004461BB995F8D70000F030FBD5F8D830BA -:1014C00033449C4204D295F8D700013000F026FB4B -:1014D0004FEA960B4FF000081FFA88F18B45D5E9CB -:1014E000003209D90AEB880103EB8800012200F0E1 -:1014F000E5FB08F10108EFE7F31842F10002C5E946 -:101500000032D5F8D83095F8D70006EB0308C5F8B7 -:10151000D88000F0F3FA804509D395F8D730D5F894 -:10152000D8000133001B85F8D730C5F8D800FF2E4E -:1015300008D800232B7300F01BFBFFF713FE08B144 -:10154000FFF72CF92B68094A9B0A0133138100230A -:10155000AB6014E726417272DF25D7B7B53400209F -:1015600000ED00E00400FA05E8340020A424002087 -:10157000B834002030B54FF00054244B22689A4212 -:1015800085B007D003F052F80446A8B900242046DD -:1015900005B030BD1E4B627D1A701E48237D03735B -:1015A0001D49C9220E3000F05BFB2046E0220021DD -:1015B00000F07CFB0124EAE7184A194D136C43F054 -:1015C00000731364AA6D174B9A42DFD12B6E013B57 -:1015D0007E2BDBD8144A07CA01AB83E80700184604 -:1015E000032100F043FC6B6D83424FF00003CDD12B -:1015F0002A6D8A4201BFAB65054B2A6E1A7003BF84 -:101600000A4BEA6D1A601C46C1E700BF9AAD44C59B -:10161000B0240020E83400201600002000380240EA -:10162000006600405041A0B05866004018230020DA -:101630002DE9F0434B4C022385B0637100230293E4 -:10164000494B1F68B7F57A7F12D3484B4848B0FB27 -:10165000F7F09F428CBF0A2311235E1EB0FBF3F507 -:1016600003FB1502F1B2002A3ED0022E3346F4D815 -:101670009DF80B303F4940485A1E9DF80A30013B07 -:101680001B0443EA0253BDF80820013A13434B60A0 -:1016900001F098FD00230193384B394900933948F4 -:1016A000394B4FF4805200F055FE384B197811B188 -:1016B000344800F075FE00F0BFFB0546FFF792FBD3 -:1016C0004FF4C873B0FBF3F202FB130305F5167079 -:1016D00010FA83F02E4B186002F09EFF08B10F2322 -:1016E000238105B0BDE8F0836B1EB3F5806FBFD2D8 -:1016F000C1EBC10C0CF103034FEAE308C3F3C703CA -:10170000A1EB030E08F101094FF47A705FFA8EF62F -:1017100008FB000059FA8EFEB0FBFEF0B0F5617FC9 -:1017200008D90CF1FF33C3F3C703C91ACEB2591E4F -:101730000F2915D8721E072A8CBF00220122991981 -:1017400001FB05500A49B1FBF0F18F4290D1002A0C -:101750008ED0ADF808508DF80A308DF80B6087E711 -:101760001346ECE7A4240020182300203F420F007A -:1017700080F937031023002000360020D10E000826 -:10178000B4240020BC3400206D120008B0240020D6 -:10179000B83400202DE9F04F91A7D7E900670FF288 -:1017A0004829D9E90089874D93B0DFF844B2864CC7 -:1017B000284600F0CBFE0DF1300A079070B31022DE -:1017C0000021504600F072FA079B197B4FF000028F -:1017D00061F303028DF83020586899680EAA03C29D -:1017E0001B680D9A63F31C029DF830300D9243F094 -:1017F00020038DF83030002352461946584601F038 -:10180000F1FC079028B9284600F0A4FE079B23703E -:10181000CEE72378072B3CD8013323701822002110 -:10182000504600F043FADFF8C8B1684C002319466F -:101830005246584601F0FEFC014670BB102208A833 -:1018400000F034FA636983F04003636100F0F6FA54 -:101850000B4612A9024611E903000DF1240C8CE895 -:1018600003009DF83410C1F3030089064CBF0E99A4 -:10187000BDF838C08DF82C0046BFC1F31C0C4CF0ED -:101880000041CCF30A010891284608A901F02AF882 -:10189000CCE7284600F05EFEC0E7284600F088FD51 -:1018A0000446002848D1DFF84CB100F0C5FADBF857 -:1018B0000030984240D300F0BFFA0790FFF792FA49 -:1018C000079A8DF8204003464FF4C87002F516724F -:1018D000B3FBF0F101FB103312FA83F3CBF80030C5 -:1018E000DFF814B19BF8001011B901238DF82030F6 -:1018F00050460791FFF78EFA0799C1F11004E4B240 -:10190000062C28BF0624224651440DF1210000F088 -:10191000A7F908AB03931823029301342C4B0193CE -:10192000E4B20123009304943B463246284600F07B -:1019300041FD00238BF8003000F07EFA254A264C4A -:101940001368C31AB3F57A7F31D3106000F076FACA -:1019500002460B46284600F007FE284600F028FD08 -:1019600028B3237BDFF894B0002B14BF032302239A -:101970008BF8053000F060FA4FF47A735146B0FBF3 -:10198000F3F0CBF800005846FFF7E6FA18230730CB -:101990000293124B0193C0F3CF0040F25513CDE9EF -:1019A00003A0009342464B46284600F003FD237BEC -:1019B0002BB1FFF73FFA237B002B7FF4F6AE13B079 -:1019C000BDE8F08FBC340020CD350020000002407F -:1019D000B4340020C8350020E8340020CC35002085 -:1019E000401DA12026812A0BF1C6A7C1D068080F8F -:1019F00000360020B8340020B5340020A424002094 -:101A000070B50F4B1B780133DBB2012B0C4611D89C -:101A10000C4D29684FF47A730E6AA2FB033201461B -:101A200022462846B047844204D1074B00221A7050 -:101A3000012070BD4FF4FA7002F090F90020F8E731 -:101A400024230020E8370020FC35002007B50023C0 -:101A5000024601210DF107008DF80730FFF7D0FF96 -:101A600020B19DF8070003B05DF804FB4FF0FF3094 -:101A7000F9E700000A4608B50421FFF7C1FF80F02E -:101A80000100C0B2404208BD30B4054C2368DD6996 -:101A9000044B0A46AC460146204630BC604700BFB6 -:101AA000E8370020A086010070B502F0F7FB094E70 -:101AB000094D3080002428683388834208D902F019 -:101AC000E7FB2B6804440133B4F5803F2B60F2D36D -:101AD00070BD00BFFE350020D035002002F0A2BC52 -:101AE00000F1006000F580300068704700F1006090 -:101AF000920000F5803002F01FBC0000054B1A6810 -:101B0000054B1B889B1A834202D9104402F0C0BBCC -:101B100000207047D0350020FE35002038B5074D35 -:101B200004462868204402F0BBFB28B928682044FA -:101B3000BDE8384002F0CCBB38BD00BFD035002036 -:101B400010F003030AD1B0F5047F05D200F1005074 -:101B5000A0F57920D0F80038184670470023FBE73D -:101B600000F10050A0F57920D0F8100A704700006D -:101B7000064991F8243033B10023086A81F82430F3 -:101B80000822FFF7B3BF0120704700BFD435002003 -:101B9000014B1868704700BF002004E0F0B5204BEF -:101BA000024618681F4B1F885D6893F90840C0F310 -:101BB0000B06BE424FEA104022D09F89BE4221D080 -:101BC0001F8BBE4206D102240C2505FB04335D6841 -:101BD00093F90840B0F5805F16D041F201039842B6 -:101BE00008BF5A24013A0A44013D0B4693420DD2E4 -:101BF00015F9016F581C5EB100F8016C0346F5E75A -:101C00000024E1E70124DFE74124EBE7184605E083 -:101C10002C2590421D7001D2981C5C70401AF0BDBA -:101C2000002004E028230020022802BF024B4FF4CA -:101C300080029A61704700BF00000240022802BF84 -:101C4000014B40229A61704700000240022801BF08 -:101C5000024A536983F04003536170470000024019 -:101C600010B50023934203D0CC5CC4540133F9E790 -:101C700010BD000010B5013810F9013F3BB191F9DA -:101C800000409C4203D11AB10131013AF4E71AB184 -:101C900091F90020981A10BD1046FCE70346024651 -:101CA000D01A12F9011B0029FAD1704702440346E9 -:101CB000934202D003F8011BFAE770472DE9F8437D -:101CC0001F4D144695F824200746884652BBDFF87E -:101CD00070909CB395F824302BB92022FF21484600 -:101CE0002F62FFF7E3FF95F82400C0F10802A2423B -:101CF00028BF2246D6B24146920005EB8000FFF78E -:101D0000AFFF95F82430A41B1E44F6B2082E1744EA -:101D10009044E4B285F82460DBD1FFF729FF002866 -:101D2000D7D108E02B6A03EB82038342CFD0FFF7C1 -:101D30001FFF0028CBD10020BDE8F8830120FBE77E -:101D4000D4350020024B1A78024B1A70704700BF3E -:101D5000FC3500202423002010B50F4C0F4801F063 -:101D60000BFB21460D4801F033FB24680C48E26E62 -:101D7000D2F8043843F00203C2F8043801F0EEFF51 -:101D80000849204601F02CFCE26ED2F8043823F01A -:101D90000203C2F8043810BDB05B0008E837002029 -:101DA00040420F00B85B0008704700000FB40020ED -:101DB00004B0704700B59BB0EFF309816822684614 -:101DC000FFF74EFFEFF30583044B9A6BDA6A9A6ACA -:101DD0009A6A9A6A9A6A9A6A9B6AFEE700ED00E03C -:101DE00000B59BB0EFF3098168226846FFF738FF22 -:101DF000EFF30583044B9A6B9A6A9A6A9A6A9A6A15 -:101E00009A6A9B6AFEE700BF00ED00E000B59BB058 -:101E1000EFF3098168226846FFF722FFEFF305839D -:101E2000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE7A5 -:101E300000ED00E0FEE7000002F02EBB02F006BB62 -:101E400030B5094D0A4491420DD011F8013B58407C -:101E5000082340F30004013B2C4013F0FF0384EA05 -:101E60005000F6D1EFE730BD2083B8EDF7B54FF065 -:101E7000FF33DFF854C0DFF854E000EB81011A466D -:101E800088421CD050F8044B019401AF042417F889 -:101E9000015B82EA05620825DB18164605F1FF356D -:101EA0005241002EBCBF83EA0C0382EA0E0215F0F9 -:101EB000FF05F1D1013C14F0FF04E8D1E0E7D8437D -:101EC000D14303B0F0BD00BF9336EAA9EBE1F04285 -:101ED0002DE9F041C56915B9C161BDE8F0814B68D4 -:101EE00023F06047C3F38A464FEAD37EC3F380787A -:101EF00016EA230638BF3E46AC462B465A68BEEB70 -:101F0000D27F22F060440AD0002A18DAA40CB4422E -:101F100017D19D420FD10D60DEE71346EEE7A742D1 -:101F200007D102F08044C2F3807242450BD054B115 -:101F3000EFE708D2EDE7CCF800100B60CDE7B44234 -:101F400001D0B442E5D81A689C46002AE5D1196050 -:101F5000C3E700002DE9F047089D01F007044FEAB0 -:101F6000D508224405F0070500EBD1004FF47F4966 -:101F7000944201D1BDE8F08704F0070705F0070A95 -:101F800057453E4638BF5646C6F10806111B8E42DD -:101F900028BF0E46E10808EBD50E415C13F80EC0D1 -:101FA000B94029FA06F721FA0AF1FFB28CEA0101D9 -:101FB00047FA0AF739408CEA010C03F80EC03444A2 -:101FC0003544D5E780EA0120082341F2210201B21D -:101FD0004000002980B203F1FF33B8BF504013F036 -:101FE000FF03F4D17047000038B50C468D18A542A8 -:101FF00000D138BD14F8011BFFF7E4FFF7E700003C -:1020000002684AB113680360C388018901339BB237 -:102010009942C38038BF03811046704770B588B0BD -:10202000202204460D4668460021FFF73FFE204669 -:102030000495FFF7E5FF024658B16B46054608AE2A -:102040001C4603CCB44228606960234605F10805AC -:10205000F6D1104608B070BD082817D909280CD051 -:102060000A280CD00B280CD00C280CD00D280CD032 -:102070000E2814BF4020302070470C2070471020DD -:1020800070471420704718207047202070470000C8 -:10209000082817D90C280CD910280CD914280CD9C9 -:1020A00018280CD920280CD930288CBF0F200E20DE -:1020B0007047092070470A2070470B2070470C209A -:1020C00070470D207047000010B54B6823B9CA8ACD -:1020D00063F30902CA8210BDC4681A681C60C36039 -:1020E000438A013B43824A60EFE700002DE9F84F45 -:1020F0001D46CB8A0F46C3F3090106298146924645 -:102100000B4630D00020AAB207F119049EB2052E6A -:102110001FFA80F80FD8904503F1010306D3FB8A1C -:102120000A4462F30903FB8201201AE01AF80060F6 -:10213000E6540130EAE79045F1D2A1F1060B1C23E9 -:102140007C68BBFBF3F203FB12BB1FFA8BF6002C7F -:1021500045D14846FFF754FF044638B978606FF020 -:102160000200BDE8F88F4FF00008E6E700260660A1 -:102170007860ADB24FF0000B454510D90AEB08036B -:10218000221D13F8011B9155B1B208F101081B295A -:102190001FFA88F82BD0454506F10106F1D8FB8AD5 -:1021A000C3F30902154465F30903BCE7013292B297 -:1021B0001C462368002BF9D1AB1F0B441C21B3FB39 -:1021C000F1F301339BB29A42D3D2BBF1000FD0D1CD -:1021D0004846FFF715FF20B9C4F800B0BFE7012259 -:1021E000E7E7C0F800B05E4620600446C1E7454519 -:1021F000D5D94846FFF704FF08B92060AFE7C0F81B -:1022000000B0002620600446B6E700002DE9F04F3C -:102210002DED028B83B0CDE90013BDF83C5007468D -:102220009146002A00F092802DB10E9B002B00F009 -:102230008D80072D32D807F10C00FFF7E1FE044630 -:1022400038B96FF00204204603B0BDEC028BBDE844 -:10225000F08F14220021FFF729FD0E992A4604F180 -:102260000800FFF7FDFC681CC0B2FFF711FFFFF785 -:10227000F3FE207499F80030013814FA80F003F06E -:102280001F0363F03F030372009B43F00041616052 -:1022900038462146FFF71CFE0124D4E700F10C0369 -:1022A0004FF0000808EE103A4FF0800A46464446C8 -:1022B00018EE100AFFF7A4FE83460028C1D01422AE -:1022C0000021FFF7F3FCC6BB019BABF808300220EE -:1022D0000E9B00F1080299195BFA82F20130C0B23C -:1022E000082801D0AE422AD3FFF7D2FEFFF7B4FE92 -:1022F00099F80020009B411E02F01F0242EA48129A -:10230000AE4208BF4FF0400A5BFA81F14AEA020A86 -:1023100043F0004281F808A08BF81000CBF80420AD -:1023200059463846FFF7D4FD0134AE4224B288F056 -:1023300001084FF0000ABBD185E70020C8E711F87B -:1023400001CB02F801CB0136B6B2C7E76FF001044A -:1023500079E70000F8B515460E462822002104460C -:102360001F46FFF7A3FC069B6360B5F5001F079BA4 -:10237000A76034BF6A094FF6FF72236204F10C00B4 -:1023800097B200239A4205D8002303602782638214 -:10239000A382F8BD0660013330462036F2E7000024 -:1023A00003781BB94BB2002BC8BF01707047000007 -:1023B000007870472DE9F74FDDF83C90BDF83050BC -:1023C0000D9E9DF83840BDF84070804692469B4671 -:1023D000B9F1000F01D1002F51D11F2C4FD898F81F -:1023E0000000B0B9072F47D835F0030347D13A466C -:1023F00049464FF6FF70FFF7F7FD20F001002D0270 -:10240000400445EA0464400C44EA40244FF6FF735C -:1024100021E040EA0520072F40EA0464F6D90025B0 -:102420004FF6FF73C5F12000A5F120022AFA05F14D -:102430000BFA00F001432BFA02F211431846C9B21D -:10244000FFF7C0FD0835402D0346EBD13A4649461B -:10245000FFF7CAFD0346CDE90097324621464046C4 -:10246000FFF7D4FE33780133DBB21F2B88BF002384 -:10247000337003B0BDE8F08F6FF00300F9E76FF041 -:102480000100F6E72DE9F04F85B09246DDF848806F -:102490000F9D9DF840209DF84490BDF84C70064675 -:1024A0009B46B8F1000F01D1002F48D11F2A46D812 -:1024B0003378002B46D00C0244EA02649DF83810B1 -:1024C00044EAC93444EA01441C43072F44F0800421 -:1024D00032D900234FF6FF72C3F1200CA3F1200084 -:1024E0002AFA03F10BFA0CFC41EA0C012BFA00F07A -:1024F0000143C9B210460393FFF764FD039B083301 -:10250000402B0246E8D13A464146FFF76DFD0346AF -:10251000CDE900872A4621463046FFF777FEB9F11C -:10252000010F06D12B780133DBB21F2B88BF0023AC -:102530002B7005B0BDE8F08F4FF6FF73E8E76FF042 -:102540000100F6E76FF00300F3E70000C06900B197 -:1025500004307047C3691A68C261C2681A60C360F8 -:10256000438A013B438270472DE9F041D0F818803F -:10257000194E14461D464146002709B9BDE8F081B1 -:10258000D1E90223A21A65EB0303964277EB03031A -:102590001ED283698B420DD1FFF796FD83691B68BC -:1025A0008361C3680B60438AC1608169013B4382D8 -:1025B0008846E2E7FFF788FD0B68C8F80030C3687B -:1025C0000B60438AC160013B4382D8F80010D4E716 -:1025D00088460968D1E700BF80841E002DE9F04FCE -:1025E0008BB00D46DDF8509014469B46804600287F -:1025F00000F01981B9F1000F00F01581531E3F2B37 -:1026000000F21181012A03D1BBF1000F40F00B81D0 -:102610000023CDE90833B8F81430B5EBC30F4FEA07 -:10262000C30703D300200BB0BDE8F08F2B199F42E6 -:10263000D8F80C303ABF7F1BFFB227461BB9D8F839 -:102640001030002B7AD02F2D4ED8C5F13006B7426E -:102650004FF000032CBFF6B23E4600932946D8F84F -:10266000080008AB3246FFF775FCA7EB060A3544B5 -:102670005FFA8AFAB8F8143003F10053063BDB0026 -:102680000493D8F80C3003933021039B13B1BAF1B3 -:10269000000F2CD1D8F8100040B1BAF1000F05D0CE -:1026A000009608AB5246691AFFF754FC38B2002F67 -:1026B000B8D066070AD00AAB03EBD401624211F826 -:1026C000083C02F00702134101F8083C082C3CD9F1 -:1026D000102C40F2B580202C40F2B780BBF1000FE7 -:1026E00000F09C80082334E0BA460026C2E7049B31 -:1026F000E02B28BFE02306930B44AB42059314D98B -:102700005A1B03980096924534BF5246D2B2691ABA -:1027100008AB04300792FFF71DFC079A1644AAEB9A -:10272000020A1544F6B25FFA8AFA049B069A0599E2 -:102730009B1A0493039B1B680393A6E70093D8F8A6 -:10274000080008AB3A462946AEE7BBF1000F13D0AC -:102750000123B4EBC30F6CD0082C12D89DF82030A5 -:10276000621E23FA02F2D50706D54FF0FF3202FAB5 -:1027700004F423438DF820309DF8203089F8003090 -:1027800051E7102C12D8BDF82030621E23FA02F255 -:10279000D10706D54FF0FF3202FA04F42343ADF817 -:1027A0002030BDF82030A9F800303CE7202C0FD8AD -:1027B0000899631E21FA03F3DA0705D54FF0FF32BB -:1027C00002FA04F40C430894089BC9F800302AE785 -:1027D000402C2BD0DDE90865611EC4F12102A4F173 -:1027E000210326FA01F105FA02F225FA03F3114357 -:1027F0001943CB0712D50122A4F12003C4F1200113 -:1028000002FA03F322FA01F1A240524243EA010321 -:1028100063EB430332432B43CDE90823DDE908236F -:10282000C9E90023FFE66FF00100FCE66FF0080045 -:10283000F9E6082CA0D9102CB3D9202CEED8C3E788 -:10284000BBF1000FADD0022383E7BBF1000FBBD07B -:1028500004237EE730B5012A144638BF0124402CFA -:1028600085B028BF40240025012ACDE9025518D89B -:102870001B788DF8083063070AD004AB03EBD4054E -:10288000624215F8083C02F00702934005F8083C44 -:10289000009103462246002102A8FFF75BFB05B02A -:1028A00030BD082AE4D9102A03D81B88ADF80830B7 -:1028B000E1E7202A8DBFD3E900231B680293CDE90D -:1028C0000223D8E710B5CB681BB98B600B618B82F4 -:1028D00010BDC4681A681C60C360438A013B438210 -:1028E000CA60F0E72DE9F04FD1F8008093B018F0FE -:1028F000800FCDE90323C8F3C01219BFC8F3C03B52 -:10290000C8F306264FF0020B1646B8F1000F044636 -:102910000D4680F2D18118F0C043059340F0CC8180 -:102920000B7B002B00F0C881BBF1020F03D00178B4 -:10293000B14240F0C48108F07F0106916AB3C8F348 -:10294000074A2B44069A93F80390760646EA0B460C -:1029500046EA82465FEAD91346EA0A06079300F080 -:10296000908000220023CDE90A23069B009367682C -:102970005B4652460AA92046B84700287ED0A76980 -:102980009FB9314604F10C00FFF748FB0746E0B958 -:102990006FF0020013B0BDE8F08FC8F30F2A18F0F3 -:1029A0007F0F08BF0AF0030ACBE73B699E420DD0B8 -:1029B0003F68002FF9D1314604F10C00FFF72EFBE0 -:1029C00007460028E4D0A3693B60A761DDE90A233C -:1029D00000264FF6FF70C6F1200E22FA06F103FA28 -:1029E0000EFEA6F1200C23FA0CFC41EA0E0141EA8E -:1029F0000C01C9B2083609920893FFF7E3FA402E9A -:102A0000DDE90832E7D1B882FB7D09F01F06C3F388 -:102A100084039B1BD7E9022198B2002BBCBF00F1B5 -:102A200020031BB252EA0100C8F304680FD00398D8 -:102A3000821A049860EB0101A74890424FF000020F -:102A40008A4104D3079A002A5BD0012B23DDFA7D4B -:102A50004FEA890302F0030203F07C031343FB7582 -:102A600039462046FFF730FB079BA3B9FB7DC3F334 -:102A70008402013262F38603FB7504E06FF00B0001 -:102A800088E7A76917B96FF00C0083E73B699E429E -:102A9000BAD03F68F6E719F0400F32D0039BBB6015 -:102AA000049BFB60142200210DA8FFF7FFF8039B95 -:102AB0000A93049B0B932B1D0C932B7BADF83EA02C -:102AC000013BDBB2ADF83C30069B8DF8433094F807 -:102AD00024308DF840B083F001038DF844308DF838 -:102AE0004160A3688DF842800AA920469847FB7D83 -:102AF000C3F38403013303F01F039B02FB82002016 -:102B000048E7FB7DC9F34012B2EBD31F40F0DA80F7 -:102B1000C3F38403B34240F0D88007992B7B4FEA7C -:102B20009912002934D0D20741D4032B40F2D0802F -:102B3000039BBB60049BFB602B7BAE1D033BDBB2A6 -:102B40003246394604F10C00FFF7D0FA00280DDABE -:102B500020463946FFF7B8FAFB7DC3F384030133FF -:102B600003F01F039B02FB82032013E7AB883B8328 -:102B70002A7B033AB88AD2B23146FFF735FAFB7D99 -:102B8000B882DA43C2F3C01262F3C713FB75B6E72B -:102B90006AB92E1D013BDBB23246394604F10C0006 -:102BA000FFF7A4FA0028D3DB2A7B013AE2E7F98A8F -:102BB000C1F30901013B0529DAB259D8281D0023C8 -:102BC00007F11A0C9A4208D910F801EB0CF801E051 -:102BD000013101330629DBB2F4D103990A9104993A -:102BE0000B91934207F11A010C9138BF04337968B5 -:102BF0000D9134BF55FA83F300230E93FB8AADF891 -:102C00003EA0C3F309031A44069B8DF8433094F8A1 -:102C10002430ADF83C2083F001038DF844300023CC -:102C20008DF840B08DF841608DF842807B602A7B42 -:102C3000B88A013A291DFFF7D7F93B8BB882834246 -:102C400003D1A3680AA92046984720460AA9FFF79E -:102C500039FEFB7DB88AC3F38403013303F01F03FD -:102C60009B02FB823B8B984214BF1120002091E60F -:102C70007B68002BB1D0062001E01C306346D3F8FE -:102C800000C0BCF1000FF8D1091A081D05F1040CB1 -:102C900000EB030905989DF8143001EB000EBEF11E -:102CA0001B0F9AD89A4298D91CF8013B09F8013BAE -:102CB000059B01330593EDE76FF009006AE66FF0BD -:102CC0000A0067E66FF00D0064E66FF00E0061E643 -:102CD0006FF00F005EE600BF80841E00404BF0B531 -:102CE0001C6C404E44F000741C641D6E45F0007571 -:102CF0001D661B6E3C4B9B6AD3F80052354045F075 -:102D00000105C3F80052D3F80042344044EA0020E1 -:102D100040F00100C3F80002002952D00020C3F89F -:102D20001C020546C3F80402C3F80C02C3F81402DF -:102D300003EBC00401301C28C4F84052C4F84452CC -:102D4000F6D100254FF0010C96781488F70748BF9C -:102D5000D3F804720CFA04F044BF0743C3F80472BA -:102D6000B70742BFD3F80C720743C3F80C7276075B -:102D700042BFD3F814620643C3F8146203EBC404E1 -:102D80005668C4F840629668C4F84462D3F81C429E -:102D900001352043A942C3F81C0202F10C02D3D131 -:102DA000D3F8002222F00102C3F800220C4B1A6C67 -:102DB00022F000721A641A6E22F000721A661B6EFC -:102DC000F0BD0122C3F84012C3F84412C3F8041244 -:102DD000C3F81412C3F80C22C3F81C22E0E700BFAA -:102DE000003802400000FFFF00360020184A916AB8 -:102DF00008B58B688B6013F0010104D013F00C0F41 -:102E000018BF4FF48031D80506D513F4406F14BFB6 -:102E100041F4003141F00201D80306D513F4402FEC -:102E200014BF41F4802141F00401D3690BB108487B -:102E30009847202383F311880648002100F0B6FF4D -:102E4000002383F31188BDE8084001F031BC00BFC6 -:102E5000003600200836002038B5124CA36ADD6821 -:102E6000AA0712D05A6922F002025A61A36913B16B -:102E7000012120469847202383F311880A48002126 -:102E800000F094FF002383F31188EB0606D5A36AB4 -:102E90001021D960236A0BB102489847BDE8384039 -:102EA00001F006BC003600201036002038B5124C68 -:102EB000A36A1D69AA0712D05A6922F010025A614A -:102EC000A36913B1022120469847202383F3118878 -:102ED0000A48002100F06AFF002383F31188EB0603 -:102EE00006D5A36A10211961236A0BB102489847DD -:102EF000BDE8384001F0DCBB003600201036002071 -:102F000038B50F4CA36A5D685D602A070AD50422B4 -:102F100022701A6822F002021A60636A13B100215B -:102F2000204698476B0706D5A36A9969236A13B1AF -:102F3000034809049847BDE8384001F0B9BB00BF19 -:102F40000036002010B50E4C204600F029F90D4B3C -:102F5000A3620B21132000F00BF90B21142000F0C9 -:102F600007F90B21152000F003F90B21162000F0C2 -:102F7000FFF80022BDE8104011461C20FFF7AEBE4E -:102F80000036002000640040114B984210B5044602 -:102F900009D1104B1A6C42F000721A641A6E42F09A -:102FA00000721A661B6EA36A01221A60A36A5A682D -:102FB000D20707D5626851681268D9611A60064A5B -:102FC0005A6110BD0121082000F0DCFDEEE700BFD2 -:102FD00000360020003802405B87010003291AD820 -:102FE000DFE801F0020A0F14836A9B6813F0E05FC8 -:102FF00014BF012000207047836A9868C0F3806086 -:103000007047836A9868C0F3C0607047836A9868A5 -:10301000C0F30070704700207047000010B503290E -:1030200025D8DFE801F00225292D836A9968C1F3CC -:103030000161183103EB0113107884064CBF54680A -:103040009488C0F300114FEA410148BF41EAC4012E -:1030500000F00F004CBF41F0040141EA44515860B8 -:1030600041F001019068D2689860DA60196010BD83 -:10307000836A03F5C073DFE7836A03F5C873DBE790 -:10308000836A03F5D073D7E701290AD002290FD04C -:1030900081B9836ADA68920701D1186903E00120D7 -:1030A0007047836AD86810F0030018BF012070478A -:1030B000836AF2E70020704710B539B9836AD9688E -:1030C00089071BD11B699C0704D110BD012915D0AC -:1030D0000229FAD1816AD1F8C031D1F8C441D1F8BE -:1030E000C8011061D1F8CC01506120200861086945 -:1030F000800717D1486940F0100012E0816AD1F8CA -:10310000B031D1F8B441D1F8B8011061D1F8BC01A7 -:1031100050612020C860C868800703D1486940F02A -:1031200002004861C3F34000C3F38001000140EA9C -:103130004111107920F030000143117189064BBF15 -:1031400091681189DB085B0D4CBF63F31C0163F3CD -:103150000A01137948BF916064F3030313714FEAC6 -:1031600014234FEA144458BF118113705480ACE704 -:1031700000F1604303F561430901C9B283F800130C -:10318000012200F01F039A4043099B0003F16043B2 -:1031900003F56143C3F880211A607047FFF7D2BE80 -:1031A000012300F10802C0E90222037000F11002BD -:1031B0000023C0E90422C0E90633C0E908334360B4 -:1031C0007047000010B52023044683F311880223C2 -:1031D00003704160FFF7D8FE04232370002383F3BC -:1031E000118810BD2DE9F0411F4604460D461646D4 -:1031F000202383F3118800F108082378052B0DD0D4 -:1032000029462046FFF7EAFE40B1204632462946CD -:10321000FFF704FF002080F3118808E0394640469C -:1032200000F0A8FD0028E8D0002383F31188BDE852 -:10323000F08100002DE9F0411F4604460D46164678 -:10324000202383F3118800F110082378052B0DD07B -:1032500029462046FFF718FF40B12046324629464E -:10326000FFF72AFF002080F3118808E03946404626 -:1032700000F080FD0028E8D0002383F31188BDE82A -:10328000F0810000026843681143016003B11847F0 -:103290007047000013B5446BD4F894341A68117861 -:1032A000042915D1217C022912D11979128901230F -:1032B0008B4013420CD101A904F14C0002F006F836 -:1032C000D4F89444019B21790246206800F0D4F997 -:1032D00002B010BD143001F089BF00004FF0FF3381 -:1032E000143001F083BF00004C3002F05BB80000E6 -:1032F0004FF0FF334C3002F055B80000143001F0AD -:1033000057BF00004FF0FF31143001F051BF0000F3 -:103310004C3002F027B800004FF0FF324C3002F082 -:1033200021B800000020704710B5D0F894341A6816 -:1033300011780429044617D1017C022914D1597946 -:10334000528901238B4013420ED1143001F0EAFE62 -:10335000024648B1D4F894444FF4807361792068F0 -:10336000BDE8104000F076B910BD0000406BFFF7DB -:10337000DBBF0000704700007FB5124B03600023E5 -:103380004360C0E90233012502260F4B0574044651 -:103390000290019300F18402294600964FF4807355 -:1033A000143001F09BFE094B0294CDE9006304F553 -:1033B00023724FF48073294604F14C0001F062FF40 -:1033C00004B070BDEC5A00086D3300089532000857 -:1033D0000B68202282F311880A7903EB82021062C3 -:1033E0004A790D3243F822008A7912B103EB820345 -:1033F000186202230374C0F89414002383F3118825 -:103400007047000038B5037F044613B190F854307C -:10341000ABB9201D01250221FFF734FF04F1140090 -:1034200025776FF0010100F0C1FC84F8545004F1DD -:103430004C006FF00101BDE8384000F0B7BC38BD6A -:1034400010B5012104460430FFF71CFF0023237749 -:1034500084F8543010BD000038B5044600251430FF -:1034600001F054FE04F14C00257701F023FF201DEC -:1034700084F854500121FFF705FF2046BDE838408D -:10348000FFF752BF90F85C3003F06003202B07D1A8 -:1034900090F85D20212A4FF0000303D81F2A06D898 -:1034A00000207047222AFBD1C0E9143303E0034A0D -:1034B0000265072242658365012070474C23002086 -:1034C00037B5D0F894341A681178042904461AD113 -:1034D000017C022917D11979128901238B401342EB -:1034E00011D100F14C05284601F0A4FF58B101A903 -:1034F000284601F0EBFED4F89444019B2179024662 -:10350000206800F0B9F803B030BD0000F0B500EB62 -:10351000810385B01E6A04460D46FEB1202383F365 -:10352000118804EB8507301D0821FFF7ABFEFB680F -:103530005B691B6806F14C001BB1019001F0D4FEE1 -:10354000019803A901F0C2FE024648B1039B294637 -:10355000204600F091F8002383F3118805B0F0BDF8 -:10356000FB685A691268002AF5D01B8A013B134098 -:10357000F1D104F15C02EAE70D3138B550F8214091 -:10358000DCB1202383F31188D4F894241368527992 -:1035900003EB8203DB689B695D6845B10421601819 -:1035A000FFF770FE294604F1140001F0C5FD204626 -:1035B000FFF7BAFE002383F3118838BD704700007F -:1035C00001F072B910B501230446282200F8243B0B -:1035D0000021FEF76BFB0023C4E9013310BD00009E -:1035E00038B50446202383F311880025C0E903552C -:1035F000C0E90555C0E90755416001F065F90223AE -:10360000237085F3118838BD70B500EB8103054642 -:103610005069DA600E46144618B110220021FEF7F8 -:1036200045FBA06918B110220021FEF73FFB31468F -:103630002846BDE8704001F011BA0000826802F02F -:10364000011282600022C0E90422C0E9062202625F -:1036500001F090BAF0B400EB81044789E4680125D9 -:10366000A4698D403D43458123600023A2606360CF -:10367000F0BC01F0ABBA0000F0B400EB81040789A4 -:10368000E468012564698D403D4305812360002382 -:10369000A2606360F0BC01F025BB000070B502239E -:1036A000002504460370C0E90255C0E90455C0E98D -:1036B00006554566056280F84C5001F06BF9636869 -:1036C0001B6823B129462046BDE87040184770BDED -:1036D000037880F868300523037043681B6810B5D1 -:1036E00004460BB1042198470023A36010BD0000DD -:1036F00090F86820436802701B680BB105211847D9 -:103700007047000070B590F84C30044613B10023A8 -:1037100080F84C3004F15C02204601F04DFA6368F9 -:103720009B68B3B994F85C3013F0600535D0002184 -:10373000204601F0B5FC0021204601F0A7FC63689B -:103740001B6813B1062120469847062384F84C30A5 -:1037500070BD204698470028E4D0B4F86230626D0E -:103760009A4288BF636594F95C30656D002B4FF019 -:10377000200380F20381002D00F0F280092284F8FA -:103780004C2083F311880021D4E914232046FFF74D -:1037900073FF002383F31188DAE794F85D2003F0C8 -:1037A0007F0343EA022340F20232934200F0C580D5 -:1037B00021D8B3F5807F48D00DD8012B3FD0022B04 -:1037C00000F09380002BB2D104F164022265022242 -:1037D0006265A365C1E7B3F5817F00F09B80B3F517 -:1037E000407FA4D194F85E30012BA0D1B4F86430AE -:1037F00043F0020332E0B3F5006F4DD017D8B3F5B4 -:10380000A06F31D0A3F5C063012B90D8636894F802 -:103810005E205E6894F85F10B4F860302046B047D0 -:10382000002884D043682365036863651AE0B3F514 -:10383000106F36D040F6024293427FF478AF5C4B73 -:103840002365022363650023C3E794F85E30012BF0 -:103850007FF46DAFB4F8643023F00203C4E914556B -:10386000A4F86430A56578E7B4F85C30B3F5A06FD0 -:103870000ED194F85E3084F86630204601F0E2F80C -:1038800063681B6813B10121204698470323237006 -:103890000023C4E914339CE704F167032365012383 -:1038A000C3E72378042B10D1202383F3118820460B -:1038B000FFF7C4FE85F311880321636884F867501D -:1038C00021701B680BB12046984794F85E30002B9E -:1038D000DED084F867300423237063681B68002BF4 -:1038E000D6D0022120469847D2E794F860301D06D2 -:1038F00003F00F0120460AD501F050F9012804D049 -:1039000002287FF414AF2B4B9AE72B4B98E701F07A -:1039100037F9F3E794F85E30002B7FF408AF94F8A2 -:10392000603013F00F01B3D01A06204602D501F023 -:10393000CBFBADE701F0BEFBAAE794F85E30002BAD -:103940007FF4F5AE94F8603013F00F01A0D01B06A1 -:10395000204602D501F0A4FB9AE701F097FB97E718 -:10396000142284F84C2083F311882B462A462946DA -:103970002046FFF76FFE85F31188E9E65DB1152259 -:1039800084F84C2083F311880021D4E914232046C5 -:10399000FFF760FEFDE60B2284F84C2083F31188CC -:1039A0002B462A4629462046FFF766FEE3E700BF7E -:1039B0001C5B0008145B0008185B000838B590F821 -:1039C0004C300446002B3ED0063BDAB20F2A34D8E6 -:1039D0000F2B32D8DFE803F0373131082232313192 -:1039E0003131313131313737456DB0F862309D4278 -:1039F00014D2C3681B8AB5FBF3F203FB12556DB9F1 -:103A0000202383F311882B462A462946FFF734FEEC -:103A100085F311880A2384F84C300EE0142384F8CF -:103A20004C30202383F3118800231A461946204680 -:103A3000FFF710FE002383F3118838BD836D03B1B7 -:103A400098470023E7E70021204601F029FB0021E9 -:103A5000204601F01BFB63681B6813B1062120465A -:103A600098470623D7E7000010B590F84C30142B88 -:103A7000044629D017D8062B05D001D81BB110BD9C -:103A8000093B022BFBD80021204601F009FB002155 -:103A9000204601F0FBFA63681B6813B1062120463B -:103AA0009847062319E0152BE9D10B2380F84C30F9 -:103AB000202383F3118800231A461946FFF7DCFD03 -:103AC000002383F31188DAE7C3689B695B68002BE6 -:103AD000D5D1836D03B19847002384F84C30CEE7ED -:103AE000024B0022C3E900339A6070472C36002055 -:103AF000002303748268054B1B6899689142FBD2CE -:103B00005A68036042601060586070472C3600208D -:103B100008B5202383F31188037C032B05D0042BE5 -:103B20000DD02BB983F3118808BD436900221A60B8 -:103B30004FF0FF334361FFF7DBFF0023F2E7D0E9EB -:103B4000003213605A60F3E7002303748268054B68 -:103B50001B6899689142FBD85A6803604260106004 -:103B6000586070472C360020054B19690874186896 -:103B700002681A605360186101230374FCF758BD92 -:103B80002C36002030B54B1C0B4D87B0044610D0AE -:103B90002B690A4A01A800F025F92046FFF7E4FF47 -:103BA000049B13B101A800F059F92B69586907B0BB -:103BB00030BDFFF7D9FFF8E72C360020113B000895 -:103BC00038B50C4D41612B6981689A689142044671 -:103BD00003D8BDE83840FFF78BBF1846FFF7B4FFA6 -:103BE00001232C61014623742046BDE83840FCF7D0 -:103BF0001FBD00BF2C360020044B1A681B6990685B -:103C00009B68984294BF0020012070472C3600200A -:103C100010B5084C236820691A682260546001229C -:103C200023611A74FFF790FF01462069BDE8104038 -:103C3000FCF7FEBC2C36002008B5FFF7DDFF18B1FD -:103C4000BDE80840FFF7E4BF08BD0000FFF7E0BF94 -:103C5000FEE7000010B50C4CFFF742FF00F0B4F88F -:103C60000A498022204600F03BF8012344F8180C52 -:103C7000037400F0F5FC002383F3118862B6044856 -:103C8000BDE8104000F04CB854360020205B00081E -:103C9000305B000800F01CB9EFF3118020B9EFF39E -:103CA0000583202282F311887047000010B530B9D7 -:103CB000EFF30584C4F3080414B180F3118810BD38 -:103CC000FFF7BAFF84F31188F9E70000034A51684F -:103CD00053685B1A9842FBD8704700BF001000E0A1 -:103CE00082600222028270478368A3F17C0243F85B -:103CF0000C2C026943F83C2C426943F8382C074AE3 -:103D000043F81C2CC26843F8102C022203F8082C3C -:103D1000002203F8072CA3F1180070474906000899 -:103D200010B5202383F31188FFF7DEFF002104463E -:103D3000FFF746FF002383F31188204610BD0000E3 -:103D4000024B1B6958610F20FFF70EBF2C36002075 -:103D5000202383F31188FFF7F3BF000008B5014665 -:103D6000202383F311880820FFF70CFF002383F33F -:103D7000118808BD49B1064B42681B6918605A603A -:103D8000136043600420FFF7FDBE4FF0FF30704723 -:103D90002C3600200368984206D01A6802605060F2 -:103DA00059611846FFF7A4BE7047000038B50446B5 -:103DB0000D462068844200D138BD036823605C60F2 -:103DC0004561FFF795FEF4E7054B03F11402C3E9E3 -:103DD00005224FF0FF310022C3E90712704700BFF0 -:103DE0002C36002070B51C4EC0E9032305460C4656 -:103DF00001F052FB334653F8142F9A420DD1306232 -:103E0000C5E901242A600A2C2CBF00190A30C6E932 -:103E10000555BDE8704001F02DBB316A431AE31827 -:103E200038BF1C469368A34202D9081901F030FB41 -:103E300073699A6894420CD85A68AC602B606A60C7 -:103E400015609A685D60121B9A604FF0FF33F36152 -:103E500070BD1B68A41AECE72C36002038B51B4C4B -:103E6000636998420DD0D0E9003213605A60002295 -:103E70008168C2609A680A449A604FF0FF33E36138 -:103E800038BD2246036842F8143F002193425A602D -:103E9000C16003D1BDE8384001F0F4BA9A68816886 -:103EA000256A0A449A6001F0F7FA63699A68411B2F -:103EB0008A42E5D9AB181D1A092D206A98BF01F175 -:103EC0000A02BDE83840104401F0E2BA2C36002066 -:103ED0002DE9F041184C002704F11406656901F042 -:103EE000DBFA236AAA68C11A8A4215D813442362EE -:103EF000D5E9003213605A606369D5F80C80EF6031 -:103F0000B34201D101F0BEFA87F311882869C04796 -:103F1000202383F31188E1E76169B14209D013449A -:103F20001B1ABDE8F0410A2B2CBFC0180A3001F063 -:103F3000AFBABDE8F08100BF2C36002000207047EA -:103F4000FEE70000704700004FF0FF3070470000B0 -:103F500002290CD0032904D00129074818BF0020EA -:103F60007047032A05D8054800EBC2007047044893 -:103F700070470020704700BF145C00085C230020DD -:103F8000C85B000870B59AB00546084601A91446FA -:103F900000F0C2F801A8FDF781FE431C5B00C5E9F3 -:103FA00000340022237003236370C6B201AB0234D5 -:103FB0001046D1B28E4204F1020401D81AB070BD8D -:103FC00013F8011B04F8021C04F8010C0132F0E79D -:103FD00008B5202383F311880348FFF771FA002303 -:103FE00083F3118808BD00BFE837002090F85C30EB -:103FF00003F01F02012A07D190F85D200B2A03D19C -:104000000023C0E9143315E003F06003202B08D12E -:10401000B0F860302BB990F85D20212A03D81F2A10 -:1040200004D8FFF72FBA222AEBD0FAE7034A026539 -:104030000722426583650120704700BF532300209B -:1040400007B5052917D8DFE801F01916031919205B -:10405000202383F31188104A01900121FFF7D4FA3D -:1040600001980E4A0221FFF7CFFA0D48FFF7F4F945 -:10407000002383F3118803B05DF804FB202383F34E -:1040800011880748FFF7BEF9F2E7202383F3118870 -:104090000348FFF7D5F9EBE7685B00088C5B000885 -:1040A000E837002038B50C4D0C4C0D492A4604F178 -:1040B0000800FFF767FF05F1CA0204F11000094983 -:1040C000FFF760FF05F5CA7204F118000649BDE864 -:1040D0003840FFF757BF00BFB03C00205C230020F2 -:1040E000485B0008525B00085D5B000870B5044641 -:1040F00008460D46FDF7D2FDC6B2204601340378CE -:104100000BB9184670BD32462946FDF7B3FD0028AD -:10411000F3D10120F6E700002DE9F84F05460C46E3 -:10412000FDF7BCFD2B49C6B22846FFF7DFFF08B1FB -:104130000336F6B228492846FFF7D8FF08B11036F3 -:10414000F6B2632E0DD8DFF88C80DFF88C90234F09 -:10415000DFF890A0DFF890B02E7846B92670BDE861 -:10416000F88F29462046BDE8F84F01F045BC252EC2 -:104170002BD1072241462846FDF77CFD58B9DBF8D4 -:1041800000302360DBF804306360BBF80830238123 -:1041900007350A34E0E7082249462846FDF76AFD5C -:1041A00098B90F4BA21C197809090232C95D02F8AF -:1041B000041C13F8011B01F00F015345C95D02F8FF -:1041C000031CF0D118340835C6E704F8016B01353B -:1041D000C2E700BF345C00085D5B00083C5C00087F -:1041E000107AF01F1C7AF01F165A0008BFF34F8F89 -:1041F000024AD368DB03FCD4704700BF003C024096 -:1042000008B5074B1B7853B9FFF7F0FF054B1A6948 -:10421000002ABFBF044A5A6002F188325A6008BDC2 -:104220000E3F0020003C02402301674508B5054BC6 -:104230001B7833B9FFF7DAFF034A136943F00043F1 -:10424000136108BD0E3F0020003C02400728F0B576 -:1042500016D80C4C0C4923787BB90C4D0E4608231C -:104260004FF0006255F8047B46F8042B013B13F035 -:10427000FF033A44F6D10123237051F82000F0BD2A -:104280000020FCE7303F0020103F0020505C000879 -:10429000014B53F820007047505C0008082070471D -:1042A000072810B5044601D9002010BDFFF7CEFF46 -:1042B000064B53F824301844C21A0BB90120F4E716 -:1042C00012680132F0D1043BF6E700BF505C0008F1 -:1042D000072838B5044628D8FFF7DEFCFFF786FF2D -:1042E000FFF78EFF124AF323D360E300DBB243F4FF -:1042F000007343F002031361136943F480331361C5 -:1043000005462046FFF772FFFFF7A0FF094B53F861 -:10431000241000F03BF92846FFF788FFFFF7C6FCA2 -:104320002046BDE83840FFF7BBBF002038BD00BFC6 -:10433000003C0240505C000812F001032DE9F041FE -:1043400005460E4614464BD18118334A914261D836 -:10435000324B1B6813F001035CD0314FFFF79CFC1C -:10436000FFF74EFFF323FB60FFF740FF314640F2BB -:104370000128032C18D824F00104294E0C446D1A8E -:1043800040F20118A142336905EB01072AD123F05D -:1043900001033361FFF74AFFFFF788FC0120BDE806 -:1043A000F081043C0435E4E7AB07E4D13B6923F436 -:1043B00040733B613B6943EA08033B6151F8046B7E -:1043C0002E60BFF34F8FFFF711FF2B689E42E8D09E -:1043D0003B6923F001033B61FFF728FFFFF766FC11 -:1043E0000020DCE723F440733361336943EA0803B8 -:1043F00033610B883B80BFF34F8FFFF7F7FE3F8899 -:1044000031F8023BBFB2BB42BCD0336923F0010399 -:104410003361E1E71846C2E70000080800380240AF -:10442000003C0240084908B50B7828B11BB9FFF7DA -:10443000E7FE01230B7008BD002BFCD0BDE808404F -:104440000870FFF7F3BE00BF0E3F002070B582B0CA -:10445000FFF722FC0E4E054601F01EF8326890422E -:1044600037BF0C4A0B49516814682EBFD1E900418F -:10447000013151600419034641F1000128460191C0 -:104480003360FFF713FC0199204602B070BD00BFF6 -:10449000343F0020383F002070B582B0FFF7FCFBAE -:1044A000104E054600F0F8FF3268904237BF0E4AC2 -:1044B0000D49516814682EBFD1E9004101315160A6 -:1044C000041941F100010346284601913360FFF7CA -:1044D000EDFB01994FF47A7200232046FBF790FE22 -:1044E00002B070BD343F0020383F002010B50244B8 -:1044F000064BD2B2904200D110BD441C00B253F81A -:10450000200041F8040BE0B2F4E700BF502800405F -:104510000F4B30B51C6F240407D41C6F44F4007497 -:104520001C671C6F44F400441C670A4C236843F466 -:10453000807323600244084BD2B2904200D130BD58 -:10454000441C00B251F8045B43F82050E0B2F4E799 -:1045500000380240007000405028004007B501229A -:1045600001A90020FFF7C2FF019803B05DF804FB2A -:1045700013B50446FFF7F2FFA04205D0012201A9BE -:1045800000200194FFF7C4FF02B010BD0144BFF347 -:104590004F8F064B884204D3BFF34F8FBFF36F8F0B -:1045A0007047C3F85C022030F4E700BF00ED00E084 -:1045B000074B45F255521A6002225A6040F6FF72CC -:1045C0009A604CF6CC421A60024B01221A70704776 -:1045D00000300040443F0020034B1B781BB1034BCD -:1045E0004AF6AA221A607047443F0020003000407B -:1045F000034B1A681AB9034AD2F874281A60704734 -:10460000403F002000300240024B4FF08072C3F860 -:10461000742870470030024008B5FFF7E9FF024BED -:104620001868C0F3407008BD403F002008B5FFF790 -:10463000DFFF024B1868C0F3007008BD403F002048 -:10464000EFF3098305494A6B22F001024A6368339C -:1046500083F30988002383F31188704700EF00E09B -:10466000202080F3118862B60D4B0E4AD96821F4E0 -:10467000E0610904090C0A43DA60D3F8FC200A4916 -:1046800042F08072C3F8FC20084AC2F8B01F1168DB -:1046900041F0010111601022DA7783F8220070479F -:1046A00000ED00E00003FA0555CEACC5001000E0B7 -:1046B00010B5202383F311880E4B5B6813F400635D -:1046C00014D0F1EE103AEFF30984683C4FF0807398 -:1046D000E361094BDB6B236684F30988FFF78CFAEF -:1046E00010B1064BA36110BD054BFBE783F31188A6 -:1046F000F9E700BF00ED00E000EF00E05B06000816 -:104700005E06000870B5BFF34F8FBFF36F8F1A4A74 -:104710000021C2F85012BFF34F8FBFF36F8F536960 -:1047200043F400335361BFF34F8FBFF36F8FC2F871 -:104730008410BFF34F8FD2F88030C3F3C900C3F3A6 -:104740004E335B0143F6E07403EA0406014646EA91 -:1047500081750139C2F86052F9D2203B13F1200F64 -:10476000F2D1BFF34F8F536943F480335361BFF3EA -:104770004F8FBFF36F8F70BD00ED00E0FEE70000CC -:104780000A4B0B480B4A90420BD30B4BDA1C121A04 -:10479000C11E22F003028B4238BF00220021FDF728 -:1047A00085BA53F8041B40F8041BECE7245E0008AC -:1047B000584000205840002058400020704700001A -:1047C00070B5D0E91B439E6800224FF0FF3504EB23 -:1047D00042135101D3F800090028BEBFD3F80009E5 -:1047E00040F08040C3F80009D3F8000B0028BEBF9A -:1047F000D3F8000B40F08040C3F8000B013263187F -:104800009642C3F80859C3F8085BE0D24FF0011391 -:10481000C4F81C3870BD00001D4B03EB80022DE96D -:10482000F043D2F80CC0DD6EDCF81420461CD2F840 -:1048300000E005EB063605EB4018516871450AD3D8 -:10484000D5F83438012202FA00F023EA0000C5F856 -:104850003408BDE8F083BCF81040AEEB0103A3427E -:1048600028BF2346D8F81849A4B2B3EB840FF0D878 -:104870009468A4F1040959F8047F3760A4EB090790 -:104880001F44042FF7D81C440B4494605360D4E7B2 -:10489000483F0020890141F02001016103699B0626 -:1048A000FCD41220FFF712BA10B5054C2046FEF7D3 -:1048B00089FE4FF0A043E366024B236710BD00BFA3 -:1048C000483F0020945C000870B50378012B054632 -:1048D00050D12A4BC46E98421BD1294B5A6B42F0DF -:1048E00080025A635A6D42F080025A655A6D5A69C5 -:1048F00042F080025A615A6922F080025A610E2108 -:1049000043205B69FEF734FC1E4BE3601E4BC4F88A -:1049100000380023C4F8003EC0232360EE6E4FF43D -:104920000413A3633369002BFCDA012333610C20E9 -:10493000FFF7CCF93369DB07FCD41220FFF7C6F987 -:104940003369002BFCDA0026A6602846FFF738FF03 -:104950006B68C4F81068DB68C4F81468C4F81C6895 -:104960004BB90A4BA3614FF0FF336361A36843F077 -:104970000103A36070BD064BF4E700BF483F002071 -:10498000003802404014004003002002003C30C0C8 -:10499000083C30C0F8B5C46E054600212046FFF73C -:1049A00079FF296F00234FF001128F68C4F8343863 -:1049B0004FF00066C4F81C284FF0FF3004EB4312A0 -:1049C00001339F42C2F80069C2F8006BC2F80809BF -:1049D000C2F8080BF2D20B68EA6E6B6763621023B1 -:1049E0001361166916F01006FBD11220FFF76EF95D -:1049F000D4F8003823F4FE63C4F80038A36943F404 -:104A0000402343F01003A3610923C4F81038C4F80D -:104A100014380A4BEB604FF0C043C4F8103B084B0E -:104A2000C4F8003BC4F81069C4F800396B6F03F197 -:104A3000100243F480136A67A362F8BD705C00083B -:104A400040800010C26E90F86610D2F8003823F44F -:104A5000FE6343EA0113C2F8003870472DE9F843BA -:104A600000EB8103C56EDA68166806F00306731E54 -:104A7000022B05EB41130C4680460FFA81F94FEAF1 -:104A800041104FF00001C3F8101B4FF0010104F179 -:104A9000100398BFB60401FA03F391698EBF334E39 -:104AA00006F1805606F5004600293AD0578A04F1EF -:104AB0005801490137436F50D5F81C180B43C5F80E -:104AC0001C382B180021C3F8101953690127611EE7 -:104AD000A7409BB3138A928B9B08012A88BF53433C -:104AE000D8F87420981842EA034301F1400205EB1C -:104AF0008202C8F87400214653602846FFF7CAFEB8 -:104B000008EB8900C3681B8A43EA84534834640174 -:104B10001E432E51D5F81C381F43C5F81C78BDE83C -:104B2000F88305EB4917D7F8001B21F40041C7F8BB -:104B3000001BD5F81C1821EA0303C0E704F13F036A -:104B400005EB83030A4A5A6028462146FFF7A2FE76 -:104B500005EB4910D0F8003923F40043C0F80039C0 -:104B6000D5F81C3823EA0707D7E700BF00800010FC -:104B700000040002026F12684267FFF721BE0000C6 -:104B80005831C36E49015B5813F4004004D013F44C -:104B9000001F0CBF02200120704700004831C36E87 -:104BA00049015B5813F4004004D013F4001F0CBFFC -:104BB000022001207047000000EB8101CB68196AD8 -:104BC0000B6813604B6853607047000000EB810373 -:104BD00030B5DD68AA691368D36019B9402B84BF6A -:104BE000402313606B8A1468C26E1C44013CB4FB02 -:104BF000F3F46343033323F0030302EB411043EA6E -:104C0000C44343F0C043C0F8103B2B6803F00303D8 -:104C1000012B09B20ED1D2F8083802EB411013F47F -:104C2000807FD0F8003B14BF43F0805343F0005323 -:104C3000C0F8003B02EB4112D2F8003B43F00443C2 -:104C4000C2F8003B30BD00002DE9F041244DEE6E6E -:104C500006EB40130446D3F8087BC3F8087B3807FB -:104C60000AD5D6F81438190706D505EB8403214672 -:104C7000DB6828465B689847FA071FD5D6F81438D2 -:104C8000DB071BD505EB8403D968CCB98B69488A4F -:104C90005A68B2FBF0F600FB16228AB91868DA6887 -:104CA00090420DD2121AC3E90024202383F3118805 -:104CB0000B482146FFF78AFF84F31188BDE8F08195 -:104CC000012303FA04F26B8923EA02036B81CB68A8 -:104CD000002BF3D021460248BDE8F041184700BF41 -:104CE000483F002000EB810370B5DD68C36E6C693E -:104CF0002668E6604A0156BB1A444FF40020C2F809 -:104D000010092A6802F00302012A0AB20ED1D3F870 -:104D1000080803EB421410F4807FD4F8000914BF94 -:104D200040F0805040F00050C4F8000903EB4212FC -:104D3000D2F8000940F00440C2F80009D3F8340862 -:104D4000012202FA01F10143C3F8341870BD19B908 -:104D5000402E84BF4020206020682E8A8419013CA8 -:104D6000B4FBF6F440EAC44040F000501A44C6E7F1 -:104D7000F8B504461E48C56E05EB4413D3F8086920 -:104D8000C3F80869F10717D5D5F81038DA0713D535 -:104D900000EB8403D9684B691F68DA68974218D220 -:104DA000D21B00271A605F60202383F311882146FD -:104DB000FFF798FF87F31188330617D5D5F8342805 -:104DC0000123A340134211D02046BDE8F840FFF76D -:104DD00023BD012303FA04F2038923EA02030381BA -:104DE0008B68002BE8D021469847E5E7F8BD00BF67 -:104DF000483F00202DE9F74FA34CE66E7569B36973 -:104E00001D4015F48058756107D02046FEF746FC1A -:104E100003B0BDE8F04FFFF74BBC002D12DAD6F817 -:104E2000003E99489F071EBFD6F8003E23F00303BB -:104E3000C6F8003ED6F8043823F00103C6F804385B -:104E4000FEF756FC280505D58F48FFF7B9FC8E48BC -:104E5000FEF73EFCA9040CD5D6F8083813F0060F6F -:104E6000F36823F470530CBF43F4105343F4A0537E -:104E7000F3602A0704D56368DB680BB18248984762 -:104E8000EB0200F18A80AF0227D5D4F86C90DFF8EE -:104E9000F8B100274FF0010A09EB4712D2F8003BA6 -:104EA00003F44023B3F5802F11D1D2F8003B002B3F -:104EB0000DDA62890AFA07F322EA0303638104EB3D -:104EC0008703DB68DB6813B1394658469847236F80 -:104ED00001379B68FFB29F42DED9E80618D5E76E1E -:104EE0003A6AC2F30A1002F00F0302F4F012B2F5AC -:104EF000802F00F09D80B2F5402F09D104EB830391 -:104F00000022DB681B6A07F58057904240F08280E0 -:104F10002B03D6F818481DD5E70302D50020FFF76C -:104F200093FEA60302D50120FFF78EFE600302D593 -:104F30000220FFF789FE210302D50320FFF784FE3C -:104F4000E20202D50420FFF77FFEA30202D505206E -:104F5000FFF77AFE6F037FF55BAFE60702D500200F -:104F6000FFF706FFA50702D50120FFF701FF600745 -:104F700002D50220FFF7FCFE210702D50320FFF730 -:104F8000F7FEE20602D50420FFF7F2FEA3067FF546 -:104F90003FAF0520FFF7ECFE3AE7E36EDFF8E8B03D -:104FA000019300274FF0010A236F9B685FFA87F98E -:104FB00099453FF668AF019B03EB4913D3F80029ED -:104FC00002F44022B2F5802F22D1D3F80029002A22 -:104FD0001EDAD3F8002942F09042C3F80029D3F832 -:104FE0000029002AFBDBE06E4946FFF753FC2289CB -:104FF0000AFA09F322EA0303238104EB8903DB683D -:105000009B6813B14946584698474846FFF704FC49 -:105010000137C9E7910708BFD7F80080072A98BF72 -:1050200003F8018B02F1010298BF4FEA18286CE7E0 -:10503000023304EB830207F580575268D2F818C098 -:10504000DCF80820DCE9001CA1EB0C0C00218842F4 -:105050000AD104EB830463689B699A6802449A60EE -:105060005A6802445A6053E711F0030F08BFD7F89B -:1050700000808C4588BF02F8018B01F1010188BFD7 -:105080004FEA1828E3E700BF483F0020C36E03EB58 -:105090004111D1F8003B43F40013C1F8003B7047C5 -:1050A000C36E03EB4111D1F8003943F40013C1F88A -:1050B00000397047C36E03EB4111D1F8003B23F474 -:1050C0000013C1F8003B7047C36E03EB4111D1F8E8 -:1050D000003923F40013C1F80039704730B5039C40 -:1050E0000172043304FB0325C0E90653049B0363E8 -:1050F0000021059BC160C0E90000C0E90422C0E9AD -:105100000842C0E90A11436330BD0000416A002231 -:10511000C0E90411C0E90A22C2606FF00101FEF784 -:1051200045BE0000D0E90432934201D1C2680AB9F9 -:10513000181D70470020704703691960C26801326A -:10514000C260C269134482690361934224BF436A07 -:1051500003610021FEF71EBE38B504460D46E36824 -:105160003BB16269131D1268A3621344E36200201D -:1051700007E0237A33B929462046FEF7FBFD0028D5 -:10518000EDDA38BD6FF00100FBE70000C368C269CB -:10519000013BC3604369134482694361934224BF66 -:1051A000436A436100238362036B03B1184770476E -:1051B00070B52023044683F31188866A3EB9FFF751 -:1051C000CBFF054618B186F31188284670BDA36A47 -:1051D000E26A13F8015BA362934202D32046FFF711 -:1051E000D5FF002383F31188EFE700002DE9F84F86 -:1051F00004460E46174698464FF0200989F3118859 -:105200000025AA46D4F828B0BBF1000F09D14146C9 -:105210002046FFF7A1FF20B18BF311882846BDE897 -:10522000F88FD4E90A12A7EB050B521A934528BF51 -:105230009346BBF1400F1BD9334601F1400251F8B0 -:10524000040B43F8040B9142F9D1A36A4033403672 -:10525000A3624035D4E90A239A4202D32046FFF7DD -:1052600095FF8AF31188BD42D8D289F31188C9E726 -:1052700030465A46FCF7F4FCA36A5B445E44A362E2 -:105280005D44E7E710B5029C0172043304FB03217F -:10529000C0E906130023C0E90A33039B0363049BA0 -:1052A000C460C0E90000C0E90422C0E908424363C9 -:1052B00010BD0000026AC260426AC0E904220022F6 -:1052C000C0E90A226FF00101FEF770BDD0E90423A6 -:1052D0009A4201D1C26822B9184650F8043B0B60CB -:1052E0007047002070470000C368C2690133C36083 -:1052F0004369134482694361934224BF436A436113 -:105300000021FEF747BD000038B504460D46E368AE -:105310003BB123691A1DA262E2691344E3620020D3 -:1053200007E0237A33B929462046FEF723FD0028FB -:10533000EDDA38BD6FF00100FBE70000036919608A -:10534000C268013AC260C269134482690361934230 -:1053500024BF436A036100238362036B03B11847D0 -:105360007047000070B520230D460446114683F3B4 -:105370001188866A2EB9FFF7C7FF10B186F311882E -:1053800070BDA36A1D70A36AE26A01339342A362EF -:1053900004D3E16920460439FFF7D0FF002080F3F1 -:1053A0001188EDE72DE9F84F04460D4690469946E1 -:1053B0004FF0200A8AF311880026B346A76A4FB936 -:1053C00049462046FFF7A0FF20B187F311883046F9 -:1053D000BDE8F88FD4E90A073A1AA8EB0607974206 -:1053E00028BF1746402F1BD905F1400355F8042B61 -:1053F00040F8042B9D42F9D1A36A4033A3624036A2 -:10540000D4E90A239A4204D3E16920460439FFF71C -:1054100095FF8BF311884645D9D28AF31188CDE7E1 -:1054200029463A46FCF71CFCA36A3B443D44A36270 -:105430003E44E5E7D0E904239A4217D1C3689BB103 -:10544000836A8BB1043B9B1A0ED01360C368013B87 -:10545000C360C3691A44836902619A4224BF436AE4 -:105460000361002383620123184670470023FBE792 -:1054700000F088B84FF08043002258631A6102227E -:10548000DA6070474FF080430022DA607047000016 -:105490004FF08043586370474FF08043586A70471D -:1054A0004B6843608B688360CB68C3600B69436162 -:1054B0004B6903628B6943620B68036070470000AD -:1054C00008B5264B26481A6940F2FF110A431A61B3 -:1054D0001A6922F4FF7222F001021A611A691A6B2A -:1054E0000A431A631A6D0A431A651E4A1B6D114658 -:1054F000FFF7D6FF02F11C0100F58060FFF7D0FF37 -:1055000002F1380100F58060FFF7CAFF02F1540193 -:1055100000F58060FFF7C4FF02F1700100F58060C4 -:10552000FFF7BEFF02F18C0100F58060FFF7B8FFC6 -:1055300002F1A80100F58060FFF7B2FF02F1C4019B -:1055400000F58060FFF7ACFF02F1E00100F580603C -:10555000FFF7A6FFBDE8084000F088B80038024019 -:1055600000000240A05C000808B500F0F3F9FEF767 -:1055700071FBFFF73DF8BDE80840FEF793BD000062 -:10558000704700000F4B1A6C42F001021A641A6E49 -:1055900042F001021A660C4A1B6E936843F0010345 -:1055A00093604FF080436B229A624FF0FF32DA62D1 -:1055B00000229A615A63DA605A6001225A611A60C5 -:1055C000704700BF00380240002004E04FF08042E6 -:1055D00008B51169D3680B40D9B2C9439B07116163 -:1055E00007D5202383F31188FEF754FB002383F3B0 -:1055F000118808BD1B4B1A696FEAC2526FEAD2527A -:105600001A611A69C2F308021A614FF0FF301A6971 -:105610005A69586100215A6959615A691A6A62F0D7 -:1056200080521A621A6A02F080521A621A6A5A6A20 -:1056300058625A6A59625A6A0B4A106840F480707C -:105640001060186F00F44070B0F5007F1EBF4FF47B -:10565000803018671967536823F40073536000F0B3 -:1056600055B900BF0038024000700040364B374A41 -:105670001A64374A4FF4404111601A6842F001023F -:105680001A601A689207FCD59A6822F003029A60A1 -:105690002D4B9A6812F00C02FBD1196801F0F90148 -:1056A00019609A601A6842F480321A601A6890038E -:1056B000FCD55A6F42F001025A67234B5A6F91078B -:1056C000FCD5244A5A601A6842F080721A60204B56 -:1056D0005A685204FCD51A6842F480321A605A683B -:1056E000D003FCD51A6842F400321A60184A536895 -:1056F0009903FCD5144B1A689201FCD5164A9A609E -:1057000040F20112C3F88C200022C3F89020134A03 -:1057100040F207331360136803F00F03072BFAD12D -:10572000094B9A6842F002029A609A6802F00C02F1 -:10573000082AFAD15A6C42F480425A645A6E42F4F2 -:1057400080425A665B6E70470038024000040010C9 -:1057500000700040106C400900948838003C024002 -:10576000074A08B5536903F00103536123B1054AA1 -:1057700013680BB150689847BDE80840FEF798BF22 -:10578000003C0140D83F0020074A08B5536903F0A8 -:105790000203536123B1054A93680BB1D06898475F -:1057A000BDE80840FEF784BF003C0140D83F002020 -:1057B000074A08B5536903F00403536123B1054A4E -:1057C00013690BB150699847BDE80840FEF770BFF8 -:1057D000003C0140D83F0020074A08B5536903F058 -:1057E0000803536123B1054A93690BB1D069984707 -:1057F000BDE80840FEF75CBF003C0140D83F0020F8 -:10580000074A08B5536903F01003536123B1054AF1 -:10581000136A0BB1506A9847BDE80840FEF748BFCD -:10582000003C0140D83F0020164B10B55C6904F4E1 -:1058300078725A61A30604D5134A936A0BB1D06AF1 -:105840009847600604D5104A136B0BB1506B98470C -:10585000210604D50C4A936B0BB1D06B9847E20537 -:1058600004D5094A136C0BB1506C9847A30504D5B5 -:10587000054A936C0BB1D06C9847BDE81040FEF719 -:1058800017BF00BF003C0140D83F0020194B10B5A6 -:105890005C6904F47C425A61620504D5164A136DB2 -:1058A0000BB1506D9847230504D5134A936D0BB186 -:1058B000D06D9847E00404D50F4A136E0BB1506EBB -:1058C0009847A10404D50C4A936E0BB1D06E98474B -:1058D000620404D5084A136F0BB1506F9847230434 -:1058E00004D5054A936F0BB1D06F9847BDE81040BF -:1058F000FEF7DEBE003C0140D83F002008B5FFF7B0 -:1059000065FEBDE80840FEF7D3BE0000062108B5DD -:105910000846FDF72DFC06210720FDF729FC06218E -:105920000820FDF725FC06210920FDF721FC0621B2 -:105930000A20FDF71DFC06211720FDF719FC0621A2 -:105940002820FDF715FCBDE8084007211C20FDF7C5 -:105950000FBC000008B5FFF74DFE00F00DF8FDF795 -:105960001DFCFDF72DFEFDF705FDFFF709FEBDE867 -:105970000840FFF77DBD00000023054A19460133AA -:10598000102BC2E9001102F10802F8D1704700BFE4 -:10599000D83F002010B501390244904201D10020C7 -:1059A00005E0037811F8014FA34201D0181B10BD88 -:1059B0000130F2E72DE9F041A3B1C91A177801448B -:1059C000044603F1FF3C8C42204601D9002009E047 -:1059D0000578BD4204F10104F5D10CEB0405D6189D -:1059E000A54201D1BDE8F08115F8018D16F801ED51 -:1059F000F045F5D0E7E70000034611F8012B03F866 -:105A0000012B002AF9D170476F72672E617264759D -:105A100070696C6F742E46726565666C7952544B72 -:105A2000000000004E6F20617070207369670A00EB -:105A3000426164206677206C656E67746820257506 -:105A40000A0042616420626F6172645F69642025AC -:105A5000752073686F756C642062652025750A0077 -:105A60004261642066772064657363726970746F45 -:105A700072206C656E6774682025750A0042616447 -:105A80002061707020435243203078253038783AB6 -:105A9000307825303878203078253038783A3078AA -:105AA000253038780A00476F6F64206669726D7719 -:105AB0006172650A0040A2E4F1646891060000008A -:105AC00053544D3332463F3F3F3F3F3F0053544DC9 -:105AD000333246375B347C355D780053544D333276 -:105AE00046375B367C375D78000000000000000020 -:105AF000F1320008DD3200081933000805330008D0 -:105B000011330008FD320008E9320008D5320008E0 -:105B10002533000800000000010000000000000024 -:105B20006D61696E0000000069646C650000000032 -:105B3000285B000870360020E837002001000000D4 -:105B4000513C0008000000004172647550696C6FA0 -:105B5000740025424F415244252D424C00255345A7 -:105B60005249414C250000000200000000000000E6 -:105B70000D3500087935000840004000803C0020C9 -:105B8000903C002002000000000000000300000024 -:105B900000000000BD3500080000000010000000FB -:105BA000A03C0020000000000100000000000000F8 -:105BB000483F00200101020041400008513F000819 -:105BC000ED3F0008D13F000843000000D05B000813 -:105BD00009024300020100C0320904000001020270 -:105BE0000100052400100105240100010424020223 -:105BF0000524060001070582030800FF09040100CF -:105C0000020A0000000705010240000007058102AA -:105C100040000000120000001C5C0008120110018E -:105C20000200004009124157000201020301000076 -:105C30000403090425424F415244250030313233D8 -:105C40003435363738394142434445460000000078 -:105C50000040000000400000004000000040000044 -:105C6000000001000000020000000200000002002D -:105C70000000000005370008BD390008693A000837 -:105C800040004000C03F0020C03F00200100000055 -:105C9000D03F00208000000040010000050000000F -:105CA0000010806A00000000AAAAAAAA00000064EE -:105CB000FFFF00000000000000A00A0000000A0032 -:105CC00000000000AAAAAAAA00000000FFFF00002E -:105CD00000000000990000000040000000000000EB -:105CE000AAAAAAAA00000020FFFF000000000000EE -:105CF000000000000000000000000000AAAAAAAAFC -:105D000000000000FFFF0000000000000000000095 -:105D10000000000000000000AAAAAAAA00000000DB -:105D2000FFFF000000000000000000000000000075 -:105D300000000000AAAAAAAA00000000FFFF0000BD -:105D40000000000000000000000000000000000053 -:105D5000AAAAAAAA00000000FFFF0000000000009D -:105D60000000000000000000000000000A00000029 -:105D70000000000003000000000000000000000020 -:105D80000000000000000000000000000000000013 -:105D900000000000000000000000000094A4FF7F4D -:105DA00001000000000000000404000000000000EA -:105DB0000000070000000000640000000000000078 -:105DC00040420F00FE2A0100D2040000FF00000044 -:105DD00000000000C05A00083F0000004904000015 -:105DE000CD5A00083F00000051040000DB5A0008B3 -:105DF0003F00000000960000000008009600000030 -:105E00000008000004000000305C000800000000F2 -:105E10000000000000000000000000000000000082 -:045E2000000000007E +:1000000000070020150500088D2F0008452F000867 +:100010006D2F0008452F0008652F00081705000800 +:10002000170500081705000817050008813F00089C +:100030001705000817050008170500081705000830 +:100040001705000817050008170500081705000820 +:10005000170500081705000895660008BD6600082A +:10006000E56600080D6700083567000817050008F9 +:1000700017050008170500081705000817050008F0 +:10008000170500081705000817050008F92E0008D5 +:10009000252F0008352F0008170500085D670008A8 +:1000A00017050008170500081705000817050008C0 +:1000B0003168000817050008170500081705000833 +:1000C00017050008170500081705000817050008A0 +:1000D0001705000817050008170500081705000890 +:1000E000C167000817050008170500081705000874 +:1000F0001705000817050008170500081705000870 +:10010000170500081705000817050008170500085F +:10011000170500081705000817050008170500084F +:10012000170500081705000817050008170500083F +:10013000170500081705000817050008170500082F +:10014000170500081705000817050008715C00086E +:10015000170500081705000817050008170500080F +:1001600017050008170500081705000817050008FF +:1001700017050008170500081705000817050008EF +:1001800017050008170500081705000817050008DF +:1001900017050008170500081705000817050008CF +:1001A00017050008170500081705000817050008BF +:1001B00017050008170500081705000817050008AF +:1001C000170500081705000817050008170500089F +:1001D000170500081705000817050008170500088F +:1001E000170500081705000817050008170500087F +:1001F000170500081705000817050008170500086F +:10020000311900080000000000000000000000009C +:1002100053B94AB9002908BF00281CBF4FF0FF316D +:100220004FF0FF3000F074B9ADF1080C6DE904CE69 +:1002300000F006F8DDF804E0DDE9022304B07047C1 +:100240002DE9F047089D04468E46002B4DD18A4289 +:10025000944669D9B2FA82F252B101FA02F3C2F1BC +:10026000200120FA01F10CFA02FC41EA030E94404D +:100270004FEA1C48210CBEFBF8F61FFA8CF708FB6E +:1002800016E341EA034306FB07F199420AD91CEB46 +:10029000030306F1FF3080F01F81994240F21C8178 +:1002A000023E63445B1AA4B2B3FBF8F008FB1033C0 +:1002B00044EA034400FB07F7A7420AD91CEB0404F5 +:1002C00000F1FF3380F00A81A74240F207816444C5 +:1002D000023840EA0640E41B00261DB1D44000234A +:1002E000C5E900433146BDE8F0878B4209D9002DAE +:1002F00000F0EF800026C5E9000130463146BDE838 +:10030000F087B3FA83F6002E4AD18B4202D38242A1 +:1003100000F2F980841A61EB030301209E46002D50 +:10032000E0D0C5E9004EDDE702B9FFDEB2FA82F2A5 +:10033000002A40F09280A1EB0C014FEA1C471FFA03 +:100340008CFE0126200CB1FBF7F307FB131140EAEA +:1003500001410EFB03F0884208D91CEB010103F1B7 +:10036000FF3802D2884200F2CB804346091AA4B279 +:10037000B1FBF7F007FB101144EA01440EFB00FE4D +:10038000A64508D91CEB040400F1FF3102D2A645B2 +:1003900000F2BB800846A4EB0E0440EA03409CE751 +:1003A000C6F12007B34022FA07FC4CEA030C20FAFE +:1003B00007F401FA06F31C43F9404FEA1C4900FA1E +:1003C00006F3B1FBF9F8200C1FFA8CFE09FB18119B +:1003D00040EA014108FB0EF0884202FA06F20BD90E +:1003E0001CEB010108F1FF3A80F08880884240F25E +:1003F0008580A8F102086144091AA4B2B1FBF9F0A2 +:1004000009FB101144EA014100FB0EFE8E4508D99C +:100410001CEB010100F1FF346CD28E456AD9023821 +:10042000614440EA0840A0FB0294A1EB0E01A14206 +:10043000C846A64656D353D05DB1B3EB080261EB74 +:100440000E0101FA07F722FA06F3F1401F43C5E94E +:10045000007100263146BDE8F087C2F12003D84084 +:100460000CFA02FC21FA03F3914001434FEA1C47C6 +:100470001FFA8CFEB3FBF7F007FB10360B0C43EAB8 +:10048000064300FB0EF69E4204FA02F408D91CEB68 +:10049000030300F1FF382FD29E422DD90238634466 +:1004A0009B1B89B2B3FBF7F607FB163341EA034106 +:1004B00006FB0EF38B4208D91CEB010106F1FF3855 +:1004C00016D28B4214D9023E6144C91A46EA00464C +:1004D00038E72E46284605E70646E3E61846F8E6DE +:1004E0004B45A9D2B9EB020864EB0C0E0138A3E727 +:1004F0004646EAE7204694E74046D1E7D0467BE708 +:10050000023B614432E7304609E76444023842E77F +:10051000704700BF02E000F000F8FEE772B637480F +:1005200080F30888364880F30988364836490860E1 +:1005300040F20000CCF200004EF63471CEF2000121 +:100540000860BFF34F8FBFF36F8F40F20000C0F21F +:10055000F0004EF68851CEF200010860BFF34F8FD5 +:10056000BFF36F8F4FF00000E1EE100A4EF63C71C2 +:10057000CEF200010860062080F31488BFF36F8F6D +:1005800004F0D4FF05F036FF4FF055301F491B4AE9 +:1005900091423CBF41F8040BFAE71D49184A9142C9 +:1005A0003CBF41F8040BFAE71A491B4A1B4B9A421D +:1005B0003EBF51F8040B42F8040BF8E7002018493D +:1005C000184A91423CBF41F8040BFAE704F0ECFFF3 +:1005D00005F064FF144C154DAC4203DA54F8041BCB +:1005E0008847F9E700F042F8114C124DAC4203DAAB +:1005F00054F8041B8847F9E704F0D4BF0007002033 +:10060000002300200000000808ED00E000010020A9 +:1006100000070020D06D000800230020CC2300201C +:10062000D0230020705600200002000804020008B9 +:1006300004020008040200082DE9F04F2DED108A95 +:10064000C1F80CD0D0F80CD0BDEC108ABDE8F08F0A +:10065000002383F311882846A047002004F054FAB1 +:10066000FEE704F0ADF900DFFEE70000F8B501F0A9 +:1006700071F904F0D5FE074604F044FF0546002852 +:100680003BD1244B9F4238D001339F4238D0224B7C +:1006900027F0FF029A4236D1F8B200F067FF2E46EB +:1006A00042F2107400F068FF08B10024264601F001 +:1006B00059FD20B1032000F085F80024264635B10D +:1006C000164B9F4203D004F015FF0024264600205D +:1006D00004F0B0FE124B1B695B0418D40EB100F09D +:1006E00087F801F0EFFA00F0B3FF01F099F9204626 +:1006F00000F014F900F07CF8F9E72E460024D1E769 +:1007000004460126CEE706464FF47A74CAE7002471 +:10071000E7E700BF010007B0000008B0263A09B0C3 +:100720000008024008B501F04DF9A0F1200358423D +:10073000584108BD07B541F21203022101A8ADF8E6 +:10074000043001F05DF903B05DF804FB38B53023E7 +:1007500083F31188174803680BB104F0A1FA164A15 +:10076000144800234FF47A7104F090FA002383F3C5 +:100770001188124C236813B12368013B236063681E +:1007800013B16368013B63600D4D2B7833B9636827 +:100790007BB9022001F010FA322363602B78032B1F +:1007A00007D163682BB9022001F006FA4FF47A737F +:1007B000636038BDD02300204D070008F0240020DE +:1007C000E8230020084B187003280CD8DFE800F05D +:1007D00008050208022001F0E7B9022001F0DAB9A9 +:1007E000024B00225A607047E8230020F0240020CA +:1007F000F8B501F0B7FC30B1404B03221A70404B02 +:1008000000225A60F8BD3F4B3F4A1C46196801312F +:10081000F8D004339342F9D162683C4B9A42F1D943 +:100820003B4B9B6803F1006303F580339A42E9D2A6 +:1008300004F034FE04F046FE002001F00BF9022023 +:10084000FFF7C0FF334B00211A6C19641A6E19664A +:100850001A6E5A6C59645A6E59665A6E1A6942F089 +:1008600000521A611A6922F000521A611B6972B6AD +:100870004FF0E023C3F8084DD4E90004BFF34F8FD5 +:10088000BFF36F8F244AC2F88410BFF34F8F5369B0 +:1008900023F480335361BFF34F8FD2F88030C3F31A +:1008A000C905C3F34E335B0143F6E07603EA060C59 +:1008B00029464CEA81770139C2F87472F9D2203B9B +:1008C00013F1200FF2D1BFF34F8FBFF36F8FBFF340 +:1008D0004F8FBFF36F8F536923F4003353610023AD +:1008E000C2F85032BFF34F8FBFF36F8F302383F3C3 +:1008F0001188854680F30888204783E7E823002095 +:10090000F02400200000010820000108FFFF00087B +:10091000002300200038024000ED00E02DE9F04FF8 +:1009200093B0B74B00902022FF210AA89D6801F0E8 +:1009300073F9B44A1378A3B9B34801210360117065 +:10094000302383F3118803680BB104F0A9F9AF4A8F +:10095000AD4800234FF47A7104F098F9002383F333 +:100960001188009B13B1AA4B009A1A60A94A009CF7 +:100970001378032B1EBF00231370A54A4FF0000A03 +:1009800018BF5360D3465646D146012001F00CF9FA +:1009900024B19F4B1B68002B00F02B82002001F03C +:1009A00011F80390039B002B01DA00F099FE039BE2 +:1009B000002BEDDB012001F0EDF8039B213B1F2B09 +:1009C000E3D801A252F823F0490A0008710A00088E +:1009D000050B00088B0900088B0900088B0900082B +:1009E000970B0008670D0008810C0008E30C000855 +:1009F0000B0D0008310D00088B090008430D00089D +:100A00008B090008B50D0008E90A00088B090008E9 +:100A1000F90D0008550A0008E90A00088B090008CA +:100A2000E30C00088B0900088B0900088B090008FB +:100A30008B0900088B0900088B0900088B09000846 +:100A40008B090008050B00080220FFF76BFE002849 +:100A500040F0F981009B0221BAF1000F08BF1C464B +:100A600005A841F21233ADF8143000F0C9FF8CE74D +:100A70004FF47A7000F0A6FF071EEBDB0220FFF7B1 +:100A800051FE0028E6D0013F052F00F2DE81DFE8AD +:100A900007F0030A0D10133605230593042105A85A +:100AA00000F0AEFF17E056480421F9E75A48042148 +:100AB000F6E75A480421F3E74FF01C08404600F0DF +:100AC000CBFF08F104080590042105A800F098FF69 +:100AD000B8F12C0FF2D1012000FA07F747EA0B0B0F +:100AE0005FFA8BFB4FF0000901F0E2F826B10BF042 +:100AF0000B030B2B08BF0024FFF71CFE45E74848FB +:100B00000421CDE7002EA5D00BF00B030B2BA1D1B8 +:100B10000220FFF707FE074600289BD0012000F0C7 +:100B200099FF0220FFF74EFE00261FFA86F8404686 +:100B300000F0A0FF0446B0B10399A1F14002514278 +:100B40005141404600F0AEFF01360028EDD1BA46D3 +:100B5000044641F21213022105A8ADF814303E46B6 +:100B600000F04EFF11E70120FFF72CFE2546244B35 +:100B70009B68AB4207D9284600F06EFF013040F079 +:100B800067810435F3E7234B00251D70204BBA46DF +:100B90005D603E46A8E7002E3FF45CAF0BF00B0310 +:100BA0000B2B7FF457AF0220FFF70CFE322000F032 +:100BB00009FFB0F10008FFF64DAF18F003077FF40E +:100BC00049AF0F4A926808EB050393423FF642AFE4 +:100BD000B8F5807F3FF73EAF124B0193B84523DD58 +:100BE0004FF47A7000F0EEFE0390039A002AFFF6AD +:100BF00031AF019B039A03F8012B0137EDE700BFEA +:100C000000230020EC240020D02300204D07000802 +:100C1000F0240020E82300200423002008230020E3 +:100C20000C230020EC230020C820FFF77BFD0746A3 +:100C300000283FF40FAF1F2D11D8C5F12002424507 +:100C40000AAB25F0030028BF4246834901921844AD +:100C500000F0BCFF019A8048FF2100F0DDFF4FEA61 +:100C6000A8037D490193C8F38702284600F0DCFF02 +:100C7000064600283FF46DAF019B05EB830533E783 +:100C80000220FFF74FFD00283FF4E4AE00F02AFFFA +:100C900000283FF4DFAE0027B846704B9B68BB428C +:100CA00018D91F2F11D80A9B01330ED027F0030348 +:100CB00012AA134453F8203C05934046042205A988 +:100CC00001F008FA04378046E7E7384600F0C4FE32 +:100CD0000590F2E7CDF81480042105A800F090FEFD +:100CE00002E70023642104A8049300F07FFE00289B +:100CF0007FF4B0AE0220FFF715FD00283FF4AAAE46 +:100D0000049800F0D7FE0590E6E70023642104A8CC +:100D1000049300F06BFE00287FF49CAE0220FFF7E6 +:100D200001FD00283FF496AE049800F0D3FEEAE7F8 +:100D30000220FFF7F7FC00283FF48CAE00F0E2FE43 +:100D4000E1E70220FFF7EEFC00283FF483AE05A99F +:100D5000142000F0DDFE04210746049004A800F0F2 +:100D60004FFE3946B9E7322000F02CFE071EFFF691 +:100D700071AEBB077FF46EAE384A926807EB090389 +:100D800093423FF667AE0220FFF7CCFC00283FF409 +:100D900061AE27F003074F44B9453FF4A5AE48467E +:100DA00000F05AFE0421059005A800F029FE09F183 +:100DB0000409F1E74FF47A70FFF7B4FC00283FF420 +:100DC00049AE00F08FFE002844D00A9B01330BD0BF +:100DD00008220AA9002000F027FF00283AD020228C +:100DE000FF210AA800F018FFFFF7A4FC1C4803F03D +:100DF00091FE13B0BDE8F08F002E3FF42BAE0BF048 +:100E00000B030B2B7FF426AE0023642105A805936A +:100E100000F0ECFD074600287FF41CAE0220FFF72F +:100E200081FC804600283FF415AEFFF783FC41F2B9 +:100E3000883003F06FFE059800F06CFF464600F026 +:100E400037FF3C46A1E506464EE64FF0000901E6B5 +:100E5000BA467EE637467CE6EC23002000230020DD +:100E6000A0860100094A136849F2690099B21B0C77 +:100E700000FB01331360064B186844F2506182B2E4 +:100E8000000C01FB0200186080B27047182300209C +:100E90001423002010B500211022044600F0BCFEEF +:100EA000034B03CB206061601868A06010BD00BFD9 +:100EB000107AF01F2DE9F041ADF54E7D0DF13408AB +:100EC0006CAC40F2751207460D460EA80021C8F81A +:100ED000001000F0A1FE4FF4C4720021204600F083 +:100EE0009BFE02F05BF8254B4FF47A72B0FBF2F0F8 +:100EF000186093E80700022384E807000DF5E97005 +:100F00002382FFF7C7FF40F204431D49238406A84C +:100F100005F09EFD182384F832310DF2E3266B4470 +:100F20000DF1300C1A4603CA6245306071601346F9 +:100F300006F10806F6D141460122204600F0ECFEFB +:100F400000230393AB7E029305F11903019380B252 +:100F50000123CDE904800093E97E06A3D3E90023B1 +:100F6000384602F0E3FB0DF54E7DBDE8F08100BF91 +:100F7000AFF300809E6AC421818A46EEF8240020E7 +:100F8000606A00082DE9F0412C4C237ADAB08046E3 +:100F90000D465BBB27A9284600F0CEFF0746002878 +:100FA00042D19DF89D60C82E3ED801464FF4A662FE +:100FB000204600F031FE4FF48073C4F8F8314FF44E +:100FC0000073C4F80C334FF44073C4F82034324635 +:100FD0000DF19E0104F1090000F0F8FD26449DF892 +:100FE0009C30777223720BB9EB7E23728122002131 +:100FF00006AC27A800F010FE0122214627A800F029 +:10100000D7FF00230393AB7E029305F1190380B24F +:1010100001932823CDE904400093E97E05A3D3E999 +:101020000023404602F082FB5AB0BDE8F08100BFC9 +:10103000AFF3008026417272DF25D7B7104600203B +:10104000F0B5254E4FF48A7505FB0065F1B096F8B2 +:10105000D83085F8DC300024D822214685F8E840D5 +:101060003AA800F0D9FD06F1090000F0CDFDD5F851 +:10107000E4308DF8F000C2B206AF06F109010DF1BF +:10108000F100CDE93A3400F0A1FD394601223AA839 +:1010900000F0BAFF80B2CDE9047008230127CDE942 +:1010A000023706F1D803019330230093317A0B48BD +:1010B00007A3D3E9002302F039FBA04206DD01F0CB +:1010C0006DFFC5F8E000384671B0F0BD2046FBE783 +:1010D00078F6339F93CACD8D10460020103500203E +:1010E0002DE9F0411D4D1E4E1E4F86B0284602F0E0 +:1010F00049FB034658B30024CDE90344ADF814403E +:10110000027B8DF8142099684068029403AA03C2F8 +:101110001B68DFF8548043F00043029301F040FF66 +:10112000821941F10003009402A9384601F004FA43 +:10113000A04205DD284602F029FB88F80040D5E7EB +:1011400098F80030072B05D8013388F8003006B036 +:10115000BDE8F081014802F019FBF8E710350020E6 +:1011600040420F0040350020454B002070B50D4631 +:1011700014461E4602F036FA50B9022E10D1012C48 +:101180000ED112A3D3E90023C5E90023012007E013 +:10119000282C10D005D8012C09D0052C0FD0002008 +:1011A00070BD302CFBD10BA3D3E90023ECE70BA3DC +:1011B000D3E90023E8E70BA3D3E90023E4E70BA37B +:1011C000D3E90023E0E700BFAFF30080401DA1207A +:1011D00026812A0B78F6339F93CACD8D9E6AC4214F +:1011E000818A46EE26417272DF25D7B7F017304A62 +:1011F00039059E5638B505460E4C0021013500F0E4 +:1012000051FCA4F82C55B4F82C0500F033FC78B14F +:10121000B4F82C0500F03EFC014648B9B4F82C05A2 +:1012200000F040FCB4F82C350133A4F82C35EAE783 +:1012300038BD00BF1046002010B50A4B0A4A1A609C +:1012400003F5805393F860203AB9DC6D2CB1204649 +:1012500001F00AF8204605F03BFBBDE810400348CA +:1012600001F002B840350020E46A000888450020FB +:101270002DE9F04F8FB000AF05460C4602F0B2F9F1 +:10128000002849D1237E022B1BD1E38A012B18D1E0 +:1012900001F084FE0646FFF7E5FD03464FF4C870F3 +:1012A000DFF8C482B3FBF0F206F5167602FB1033CA +:1012B00016FA83F3C8F80030E37E33B9A34B00225B +:1012C0001A703C37BD46BDE8F08F07F12401204677 +:1012D00000F0F0FD0028F4D107F11400FFF7DAFD6B +:1012E00097F8264007F11401224607F1270005F080 +:1012F00039FB0028E2D10F2C08D8944B1C70D8F889 +:101300000030A3F51673C8F80030DAE797F8241018 +:10131000284602F05FF9D4E7E38A282B2BD010D8B7 +:10132000012B23D0052BCCD1BFF34F8F8849894B9C +:10133000CA6802F4E0621343CB60BFF34F8F00BF73 +:10134000FDE7302BBDD1844EE17E327A9142B8D197 +:10135000607E3146002291F8DC50854200F0A58085 +:101360000132042A01F58A71F5D1AAE721462846FF +:10137000FFF7A0FDA5E721462846FFF703FEA0E7FB +:10138000B2F8EC507B6005F103094FEA99094FEA86 +:101390008902D11DC908A8EBC1039D46EB46002177 +:1013A000584600F039FC04F1EE012A463144584613 +:1013B00000F00CFC7B6813B9012000F04BFB96F8A1 +:1013C000D20000F057FB044630B9307200F08AFBBF +:1013D000204600F03FFBB1E0D6F8D4203AB996F8A9 +:1013E000D200B6F82C25824201D8FFF703FFD6F8C9 +:1013F000D4202A44944208D296F8D200B6F82C257C +:101400000130824201D8FFF7F5FE70685FFA89F279 +:10141000594600F009FC08B9C54679E0726896F8AB +:10142000D2002A447260D6F8D42005EB0209C6F82F +:10143000D49000F01FFB814509D396F8D220D6F84E +:10144000D4000132001B86F8D220C6F8D400FF2D4C +:101450000FD80024347200F045FB204600F0FAFA61 +:1014600000F080FE3D4B188108B9FFF7C1F9C54671 +:1014700027E7BB6896F8D9000AFB0362FB68D2F83D +:10148000E41082F8E83001F58061C2F8E030C2F87B +:10149000E410FFF7D5FDFFF723FE96F8D9200132BF +:1014A00002F0030286F8D920B6E74FF48A7A0AFBE5 +:1014B00002F505F1EA013144204600F0D1FDF86063 +:1014C00000287FF4FEAE3544012285F8E82001F0C3 +:1014D00065FDD5F8E020D6ED007ADFED216A801AAF +:1014E000192838BF192040F6B832904228BF10465C +:1014F000B8EE677A07EE900AF8EEE77A67EEA67A1A +:10150000DFED186AE7EE267AFCEEE77AC6ED007AA0 +:1015100096F8D930BB60BA6873680AFB02F43219D6 +:1015200092F8E81059B1D2F8E4108B42E8463FF443 +:1015300027AF002182F8E810C2F8E010C5467368B2 +:10154000064A9B0A01331381BBE600BF0935002020 +:1015500000ED00E00400FA0510460020F824002009 +:10156000CDCCCC3D6666663F0C350020014B187033 +:10157000704700BF0425002030B54FF000542B4BBE +:1015800022689A4285B007D003F0C6FF044620BB0C +:101590000024204605B030BD254B627D25481A70D9 +:1015A000237D03724FF48073C0F8F8314FF4007359 +:1015B000C0F80C3300254FF44073C0F820341E49A6 +:1015C000C0F8E450C922093000F000FB2046E022B8 +:1015D000294600F021FB0124DBE7184A184D136C63 +:1015E00043F000731364AA6D164B9A42D0D12B6E50 +:1015F000013B7E2BCCD8144A07CA01AB83E8070015 +:101600001846032100F07CFD6B6D83424FF0000310 +:10161000BED12A6D8A4201BFAB65054B2A6E1A7096 +:1016200003BF0A4BEA6D1A601C46B2E79AAD44C587 +:10163000042500201046002016000020003802403B +:10164000006600405041A0B05866004010230020C2 +:1016500037B51A4D00F086FD02236B71184B2881B7 +:1016600019681848012201F037FB00230193164B3B +:10167000164900931648174B4FF4805201F082FF31 +:10168000154B197811B1124801F0A4FF01F086FC46 +:101690000446FFF7E7FB4FF4C873B0FBF3F202FB1D +:1016A000130304F5167010FA83F00C4B186003F066 +:1016B00029FF08B10F232B8103B030BDF82400208F +:1016C00010230020403500206D110008082500205F +:1016D0001035002071120008042500200C35002070 +:1016E0002DE9F04F2DED028B0FF23829D9E9008951 +:1016F000834C93B00BAE9FED7E8BFFF7F1FC814FD7 +:10170000DFF828A200230A93ADF834300B937360FE +:101710004FF0000B5B468DED008B01250DF11D0296 +:1017200007A938468DF81C508DF81DB001F084FAD9 +:101730009DF81C30002B40F0A580204601F052FFA0 +:101740000646002845D1704F01F028FC3B689842BE +:101750003FD301F023FC8246FFF784FB4FF4C873AC +:10176000B0FBF3F202FB13030AF5167010FA83F0D4 +:101770003860664F97F800B0CBF1100ABBF1000F4C +:1017800014BF33462B465FFA8AFA0EA88DF828302C +:10179000FFF780FBBAF1060F28BF4FF0060A0EAB29 +:1017A00003EB0B0152460DF1290000F00FFA0AABD2 +:1017B0000393182302930AF10102554BD2B2CDE9EB +:1017C0000053049220464CA3D3E9002301F050FFBC +:1017D0003E7001F0E3FB4F4A4F4D1368C31AB3F557 +:1017E0007A7F2ED3106001F0DBFB02460B462046C9 +:1017F00001F0D6FF204601F0F5FE10B32B7A474EDC +:10180000002B14BF03230223737101F0C7FB0EAF3B +:101810004FF47A730122B0FBF3F039463060304662 +:1018200000F020FB182302933D4B019380B240F25D +:101830005513CDE90370009342464B46204601F014 +:1018400017FF2B7A93B101F0A9FB002607464FF44E +:101850008A7A95F8D900304400F003000AFB00535F +:1018600093F8E82092B30136042EF2D1C82003F099 +:1018700051F92B7A002B7FF43DAF13B0BDEC028BF6 +:10188000BDE8F08FDAF8143083F04003CAF8143062 +:10189000594610220EA800F0BFF90DF11E0308AA48 +:1018A0000AA9384600F046FF96E803000FAB83E82C +:1018B00003009DF834308DF844300A9B0E930EA936 +:1018C000DDE90823204602F03FF921E7D3F8E020C4 +:1018D00042B12B68FA2B38BFFA23BA1A0533B2EBA0 +:1018E000430FC0D3FFF7ACFB0028BCD1BEE700BF5D +:1018F0000000000000000000401DA12026812A0BEE +:1019000010350020403500200C350020093500201E +:1019100008350020404B002010460020F82400200D +:10192000444B0020F1C6A7C1D068080F0000024058 +:1019300008B5054800F098FFBDE80840034A04498F +:10194000002004F0BFBF00BF40350020804B0020C6 +:10195000391200087047000070B50F4B1B78013337 +:10196000DBB2012B0C4611D80C4D29684FF47A7369 +:101970000E6AA2FB0332014622462846B047844243 +:1019800004D1074B00221A70012070BD4FF4FA7089 +:1019900003F0C0F80020F8E71C230020F84D0020D9 +:1019A000744B002070B504464FF47A76412C2546DE +:1019B00028BF412506FB05F003F0ACF8641BF5D108 +:1019C00070BD000007B50023024601210DF107009C +:1019D0008DF80730FFF7C0FF20B19DF8070003B076 +:1019E0005DF804FB4FF0FF30F9E700000A4608B548 +:1019F0000421FFF7B1FF80F00100C0B2404208BDF2 +:101A000030B4054C2368DD69044B0A46AC460146F8 +:101A1000204630BC604700BFF84D0020A086010082 +:101A200070B503F087FB094E094D3080002428680B +:101A30003388834208D903F077FB2B6804440133D1 +:101A4000B4F5803F2B60F2D370BD00BF764B002011 +:101A5000484B002003F01EBC00F1006000F5803010 +:101A60000068704700F10060920000F5803003F0DC +:101A7000A7BB0000054B1A68054B1B889B1A8342C5 +:101A800002D9104403F050BB00207047484B00209F +:101A9000764B0020024B1B68184403F04DBB00BF7F +:101AA000484B0020024B1B68184403F05DBB00BF8D +:101AB000484B002010F003030AD1B0F5047F05D293 +:101AC00000F10050A0F57920D0F800381846704792 +:101AD0000023FBE700F10050A0F57920D0F8100AB0 +:101AE00070470000064991F8243033B10023086A9A +:101AF00081F824300822FFF7B5BF0120704700BFEE +:101B00004C4B0020014B1868704700BF002004E0D8 +:101B1000F0B51E4B1D6801382E0C0A181C48C5F381 +:101B20000B04032335460788A7420BD144680B46B4 +:101B3000013C934218461BD214F9010F48B103F837 +:101B4000010BF6E7013B00F10800ECD191420ED207 +:101B50000B4618462C24B6F5805F00F8014B0AD1DD +:101B6000824202D94122981C5A70401AF0BD0846A0 +:101B7000B6F5805FF9D041F201039D42F5D1824272 +:101B8000F3D95A2300F8013BEFE700BF002004E03F +:101B900020230020022802BF024B4FF480029A61EA +:101BA000704700BF00000240022802BF014B4022E4 +:101BB0009A61704700000240022801BF024A53693F +:101BC00083F04003536170470000024010B50023CA +:101BD000934203D0CC5CC4540133F9E710BD00003C +:101BE00010B5013810F9013F3BB191F900409C421A +:101BF00003D11AB10131013AF4E71AB191F9002089 +:101C0000981A10BD1046FCE703460246D01A12F996 +:101C1000011B0029FAD1704702440346934202D0C7 +:101C200003F8011BFAE770472DE9F8431F4D1446EE +:101C300095F824200746884652BBDFF870909CB385 +:101C400095F824302BB92022FF2148462F62FFF758 +:101C5000E3FF95F82400C0F10802A24228BF224603 +:101C6000D6B24146920005EB8000FFF7AFFF95F832 +:101C70002430A41B1E44F6B2082E17449044E4B24C +:101C800085F82460DBD1FFF72DFF0028D7D108E0CD +:101C90002B6A03EB82038342CFD0FFF723FF002898 +:101CA000CBD10020BDE8F8830120FBE74C4B00209E +:101CB000024B1A78024B1A70704700BF744B002019 +:101CC0001C23002010B5104C104802F04BFA21469E +:101CD0000E4802F073FA2468E26ED2F8043843F03A +:101CE0000203C2F804384FF47A70FFF75BFE08492C +:101CF000204602F06BFBE26ED2F8043823F00203B8 +:101D0000C2F8043810BD00BFD06B0008F84D0020A9 +:101D1000D86B0008704700002DE9F0470D460446D7 +:101D200000219046284640F27912FFF775FF2346BE +:101D300020220021284601F0A9FE231D0222202195 +:101D4000284601F0A3FE631D03222221284601F04C +:101D50009DFEA31D03222521284601F097FE04F1D4 +:101D6000080310222821284601F090FE04F11003F8 +:101D700008223821284601F089FE04F111030822C7 +:101D80004021284601F082FE04F112030822482176 +:101D9000284601F07BFE04F114032022502128463E +:101DA00001F074FE04F1180340227021284601F06E +:101DB0006DFE04F120030822B021284601F066FEE2 +:101DC00004F121030822B821284601F05FFE04F146 +:101DD0002207C0263B46314608222846083601F035 +:101DE00055FEB6F5A07F07F10107F3D104F13203E8 +:101DF00008223146284601F049FE002704F1330A43 +:101E000094F832304FEAC7099F4209F5A47615D3FA +:101E1000B8F1000F08D1314604F59973072228461E +:101E200001F034FE09F24F16274694F832213B1B8D +:101E300093420CD3F01DC008BDE8F0870AEB0703FE +:101E400008223146284601F021FE0137D8E707F283 +:101E5000331331460822284601F018FE08360137B0 +:101E6000E3E7000013B5044608460021016023465D +:101E7000C0F803102022019001F008FE0198231DF4 +:101E80000222202101F002FE0198631D032222217B +:101E900001F0FCFD0198A31D0322252101F0F6FDB0 +:101EA000019804F108031022282101F0EFFD07201A +:101EB00002B010BDF7B50023047F00910E46072243 +:101EC0001946054601F0A6FC731C0093012200236D +:101ED0000721284601F09EFCC4B9B31C00930522DB +:101EE00023460821284601F095FC0D243746B27898 +:101EF000BB1B934211D32B7FA88A0734E408BBB9DC +:101F0000844294BF0020012003B0F0BDAB8ADB0007 +:101F1000083BDB08B3700824E8E7FB1C009321466C +:101F200000230822284601F075FC08340137DEE75B +:101F3000201A18BF0120E7E7F7B50023047F0091BE +:101F40000E4608221946054601F064FC731CC4B90C +:101F50000822009311462346284601F05BFC10241A +:101F6000012372785F1C013B934211D32B7FA88A17 +:101F70000734E408BBB9844294BF0020012003B0B9 +:101F8000F0BDAB8ADB00083BDB0873700824E7E791 +:101F9000F3190093214600230822284601F03AFC59 +:101FA00008343B46DDE7201A18BF0120E7E70000B0 +:101FB000F8B50E4605461446002181223046FFF74B +:101FC0002BFE2B4608220021304601F05FFD7CB934 +:101FD0006B1C07220821304601F058FD0F24012315 +:101FE0006A785F1C013B934204D3E01DC008F8BD32 +:101FF0000824F4E7EB1921460822304601F046FD9B +:1020000008343B46ECE70000F8B50E46054614469A +:102010000021CE223046FFF7FFFD2B46282200216B +:10202000304601F033FD7CB905F108030822282170 +:10203000304601F02BFD30242F462A7A7B1B934239 +:1020400004D3E01DC008F8BD2824F5E707F1090313 +:1020500021460822304601F019FD08340137ECE72B +:10206000F7B5047F00910E4601231022002105469A +:1020700001F0D0FBC4B9B31C009309222346102100 +:10208000284601F0C7FB192437467288BB1B9A42C9 +:1020900011D82B7FA88A0734E408BBB9844294BFC7 +:1020A0000020012003B0F0BDAB8ADB00103BDB0851 +:1020B00073801024E8E73B1D00932146002308228B +:1020C000284601F0A7FB08340137DEE7201A18BFC5 +:1020D0000120E7E730B5094D0A4491420DD011F8CF +:1020E000013B5840082340F30004013B2C4013F00F +:1020F000FF0384EA5000F6D1EFE730BD2083B8ED4E +:10210000F7B54FF0FF33DFF854C0DFF854E000EBD1 +:1021100081011A4688421CD050F8044B019401AF4B +:10212000042417F8015B82EA05620825DB181646CD +:1021300005F1FF355241002EBCBF83EA0C0382EA51 +:102140000E0215F0FF05F1D1013C14F0FF04E8D1B7 +:10215000E0E7D843D14303B0F0BD00BF9336EAA90E +:10216000EBE1F042F7B53A4A106851686B4603C399 +:102170006A4638493848082304F004FC044600281D +:1021800035D10A25354A106851686B4603C36A4643 +:1021900033493148082304F0F5FB044600284DD0AC +:1021A0000369B3F5E02F49D8B0F8662040F2044146 +:1021B0008A4201D0552A41D12A4A224402F15C01C7 +:1021C0008B423BD35C3B244900209E1AFFF782FFE1 +:1021D0003246074604F164010020FFF77BFFA36845 +:1021E0009F422BD1E368984208BF002526E003698F +:1021F000B3F5E02F29D8428B40F204418A4201D046 +:10220000552A20D1174A224402F110018B4218D3DB +:10221000103B114900209D1AFFF75CFF2A46064635 +:1022200004F118010020FFF755FFA3689E4202D178 +:10223000E368984201D00D25A4E70025284603B0A5 +:10224000F0BD10259EE70C259CE70B259AE700BF03 +:10225000A86A0008DCFF060000000108B16A000857 +:1022600090FF06000800FFF710B5037C044613B981 +:10227000006804F06FFB204610BD00000023BFF390 +:102280005B8FC360BFF35B8FBFF35B8F8360BFF374 +:102290005B8F7047BFF35B8F0068BFF35B8F704746 +:1022A00070B505460C30FFF7F5FF05F1080604464A +:1022B0003046FFF7EFFFA04206D930466D68FFF7C2 +:1022C000E9FF2544281A70BD3046FFF7E3FF201AC6 +:1022D000F9E7000070B50546406898B105F10800BF +:1022E000FFF7D8FF05F10C0604463046FFF7D2FF92 +:1022F0008442304694BF6D680025FFF7CBFF013C58 +:102300002C44201A70BD000038B50C460546FFF776 +:10231000C7FFA04210D305F10800FFF7BBFF04443C +:102320006868B4FBF0F100FB1144BFF35B8F012040 +:10233000AC60BFF35B8F38BD0020FCE72DE9F041B6 +:10234000144607460D46FFF7C5FF844228BF0446E2 +:10235000D4B1B84658F80C6B4046FFF79BFF3044A9 +:10236000286040467E68FFF795FF331A9C4203D8E9 +:102370006C600120BDE8F0816B60A41B3B68AB6022 +:102380002044E8600220F5E72046F3E738B50C4624 +:102390000546FFF79FFFA04210D305F10C00FFF7A1 +:1023A00079FF04446868B4FBF0F100FB1144BFF30B +:1023B0005B8F0120EC60BFF35B8F38BD0020FCE732 +:1023C0002DE9FF41884669460746FFF7B7FF6C468F +:1023D00006B204EBC6060025B44209D06268206844 +:1023E00008EB0501FFF7F2FB636808341D44F3E7CF +:1023F00029463846FFF7CAFF284604B0BDE8F081F9 +:10240000F8B505460C300F46FFF744FF05F1080606 +:1024100004463046FFF73EFFA042304688BF6C6856 +:10242000FFF738FF201A386020B130462C68FFF7DC +:1024300031FF2044F8BD000073B5144606460D4632 +:10244000FFF72EFF844228BF04460190DCB101A9AA +:102450003046FFF7D5FF019B33B93268C5E9023337 +:10246000C5E9002401200CE09C4238BF019428609B +:10247000019868608442F5D93368AB60241AEC6037 +:10248000022002B070BD2046FBE700002DE9FF41AD +:102490000F466946FFF7D0FF6C4600B204EBC0055B +:1024A0000026AC4209D0D4F8048054F8081BB819AF +:1024B0004246FFF78BFB4644F3E7304604B0BDE8E5 +:1024C000F081000038B50546FFF7E0FF04460146FD +:1024D0002846FFF719FF204638BD0000302383F35C +:1024E000118862B670470000002383F3118862B63A +:1024F0007047000010B4026854681A4623465DF81D +:10250000044B184701207047002070470020704797 +:1025100070470000002070470E20704700F5805083 +:1025200090F8C800C0F340007047000000F58050EC +:1025300090F9C90070470000F7B50C68BDF820702D +:1025400014F000541E466FD10B7B082B6CD8FFF79C +:10255000C5FF4569AB685B010CD4AB681B0108D4AF +:10256000AC6814F080545DD1FFF7BEFF204603B085 +:10257000F0BD01240B6804F1180C002BB8BFDB0080 +:102580004FEA0C1CB4BF43F004035B0545F80C3064 +:102590000B680FFA84FC13F0804F18BF05EB0C1E7C +:1025A00005EB0C1C1EBFDEF8803143F00203CEF8B1 +:1025B00080310B7BCCF8843105EB04158B68C5F8B2 +:1025C0008C314B68C5F88831DCF8803143F0010369 +:1025D000CCF8803100EB441541F268031D4403EB55 +:1025E00044130344C5E9002608330D4601F10C0CE1 +:1025F00055F804EB43F804EB6545F9D184342D8894 +:102600001D8000EB441407F00303257925F00B052A +:102610002B432371FFF768FF0097334600F0E0FC7F +:102620000120A4E70224A5E74FF0FF309FE7000058 +:1026300013B500F580540191E06DFFF74BFE1F28A4 +:102640000AD90199E06D2022FFF7BAFEA0F120031C +:102650005842584102B010BD0020FBE708B500F514 +:102660008050FFF73BFFC06DFFF708FEBDE8084054 +:10267000FFF73ABF002202608281426082607047A9 +:1026800010B500220023C0E9002300230446038183 +:102690000C30FFF7EFFF204610BD0000F0B50546F7 +:1026A00000F580500C4690F8C83013F0040FC3F3C7 +:1026B000800108BF114661F3820304F1840680F8AB +:1026C000C83005EB461389B01B79D8072ED57AB3ED +:1026D00019072DD46846FFF7D3FF05EB441303F524 +:1026E000835303F1180703AA103318685968144676 +:1026F00003C40833BB422246F7D1186820609B8888 +:10270000A380DDE90E23CDE900230123ADF80830D5 +:102710002B686946DB6B2846984705EB46152B79F5 +:102720001A075CBF43F008032B7101E0002AF4D1C3 +:1027300009B0F0BD2DE9F047074688B007F5805491 +:1027400068469A468846FFF7C9FE9146FFF798FF0C +:10275000E06DFFF7A5FD1F2829D9E06D202269460D +:10276000FFF7B0FE202822D103AD444605AB2E462C +:1027700003CE9E4220606160354604F10804F6D124 +:1027800030682060B388A380DDE90023C9E9002315 +:10279000BDF80830AAF80030FFF7A6FE4A465346B7 +:1027A0004146384608B0BDE8F04700F007BCFFF7E7 +:1027B0009BFE002008B0BDE8F08700002DE9F84F2F +:1027C0000023C0E90133254B044640F8183B0F466F +:1027D000FFF750FF04F12800FFF752FF04F148080B +:1027E00004F582554646083530462036FFF748FF47 +:1027F000AE42F9D104F580554FF480534FF00009F3 +:10280000C5E91339C5F848800123EE6504F58758FA +:1028100004F58456C5F8549085F8583085F8603032 +:10282000083608F108084FF0000A4FF0000B46E99F +:1028300008ABA6F11800FFF71DFF203646F8289CCC +:102840004645F4D185F8C97017B1054800F0A0FBE2 +:10285000044B63612046BDE8F88F00BFE46A0008BE +:10286000BC6A00080064004010B5044B19780446A7 +:102870004A1C1A70FFF7A2FF204610BD7C4B0020B7 +:102880002DE9F04300294FD0284B2948B0FBF1F047 +:1028900099428CBF0A2311235D1EB0FBF3F703FBA3 +:1028A0001703ECB22BB1022D2B46F5D80020BDE862 +:1028B000F0837E1EB6F5806FF8D2C4EBC40C0CF129 +:1028C00003034FEAE308C3F3C703A4EB030E08F1C5 +:1028D00001094FF47A755FFA8EF008FB055559FA35 +:1028E0008EFEB5FBFEF5B5F5617FC1BF0CF1FF3380 +:1028F000C3F3C703E01AC0B25C1C50FA84F40C4D59 +:102900007C43B5FBF4F4A142D0D1013BDBB20F2BE9 +:10291000CCD80138C0B20728C8D800211071168061 +:102920009170D3700120C2E70846C0E73F420F0014 +:1029300080F9370370B505460E464FF47A746B691B +:102940005B6803F00103B34207D04FF47A7002F0E2 +:10295000E1F8013CF3D1204670BD0120FCE7000006 +:1029600030B54269936913F0700F16D000230B4CF9 +:10297000936103F1840200EB421211794D0709D5EE +:10298000890707D5416954F823508D60117941F0CA +:10299000040111710133032BEBD130BDD06A000863 +:1029A00073B51D46436916469A68D207044609D591 +:1029B0009A6801219960C2F34002CDE900650021C7 +:1029C000FFF76CFE63699A68D1050BD59A684FF4DE +:1029D00080719960C2F34022CDE900650121204653 +:1029E000FFF75CFE63699A68D2030BD59A684FF4CF +:1029F00080319960C2F34042CDE900650221204652 +:102A0000FFF74CFE204602B0BDE87040FFF7A8BFBC +:102A1000F8B50446466900296CD106F10C07386800 +:102A200080076AD006EB01153868D5F8B00110F0C0 +:102A3000040FD5F8B0011ABFC00840F00040400DA7 +:102A4000A061D5F8B0C11CF0020F1CBF40F080405F +:102A5000A061D5F8B40106EB011100F00F0084F875 +:102A60002400D1F8B8012077D1F8B801000A6077C6 +:102A7000D1F8B801000CA077D1F8B801000EE077CA +:102A8000D1F8BC0184F82000D1F8BC01000A84F818 +:102A90002100D1F8BC01000C84F82200D1F8BC114F +:102AA000090E84F823103821396004F1340004F150 +:102AB000180104F1240551F8046B40F8046BA94295 +:102AC000F9D109880180C4E90A232146002323861D +:102AD00051F8283B2046DB6B984704F5805220468E +:102AE00092F8C83043F0040382F8C830BDE8F840DB +:102AF000FFF736BF06F1100791E7F8BD10B50446A1 +:102B000000F04EFA02460B4652EA030102D0013AA7 +:102B100063F100030449086820B12146BDE8104074 +:102B2000FFF776BF10BD00BF784B0020F8B500F569 +:102B300083511E46FFF7D2FCDFF844C00831002461 +:102B400004F1840500EB45152B795F070ED4DB06F5 +:102B50000CD5D1E900739742B34107D243695CF8C1 +:102B600024709F602B7943F004032B710134032CF4 +:102B700001F12001E4D1BDE8F840FFF7B5BC00BF8A +:102B8000D06A000808B5FFF7A9FCFFF7E9FEBDE829 +:102B90000840FFF7A9BC0000F8B5436905469868EE +:102BA00000F0E050B0F1E05F0F461FD0E8B1FFF752 +:102BB00095FC05F583541034002606F1840305EBDB +:102BC00043131B791A0706D50136032E04F120049E +:102BD000F3D1012007E05B07F6D42146384600F028 +:102BE00039FA0028F0D1FFF77FFCF8BD0120FCE79F +:102BF00000F5805008B5FFF771FCC06DFFF750FB82 +:102C0000FFF772FC43090CBF0120002008BD000043 +:102C1000F8B51D46002313700F4606461446FFF70D +:102C2000E7FF80F00100387025B129463046FFF7F4 +:102C3000B3FF2070F8BD00002DE9B8410C461546E1 +:102C40001F46804600F0ACF90B462178024609B9D0 +:102C5000287850B14046FFF769FFFFF793FF3B46E6 +:102C60002A462146FFF7D4FF0120BDE8B8810000C5 +:102C700010B5FFF733FC174B1A6C42F000721A6460 +:102C80001A6A42F000721A621A6A00F5805422F041 +:102C900000721A62FFF728FC94F8C830DB0718D4DA +:102CA000B9B103211320FFF719FC01F0CBF903217F +:102CB000142001F0C7F90321152001F0C3F994F89D +:102CC000C83043F0010384F8C830BDE81040FFF776 +:102CD0000BBC10BD003802402DE9F04700F58055CF +:102CE00088B095F8C930012B0446884616467FD82F +:102CF000804F57F823200AB947F82300D7F800A0DF +:102D0000C4F80C802674BAF1000F63D095F8C9306E +:102D1000012B6FD001212046FFF7AAFFFFF7DEFB52 +:102D20006269136823F0020313606269136843F059 +:102D300001031360636900275F6101212046FFF7EB +:102D4000D3FBFFF7F7FD002800F09580E86DFFF753 +:102D500095FA04F58359BA4609F1080920220021A1 +:102D60006846FEF759FF02A8FFF784FCCDF818A0CB +:102D70006A4609EB07030DF1180E9446BCE8030000 +:102D8000F44518605960624603F10803F5D1DCF898 +:102D90000000186020379CF804201A71602FDDD1E4 +:102DA00095F8C8306FF38203002785F8C8306A466B +:102DB00041462046ADF80070ADF802708DF8047001 +:102DC000FFF75EFD636948BB4FF400421A6008B02C +:102DD000BDE8F08741F2D00003F07CFD814610B1E0 +:102DE0005146FFF7EBFCC7F80090B9F1000F8DD109 +:102DF0000020ECE7386803681B6B98470146002801 +:102E000088D13868FFF734FF3868036832465B685A +:102E10004146984700287FF47DAFE9E761221A60B8 +:102E20009DF802309DF803201B06120402F4702264 +:102E300003F040731343BDF80020C2F309021343AB +:102E40009DF804201205022E02F4E0020CBF4FF0A0 +:102E500000410021134362690B43D361636913226C +:102E60005A616269136823F00103136039462046F2 +:102E7000FFF760FD08B96369A6E795F8C93093BB11 +:102E80006169D1F8002242F00102C1F800226169B3 +:102E9000D1F8002222F47C5222F00E02C1F8002266 +:102EA0006169D1F8002242F46062C1F800226269CF +:102EB000C2F814326269C2F80432626941F6FF71E5 +:102EC000C2F80C126269C2F840326269C2F8443238 +:102ED00063690122C3F81C226269D2F8003223F030 +:102EE0000103C2F8003295F8C83043F0020385F8B8 +:102EF000C8306CE7784B002008B500F051F850EA74 +:102F00000103024602D0421E61F10001044B186821 +:102F100010B10B46FFF744FDBDE8084001F068B86A +:102F2000784B002008B50020FFF7E8FDBDE8084019 +:102F300001F05EB808B50120FFF7E0FDBDE80840EC +:102F400001F056B800B59BB0EFF3098168226846DE +:102F5000FEF73CFEEFF30583014B9B6BFEE700BFE2 +:102F600000ED00E008B5FFF7EDFF000000B59BB0F5 +:102F7000EFF3098168226846FEF728FEEFF3058328 +:102F8000014B5B6BFEE700BF00ED00E0FEE70000D9 +:102F90000FB408B5029801F049FDFEE702F0DEB972 +:102FA00002F0B6B913B56C4684E80600031D94E838 +:102FB000030083E80500012002B010BD73B58568E9 +:102FC000019155B11B885B0707D4D0E900369B6B94 +:102FD0009847019AC1B23046A847012002B070BD9F +:102FE000F0B5866889B005460C465EB1BDF838304C +:102FF0005B070AD4D0E900379B6B98472246C1B2E1 +:103000003846B047012009B0F0BD00220023CDE9C9 +:1030100000230023ADF808300A4603AB01F108068F +:10302000106851681C4603C40832B2422346F7D1E7 +:10303000106820609288A280FFF7B2FF0423ADF8E9 +:1030400008302B68CDE90001DB6B694628469847BC +:10305000D8E7000030B503680968DD0FB5EBD17F14 +:1030600023F0604421F060424FEAD1700BD0002B76 +:10307000B8BFA40C0029B8BF920C944202D034BF50 +:103080000120002030BD944205D1C1F38070C3F30C +:1030900080738342F6D194422CBF00200120F1E7D7 +:1030A0002DE9F041456A15B94162BDE8F0814B68F0 +:1030B00023F06047C3F38A464FEAD37EC3F3807898 +:1030C00016EA230638BF3E46AC462B465A68BEEB8E +:1030D000D27F22F060440AD0002A18DAA40CB4424D +:1030E00017D19D420FD10D60DEE71346EEE7A742F0 +:1030F00007D102F08044C2F3807242450BD054B134 +:10310000EFE708D2EDE7CCF800100B60CDE7B44252 +:1031100001D0B442E5D81A689C46002AE5D119606E +:10312000C3E700002DE9F047089D01F007044FEACE +:10313000D508224405F0070500EBD1004FF47F4984 +:10314000944201D1BDE8F08704F0070705F0070AB3 +:1031500057453E4638BF5646C6F10806111B8E42FB +:1031600028BF0E46E10808EBD50E415C13F80EC0EF +:10317000B94029FA06F721FA0AF1FFB28CEA0101F7 +:1031800047FA0AF739408CEA010C03F80EC03444C0 +:103190003544D5E780EA0120082341F2210201B23B +:1031A0004000002980B203F1FF33B8BF504013F054 +:1031B000FF03F4D17047000038B50C468D18A542C6 +:1031C00000D138BD14F8011BFFF7E4FFF7E700005A +:1031D00042684AB1136843604389818901339BB2D5 +:1031E0009942438138BF83811046704770B588B0DB +:1031F000202204460D4668460021FEF70DFD2046BC +:103200000495FFF7E5FF024658B16B46054608AE48 +:103210001C4603CCB44228606960234605F10805CA +:10322000F6D1104608B070BD082817D909280CD06F +:103230000A280CD00B280CD00C280CD00D280CD050 +:103240000E2814BF4020302070470C2070471020FB +:1032500070471420704718207047202070470000E6 +:10326000082817D90C280CD910280CD914280CD9E7 +:1032700018280CD920280CD930288CBF0F200E20FC +:103280007047092070470A2070470B2070470C20B8 +:1032900070470D20704700002DE9F843078C072F79 +:1032A00004461ED9D0E9029800254FF6FF73C5F1F8 +:1032B0002006A5F1200029FA05F108FA06F628FAF9 +:1032C00000F031430143C9B21846FFF763FF0835E8 +:1032D000402D0346EBD1E1693A46BDE8F843FFF7DC +:1032E0006BBF4FF6FF70BDE8F883000010B54B6868 +:1032F00023B9CA8A63F30902CA8210BD04691A6835 +:103300001C600361C38A013BC3824A60EFE700008F +:103310002DE9F84F1D46CB8A0F46C3F30901052955 +:10332000814692460B4630D00020AAB207F11A041B +:103330009EB2042E1FFA80F80FD8904503F10103C6 +:1033400006D3FB8A0A4462F30903FB8201201AE0D8 +:103350001AF80060E6540130EAE79045F1D2A1F195 +:10336000050B1C237C68BBFBF3F203FB12BB1FFAAB +:103370008BF6002C45D14846FFF72AFF044638B9A2 +:1033800078606FF00200BDE8F88F4FF00008E6E7C4 +:10339000002606607860ADB24FF0000B454510D9AD +:1033A0000AEB0803221D13F8011B9155B1B208F175 +:1033B00001081B291FFA88F82BD0454506F10106A4 +:1033C000F1D8FB8AC3F30902154465F30903BCE78E +:1033D000013292B21C462368002BF9D16B1F0B44BB +:1033E0001C21B3FBF1F301339BB29A42D3D2BBF160 +:1033F000000FD0D14846FFF7EBFE20B9C4F800B06B +:10340000BFE70122E7E7C0F800B05E46206004464F +:10341000C1E74545D5D94846FFF7DAFE08B920602F +:10342000AFE7C0F800B0002620600446B6E7000011 +:103430002DE9F04F2DED028B1C4683B05B690192A4 +:1034400007468846002B00F09A80238C2BB1E26956 +:10345000002A00F09480072B35D807F10C00FFF705 +:10346000B7FE054638B96FF00205284603B0BDEC3B +:10347000028BBDE8F08F14220021FEF7CDFB228CD9 +:10348000E16905F10800FEF7A1FB208C013080B254 +:10349000FFF7E6FEFFF7C8FE013880B22084013056 +:1034A00028746369228C1B782A4403F01F0363F09D +:1034B0003F0348F000411372384669602946FFF720 +:1034C000EFFD0125D1E700F10C034FF0000908EEF4 +:1034D000103A4FF0800A4E464D4618EE100AFFF79C +:1034E00077FE83460028BED014220021FEF794FB0D +:1034F000002E3AD1019BABF8083002220BF1080EE6 +:103500001FFA82FC0CF10100BCF1060F218C80B285 +:1035100001D88E422BD3FFF7A3FEFFF785FE626929 +:103520001278013802F01F028E4208BF4FF0400AA5 +:1035300042EA49121BFA80F14AEA020A013048F0D5 +:10354000004281F808A08BF81000CBF804205946FF +:103550003846FFF7A5FD238C0135B3422DB289F023 +:1035600001094FF0000AB8D17FE70022C6E7E16900 +:10357000895D0EF802100136B6B20132C0E76FF075 +:10358000010572E7F8B515460E46302200210446C3 +:103590001F46FEF741FB069B6360B5F5001F079BC6 +:1035A000A76034BF6A094FF6FF72A36297B2E66163 +:1035B00004F1100000239A4206D800230360A7827A +:1035C000E3822383E360F8BD066001333046203692 +:1035D000F1E7000003781BB94BB2002BC8BF0170A4 +:1035E0007047000000787047F8B50C46C969074677 +:1035F00011B9238C002B37D1257E1F2D34D8387874 +:1036000028BB228C072A2CD8268A36F003032BD11C +:103610004FF6FF70FFF7D0FD20F0010031024004AB +:1036200041EA0561400C41EA40254FF6FF7223460E +:1036300029463846FFF7FCFE002807DD626913784B +:103640000133DBB21F2B88BF00231370F8BD218A22 +:103650002D0645EA012505432046FFF71DFE0246DB +:10366000E5E76FF00300F1E76FF00100EEE700001F +:1036700070B58AB0044616460021282268461D46C9 +:10368000FEF7CAFABDF83830ADF810300F9B05933D +:103690009DF840308DF81830119B07936946BDF8AE +:1036A0004830ADF820302046CDE90265FFF79CFF99 +:1036B0000AB070BD2DE9F041D36905460C461646A7 +:1036C0000BB9138C5BBB377E1F2F28D895F8008071 +:1036D000B8F1000F26D03046FFF7DEFD3378210227 +:1036E00041EAC33141EA0801338A41EA076141EA0C +:1036F00003410246334641F080012846FFF798FE19 +:1037000000280ADD3378012B07D172691378013361 +:10371000DBB21F2B88BF00231370BDE8F0816FF070 +:103720000100FAE76FF00300F7E70000F0B58BB097 +:1037300004460D4617460021282268461E46FEF71D +:103740006BFA9DF84C305A1E534253418DF80030AD +:103750009DF84030ADF81030119B05939DF848302E +:103760008DF81830149B07936A46BDF85430ADF8B5 +:10377000203029462046CDE90276FFF79BFF0BB0AB +:10378000F0BD0000406A00B104307047436A1A6817 +:10379000426202691A600361C38A013BC3827047B7 +:1037A0002DE9F041D0F82080194E14461D464146BF +:1037B000002709B9BDE8F081D1E90223A21A65EB1F +:1037C0000303964277EB03031ED2036A8B420DD1AB +:1037D000FFF78CFD036A1B68036203690B60C38AF1 +:1037E0000161016A013BC3828846E2E7FFF77EFD83 +:1037F0000B68C8F8003003690B60C38A0161013BA4 +:10380000C382D8F80010D4E788460968D1E700BF22 +:1038100080841E002DE9F04F8BB00D46DDF85090EE +:1038200014469B468046002800F01981B9F1000F2C +:1038300000F01581531E3F2B00F21181012A03D1A4 +:10384000BBF1000F40F00B810023CDE90833B8F83D +:103850001430B5EBC30F4FEAC30703D300200BB0FE +:10386000BDE8F08F2B199F42D8F80C303ABF7F1B70 +:10387000FFB227461BB9D8F81030002B7AD0272D7D +:103880004ED8C5F12806B7424FF000032CBFF6B260 +:103890003E4600932946D8F8080008AB3246FFF7A9 +:1038A00041FCA7EB060A35445FFA8AFAB8F81430EF +:1038B00003F10053053BDB000493D8F80C3003936D +:1038C0002821039B13B1BAF1000F2CD1D8F81000B6 +:1038D00040B1BAF1000F05D0009608AB5246691A04 +:1038E000FFF720FC38B2002FB8D066070AD00AAB29 +:1038F00003EBD401624211F8083C02F007021341C5 +:1039000001F8083C082C3CD9102C40F2B580202C42 +:1039100040F2B780BBF1000F00F09C80082334E038 +:10392000BA460026C2E7049BE02B28BFE02306939B +:103930000B44AB42059314D95A1B03980096924549 +:1039400034BF5246D2B2691A08AB04300792FFF76F +:10395000E9FB079A1644AAEB020A1544F6B25FFA8D +:103960008AFA049B069A05999B1A0493039B1B6889 +:103970000393A6E70093D8F8080008AB3A46294617 +:10398000AEE7BBF1000F13D00123B4EBC30F6CD033 +:10399000082C12D89DF82030621E23FA02F2D507B7 +:1039A00006D54FF0FF3202FA04F423438DF820309D +:1039B0009DF8203089F8003051E7102C12D8BDF85E +:1039C0002030621E23FA02F2D10706D54FF0FF32F3 +:1039D00002FA04F42343ADF82030BDF82030A9F8F2 +:1039E00000303CE7202C0FD80899631E21FA03F31E +:1039F000DA0705D54FF0FF3202FA04F40C430894BD +:103A0000089BC9F800302AE7402C2BD0DDE9086577 +:103A1000611EC4F12102A4F1210326FA01F105FA85 +:103A200002F225FA03F311431943CB0712D5012201 +:103A3000A4F12003C4F1200102FA03F322FA01F1F8 +:103A4000A240524243EA010363EB430332432B4358 +:103A5000CDE90823DDE90823C9E90023FFE66FF07B +:103A60000100FCE66FF00800F9E6082CA0D9102C44 +:103A7000B3D9202CEED8C3E7BBF1000FADD00223A1 +:103A800083E7BBF1000FBBD004237EE730B5012AEA +:103A9000144638BF0124402C85B028BF402400259F +:103AA000012ACDE9025518D81B788DF80830630734 +:103AB0000AD004AB03EBD405624215F8083C02F0CF +:103AC0000702934005F8083C009103462246002176 +:103AD00002A8FFF727FB05B030BD082AE4D9102A59 +:103AE00003D81B88ADF80830E1E7202A8DBFD3E961 +:103AF00000231B680293CDE90223D8E710B5CB68F9 +:103B00001BB98B600B618B8210BD04691A681C6045 +:103B10000361C38A013BC382CA60F0E703064CBF5E +:103B2000C0F3C0300220704708B50246FFF7F6FF29 +:103B3000022806D15306C2F30F2001D100F0030082 +:103B400008BDC2F30740FBE72DE9F04F93B0CDE984 +:103B500003230A6804461046FFF7E0FF022814BF5B +:103B6000C2F306260026002A0D46824680F2F28124 +:103B700012F0C04940F0EE81097B002900F0EA8193 +:103B8000022803D02378B34240F0E781C2F30463F4 +:103B90000693104602F07F030593FFF7C5FF059BD0 +:103BA00029444FEA834848EA0A4848EA4668CE78FA +:103BB00000230022CDE90823F309834648EA0008E0 +:103BC000029367D0059B009302466768534608A995 +:103BD0002046B847002800F0C381276A4FB9414604 +:103BE00004F10C00FFF702FB074690B96FF00200EA +:103BF00054E03B6998450DD03F68002FF9D141460C +:103C000004F10C00FFF7F2FA07460028EED0236A11 +:103C10003B60276297F817C006F01F08CCF3840CAE +:103C2000ACEB08001FFA80FE0028B8BF0EF12000A0 +:103C3000A8EB0C031FFA83FED7E90221B8BF00B23C +:103C4000002B0793BEBF0EF120031BB2079352EA6D +:103C5000010338D0039BDFF824E39A1A049B4FF04A +:103C6000000C63EB010196457CEB01032BD36B7BCE +:103C700097F81AE0734519D1029B002B78D00128E0 +:103C800021DC7868F8B9DFF8F0C2944570EB0103E5 +:103C900016D337E0276A27B96FF00C0013B0BDE8E0 +:103CA000F08F3B699845B5D03F68F4E7B248904241 +:103CB0007CEB010301D30020F0E7029B002BFAD03C +:103CC000079B0F2B17DCFA7DB30002F0030203F011 +:103CD0007C031343FB7539462046FFF707FB6B7BDC +:103CE000BB76029B3BB9FB7DC3F38402013262F3D6 +:103CF0008603FB75D0E76A7BBB7E9A42DBD1029BD1 +:103D0000002B35D0B309022B32D0039BBB60049B40 +:103D1000FB60142200210DA8FDF77EFF039B0A9390 +:103D2000049B0B932B1D0C932B7BADF83EB0013BFA +:103D3000DBB2ADF83C30069B8DF84230059B8DF828 +:103D4000433094F82C308DF840A083F001038DF8B7 +:103D500044308DF84180A3680AA920469847FB7D2E +:103D6000C3F38403013303F01F039B02FB82A2E72A +:103D7000FB7DC6F34012B2EBD31F40F0F480C3F3D7 +:103D80008403434540F0F280029A2B7BB609002A57 +:103D90004DD0F2075DD4032B40F2EB80039BBB6058 +:103DA000049BFB602B7BAE1D033BDBB232463946E6 +:103DB00004F10C00FFF7ACFA00280CDA3946204673 +:103DC000FFF794FAFB7DC3F38403013303F01F0371 +:103DD0009B02FB820AE7DDE90884AB883B834FF650 +:103DE000FF73C9F12000A9F1200228FA09F104FAB1 +:103DF00000F0014324FA02F211431846C9B2FFF75A +:103E0000C9F909F10809B9F1400F0346E9D1B882AF +:103E10002A7B033AD2B23146FFF7CEF9FB7DB88256 +:103E2000DA43C2F3C01262F3C713FB7543E786B9E6 +:103E30002E1D013BDBB23246394604F10C00FFF780 +:103E400067FA0028BADB2A7BB88A013AD2B2314637 +:103E5000E2E7F98AC1F30901013B0429DAB25BD830 +:103E6000281D002307F11B069A4208D910F801CB40 +:103E700006F801C0013101330529DBB2F4D1039901 +:103E80000A9104990B91934207F11B010C9138BFE1 +:103E9000043379680D9134BF55FA83F300230E93F0 +:103EA000FB8AADF83EB0C3F309031A44069B8DF8B4 +:103EB0004230059B8DF8433094F82C30ADF83C200F +:103EC00083F001038DF8443000238DF840A08DF875 +:103ED00041807B602A7BB88A013A291DFFF76CF983 +:103EE0003B8BB882834203D1A3680AA92046984736 +:103EF00020460AA9FFF702FEFB7DBA8AC3F38403BA +:103F0000013303F01F039B02FB823B8B9A420CBFE1 +:103F100000206FF01000C1E67B68002BAFD00520B9 +:103F200001E01C3033461E68002EFAD1091A081D24 +:103F30002E1D184401EB090CBCF11B0F5FFA89F32D +:103F40009DD89A429BD916F8013B00F8013B09F134 +:103F50000109EFE76FF00900A0E66FF00A009DE6A7 +:103F60006FF00B009AE66FF00D0097E66FF00E0011 +:103F700094E66FF00F0091E640420F0080841E002F +:103F8000EFF3098305494A6B22F001024A63683363 +:103F900083F30988002383F31188704700EF00E062 +:103FA000302080F3118862B60D4B0E4AD96821F497 +:103FB000E0610904090C0A43DA60D3F8FC200A49DD +:103FC00042F08072C3F8FC20084AC2F8B01F1168A2 +:103FD00041F0010111602022DA7783F82200704756 +:103FE00000ED00E00003FA0555CEACC5001000E07E +:103FF00010B5302383F311880E4B5B6813F4006314 +:1040000014D0F1EE103AEFF30984683C4FF080735E +:10401000E361094BDB6B236684F3098800F0C4FC81 +:1040200010B1064BA36110BD054BFBE783F311886C +:10403000F9E700BF00ED00E000EF00E063060008D4 +:104040006606000800F1604303F561430901C9B247 +:1040500083F80013012200F01F039A4043099B00DC +:1040600003F1604303F56143C3F880211A60704790 +:10407000026843681143016003B1184770470000AC +:1040800013B5446BD4F894341A681178042915D107 +:10409000217C022912D11979128901238B40134204 +:1040A0000CD101A904F14C0002F060F8D4F894445A +:1040B000019B21790246206800F0D6F902B010BDBC +:1040C000143001F0E3BF00004FF0FF33143001F073 +:1040D000DDBF00004C3002F0B5B800004FF0FF33F8 +:1040E0004C3002F0AFB80000143001F0B1BF000056 +:1040F0004FF0FF31143001F0ABBF00004C3002F044 +:1041000081B800004FF0FF324C3002F07BB8000065 +:104110000020704710B5D0F894341A68117804293B +:10412000044617D1017C022914D1597952890123FF +:104130008B4013420ED1143001F044FF024648B1C7 +:10414000D4F894444FF4807361792068BDE810403E +:1041500000F078B910BD0000406BFFF7DBBF000036 +:10416000704700007FB5124B036000234360C0E935 +:104170000233012502260F4B057404460290019379 +:1041800000F18402294600964FF48073143001F048 +:10419000F5FE094B0294CDE9006304F523724FF458 +:1041A0008073294604F14C0001F0BCFF04B070BDDF +:1041B000246B000859410008814000080B68302238 +:1041C00082F311880A7903EB820210624A790D3278 +:1041D00043F822008A7912B103EB820318620223AA +:1041E000C0F894140374002080F311887047000015 +:1041F00038B5037F044613B190F85430ABB9201D95 +:1042000001250221FFF734FF04F1140025776FF038 +:10421000010100F0A7FC84F8545004F14C006FF049 +:104220000101BDE8384000F09DBC38BD10B501214A +:1042300004460430FFF71CFF0023237784F8543032 +:1042400010BD000038B504460025143001F0AEFE64 +:1042500004F14C00257701F07DFF201D84F85450B7 +:104260000121FFF705FF2046BDE83840FFF752BFA8 +:1042700090F85C3003F06003202B07D190F85D20AC +:10428000212A4FF0000303D81F2A06D800207047C8 +:10429000222AFBD1C0E9143303E0034A0265072256 +:1042A00042658365012070473823002037B5D0F878 +:1042B00094341A681178042904461AD1017C022921 +:1042C00017D11979128901238B40134211D100F1C2 +:1042D0004C05284601F0FEFF58B101A9284601F01F +:1042E00045FFD4F89444019B21790246206800F0F0 +:1042F000BBF803B030BD0000F0B500EB810385B022 +:104300001E6A04460D46FEB1302383F3118804EB88 +:104310008507301D0821FFF7ABFEFB685B691B6852 +:1043200006F14C001BB1019001F02EFF019803A98A +:1043300001F01CFF024648B1039B2946204600F0CD +:1043400093F8002383F3118805B0F0BDFB685A6928 +:104350001268002AF5D01B8A013B1340F1D104F109 +:104360005C02EAE70D3138B550F82140DCB130236A +:1043700083F31188D4F894241368527903EB8203F1 +:10438000DB689B695D6845B104216018FFF770FE2A +:10439000294604F1140001F01FFE2046FFF7BAFE83 +:1043A000002383F3118838BD7047000001F080B905 +:1043B00010B501230446282200F8243B0021FDF714 +:1043C0002BFC0023C4E9013310BD000038B50446BE +:1043D000302383F311880025C0E90355C0E9055552 +:1043E000C0E90755416001F073F90223237085F39A +:1043F0001188284638BD000070B500EB81030546E2 +:104400005069DA600E46144618B110220021FDF7FB +:1044100003FCA06918B110220021FDF7FDFB314615 +:104420002846BDE8704001F01DBA0000826802F025 +:10443000011282600022C0E90422C0E90622026261 +:1044400001F09CBAF0B400EB81044789E4680125CF +:10445000A4698D403D43458123600023A2606360D1 +:10446000F0BC01F0B7BA0000F0B400EB810407899A +:10447000E468012564698D403D4305812360002384 +:10448000A2606360F0BC01F031BB000070B5022394 +:10449000002504460370C0E90255C0E90455C0E98F +:1044A00006554566056280F84C5001F077F963685F +:1044B0001B6823B129462046BDE87040184770BDEF +:1044C0000378052B10B504460AD080F86830052320 +:1044D000037043681B680BB1042198470023A36055 +:1044E00010BD00000178052906D190F868204368C6 +:1044F00002701B6803B118477047000070B590F850 +:104500004C30044613B1002380F84C3004F15C02B7 +:10451000204601F055FA63689B68B3B994F85C30A3 +:1045200013F0600535D00021204601F009FD00217F +:10453000204601F0FBFC63681B6813B1062120468E +:104540009847062384F84C3070BD204698470028D1 +:10455000E4D0B4F86230626D9A4288BF636594F922 +:104560005C30656D002B4FF0300380F20381002D2D +:1045700000F0F280092284F84C2083F31188002196 +:10458000D4E914232046FFF76FFF002383F311883B +:10459000DAE794F85D2003F07F0343EA022340F258 +:1045A0000232934200F0C58021D8B3F5807F48D015 +:1045B0000DD8012B3FD0022B00F09380002BB2D1FD +:1045C00004F16402226502226265A365C1E7B3F5C6 +:1045D000817F00F09B80B3F5407FA4D194F85E30DA +:1045E000012BA0D1B4F8643043F0020332E0B3F5FC +:1045F000006F4DD017D8B3F5A06F31D0A3F5C063CD +:10460000012B90D8636894F85E205E6894F85F1080 +:10461000B4F860302046B047002884D04368236552 +:10462000036863651AE0B3F5106F36D040F60242B6 +:1046300093427FF478AF5C4B2365022363650023CC +:10464000C3E794F85E30012B7FF46DAFB4F86430AB +:1046500023F00203C4E91455A4F86430A56578E793 +:10466000B4F85C30B3F5A06F0ED194F85E3084F8E6 +:104670006630204601F0EAF863681B6813B1012137 +:1046800020469847032323700023C4E914339CE792 +:1046900004F1670323650123C3E72378042B10D1BA +:1046A000302383F311882046FFF7C0FE85F311887D +:1046B0000321636884F8675021701B680BB12046A2 +:1046C000984794F85E30002BDED084F867300423DE +:1046D000237063681B68002BD6D0022120469847C0 +:1046E000D2E794F860301D0603F00F0120460AD58A +:1046F00001F058F9012804D002287FF414AF2B4BA5 +:104700009AE72B4B98E701F03FF9F3E794F85E3016 +:10471000002B7FF408AF94F8603013F00F01B3D092 +:104720001A06204602D501F01FFCADE701F012FC8D +:10473000AAE794F85E30002B7FF4F5AE94F8603071 +:1047400013F00F01A0D01B06204602D501F0F8FBA4 +:104750009AE701F0EBFB97E7142284F84C2083F3EF +:1047600011882B462A4629462046FFF76BFE85F323 +:104770001188E9E65DB1152284F84C2083F3118895 +:104780000021D4E914232046FFF75CFEFDE60B224E +:1047900084F84C2083F311882B462A46294620466C +:1047A000FFF762FEE3E700BF546B00084C6B0008A4 +:1047B000506B000838B590F84C300446002B3ED0C2 +:1047C000063BDAB20F2A34D80F2B32D8DFE803F0D9 +:1047D00037313108223231313131313131313737EE +:1047E000456DB0F862309D4214D2C3681B8AB5FB98 +:1047F000F3F203FB12556DB9302383F311882B4676 +:104800002A462946FFF730FE85F311880A2384F8EB +:104810004C300EE0142384F84C30302383F311889D +:1048200000231A4619462046FFF70CFE002383F3A7 +:10483000118838BD836D03B198470023E7E7002155 +:10484000204601F07DFB0021204601F06FFB6368EC +:104850001B6813B10621204698470623D7E70000BE +:1048600010B590F84C30142B044629D017D8062BDD +:1048700005D001D81BB110BD093B022BFBD800218C +:10488000204601F05DFB0021204601F04FFB6368EC +:104890001B6813B1062120469847062319E0152B03 +:1048A000E9D10B2380F84C30302383F311880023A7 +:1048B0001A461946FFF7D8FD002383F31188DAE77B +:1048C000C3689B695B68002BD5D1836D03B19847A2 +:1048D000002384F84C30CEE7002303758268036917 +:1048E0001B6899689142FBD25A680360426010606D +:1048F0005860704700230375826803691B689968D4 +:104900009142FBD85A68036042601060586070475B +:1049100008B50846302383F311880B7D032B05D09F +:10492000042B0DD02BB983F3118808BD8B690022AD +:104930001A604FF0FF338361FFF7CEFF0023F2E7E9 +:10494000D1E9003213605A60F3E70000FFF7C4BFFB +:10495000054BD9680875186802681A60536001220F +:104960000275D860FBF768BE884B002030B50C4B51 +:10497000DD684B1C87B004460FD02B46094A6846B9 +:1049800000F084F92046FFF7E3FF009B13B168466F +:1049900000F086F9A86907B030BDFFF7D9FFF9E745 +:1049A000884B002011490008044B1A68DB689068A6 +:1049B0009B68984294BF002001207047884B0020DC +:1049C000084B10B51C68D86822681A605360012231 +:1049D0002275DC60FFF78EFF01462046BDE81040DF +:1049E000FBF72ABE884B0020044B1A68DB689268EC +:1049F0009B689A4201D9FFF7E3BF7047884B0020BC +:104A000038B5074C07490848012300252370656025 +:104A100001F098FC0223237085F3118838BD00BF94 +:104A2000F04D00205C6B0008884B002008B572B682 +:104A3000044B186500F042FC00F02EFD024B0322EF +:104A40001A70FEE7884B0020F04D002000F05EB9A0 +:104A5000EFF3118020B9EFF30583302282F3118840 +:104A60007047000010B530B9EFF30584C4F30804B3 +:104A700014B180F3118810BDFFF7B6FF84F31188DD +:104A8000F9E70000034A516853685B1A9842FBD863 +:104A9000704700BF001000E08B60022308618B822A +:104AA000084670478368A3F1840243F8142C026916 +:104AB00043F8442C426943F8402C094A43F8242C1B +:104AC000C26843F8182C022203F80C2C002203F8C9 +:104AD0000B2C044A43F8102CA3F12000704700BFB0 +:104AE00051060008884B002008B5FFF7DBFFBDE842 +:104AF0000840FFF72BBF0000024BDB6898610F20D6 +:104B0000FFF726BF884B0020302383F31188FFF77F +:104B1000F3BF000008B50146302383F31188082055 +:104B2000FFF724FF002383F3118808BD064BDB68E1 +:104B300039B1426818605A60136043600420FFF77F +:104B400015BF4FF0FF307047884B00200368984234 +:104B500006D01A680260506099611846FFF7F6BEE9 +:104B60007047000038B504460D462068844200D1E5 +:104B700038BD036823605C608561FFF7E7FEF4E7FA +:104B800010B503689C68A2420CD85C688A600B6010 +:104B90004C602160596099688A1A9A604FF0FF331F +:104BA000836010BD1B68121BECE700000A2938BFA8 +:104BB0000A2170B504460D460A26601901F0BCFBB7 +:104BC00001F0A8FB041BA54203D8751C2E46044621 +:104BD000F3E70A2E04D9BDE87040012001F0F2BBD2 +:104BE00070BD0000F8B5144B0D46D96103F11001FA +:104BF00041600A2A1969826038BF0A220160486050 +:104C00001861A818144601F089FB0A2701F082FBFD +:104C1000431BA342064606D37C1C281901F08CFBDB +:104C200027463546F2E70A2F04D9BDE8F8400120AF +:104C300001F0C8BBF8BD00BF884B0020F8B50646A0 +:104C40000D4601F067FB0F4A134653F8107F9F4251 +:104C500006D12A4601463046BDE8F840FFF7C2BFFC +:104C6000D169BB68441A2C1928BF2C46A34202D92B +:104C70002946FFF79BFF224631460348BDE8F8402E +:104C8000FFF77EBF884B0020984B002010B4C0E98E +:104C9000032300235DF8044B4361FFF7CFBF0000FF +:104CA00010B5194C236998420DD0D0E900328168C3 +:104CB00013605A609A680A449A60002303604FF0B8 +:104CC000FF33A36110BD2346026843F8102F5360E1 +:104CD0000022026022699A4203D1BDE8104001F02F +:104CE00025BB936881680B44936001F013FB226934 +:104CF000E1699268441AA242E4D91144BDE8104027 +:104D0000091AFFF753BF00BF884B00202DE9F04779 +:104D1000DFF8BC8008F110072C4ED8F8105001F0D5 +:104D2000F9FAD8F81C40AA68031B9A423ED81444EA +:104D3000D5E900324FF00009C8F81C4013605A60F2 +:104D4000C5F80090D8F81030B34201D101F0EEFA66 +:104D500089F31188D5E9033128469847302383F336 +:104D600011886B69002BD8D001F0D4FA6A69A0EBE6 +:104D700004094A4582460DD2022001F023FB00229D +:104D8000D8F81030B34208D151462846BDE8F04764 +:104D9000FFF728BF121A2244F2E712EB090938BFC5 +:104DA0004A4629463846FFF7EBFEB5E7D8F81030FB +:104DB000B34208D01444211AC8F81C00A960BDE809 +:104DC000F047FFF7F3BEBDE8F08700BF984B002027 +:104DD000884B002000207047FEE70000704700006D +:104DE0004FF0FF307047000002290CD0032904D097 +:104DF0000129074818BF00207047032A05D8054835 +:104E000000EBC2007047044870470020704700BFA5 +:104E1000346C000848230020E86B000870B59AB095 +:104E20000546084601A9144600F0C2F801A8FCF79F +:104E3000EBFE431C5B00C5E9003400222370032312 +:104E40006370C6B201AB02341046D1B28E4204F197 +:104E5000020401D81AB070BD13F8011B04F8021C3B +:104E600004F8010C0132F0E708B5302383F3118810 +:104E70000348FFF71BFA002383F3118808BD00BF26 +:104E8000F84D002090F85C3003F01F02012A07D192 +:104E900090F85D200B2A03D10023C0E9143315E0FC +:104EA00003F06003202B08D1B0F860302BB990F8E4 +:104EB0005D20212A03D81F2A04D8FFF7D9B9222A56 +:104EC000EBD0FAE7034A02650722426583650120B9 +:104ED000704700BF3F23002007B5052917D8DFE83A +:104EE00001F0191603191920302383F31188104A91 +:104EF00001900121FFF780FA01980E4A0221FFF785 +:104F00007BFA0D48FFF79EF9002383F3118803B065 +:104F10005DF804FB302383F311880748FFF768F935 +:104F2000F2E7302383F311880348FFF77FF9EBE7BB +:104F3000886B0008AC6B0008F84D002038B50C4DAC +:104F40000C4C0D492A4604F10800FFF767FF05F1F4 +:104F5000CA0204F110000949FFF760FF05F5CA72A3 +:104F600004F118000649BDE83840FFF757BF00BFFD +:104F7000C052002048230020686B0008726B0008B4 +:104F80007D6B000870B5044608460D46FCF73CFEF4 +:104F9000C6B22046013403780BB9184670BD3246BC +:104FA0002946FCF71DFE0028F3D10120F6E700009A +:104FB0002DE9F84F05460C46FCF726FE2B49C6B2F4 +:104FC0002846FFF7DFFF08B10336F6B22849284626 +:104FD000FFF7D8FF08B11036F6B2632E0DD8DFF810 +:104FE0008C80DFF88C90234FDFF890A0DFF890B032 +:104FF0002E7846B92670BDE8F88F29462046BDE8D0 +:10500000F84F01F025BD252E2BD107224146284619 +:10501000FCF7E6FD58B9DBF800302360DBF804301C +:105020006360BBF80830238107350A34E0E70822C3 +:1050300049462846FCF7D4FD98B90F4BA21C1978B5 +:1050400009090232C95D02F8041C13F8011B01F0C2 +:105050000F015345C95D02F8031CF0D1183408351F +:10506000C6E704F8016B0135C2E700BF546C0008C5 +:105070007D6B00085C6C0008107AF01F1C7AF01F32 +:105080006E6A0008BFF34F8F024AD368DB03FCD47B +:10509000704700BF003C024008B5074B1B7853B96E +:1050A000FFF7F0FF054B1A69002ABFBF044A5A6098 +:1050B00002F188325A6008BD1E550020003C0240B3 +:1050C0002301674508B5054B1B7833B9FFF7DAFFB5 +:1050D000034A136943F00043136108BD1E550020C5 +:1050E000003C02400728F0B516D80C4C0C49237838 +:1050F0007BB90C4D0E4608234FF0006255F8047B37 +:1051000046F8042B013B13F0FF033A44F6D1012388 +:10511000237051F82000F0BD0020FCE7405500202E +:1051200020550020706C0008014B53F82000704798 +:10513000706C000808207047072810B5044601D994 +:10514000002010BDFFF7CEFF064B53F82430184463 +:10515000C21A0BB90120F4E712680132F0D1043B06 +:10516000F6E700BF706C0008072810B5044621D888 +:10517000FFF788FFFFF790FF0F4AF323D360C300C8 +:10518000DBB243F4007343F002031361136943F489 +:1051900080331361FFF776FFFFF7A4FF074B53F847 +:1051A000241000F055F9FFF78DFF2046BDE81040B0 +:1051B000FFF7C2BF002010BD003C0240706C000829 +:1051C000F8B512F00103144642D185182E4A9542D3 +:1051D00057D82E4B1B6813F0010352D02C4DFFF70C +:1051E0005BFFF323EB60FFF74DFF40F20127032C39 +:1051F00015D824F001046618254C401A40F2011716 +:10520000B142236900EB010524D123F0010323619E +:10521000FFF758FF0120F8BD043C0430E7E783079F +:10522000E7D12B6923F440732B612B693B432B613E +:1052300051F8046B0660BFF34F8FFFF723FF03683D +:105240009E42E9D02B6923F001032B61FFF73AFF5F +:105250000020E0E723F44073236123693B4323618B +:105260000B882B80BFF34F8FFFF70CFF2D8831F891 +:10527000023BADB2AB42C3D0236923F001032361EB +:10528000E4E71846C7E700BF0000080800380240FE +:10529000003C0240084908B50B7828B11BB9FFF75C +:1052A000FBFE01230B7008BD002BFCD0BDE80840BD +:1052B0000870FFF707BF00BF1E55002008B54FF468 +:1052C00080314FF0005000F0D5F809484FF43031EC +:1052D00000F0D0F807484FF4804100F0CBF8BDE86B +:1052E00008404FF470514FF4805000F0C3B800BF35 +:1052F0000000012000C003200846114601F00CBB4D +:10530000012001F009BB0000084601F023BB0000AA +:1053100070B582B0FFF79CFB0E4E054600F0FAFF19 +:105320003268904237BF0C4A0B49516814682EBF4F +:10533000D1E90041013151600419034641F10001F6 +:10534000284601913360FFF78DFB0199204602B09A +:1053500070BD00BF445500204855002070B582B094 +:10536000FFF776FB104E054600F0D4FF32689042FE +:1053700037BF0E4A0D49516814682EBFD1E900416C +:1053800001315160041941F10001034628460191A1 +:105390003360FFF767FB01994FF47A7200232046D0 +:1053A000FAF736FF02B070BD445500204855002082 +:1053B00010B50244064BD2B2904200D110BD441C3D +:1053C00000B253F8200041F8040BE0B2F4E700BF4C +:1053D000502800400F4B30B51C6F240407D41C6FBD +:1053E00044F400741C671C6F44F400441C670A4CAE +:1053F000236843F4807323600244084BD2B2904286 +:1054000000D130BD441C00B251F8045B43F8205079 +:10541000E0B2F4E70038024000700040502800403D +:1054200007B5012201A90020FFF7C2FF019803B0D0 +:105430005DF804FB13B50446FFF7F2FFA04205D068 +:10544000012201A900200194FFF7C4FF02B010BDA2 +:105450000144BFF34F8F064B884204D3BFF34F8FF5 +:10546000BFF36F8F7047C3F85C022030F4E700BFD2 +:1054700000ED00E00144BFF34F8F064B884204D398 +:10548000BFF34F8FBFF36F8F7047C3F870022030A8 +:10549000F4E700BF00ED00E070470000074B45F265 +:1054A00055521A6002225A6040F6FF729A604CF61A +:1054B000CC421A60024B01221A7070470030004043 +:1054C00054550020034B1B781BB1034B4AF6AA220C +:1054D0001A6070475455002000300040034B1A6892 +:1054E0001AB9034AD2F874281A6070475055002040 +:1054F00000300240024B4FF08072C3F874287047AE +:105500000030024008B5FFF7E9FF024B1868C0F30E +:10551000407008BD5055002008B5FFF7DFFF024B73 +:105520001868C0F3007008BD5055002070B5BFF377 +:105530004F8FBFF36F8F1A4A0021C2F85012BFF38A +:105540004F8FBFF36F8F536943F400335361BFF341 +:105550004F8FBFF36F8FC2F88410BFF34F8FD2F815 +:105560008030C3F3C900C3F34E335B0143F6E074EC +:1055700003EA0406014646EA81750139C2F8605221 +:10558000F9D2203B13F1200FF2D1BFF34F8F5369B3 +:1055900043F480335361BFF34F8FBFF36F8F70BD00 +:1055A00000ED00E0FEE7000070B5214B2148224AE3 +:1055B000904237D3214BDA1C121AC11E22F003028B +:1055C0008B4238BF00220021FCF726FB1C4A002337 +:1055D000C2F88430BFF34F8FD2F88030C3F3C900D4 +:1055E000C3F34E335B0143F6E07403EA040601465D +:1055F00046EA81750139C2F86C52F9D2203B13F1A9 +:10560000200FF2D1BFF34F8FBFF36F8FBFF34F8FD8 +:10561000BFF36F8F0023C2F85032BFF34F8FBFF339 +:105620006F8F70BD53F8041B40F8041BC0E700BF28 +:105630009C6E0008705600207056002070560020A6 +:1056400000ED00E070B5D0E91B439E6800224FF0EA +:10565000FF3504EB42135101D3F800090028BEBF07 +:10566000D3F8000940F08040C3F80009D3F8000BDC +:105670000028BEBFD3F8000B40F08040C3F8000BF9 +:10568000013263189642C3F80859C3F8085BE0D2A8 +:105690004FF00113C4F81C3870BD0000890141F0BF +:1056A0002001016103699B06FCD41220FFF7EAB9CF +:1056B00010B5054C2046FEF77BFE4FF0A043E36695 +:1056C000024B236710BD00BF58550020B46C000882 +:1056D00070B50378012B054650D12A4BC46E984211 +:1056E0001BD1294B5A6B42F080025A635A6D42F02B +:1056F00080025A655A6D5A6942F080025A615A69AD +:1057000022F080025A610E2143205B69FEF79AFC69 +:105710001E4BE3601E4BC4F800380023C4F8003E63 +:10572000C0232360EE6E4FF40413A3633369002B90 +:10573000FCDA012333610C20FFF7A4F93369DB079E +:10574000FCD41220FFF79EF93369002BFCDA002607 +:10575000A6602846FFF776FF6B68C4F81068DB6820 +:10576000C4F81468C4F81C684BB90A4BA3614FF025 +:10577000FF336361A36843F00103A36070BD064B70 +:10578000F4E700BF585500200038024040140040A4 +:1057900003002002003C30C0083C30C0F8B5C46EA5 +:1057A000054600212046FFF779FF296F00234FF0BF +:1057B00001128F68C4F834384FF00066C4F81C2812 +:1057C0004FF0FF3004EB431201339F42C2F80069EF +:1057D000C2F8006BC2F80809C2F8080BF2D20B68D5 +:1057E000EA6E6B67636210231361166916F0100688 +:1057F000FBD11220FFF746F9D4F8003823F4FE63FA +:10580000C4F80038A36943F4402343F01003A361B4 +:105810000923C4F81038C4F814380A4BEB604FF071 +:10582000C043C4F8103B084BC4F8003BC4F81069EF +:10583000C4F800396B6F03F1100243F480136A67F8 +:10584000A362F8BD906C000840800010C26E90F812 +:105850006610D2F8003823F4FE6343EA0113C2F85D +:10586000003870472DE9F84300EB8103C56EDA6814 +:10587000166806F00306731E022B05EB41130C4657 +:1058800080460FFA81F94FEA41104FF00001C3F84A +:10589000101B4FF0010104F1100398BFB60401FA88 +:1058A00003F391698EBF334E06F1805606F500462C +:1058B00000293AD0578A04F15801490137436F5003 +:1058C000D5F81C180B43C5F81C382B180021C3F859 +:1058D000101953690127611EA7409BB3138A928B4D +:1058E0009B08012A88BF5343D8F87420981842EACD +:1058F000034301F1400205EB8202C8F8740021461F +:1059000053602846FFF7CAFE08EB8900C3681B8A6C +:1059100043EA8453483464011E432E51D5F81C38A1 +:105920001F43C5F81C78BDE8F88305EB4917D7F885 +:10593000001B21F40041C7F8001BD5F81C1821EA10 +:105940000303C0E704F13F0305EB83030A4A5A60EF +:1059500028462146FFF7A2FE05EB4910D0F8003992 +:1059600023F40043C0F80039D5F81C3823EA0707B0 +:10597000D7E700BF0080001000040002026F126829 +:105980004267FFF75FBE00005831C36E49015B58A4 +:1059900013F4004004D013F4001F0CBF02200120B8 +:1059A000704700004831C36E49015B5813F4004052 +:1059B00004D013F4001F0CBF022001207047000028 +:1059C00000EB8101CB68196A0B6813604B68536068 +:1059D0007047000000EB810330B5DD68AA691368E9 +:1059E000D36019B9402B84BF402313606B8A1468BD +:1059F000C26E1C44013CB4FBF3F46343033323F055 +:105A0000030302EB411043EAC44343F0C043C0F830 +:105A1000103B2B6803F00303012B09B20ED1D2F81F +:105A2000083802EB411013F4807FD0F8003B14BF1C +:105A300043F0805343F00053C0F8003B02EB4112A7 +:105A4000D2F8003B43F00443C2F8003B30BD0000F5 +:105A50002DE9F041244DEE6E06EB40130446D3F8D9 +:105A6000087BC3F8087B38070AD5D6F8143819071D +:105A700006D505EB84032146DB6828465B6898471A +:105A8000FA071FD5D6F81438DB071BD505EB8403BE +:105A9000D968CCB98B69488A5A68B2FBF0F600FB2A +:105AA00016228AB91868DA6890420DD2121AC3E930 +:105AB0000024302383F311880B482146FFF78AFF27 +:105AC00084F31188BDE8F081012303FA04F26B89A5 +:105AD00023EA02036B81CB68002BF3D021460248F6 +:105AE000BDE8F041184700BF5855002000EB810386 +:105AF00070B5DD68C36E6C692668E6604A0156BB06 +:105B00001A444FF40020C2F810092A6802F0030278 +:105B1000012A0AB20ED1D3F8080803EB421410F49C +:105B2000807FD4F8000914BF40F0805040F000504E +:105B3000C4F8000903EB4212D2F8000940F0044017 +:105B4000C2F80009D3F83408012202FA01F1014336 +:105B5000C3F8341870BD19B9402E84BF40202060AE +:105B600020682E8A8419013CB4FBF6F440EAC44054 +:105B700040F000501A44C6E72DE9F8433B4DEE6E65 +:105B800006EB40130446D3F80889C3F8088918F0D7 +:105B9000010F4FEA40171AD0D6F81038DB0716D598 +:105BA00005EB8003D9684B691868DA68904230D2F7 +:105BB000121A4FF000091A60C3F80490302383F3DF +:105BC000118821462846FFF791FF89F3118818F0C4 +:105BD000800F1CD0D6F834380126A640334216D0A8 +:105BE00005EB8403ED6ED3F80CC0DCF8142001340F +:105BF000E4B2D2F800E005EB04342F44516871455B +:105C000015D3D5F8343823EA0606C5F83468BDE85C +:105C1000F883012303FA04F22B8923EA02032B8180 +:105C20008B68002BD3D0214628469847CFE7BCF895 +:105C30001000AEEB0103834228BF0346D7F81809D2 +:105C400080B2B3EB800FE2D89068A0F1040959F854 +:105C5000048FC4F80080A0EB09089844B8F1040F41 +:105C6000F5D818440B4490605360C7E7585500209E +:105C70002DE9F74FAC4CE56E6E69AB691E4016F42A +:105C800080586E6107D02046FEF700FC03B0BDE8E7 +:105C9000F04FFEF7ADB9002E12DAD5F8003EA2485B +:105CA0009B071EBFD5F8003E23F00303C5F8003E56 +:105CB000D5F8043823F00103C5F80438FEF712FCC8 +:105CC000370505D59848FFF7BDFC9748FEF7F8FB68 +:105CD000B0040CD5D5F8083813F0060FEB6823F4A0 +:105CE00070530CBF43F4105343F4A053EB603107DF +:105CF0001BD56368DB681BB9AB6923F00803AB6194 +:105D00002378052B0CD1D5F8003E87489A071EBF93 +:105D1000D5F8003E23F00303C5F8003EFEF7E2FB92 +:105D20006368DB680BB180489847F30200F1898013 +:105D3000B70227D5D4F86C90DFF8ECB100274FF00C +:105D4000010A09EB4712D2F8003B03F44023B3F5F4 +:105D5000802F11D1D2F8003B002B0DDA62890AFAAC +:105D600007F322EA0303638104EB8703DB68DB6844 +:105D700013B1394658469847236F01379B68FFB2E5 +:105D80009F42DED9F00617D5E76E3A6AC2F30A10D1 +:105D900002F00F0302F4F012B2F5802F00F09980A8 +:105DA000B2F5402F08D104EB83030022DB681B6AA5 +:105DB00007F5805790427ED13303D5F818481DD59A +:105DC000E70302D50020FFF743FEA50302D501201B +:105DD000FFF73EFE600302D50220FFF739FE2103E4 +:105DE00002D50320FFF734FEE20202D50420FFF7BC +:105DF0002FFEA30202D50520FFF72AFE77037FF5C9 +:105E000045AFE60702D50020FFF7B6FEA50702D58D +:105E10000120FFF7B1FE600702D50220FFF7ACFEBC +:105E2000210702D50320FFF7A7FEE20602D50420D2 +:105E3000FFF7A2FEA3067FF529AF0520FFF79CFE22 +:105E400024E7E36EDFF8E0A0019300274FF001099B +:105E5000236F9B685FFA87FB9B453FF669AF019B09 +:105E600003EB4B13D3F8001901F44021B1F5802F57 +:105E70001FD1D3F8001900291BDAD3F8001941F01B +:105E80009041C3F80019D3F800190029FBDB5946EB +:105E9000E06EFFF703FC218909FA0BF321EA030303 +:105EA000238104EB8B03DB689B6813B15946504692 +:105EB00098470137CCE7910708BFD7F80080072A39 +:105EC00098BF03F8018B02F1010298BF4FEA18282E +:105ED00070E7023304EB830207F580575268D2F86B +:105EE00018C0DCF80820DCE9001CA1EB0C0C002138 +:105EF00088420AD104EB830463689B699A68024470 +:105F00009A605A6802445A6056E711F0030F08BFBE +:105F1000D7F800808C4588BF02F8018B01F10101A0 +:105F200088BF4FEA1828E3E758550020C36E03EBFB +:105F30004111D1F8003B43F40013C1F8003B704716 +:105F4000C36E03EB4111D1F8003943F40013C1F8DB +:105F500000397047C36E03EB4111D1F8003B23F4C5 +:105F60000013C1F8003B7047C36E03EB4111D1F839 +:105F7000003923F40013C1F80039704730B5039C91 +:105F80000172043304FB0325C0E90653049B036339 +:105F90000021059BC160C0E90000C0E90422C0E9FE +:105FA0000842C0E90A11436330BD0000416A002283 +:105FB000C0E90411C0E90A22C2606FF00101FEF7D6 +:105FC000D1BD0000D0E90432934201D1C2680AB9C0 +:105FD000181D70470020704703691960C2680132BC +:105FE000C260C269134482690361934224BF436A59 +:105FF00003610021FEF7AABD38B504460D46E368EB +:106000003BB16269131D1268A3621344E36200206E +:1060100007E0237A33B929462046FEF787FD00289A +:10602000EDDA38BD6FF00100FBE70000C368C2691C +:10603000013BC3604369134482694361934224BFB7 +:10604000436A436100238362036B03B118477047BF +:1060500070B53023044683F31188866A3EB9FFF792 +:10606000CBFF054618B186F31188284670BDA36A98 +:10607000E26A13F8015BA362934202D32046FFF762 +:10608000D5FF002383F31188EFE700002DE9F84FD7 +:1060900004460E46174698464FF0300989F311889A +:1060A0000025AA46D4F828B0BBF1000F09D141461B +:1060B0002046FFF7A1FF20B18BF311882846BDE8E9 +:1060C000F88FD4E90A12A7EB050B521A934528BFA3 +:1060D0009346BBF1400F1BD9334601F1400251F802 +:1060E000040B43F8040B9142F9D1A36A40334036C4 +:1060F000A3624035D4E90A239A4202D32046FFF72F +:1061000095FF8AF31188BD42D8D289F31188C9E777 +:1061100030465A46FBF75AFDA36A5B445E44A362CD +:106120005D44E7E710B5029C0172043303FB0421D0 +:10613000C0E906130023C0E90A33039B0363049BF1 +:10614000C460C0E90000C0E90422C0E9084243631A +:1061500010BD0000026AC260426AC0E90422002247 +:10616000C0E90A226FF00101FEF7FCBCD0E904236C +:106170009A4201D1C26822B9184650F8043B0B601C +:10618000704700231846FAE7C368C2690133C36049 +:106190004369134482694361934224BF436A436164 +:1061A0000021FEF7D3BC000038B504460D46E36875 +:1061B0003BB123691A1DA262E2691344E362002025 +:1061C00007E0237A33B929462046FEF7AFFC0028C2 +:1061D000EDDA38BD6FF00100FBE7000003691960DC +:1061E000C268013AC260C269134482690361934282 +:1061F00024BF436A036100238362036B03B1184722 +:106200007047000070B530230D460446114683F3F5 +:106210001188866A2EB9FFF7C7FF10B186F311887F +:1062200070BDA36A1D70A36AE26A01339342A36240 +:1062300004D3E16920460439FFF7D0FF002080F342 +:106240001188EDE72DE9F84F04460D469046994632 +:106250004FF0300A8AF311880026B346A76A4FB977 +:1062600049462046FFF7A0FF20B187F3118830464A +:10627000BDE8F88FD4E90A073A1AA8EB0607974257 +:1062800028BF1746402F1BD905F1400355F8042BB2 +:1062900040F8042B9D42F9D1A36A4033A3624036F3 +:1062A000D4E90A239A4204D3E16920460439FFF76E +:1062B00095FF8BF311884645D9D28AF31188CDE733 +:1062C00029463A46FBF782FCA36A3B443D44A3625D +:1062D0003E44E5E7D0E904239A4217D1C3689BB155 +:1062E000836A8BB1043B9B1A0ED01360C368013BD9 +:1062F000C360C3691A44836902619A4224BF436A36 +:106300000361002383620123184670470023FBE7E3 +:1063100000F0D2B84FF08043586A70474FF0804386 +:10632000002258631A610222DA6070474FF08043FE +:106330000022DA60704700004FF0804358637047D6 +:10634000FEE7000070B51B4B01630025044686B0D4 +:10635000586085620E46FDF723FE04F11003C4E980 +:1063600004334FF0FF33C4E90635C4E90044A560A7 +:10637000E562FFF7CFFF2B460246C4E9082304F18C +:1063800034010D4A256580232046FEF785FB012355 +:10639000E0600A4A0375009272680192B268CDE922 +:1063A0000223074B6846CDE90435FEF79DFB06B096 +:1063B00070BD00BFF04D0020C06C0008C56C000827 +:1063C00041630008024AD36A1843D062704700BF95 +:1063D000884B00204B6843608B688360CB68C36048 +:1063E0000B6943614B6903628B6943620B6803600D +:1063F0007047000008B5264B26481A6940F2FF1185 +:106400000A431A611A6922F4FF7222F001021A612A +:106410001A691A6B0A431A631A6D0A431A651E4AEF +:106420001B6D1146FFF7D6FF02F11C0100F58060DD +:10643000FFF7D0FF02F1380100F58060FFF7CAFFD7 +:1064400002F1540100F58060FFF7C4FF02F1700112 +:1064500000F58060FFF7BEFF02F18C0100F580605F +:10646000FFF7B8FF02F1A80100F58060FFF7B2FF67 +:1064700002F1C40100F58060FFF7ACFF02F1E0011A +:1064800000F58060FFF7A6FFBDE8084000F088B87F +:106490000038024000000240CC6C000808B500F053 +:1064A000F3F9FEF7ADFAFFF719F8BDE80840FEF77B +:1064B00045BD0000704700000F4B1A6C42F001020E +:1064C0001A641A6E42F001021A660C4A1B6E936837 +:1064D00043F0010393604FF080436B229A624FF0C8 +:1064E000FF32DA6200229A615A63DA605A6001224E +:1064F0005A611A60704700BF00380240002004E073 +:106500004FF0804208B51169D3680B40D9B2C94336 +:106510009B07116107D5302383F31188FEF796FAA4 +:10652000002383F3118808BD1B4B1A696FEAC2521E +:106530006FEAD2521A611A69C2F308021A614FF067 +:10654000FF301A695A69586100215A6959615A69BC +:106550001A6A62F080521A621A6A02F080521A6253 +:106560001A6A5A6A58625A6A59625A6A0B4A106819 +:1065700040F480701060186F00F44070B0F5007F38 +:106580001EBF4FF4803018671967536823F40073F7 +:10659000536000F055B900BF003802400070004061 +:1065A000364B374A1A64374A4FF4404111601A6833 +:1065B00042F001021A601A689207FCD59A6822F02C +:1065C00003029A602D4B9A6812F00C02FBD11968F5 +:1065D00001F0F90119609A601A6842F480321A6079 +:1065E0001A689003FCD55A6F42F001025A67234B98 +:1065F0005A6F9107FCD5244A5A601A6842F080729B +:106600001A60204B5A685204FCD51A6842F4803252 +:106610001A605A68D003FCD51A6842F400321A6036 +:10662000184A53689903FCD5144B1A689201FCD59B +:10663000164A9A6040F20112C3F88C200022C3F877 +:106640009020134A40F207331360136803F00F03DE +:10665000072BFAD1094B9A6842F002029A609A68B5 +:1066600002F00C02082AFAD15A6C42F480425A64B1 +:106670005A6E42F480425A665B6E704700380240A0 +:106680000004001000700040106C4009009488382D +:10669000003C0240074A08B5536903F00103536107 +:1066A00023B1054A13680BB150689847BDE808400C +:1066B000FDF79EBC003C0140E8550020074A08B5A4 +:1066C000536903F00203536123B1054A93680BB188 +:1066D000D0689847BDE80840FDF78ABC003C0140FF +:1066E000E8550020074A08B5536903F004035361D5 +:1066F00023B1054A13690BB150699847BDE80840BA +:10670000FDF776BC003C0140E8550020074A08B57B +:10671000536903F00803536123B1054A93690BB130 +:10672000D0699847BDE80840FDF762BC003C0140D5 +:10673000E8550020074A08B5536903F01003536178 +:1067400023B1054A136A0BB1506A9847BDE8084067 +:10675000FDF74EBC003C0140E8550020164B10B53B +:106760005C6904F478725A61A30604D5134A936AEB +:106770000BB1D06A9847600604D5104A136B0BB171 +:10678000506B9847210604D50C4A936B0BB1D06B24 +:106790009847E20504D5094A136C0BB1506C984731 +:1067A000A30504D5054A936C0BB1D06C9847BDE89E +:1067B0001040FDF71DBC00BF003C0140E855002023 +:1067C000194B10B55C6904F47C425A61620504D52A +:1067D000164A136D0BB1506D9847230504D5134A23 +:1067E000936D0BB1D06D9847E00404D50F4A136E3A +:1067F0000BB1506E9847A10404D50C4A936E0BB1AF +:10680000D06E9847620404D5084A136F0BB1506FDD +:106810009847230404D5054A936F0BB1D06F98476E +:10682000BDE81040FDF7E4BB003C0140E855002006 +:1068300008B5FFF765FEBDE80840FDF7D9BB0000CD +:10684000062108B50846FDF7FDFB06210720FDF7E8 +:10685000F9FB06210820FDF7F5FB06210920FDF7CD +:10686000F1FB06210A20FDF7EDFB06211720FDF7BD +:10687000E9FB06212820FDF7E5FBBDE808400721DC +:106880001C20FDF7DFBB000008B5FFF74DFE00F050 +:106890000BF8FDF78BFDFDF763FCFFF70BFEBDE882 +:1068A0000840FFF735BD00000023054A19460133B3 +:1068B000102BC2E9001102F10802F8D1704700BFA5 +:1068C000E85500200B460146184600F02DB80000A0 +:1068D00000F040B8012838BF012010B5044620461A +:1068E00000F030F830B900F007F808B900F00CF803 +:1068F0008047F4E710BD0000024B1868BFF35B8FC0 +:10690000704700BF6856002008B5062000F084F8E4 +:106910000120FEF761FA0000024B0A4601461868A2 +:10692000FEF7EABC6823002010B5054C13462CB1D5 +:106930000A4601460220AFF3008010BD2046FCE766 +:1069400000000000024B01461868FEF7D9BC00BFEA +:1069500068230020024B01461868FEF7D5BC00BF33 +:106960006823002010B501390244904201D1002073 +:1069700005E0037811F8014FA34201D0181B10BDA8 +:106980000130F2E72DE9F041A3B1C91A17780144AB +:10699000044603F1FF3C8C42204601D9002009E067 +:1069A0000578BD4204F10104F5D10CEB0405D618BD +:1069B000A54201D1BDE8F08115F8018D16F801ED71 +:1069C000F045F5D0E7E700001F2938B504460D462D +:1069D00004D9162303604FF0FF3038BD426C12B16A +:1069E00052F821304BB9204600F030F82A460146D3 +:1069F0002046BDE8384000F017B8012B0AD0591CDA +:106A000003D1162303600120E7E7002442F8254064 +:106A1000284698470020E0E7024B01461868FFF738 +:106A2000D3BF00BF6823002038B5074D00230446BC +:106A3000084611462B60FEF7D3F9431C02D12B68A0 +:106A400003B1236038BD00BF6C560020FEF7C2B909 +:106A5000034611F8012B03F8012B002AF9D17047E6 +:106A60006F72672E6172647570696C6F742E4672F6 +:106A70006565666C7952544B0000000053544D33E9 +:106A800032463F3F3F3F3F3F0053544D333246373E +:106A90005B347C355D780053544D333246375B367A +:106AA0007C375D780000000040A2E4F16468910644 +:106AB0000041A3E5F265699207000000426164208D +:106AC00043414E496661636520696E6465782E00B6 +:106AD0008000000000800000000080000000000036 +:106AE00000000000F5240008D92C0008392C00080B +:106AF0000525000839250008352700080925000864 +:106B0000192500080D250008152500081125000885 +:106B10005D2600081D250008A52F00082D2500086A +:106B20003126000800000000DD400008C9400008D0 +:106B300005410008F1400008FD400008E940000858 +:106B4000D5400008C14000081141000800000000C5 +:106B5000010000000000000063300000586B0008D6 +:106B6000E04B0020F04D00204172647550696C6F5D +:106B7000740025424F415244252D424C0025534577 +:106B80005249414C250000000200000000000000B6 +:106B9000F942000865430008400040009052002080 +:106BA000A0520020020000000000000003000000CE +:106BB00000000000A94300080000000010000000D1 +:106BC000B0520020000000000100000000000000A2 +:106BD0005855002001010200D94E0008E94D000877 +:106BE000854E0008694E000843000000F06B000865 +:106BF00009024300020100C0320904000001020240 +:106C000001000524001001052401000104240202F2 +:106C10000524060001070582030800FF090401009E +:106C2000020A00000007050102400000070581027A +:106C300040000000120000003C6C0008120110012E +:106C40000200004009124157000201020301000046 +:106C50000403090425424F415244250030313233A8 +:106C60003435363738394142434445460000000048 +:106C70000040000000400000004000000040000014 +:106C800000000100000002000000020000000200FD +:106C900000000000FD440008B547000861480008F6 +:106CA00040004000D0550020D055002001000000D9 +:106CB000E0550020800000004001000005000000B9 +:106CC0006D61696E0069646C650000000010806A87 +:106CD00000000000AAAAAAAA00000064FFFF0000AA +:106CE0000000000000A00A0000000A0000000000F0 +:106CF000AAAAAAAA00000000FFFF000000000000EE +:106D0000990000000040000000000000AAAAAAAA02 +:106D100000000020FFFF0000000000000000000055 +:106D20000000000000000000AAAAAAAA00000000BB +:106D3000FFFF000000000000000000000000000055 +:106D400000000000AAAAAAAA00000000FFFF00009D +:106D50000000000000000000000000000000000033 +:106D6000AAAAAAAA00000000FFFF0000000000007D +:106D7000000000000000000000000000AAAAAAAA6B +:106D800000000000FFFF0000000000000000000005 +:106D900000000000000000000A00000000000000E9 +:106DA00003000000000000000000000000000000E0 +:106DB00000000000000000000000000000000000D3 +:106DC00000000000000000007894FF7F0100000038 +:106DD00004040000000000000000070000000000A4 +:106DE00040420F00FE2A0100D2040000FF00000014 +:106DF000000000007C6A000849040000896A00085D +:106E000051040000976A0008009600000000080086 +:106E1000960000000008000004000000506C00080C +:106E20000000000000000000000000000000000062 +:106E300000000000000000006C23002000000000A3 +:106E40000000000000000000000000000000000042 +:106E50000000000000000000000000000000000032 +:106E60000000000000000000000000000000000022 +:106E70000000000000000000000000000000000012 +:106E80000000000000000000000000000000000002 +:0C6E9000000000000000000000000000F6 :00000001FF diff --git a/Tools/bootloaders/G4-ESC_bl.bin b/Tools/bootloaders/G4-ESC_bl.bin new file mode 100755 index 00000000000000..c728bfb26d94c3 Binary files /dev/null and b/Tools/bootloaders/G4-ESC_bl.bin differ diff --git a/Tools/bootloaders/Here4AP_bl.bin b/Tools/bootloaders/Here4AP_bl.bin new file mode 100755 index 00000000000000..a815282c2037dc Binary files /dev/null and b/Tools/bootloaders/Here4AP_bl.bin differ diff --git a/Tools/bootloaders/Hitec-Airspeed_bl.bin b/Tools/bootloaders/Hitec-Airspeed_bl.bin index 702c2df8a322e4..55619f2fe2f12d 100755 Binary files a/Tools/bootloaders/Hitec-Airspeed_bl.bin and b/Tools/bootloaders/Hitec-Airspeed_bl.bin differ diff --git a/Tools/bootloaders/Hitec-Airspeed_bl.elf b/Tools/bootloaders/Hitec-Airspeed_bl.elf index ea39d2e94d3aa5..4d314a924ab645 100755 Binary files a/Tools/bootloaders/Hitec-Airspeed_bl.elf and b/Tools/bootloaders/Hitec-Airspeed_bl.elf differ diff --git a/Tools/bootloaders/Hitec-Airspeed_bl.hex b/Tools/bootloaders/Hitec-Airspeed_bl.hex index b51c935d30018f..efa3593106fa24 100644 --- a/Tools/bootloaders/Hitec-Airspeed_bl.hex +++ b/Tools/bootloaders/Hitec-Airspeed_bl.hex @@ -1,19 +1,19 @@ :020000040800F2 -:1000000000090020F5040008492C0008012C000814 -:10001000292C0008012C0008212C0008F7040008F6 -:10002000F7040008F7040008F7040008193C00086A +:1000000000090020F50400086928000821280008DC +:10001000492800082128000841280008F7040008A2 +:10002000F7040008F7040008F7040008493800083E :10003000F7040008F7040008F7040008F7040008B4 :10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F70400088D4F0008B54F0008AA -:10006000DD4F0008055000082D500008F704000877 +:10005000F7040008F7040008BD450008E54500085E +:100060000D460008354600085D460008F704000804 :10007000F7040008F7040008F7040008F704000874 :10008000F7040008F7040008F7040008F704000864 -:10009000F7040008E12B0008F12B00085550000878 +:10009000F704000801280008112800088546000818 :1000A000F7040008F7040008F7040008F704000844 -:1000B0003D510008F7040008F7040008F7040008A1 +:1000B00059470008F7040008F7040008F70400088F :1000C000F7040008F7040008F7040008F704000824 -:1000D000F704000829510008F7040008F704000895 -:1000E000B9500008F7040008F7040008F7040008F6 +:1000D000F7040008F7040008F7040008F704000814 +:1000E000E9460008F7040008F7040008F7040008D0 :1000F000F7040008F7040008F7040008F7040008F4 :10010000F7040008F7040008F7040008F7040008E3 :10011000F7040008F7040008F7040008F7040008D3 @@ -29,7 +29,7 @@ :1001B000F7040008F7040008F7040008F704000833 :1001C000F7040008F7040008F7040008F704000823 :1001D000F7040008F7040008F7040008F704000813 -:1001E0007D16000800000000000000000000000074 +:1001E0007112000800000000000000000000000084 :1001F00053B94AB9002908BF00281CBF4FF0FF318E :100200004FF0FF3000F074B9ADF1080C6DE904CE89 :1002100000F006F8DDF804E0DDE9022304B07047E1 @@ -85,1276 +85,1111 @@ :10053000F0004EF68851CEF200010860BFF34F8FF5 :10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 :10055000CEF200010860062080F31488BFF36F8F8D -:1005600004F044FB04F0D6FB4FF055301F491B4A02 +:1005600003F05CFE03F0EEFE4FF055301F491B4ACE :1005700091423CBF41F8040BFAE71D49184A9142E9 :100580003CBF41F8040BFAE71A491B4A1B4B9A423D :100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE704F022FBE1 -:1005B00004F0F6FB144C154DAC4203DA54F8041B5E +:1005A000184A91423CBF41F8040BFAE703F03AFEC7 +:1005B00003F00EFF144C154DAC4203DA54F8041B43 :1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E704F00ABB000900201F +:1005D00054F8041B8847F9E703F022BE0009002005 :1005E000001100200000000808ED00E000010020DC -:1005F0000009002048540008001100208C11002040 -:1006000090110020703C0020E0010008E401000887 +:1005F00000090020104A0008001100207C11002092 +:1006000080110020D83E0020E0010008E40100082D :10061000E4010008E40100082DE9F04F2DED108AF7 :10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F054FFCD -:10064000FEE703F0B7FE00DFFEE70000F8B504F0B8 -:100650006FFA074604F0C0FA0546B8BB204B9F422C -:1006600034D001339F4234D01E4B27F0FF029A4210 -:1006700032D1F8B200F04EFE2E4642F2107400F075 -:100680004FFE08B10024264601F0A6FA20B103204F -:1006900000F07CF80024264635B1134B9F4203D06E -:1006A00004F092FA00242646002004F04BFA0EB122 -:1006B00000F082F801F05AF900F056FE01F04CF813 -:1006C000204600F0D7F800F077F8F9E72E4600242E -:1006D000D5E704460126D2E706464FF47A74CEE702 -:1006E000010007B0000008B0263A09B008B500F0D4 -:1006F000FFFFA0F120035842584108BD07B541F261 -:100700001203022101A8ADF8043001F00FF803B084 -:100710005DF804FB38B5302383F31188174803686C -:100720000BB103F09FFF164A144800234FF47A716F -:1007300003F08EFF002383F31188124C236813B15A -:100740002368013B2360636813B16368013B636006 -:100750000D4D2B7833B963687BB9022001F094F812 -:10076000322363602B78032B07D163682BB90220F7 -:1007700001F08AF84FF47A73636038BD901100205D -:1007800015070008B0120020A8110020084B1870AF -:1007900003280CD8DFE800F008050208022001F069 -:1007A0006BB8022001F060B8024B00225A6070471B -:1007B000A8110020B012002038B501F00DFA30B1B8 -:1007C000254B03221A70254B00225A6038BD244B5A -:1007D000244A19680131F9D004339342F9D1224CEB -:1007E0001F4DD4F80428AA42F0D3204B9B6803F194 -:1007F000006303F5D0439A42E8D204F0B7F904F05D -:10080000C9F9002000F0C2FF0220FFF7BFFF184B1C -:100810009A6D00229A65996F9A67996FD96DDA651A -:10082000D96FDA67D96F196E1A66D3F88010C3F8DA -:100830008020D3F8803072B64FF0E0233021C3F827 -:10084000085DD4F80038D4F8042881F311889D4657 -:1008500083F308881047B9E7A8110020B0120020E0 -:1008600000680008206800080060000800110020EF -:10087000001002402DE9F04F93B0AC4B00902022C5 -:10088000FF210AA89D6801F01BF8A94A1378A3B9B3 -:10089000A848012103601170302383F31188036895 -:1008A0000BB103F0DFFEA44AA24800234FF47A7193 -:1008B00003F0CEFE002383F31188009B13B19F4BFE -:1008C000009A1A609E4A009C1378032B1EBF0023D7 -:1008D00013709A4A4FF0000A18BF5360D346564629 -:1008E000D146012000F0C8FF24B1944B1B68002BB7 -:1008F00000F01582002000F0FBFE0390039B002B0C -:1009000001DA00F079FD039B002BEDDB012000F004 -:10091000ABFF039B213B162BE3D801A252F823F037 -:100920007D090008A5090008390A0008E308000845 -:10093000E3080008E3080008C30A0008930C000855 -:10094000AD0B00080F0C0008370C00085D0C000808 -:10095000E30800086F0C0008E3080008E10C000839 -:100960001D0A0008E3080008250D00088909000891 -:100970001D0A0008E30800080F0C00080220FFF71A -:10098000B5FE002840F0F581009B0221BAF1000F6E -:1009900008BF1C4605A841F21233ADF8143000F030 -:1009A000C5FE9EE74FF47A7000F0A2FE071EEBDB57 -:1009B0000220FFF79BFE0028E6D0013F052F00F242 -:1009C000DA81DFE807F0030A0D10133605230593DB -:1009D000042105A800F0AAFE17E054480421F9E715 -:1009E00058480421F6E758480421F3E74FF01C0863 -:1009F000404600F0CDFE08F104080590042105A84A -:100A000000F094FEB8F12C0FF2D1012000FA07F7A4 -:100A100047EA0B0B5FFA8BFB4FF0000900F09CFFDD -:100A200026B10BF00B030B2B08BF0024FFF766FE6B -:100A300057E746480421CDE7002EA5D00BF00B0365 -:100A40000B2BA1D10220FFF751FE074600289BD0B7 -:100A5000012000F09BFE0220FFF798FE00265FFABF -:100A600086F8404600F0A4FE044690B100214046BE -:100A700000F0AEFE01360028F1D1BA46044641F23C -:100A80001213022105A8ADF814303E4600F04EFEC8 -:100A900027E70120FFF77AFE2546244B9B68AB42EF -:100AA00007D9284600F074FE013040F06781043514 -:100AB000F3E7234B00251D70204BBA465D603E4690 -:100AC000ACE7002E3FF460AF0BF00B030B2B7FF471 -:100AD0005BAF0220FFF75AFE322000F009FEB0F1B2 -:100AE0000008FFF651AF18F003077FF44DAF0F4A2F -:100AF000926808EB050393423FF646AFB8F5807F56 -:100B00003FF742AF124B0193B84523DD4FF47A70A3 -:100B100000F0EEFD0390039A002AFFF635AF019B2B -:100B2000039A03F8012B0137EDE700BF0011002005 -:100B3000AC1200209011002015070008B012002010 -:100B4000A811002004110020081100200C11002021 -:100B5000AC110020C820FFF7C9FD074600283FF46C -:100B600013AF1F2D11D8C5F1200242450AAB25F065 -:100B7000030028BF424683490192184400F08EFECC -:100B8000019A8048FF2100F09BFE4FEAA8037D49AF -:100B90000193C8F38702284600F09AFE0646002813 -:100BA0003FF46DAF019B05EB830537E70220FFF7AC -:100BB0009DFD00283FF4E8AE00F01CFE00283FF445 -:100BC000E3AE0027B846704B9B68BB4218D91F2F75 -:100BD00011D80A9B01330ED027F0030312AA134445 -:100BE00053F8203C05934046042205A900F0DEFF9F -:100BF00004378046E7E7384600F0CAFD0590F2E783 -:100C0000CDF81480042105A800F090FD06E700232C -:100C1000642104A8049300F07FFD00287FF4B4AEA3 -:100C20000220FFF763FD00283FF4AEAE049800F009 -:100C3000D7FD0590E6E70023642104A8049300F0A3 -:100C40006BFD00287FF4A0AE0220FFF74FFD0028C7 -:100C50003FF49AAE049800F0C5FDEAE70220FFF7E2 -:100C600045FD00283FF490AE00F0D4FDE1E70220FE -:100C7000FFF73CFD00283FF487AE05A9142000F0E3 -:100C8000CFFD04210746049004A800F04FFD39462B -:100C9000B9E7322000F02CFD071EFFF675AEBB074A -:100CA0007FF472AE384A926807EB090393423FF62D -:100CB0006BAE0220FFF71AFD00283FF465AE27F067 -:100CC00003074F44B9453FF4A9AE484600F060FD24 -:100CD0000421059005A800F029FD09F10409F1E7B8 -:100CE0004FF47A70FFF702FD00283FF44DAE00F09C -:100CF00081FD002844D00A9B01330BD008220AA9A9 -:100D0000002000F0E5FD00283AD02022FF210AA8AB -:100D100000F0D6FDFFF7F2FC1C4803F0EBFB13B02C -:100D2000BDE8F08F002E3FF42FAE0BF00B030B2B22 -:100D30007FF42AAE0023642105A8059300F0ECFCA3 -:100D4000074600287FF420AE0220FFF7CFFC804644 -:100D500000283FF419AEFFF7D1FC41F2883003F0D0 -:100D6000C9FB059800F00EFE464600F0F5FD3C4636 -:100D7000B7E5064652E64FF0000905E6BA467EE6BC -:100D800037467CE6AC11002000110020A08601004F -:100D9000094A136849F2690099B21B0C00FB013340 -:100DA0001360064B186844F2506182B2000C01FBDC -:100DB0000200186080B2704714110020101100204A -:100DC00010B500211022044600F07AFD034B03CB3E -:100DD000206061601868A06010BD00BF9075FF1FA3 -:100DE0002DE9F041ADF5507D0DF13C086EAC40F2BF -:100DF000751207460D4610A80021C8F8001000F033 -:100E00005FFD4FF4C4720021204600F059FD01F04F -:100E100023FF254B4FF47A72B0FBF2F0186093E891 -:100E20000700012384E807000DF5ED702382FFF72A -:100E3000C7FF41F204631D49238407A804F01AFA8E -:100E40001C2384F832310DF2EB226B440DF1340C8B -:100E50001E4603CE664510605160334602F108021B -:100E6000F6D13068106041460122204600F0A4FD12 -:100E700000230393AB7E029305F11903019380B223 -:100E80000123CDE904800093E97E05A3D3E9002383 -:100E9000384602F0A1FA0DF5507DBDE8F08100BFA3 -:100EA0009E6AC421818A46EEB8120020845200084E -:100EB0002DE9F043224DBBB001F0CEFEAB6840F20D -:100EC000ED22C31A934232D906AFA8602B462822DE -:100ED0000021384602F030FC05F10E0000F0E8FC7D -:100EE000002604465FFA80F905F10E08F3B2F1001E -:100EF000994501F1280107D908EB06030822384675 -:100F000002F01AFC0136F1E708230122CDE9023292 -:100F100005340C4B0193A4B230230093CDE9047443 -:100F200005A3D3E90023297B074802F055FA3BB01B -:100F3000BDE8F083AFF3008078F6339F93CACD8D80 -:100F4000B0370020BD370020D0220020F0B58B8ABA -:100F5000013B9BB2C92BC9B006460C4647D8274D6A -:100F60002F7B27BB05F10C03009308223B46394633 -:100F7000204602F0A5FA7B1CFAB2D9001F46A38ACC -:100F8000013B9A4205DA0E322A44009200230822DD -:100F9000EEE700230022C5E900230023AB6085F8BB -:100FA000D730C5F8D8302B7B0BB9E37E2B73812269 -:100FB000002106AD27A800F083FC0122294627A8BE -:100FC00000F0C8FD00230393A37E029304F11903EC -:100FD00080B201932823CDE90450E17E009330468E -:100FE00004A3D3E9002302F0F7F9FFF761FF49B04A -:100FF000F0BD00BF26417272DF25D7B7B0370020A1 -:1010000070B50D4614461E4602F042F950B9022E44 -:1010100010D1012C0ED112A3D3E90023C5E900237E -:10102000012007E0282C10D005D8012C09D0052C70 -:101030000FD0002070BD302CFBD10BA3D3E90023CF -:10104000ECE70BA3D3E90023E8E70BA3D3E90023E4 -:10105000E4E70BA3D3E90023E0E700BFAFF3008090 -:10106000401DA12026812A0B78F6339F93CACD8D8F -:101070009E6AC421818A46EE26417272DF25D7B767 -:10108000F017304A39059E562DE9F04F8DB002AF6A -:1010900080460D4602F0FCF8044600285CD12B7E09 -:1010A000022B1BD1EB8A012B18D101F0D5FD06468E -:1010B000FFF76EFE03464FF4C870DFF81C92B3FBD7 -:1010C000F0F206F5167602FB103316FA83F3C9F830 -:1010D0000030EB7E33B97B4B00221A702C37BD46B3 -:1010E000BDE8F08FAB8AE6B2013BB34204F10104E4 -:1010F0000CD907F108031E44E100009600230822E2 -:1011000001F0F801284602F0DBF9EBE707F11800DF -:10111000FFF756FE324607F1180107F1080004F008 -:1011200077F80028D7D10F2E08D8664B1E70D9F853 -:101130000030A3F51673C9F80030CFE7FB1DF87136 -:101140000146009307220346284602F0B9F9F979CF -:10115000404602F095F8C1E7EB8A282B26D010D83C -:10116000012B1ED0052BB9D1BFF34F8F5649574BDA -:10117000CA6802F4E0621343CB60BFF34F8F00BF35 -:10118000FDE7302BAAD16B7E514C0133627BDBB281 -:101190009342E94603D1EA7E237B9A420BD0CD46A7 -:1011A0009CE729464046FFF71BFE97E72946404645 -:1011B000FFF7CCFE92E74FF0000807F11803A7F8FD -:1011C00018801022009341460123284602F078F946 -:1011D000AE8A023EB6B2F31C9B109B000733DB08BD -:1011E000A9EBC3039D460DF1080A1FFA88F34FEAE5 -:1011F000C8019E4201F110010AD90AEB08030093CD -:1012000008220023284602F05BF908F10108ECE708 -:1012100094F8D70000F0CCFAD4F8D810054619B9E4 -:1012200094F8D70000F0D4FAD4F8D83033449D4273 -:1012300005D294F8D7000021013000F0C9FA4FEA36 -:10124000960B4FF000081FFA88F18B45D4E9003265 -:1012500009D90AEB880103EB8800012200F038FB72 -:1012600008F10108EFE7F31842F10002C4E9003287 -:10127000D4F8D83094F8D70006EB0308C4F8D88027 -:1012800000F096FA804509D394F8D730D4F8D80006 -:101290000133401B84F8D730C4F8D800FF2E0D4D21 -:1012A00009D80023237300F0A5FA00F095FC2881EB -:1012B00008B9FFF781FA23689B0A01332B810023C9 -:1012C000A3606CE7C922002000ED00E00400FA05ED -:1012D000B0370020B8120020CC22002010B50A4BF5 -:1012E0000A4A1A6003F5805393F848203AB95C6CB7 -:1012F0002CB1204600F0EEFC204603F071FFBDE863 -:101300001040034800F0E6BC00230020E052000833 -:1013100030330020014B1870704700BFC41200200A -:1013200010B54FF000540C4B22689A4211D10B4B70 -:10133000627D1A700A48237D03730A49C9220E3060 -:1013400000F0ACFAE0220021204600F0B9FA0120BA -:1013500010BD0020FCE700BF9AAD44C5C4120020B8 -:10136000B03700201600002037B500F035FC194DCD -:101370001949288102236B7100220123174801F0CB -:101380006FF800230193164B164900931648174B2C -:101390004FF4805201F04CFF154B197811B11248EF -:1013A00001F06EFF01F058FC0446FFF7F1FC4FF42A -:1013B000C873B0FBF3F202FB130304F5167010FAC6 -:1013C00083F00C4B186003F007FC08B10F232B814E -:1013D00003B030BDB812002040420F0000230020AF -:1013E00001100008C8120020D02200208910000837 -:1013F000C4120020CC2200202DE9F04F2DED028BED -:1014000095A7D7E900670FF25829D9E900898C4CD4 -:1014100095B0DFF854A2DFF854B2204602F008F885 -:10142000034650B30025CDE911551095ADF84C5049 -:10143000027B8DF84C209968406811AA03C21B6892 -:1014400043F00043109301F009FC10EB0A0241F154 -:101450000003009510A9584600F0DAFDA842794A29 -:1014600005DD204601F0E8FF764A1570D5E71378D0 -:10147000072B00F2B980013313700DAD9FED6E8B19 -:101480000023DFF8E8B10C93ADF83C300D936B60AE -:1014900000230DF125028DED008B4FF0010A09A903 -:1014A00058468DF825308DF824A001F03DFB9DF8BD -:1014B00024200023002A40F09B80204601F0E8FE13 -:1014C0000546002847D1DFF8A8B101F0C5FBDBF8DD -:1014D000003098423FD301F0BFFB0790FFF758FC64 -:1014E000079A4FF4C87302F51672B0FBF3F101FBD3 -:1014F000130312FA83F3CBF80030DFF878B19BF8CE -:1015000000100791002914BF2B46534610A88DF8F0 -:101510003030FFF755FC0799C1F11002D2B2062A0C -:1015200010AB28BF062219440DF13100079200F0DC -:10153000B5F9079A0CAB0393182302930132424B7F -:10154000D2B2CDE900A304923B463246204601F0D8 -:10155000E5FE8BF8005001F07FFB3C4A3C4D1368E0 -:10156000C31AB3F57A7F32D3106001F077FB0246DD -:101570000B46204601F06AFF204601F089FE30B399 -:101580002B7BDFF8F4A0002B14BF032302238AF87F -:10159000053001F061FB0DF1400B4FF47A7301222D -:1015A000B0FBF3F05946CAF80000504600F0AAFA22 -:1015B00018230293274B019380B240F25513CDE9D3 -:1015C00003B0009342464B46204601F0A7FE2B7B1A -:1015D0002BB1FFF76DFC2B7B002B7FF41AAF15B0FE -:1015E000BDEC028BBDE8F08F204601F025FF44E7FB -:1015F0004FF0904110A84A6982F040024A611946B2 -:10160000102200F05DF90DF126030AAA0CA9584634 -:1016100000F0F0FD95E8030011AB83E803009DF8AE -:101620003C308DF84C300C9B109310A9DDE90A2357 -:10163000204602F0C9F82BE700000000000000007F -:10164000D022002095380020C822002090380020A9 -:10165000B037002094380020401DA12026812A0B9D -:10166000F1C6A7C1D068080F40420F000023002038 -:10167000CC220020C9220020B812002008B505485D -:1016800000F05CFEBDE80840034A0449002003F076 -:10169000A1BD00BF00230020E8380020DD120008B3 -:1016A00070B5104B1B780133DBB2012B0C4612D8FE -:1016B0000D4B1D6829684FF47A730E6AA2FB033242 -:1016C000014622462846B047844204D1074B0022F7 -:1016D0001A70012070BD4FF4FA7002F00BFF002069 -:1016E000F8E700BF181100201C110020DC38002092 -:1016F00007B50023024601210DF107008DF80730E0 -:10170000FFF7CEFF20B19DF8070003B05DF804FBA2 -:101710004FF0FF30F9E700000A4608B50421FFF753 -:10172000BFFF80F00100C0B2404208BD30B4074B9B -:101730000A461978064B53F821402368DD69054BAA -:101740000146AC46204630BC604700BFDC38002074 -:101750001C110020A086010070B503F073F8094E3B -:10176000094D3080002428683388834208D903F06B -:1017700065F82B6804440133B4F5D04F2B60F2D3E5 -:1017800070BD00BFDE3800209838002003F01EB97D -:1017900000F1006000F5C040D0F80008704700007C -:1017A00000F10060920000F5D04003F08FB8000017 -:1017B000054B1A68054B1B889B1A834202D91044BB -:1017C00003F03CB80020704798380020DE38002035 -:1017D000024B1B68184403F049B800BF983800203A -:1017E0000020704700F10050A0F51040D0F890059F -:1017F00070470000064991F8243033B10023086A8D -:1018000081F824300822FFF7CBBF0120704700BFCA -:101810009C380020014B1868704700BF002004E08E -:1018200030B50F4B0F4C1B682288C3F30B030138F4 -:10183000934208440BD164680A46013C8242134635 -:101840000BD214F9015F2DB102F8015BF6E781427A -:101850000B4602D22C2203F8012B581A30BD00BFD0 -:10186000002004E020110020022802BF4FF0904326 -:1018700040229A6170470000022802BF4FF0904357 -:101880004FF480029A617047022801BF4FF09042E6 -:10189000536983F0400353617047000010B5002383 -:1018A000934203D0CC5CC4540133F9E710BD00006F -:1018B00003460246D01A12F9011B0029FAD17047DB -:1018C00002440346934202D003F8011BFAE7704733 -:1018D0002DE9F8431F4D144695F824200746884605 -:1018E00052BBDFF870909CB395F824302BB92022BE -:1018F000FF2148462F62FFF7E3FF95F82400C0F16F -:101900000802A24228BF2246D6B24146920005EB09 -:101910008000FFF7C3FF95F82430A41B1E44F6B2E5 -:10192000082E17449044E4B285F82460DBD1FFF719 -:1019300061FF0028D7D108E02B6A03EB82038342C2 -:10194000CFD0FFF757FF0028CBD10020BDE8F883A8 -:101950000120FBE79C380020024B1A78024B1A70DA -:10196000704700BFDC3800201811002003494FF4F5 -:1019700061430B60024B186802F082BCC43800203F -:101980001C110020094B10B51822044600211846EE -:10199000FFF796FF064A074B127804600146BDE840 -:1019A000104053F8220002F06BBC00BFC438002086 -:1019B000DC3800201C1100202DE9F0470D460446BC -:1019C00000219046284640F27912FFF779FF23461E -:1019D00020220021284601F0AFFE231D02222021F3 -:1019E000284601F0A9FE631D03222221284601F0AA -:1019F000A3FEA31D03222521284601F09DFE04F12C -:101A0000080310222821284601F096FE04F1100355 -:101A100008223821284601F08FFE04F11103082224 -:101A20004021284601F088FE04F1120308224821D3 -:101A3000284601F081FE04F114032022502128469B -:101A400001F07AFE04F1180340227021284601F0CB -:101A500073FE04F120030822B021284601F06CFE39 -:101A600004F121030822B821284601F065FE04F1A3 -:101A70002207C0263B46314608222846083601F098 -:101A80005BFEB6F5A07F07F10107F3D104F1320345 -:101A900008223146284601F04FFE002704F1330AA0 -:101AA00094F832304FEAC7099F4209F5A47615D35E -:101AB000B8F1000F08D1314604F599730722284682 -:101AC00001F03AFE09F24F16274694F832213B1BEB -:101AD00093420CD3F01DC008BDE8F0870AEB070362 -:101AE00008223146284601F027FE0137D8E707F2E1 -:101AF000331331460822284601F01EFE083601370E -:101B0000E3E7000013B504460846002101602346C0 -:101B1000C0F803102022019001F00EFE0198231D51 -:101B20000222202101F008FE0198631D03222221D8 -:101B300001F002FE0198A31D0322252101F0FCFD06 -:101B4000019804F108031022282101F0F5FD072077 -:101B500002B010BDF8B50E4605461446002181229C -:101B60003046FFF7ADFE2B4608220021304601F03B -:101B7000E3FD7CB96B1C07220821304601F0DCFD37 -:101B80000F2401236A785F1C013B934204D3E01DBC -:101B9000C008F8BD0824F4E7EB19214608223046B6 -:101BA00001F0CAFD08343B46ECE7000030B5094DB2 -:101BB0000A4491420DD011F8013B5840082340F3EC -:101BC0000004013B2C4013F0FF0384EA5000F6D1DF -:101BD000EFE730BD2083B8ED73B5384A106851681F -:101BE0006B4603C36A4636493648082303F020FB98 -:101BF000044670B9344A106851686B4603C36A469C -:101C000032493048082303F013FB044630BB0A2056 -:101C100022E00369B3F5CC3FECD8418B40F2164289 -:101C20009142E7D12A4A024402F110018B42E1D3EA -:101C3000103B244900209D1AFFF7B8FF2A460646AC -:101C400004F118010020FFF7B1FFA3689E42D1D133 -:101C5000E3689842CED1002002B070BD0369B3F5AD -:101C6000CC3F22D8B0F8661040F2164291421ED105 -:101C7000174A024402F15C018B421AD35C3B1149C2 -:101C800000209D1AFFF792FF2A46064604F16401E0 -:101C90000020FFF78BFFA268964203460BD1E06855 -:101CA000834214BF0D200020D6E70B20D4E70C2080 -:101CB000D2E71020D0E70D20CEE700BFB0520008D9 -:101CC000DC97010000680008B952000890970100F5 -:101CD0000898FFF710B5037C044613B9006803F0B9 -:101CE0008FFA204610BD00000023BFF35B8FC36056 -:101CF000BFF35B8FBFF35B8F8360BFF35B8F704776 -:101D0000BFF35B8F0068BFF35B8F704770B505460C -:101D10000C30FFF7F5FF05F1080604463046FFF7E3 -:101D2000EFFFA04206D930466D68FFF7E9FF254472 -:101D3000281A70BD3046FFF7E3FF201AF9E70000CC -:101D400070B50546406898B105F10800FFF7D8FF67 -:101D500005F10C0604463046FFF7D2FF84423046B8 -:101D600094BF6D680025FFF7CBFF013C2C44201A7F -:101D700070BD000038B50C460546FFF7C7FFA0420E -:101D800010D305F10800FFF7BBFF04446868B4FBFB -:101D9000F0F100FB1144BFF35B8F0120AC60BFF397 -:101DA0005B8F38BD0020FCE72DE9F0411446074663 -:101DB0000D46FFF7C5FF844228BF0446D4B1B8469C -:101DC00058F80C6B4046FFF79BFF304428604046B4 -:101DD0007E68FFF795FF331A9C4203D86C600120A0 -:101DE000BDE8F0816B60A41B3B68AB602044E860F9 -:101DF0000220F5E72046F3E738B50C460546FFF725 -:101E00009FFFA04210D305F10C00FFF779FF0444B7 -:101E10006868B4FBF0F100FB1144BFF35B8F012055 -:101E2000EC60BFF35B8F38BD0020FCE72DE9FF417C -:101E3000884669460746FFF7B7FF6C4606B204EBD3 -:101E4000C6060025B44209D06268206808EB050187 -:101E5000FFF724FD636808341D44F3E7294638463C -:101E6000FFF7CAFF284604B0BDE8F081F8B5054683 -:101E70000C300F46FFF744FF05F1080604463046D4 -:101E8000FFF73EFFA042304688BF6C68FFF738FF7F -:101E9000201A386020B130462C68FFF731FF20440B -:101EA000F8BD000073B5144606460D46FFF72EFF39 -:101EB000844228BF04460190DCB101A93046FFF7F7 -:101EC000D5FF019B33B93268C5E90233C5E9002467 -:101ED00001200CE09C4238BF0194286001986860A2 -:101EE0008442F5D93368AB60241AEC60022002B05A -:101EF00070BD2046FBE700002DE9FF410F46694613 -:101F0000FFF7D0FF6C4600B204EBC0050026AC42E0 -:101F100009D0D4F8048054F8081BB8194246FFF7DA -:101F2000BDFC4644F3E7304604B0BDE8F081000054 -:101F300038B50546FFF7E0FF044601462846FFF79F -:101F400019FF204638BD0000302383F3118862B6A4 -:101F500070470000002383F3118862B670470000C9 -:101F6000012070477047000010B4134602681468DF -:101F70000022A4465DF8044B6047000000F5805045 -:101F800090F859047047000000F5805090F8520412 -:101F90007047000000F5805090F958047047000029 -:101FA0005020704700F5805208B5FFF7CDFFD2F8FA -:101FB0009834D2F894041844D2F890341844D2F8E3 -:101FC00078341844D2F888341844D2F88434184449 -:101FD000FFF7C0FF08BD000038B5C26A936923F05F -:101FE00001039361044600F037FE0546E36A9B69EE -:101FF000DB0706D500F030FE431BFA2BF6D9002094 -:1020000004E004F58054012084F8520438BD000037 -:102010002DE9F04F0C4600F5805185B01F4691F830 -:102020005234BDF83890054690469BB1D1F87434CF -:102030000133C1F8743423689A0006D4237B082B3B -:102040000BD9627B0AB10F2B07D9D1F87834013351 -:10205000C1F878344FF0FF300FE0FFF775FFEB6AFF -:10206000D3F8C42012F4001A0AD0D1F87C3401331A -:10207000C1F87C34FFF76EFF002005B0BDE8F08F9B -:10208000D3F8C46022686B6AC6F301464FF0480B70 -:10209000002A1BFB063BB4BF42F080429204CBF8FF -:1020A000002023685B0044BF42F00052CBF80020C0 -:1020B000227B330643EA0243CBF80430607B720193 -:1020C00018B343F44013CBF80430D1F8A4340133EF -:1020D000C1F8A434AB1803F58353197B41F02001F8 -:1020E0001973207B039200F015FE039A03308010D1 -:1020F0005FFA8AF383420AF1010A0DDA04EB8301E5 -:102100000BEB830349689960F2E7AB1803F583533F -:10211000197B60F34511E3E7EB6A0121B140C3F895 -:10212000CC10AB1803F58253C3E9048705EB4613C3 -:1021300003F582532146183304F10C0051F804CB07 -:1021400043F804CB8142F9D1098819802A4441F22D -:1021500068032846D65002F5805209F0030392F82E -:102160006C1043F0100321F01F010B4382F86C3018 -:10217000FFF7F0FE4246CDF800903B46214600F0C6 -:102180008FFD012079E7000013B500F5805401911F -:10219000606CFFF7D5FD1F280AD90199606C2022D9 -:1021A000FFF744FEA0F120035842584102B010BD91 -:1021B0000020FBE708B500F58050FFF7C5FE406C36 -:1021C000FFF792FDBDE80840FFF7C4BE00220260A1 -:1021D000828142608260704710B500220023C0E90E -:1021E00000230023044603810C30FFF7EFFF204655 -:1021F00010BD00002DE9F047074688B007F5805470 -:1022000068469A468846FFF79FFE9146FFF7E4FF2F -:10221000606CFFF77BFD1F282CD9606C202269467B -:10222000FFF786FE202825D194F8523413B303AD6E -:10223000444605AB2E4603CE9E4220606160354683 -:1022400004F10804F6D130682060B388A380DDE98A -:102250000023C9E90023BDF80830AAF80030FFF7D1 -:1022600079FE4A4653464146384608B0BDE8F04735 -:1022700000F004BDFFF76EFE002008B0BDE8F08757 -:102280002DE9F84F00230646C0E90133284B46F8F4 -:10229000303B00F5815405468846374610343846B1 -:1022A0002037FFF799FFA742F9D105F580544FF485 -:1022B000805326630026C4E90D366764012305F5C3 -:1022C000835705F5A359E66384F8403084F8483015 -:1022D000103709F110094FF0000A4FF0000B47E9E1 -:1022E00008ABA7F11800FFF771FF203747F8286CFB -:1022F0004F45F4D184F85884A4F85A64A4F85C6477 -:10230000A4F85E6484F86064A4F86264A4F8646469 -:10231000A4F8666484F86864B8F1000F02D0054838 -:1023200000F094FC044BEB622846BDE8F88F00BF38 -:10233000E0520008C45200080064004010B5044B8D -:10234000197804464A1C1A70FFF79AFF204610BD00 -:10235000E53800202DE9F04300295FD03048314BAB -:10236000B3FBF1F381428CBF0A201120451EB3FB61 -:10237000F0F700FB1730ECB220B1022D2846F5D85B -:10238000002037E07D1EB5F5806F33D2C4EBC40862 -:1023900008F103034FEAE30EC3F3C703A4EB030CF6 -:1023A0000EF101094FF47A705FFA8CF60EFB000E05 -:1023B00059FA8CFCBEFBFCFCBCF5617F1CDC1FFAEF -:1023C0008CF4581C56FA80F047431648B0FBF7F7D8 -:1023D000B942D5D1013BDBB20F2BD1D8711EC9B2A6 -:1023E00007294FF0000005D81071148055805371F3 -:1023F00091710120BDE8F08308F1FF334FEAE30C4F -:10240000C3F3C703E41A0CF1010EE6B20CFB0000A3 -:102410005EFA84F4B0FBF4F4A4B2D2E70846E9E72C -:102420003F420F0000366E010B4B10B54FF4547253 -:10243000044600211846FFF743FA084BA3614033D6 -:10244000E361D8332362F0336362E36A60610022A0 -:10245000C3F8C02010BD00BF00A4004070A400401D -:102460002DE9F04F00F58055994695F85834012B29 -:1024700089B004468A46904604D90027384609B0F8 -:10248000BDE8F08F904A52F8231009B942F82300B2 -:102490008E49C4F80CA00B7884F8109093B9FFF71C -:1024A00053FD8B4B9A6D42F000729A659A6B42F025 -:1024B00000729A639A6B22F000729A6301230B7088 -:1024C000FFF748FD95F8513473B903211520FFF744 -:1024D0003BFD01F01FFD0321162001F01BFD012330 -:1024E00085F85134FFF736FDFFF72EFDE26A936958 -:1024F00023F01003936100F0AFFB0746E36A9E6987 -:1025000016F0080607D000F0A7FBC31BFA2BF5D97D -:10251000FFF720FDB1E79A6942F001029A6100F0ED -:102520009BFB0746E36A9A69D00705D400F094FB49 -:10253000C31BFA2BF6D9EBE79A6942F002029A61C3 -:10254000E36A00275F65FFF705FD686CFFF7CCFBCA -:1025500004F5825B0BF1100B202200216846FFF787 -:10256000AFF902A8FFF732FE06976A460BEB0603A7 -:102570000DF1180E9446BCE80300F445186059604C -:10258000624603F10803F5D1DCF80000186020363C -:102590009CF804201A71B6F5806FDDD1002304F594 -:1025A000A25285F8503485F853341A3251462046E9 -:1025B000FFF7D0FE074690B9E26A936923F0010362 -:1025C000936100F049FB0546E36A9B69D9077FF5F3 -:1025D00054AF00F041FB431BFA2BF5D94DE795F8BA -:1025E0005F6495F85E24C5F86CA4360246EA42663C -:1025F00095F86024E36A1643B5F85C2446EA02467F -:10260000DE61B8F1000F29D004F5A3520232414631 -:102610002046FFF79FFE90B9E26A936923F0010319 -:10262000936100F019FB0546E36A9B69DA077FF5C1 -:1026300024AF00F011FB431BFA2BF5D91DE795F8E9 -:10264000683495F86714C5F870841B0143EA0123C8 -:10265000B5F86414E26A43EA0143D3602046FFF709 -:10266000E3FE002385F85934E36A6FF040421A65AF -:10267000E36A184A5A65E36A44229A65E36A0722C4 -:10268000C3F8DC20E36A0322DA65E26A9369B9F1F0 -:10269000030F43F4407393613FF4F0AEE26A936931 -:1026A00023F00103936100F0D7FA0646E36A9B69C1 -:1026B000DB0705D500F0D0FA831BFA2BF6D9DCE650 -:1026C000012385F85234D9E6E0380020E4380020B0 -:1026D000001002409B0008002DE9F04F054689B02C -:1026E00090469946002741F2680A00F58056EB6A49 -:1026F000D3F8D430FB40D8074AD505EB47125244F3 -:102700004FEA471B1379190742D4D6F880340133B6 -:10271000C6F8803413799A0648BFD6F8A83405EB7A -:102720000B0248BF0133524448BFC6F8A83413799E -:1027300043F008031371DB0722D596F85334FBB13D -:1027400005F58254183468465C44FFF745FD03AB39 -:1027500004F1080C206861681A4603C20834644515 -:102760001346F7D120681060A2889A800123ADF843 -:1027700008302B68CDE90089DB6B6946284698470D -:10278000D6F8543423B1D6F89C340133C6F89C34BF -:102790000137202FABD109B0BDE8F08F2DE9F04F04 -:1027A0008DB004460F4600F059FA82468946002F44 -:1027B00056D1E36AD3F89020920141BF04F58051CD -:1027C000D1F894240132C1F89424D3F8902016074C -:1027D00003D100200DB0BDE8F08FD3F89050E6692A -:1027E000C5F30125482303FB0566E8464046FFF78D -:1027F000EDFC326851004ABF22F06043C2F38A43C5 -:1028000043F00043920048BF43F080430093736855 -:1028100013F400131FBF04F5805201238DF80D300F -:10282000D2F8AC340EBF8DF80D300133C2F8AC34A1 -:10283000F38803F00F038DF80C304FF0000B9DF878 -:102840000C0000F067FA5FFA8BF3984220D9F21877 -:102850000CA90B44127A03F82C2C0BF1010BEEE7B8 -:10286000012FB6D1E36AD3F89820950141BF04F552 -:102870008051D1F894240132C1F89424D3F89820DF -:102880001007A6D0D3F89850266AC5F30125A9E70A -:10289000EFB9E36AC3F8945004A8FFF79DFC98E8E9 -:1028A0000F0007AD07C52B800023ADF81830236853 -:1028B0002046CDE904A9DB6B04A9984704F58054B0 -:1028C00058B1D4F88C340133C4F88C3482E7012F2A -:1028D00004BFE36AC3F89C50DEE7D4F890340133B8 -:1028E000C4F89034012075E7F8B505460F4600F5A9 -:1028F0008054012639462846FFF750FF10B184F86E -:102900005364F7E7D4F8543423B1D4F89C3401333A -:10291000C4F89C34F8BD0000F0B5C36A1A6C12F418 -:102920007F0F2BD000F580541B6CC4F8A03441F20B -:102930006805002347194FF0010C00EB43122A44AD -:102940005E01117911F0020F15D0490713D4B9595E -:10295000C66AD6F8C8E00CFA01F111EA0E0F0AD0E7 -:10296000C6F8D010117941F004011171D4F888240F -:102970000132C4F888240133202BDED1F0BD0000E1 -:1029800010B5254C254B226802B338B31A6D1206D8 -:102990000ED580221A6500F061F950EA01020B465B -:1029A00002D0013861F1000302462068FFF794FE6F -:1029B0001A4A136D1B032AD523684FF4002103F52F -:1029C00080531165012283F8592420E001221A6501 -:1029D00008221A654FF480621A6510BD196DC80788 -:1029E00002D4196D890705D5032119651046002108 -:1029F000FFF77AFF094B1A6D100702D41A6DD10642 -:102A000005D518221A6520680121FFF76DFF20689F -:102A1000BDE81040FFF780BFE038002000640040B0 -:102A200008B5FFF791FAFFF777FFBDE80840FFF719 -:102A300091BA0000C36AD3F8C40080F40010C0F358 -:102A40004050704700F5805008B5FFF77DFA406CA4 -:102A5000FFF75CF9FFF77EFA43090CBF0120002065 -:102A600008BD000000F5805393F8592462B1C16A93 -:102A70008A6922F001028A61D3F898240132C3F8EE -:102A80009824002283F85924704700002DE9F74369 -:102A900000F5825198461031FFF756FA002541F2B1 -:102AA000680E4FF0010900F5805C00EB451474449A -:102AB00023795E071CD4DB061AD5C36A8E69D3F866 -:102AC000C87009FA06F63E4212D04F6801970F68A7 -:102AD0009742019F77EB08070AD2C3F8D0602379A9 -:102AE00043F004032371DCF884340133CCF88434DC -:102AF0000135202D01F12001D7D103B0BDE8F0430D -:102B0000FFF728BAF8B51E46002313700F46054696 -:102B10001446FFF797FF80F0010038701EB1284679 -:102B2000FFF788FF2070F8BD2DE9F04F85B099467A -:102B3000DDE90EA30D4602931378019391F800B0DE -:102B40008046164600F08AF82B7804460F4613B9E3 -:102B50003378002B42D022463B464046FFF796FF93 -:102B6000FFF75EFFFFF77EFF4B4632462946FFF731 -:102B7000C9FF2B7833B1BBF1000F03D0012005B0A2 -:102B8000BDE8F08F337813B1019B002BF6D108F527 -:102B900080530393029B544577EB03031ED2039BA0 -:102BA000D3F85404D0B10368AAEB0401DB6889B2FE -:102BB00098474B46324629464046FFF7A3FF2B78FD -:102BC00013B1BBF1000FD9D1337813B1019B002BA6 -:102BD000D4D100F043F804460F46DBE70020CEE7EF -:102BE00008B50020FFF7CCFEBDE8084001F048B86A -:102BF00008B50120FFF7C4FEBDE8084001F040B869 -:102C000000B59BB0EFF3098168226846FEF746FEE7 -:102C1000EFF30583014B9B6BFEE700BF00ED00E087 -:102C200008B5FFF7EDFF000000B59BB0EFF3098199 -:102C300068226846FEF732FEEFF30583014B5B6BBB -:102C4000FEE700BF00ED00E0FEE700000FB408B5AE -:102C5000029801F0E5FBFEE701F006BF01F0DEBEE1 -:102C600001F0DCBE13B56C4684E80600031D94E851 -:102C7000030083E80500012002B010BD73B585682C -:102C8000019155B11B885B0707D4D0E900369B6BD7 -:102C90009847019AC1B23046A847012002B070BDE2 -:102CA000F0B5866889B005460C465EB1BDF838308F -:102CB0005B070AD4D0E900379B6B98472246C1B224 -:102CC0003846B047012009B0F0BD00220023CDE90D -:102CD00000230023ADF808300A4603AB01F10806D3 -:102CE000106851681C4603C40832B2422346F7D12B -:102CF000106820609288A280FFF7B2FF0423ADF82D -:102D000008302B68CDE90001DB6B694628469847FF -:102D1000D8E70000082817D909280CD00A280CD0B9 -:102D20000B280CD00C280CD00D280CD00E2814BF6A -:102D30004020302070470C2070471020704714202E -:102D40007047182070472020704700002DE9F0419F -:102D5000456A15B94162BDE8F0814B6823F06047D0 -:102D6000C3F38A464FEAD37EC3F3807816EA23067C -:102D700038BF3E46AC462B465A68BEEBD27F22F0A7 -:102D800060440AD0002A18DAA40CB44217D19D423C -:102D90000FD10D60DEE71346EEE7A74207D102F040 -:102DA0008044C2F3807242450BD054B1EFE708D2A1 -:102DB000EDE7CCF800100B60CDE7B44201D0B4428F -:102DC000E5D81A689C46002AE5D11960C3E70000DF -:102DD0002DE9F047089D01F007044FEAD508224489 -:102DE00005F0070500EBD1004FF47F49944201D173 -:102DF000BDE8F08704F0070705F0070A57453E468F -:102E000038BF5646C6F10806111B8E4228BF0E4633 -:102E1000E10808EBD50E415C13F80EC0B94029FA61 -:102E200006F721FA0AF1FFB28CEA010147FA0AF724 -:102E300039408CEA010C03F80EC034443544D5E720 -:102E400080EA0120082341F2210201B2400000295A -:102E500080B203F1FF33B8BF504013F0FF03F4D149 -:102E60007047000038B50C468D18A54200D138BD1A -:102E700014F8011BFFF7E4FFF7E7000042684AB1CE -:102E8000136843604389818901339BB2994243812E -:102E900038BF83811046704770B588B02022044641 -:102EA0000D4668460021FEF70BFD20460495FFF70E -:102EB000E5FF024658B16B46054608AE1C4603CCFA -:102EC000B44228606960234605F10805F6D1104632 -:102ED00008B070BD082817D909280CD00A280CD0D2 -:102EE0000B280CD00C280CD00D280CD00E2814BFA9 -:102EF0004020302070470C2070471020704714206D -:102F0000704718207047202070470000082817D904 -:102F10000C280CD910280CD914280CD918280CD935 -:102F200020280CD930288CBF0F200E207047092094 -:102F300070470A2070470B2070470C2070470D2007 -:102F4000704700002DE9F843078C072F04461ED96F -:102F5000D0E9029800254FF6FF73C5F12006A5F1D0 -:102F6000200029FA05F108FA06F628FA00F03143A4 -:102F70000143C9B21846FFF763FF0835402D0346E9 -:102F8000EBD1E1693A46BDE8F843FFF76BBF4FF676 -:102F9000FF70BDE8F883000010B54B6823B9CA8AFA -:102FA00063F30902CA8210BD04691A681C600361D8 -:102FB000C38A013BC3824A60EFE700002DE9F84F66 -:102FC0001D46CB8A0F46C3F3090105298146924667 -:102FD0000B4630D00020AAB207F11A049EB2042E8C -:102FE0001FFA80F80FD8904503F1010306D3FB8A3E -:102FF0000A4462F30903FB8201201AE01AF8006018 -:10300000E6540130EAE79045F1D2A1F1050B1C230B -:103010007C68BBFBF3F203FB12BB1FFA8BF6002CA0 -:1030200045D14846FFF72AFF044638B978606FF06B -:103030000200BDE8F88F4FF00008E6E700260660C2 -:103040007860ADB24FF0000B454510D90AEB08038C -:10305000221D13F8011B9155B1B208F101081B297B -:103060001FFA88F82BD0454506F10106F1D8FB8AF6 -:10307000C3F30902154465F30903BCE7013292B2B8 -:103080001C462368002BF9D16B1F0B441C21B3FB9A -:10309000F1F301339BB29A42D3D2BBF1000FD0D1EE -:1030A0004846FFF7EBFE20B9C4F800B0BFE70122A5 -:1030B000E7E7C0F800B05E4620600446C1E745453A -:1030C000D5D94846FFF7DAFE08B92060AFE7C0F867 -:1030D00000B0002620600446B6E700002DE9F04F5E -:1030E0002DED028B1C4683B05B6901920746884632 -:1030F000002B00F09A80238C2BB1E269002A00F0AB -:103100009480072B35D807F10C00FFF7B7FE054672 -:1031100038B96FF00205284603B0BDEC028BBDE85C -:10312000F08F14220021FEF7CBFB228CE16905F120 -:103130000800FEF7B3FB208C013080B2FFF7E6FEFB -:10314000FFF7C8FE013880B220840130287463691B -:10315000228C1B782A4403F01F0363F03F0348F0DE -:1031600000411372384669602946FFF7EFFD0125DB -:10317000D1E700F10C034FF0000908EE103A4FF0D0 -:10318000800A4E464D4618EE100AFFF777FE83463A -:103190000028BED014220021FEF792FB002E3AD167 -:1031A000019BABF8083002220BF1080E1FFA82FCDB -:1031B0000CF10100BCF1060F218C80B201D88E42C7 -:1031C0002BD3FFF7A3FEFFF785FE62691278013863 -:1031D00002F01F028E4208BF4FF0400A42EA491235 -:1031E0001BFA80F14AEA020A013048F0004281F8F5 -:1031F00008A08BF81000CBF8042059463846FFF79A -:10320000A5FD238C0135B3422DB289F001094FF0A1 -:10321000000AB8D17FE70022C6E7E169895D0EF8B0 -:1032200002100136B6B20132C0E76FF0010572E755 -:10323000F8B515460E463022002104461F46FEF71B -:103240003FFB069B6360B5F5001F079BA76034BF7B -:103250006A094FF6FF72A36297B2E66104F11000AB -:1032600000239A4206D800230360A782E3822383C7 -:10327000E360F8BD0660013330462036F1E7000018 -:1032800003781BB94BB2002BC8BF01707047000018 -:1032900000787047F8B50C46C969074611B9238C08 -:1032A000002B37D1257E1F2D34D8387828BB228CAF -:1032B000072A2CD8268A36F003032BD14FF6FF704D -:1032C000FFF7D0FD20F001003102400441EA056122 -:1032D000400C41EA40254FF6FF7223462946384606 -:1032E000FFF7FCFE002807DD626913780133DBB2CB -:1032F0001F2B88BF00231370F8BD218A2D0645EAD5 -:10330000012505432046FFF71DFE0246E5E76FF065 -:103310000300F1E76FF00100EEE7000070B58AB03E -:10332000044616460021282268461D46FEF7C8FAC4 -:10333000BDF83830ADF810300F9B05939DF8403044 -:103340008DF81830119B07936946BDF84830ADF8E9 -:1033500020302046CDE90265FFF79CFF0AB070BD22 -:103360002DE9F041D36905460C4616460BB9138C7E -:103370005BBB377E1F2F28D895F80080B8F1000F6F -:1033800026D03046FFF7DEFD3378210241EAC33113 -:1033900041EA0801338A41EA076141EA03410246F2 -:1033A000334641F080012846FFF798FE00280ADDE9 -:1033B0003378012B07D1726913780133DBB21F2BED -:1033C00088BF00231370BDE8F0816FF00100FAE7B9 -:1033D0006FF00300F7E70000F0B58BB004460D4630 -:1033E00017460021282268461E46FEF769FA9DF816 -:1033F0004C305A1E534253418DF800309DF84030F6 -:10340000ADF81030119B05939DF848308DF81830B9 -:10341000149B07936A46BDF85430ADF82030294616 -:103420002046CDE90276FFF79BFF0BB0F0BD000010 -:10343000406A00B104307047436A1A684262026908 -:103440001A600361C38A013BC38270472DE9F041D2 -:10345000D0F82080194E14461D464146002709B970 -:10346000BDE8F081D1E90223A21A65EB030396427D -:1034700077EB03031ED2036A8B420DD1FFF78CFD5D -:10348000036A1B68036203690B60C38A0161016AF6 -:10349000013BC3828846E2E7FFF77EFD0B68C8F870 -:1034A000003003690B60C38A0161013BC382D8F815 -:1034B0000010D4E788460968D1E700BF80841E0069 -:1034C0002DE9F04F8BB00D46DDF8509014469B4629 -:1034D0008046002800F01981B9F1000F00F0158135 -:1034E000531E3F2B00F21181012A03D1BBF1000FC3 -:1034F00040F00B810023CDE90833B8F81430B5EB68 -:10350000C30F4FEAC30703D300200BB0BDE8F08F11 -:103510002B199F42D8F80C303ABF7F1BFFB22746C9 -:103520001BB9D8F81030002B7AD0272D4ED8C5F112 -:103530002806B7424FF000032CBFF6B23E46009378 -:103540002946D8F8080008AB3246FFF741FCA7EB44 -:10355000060A35445FFA8AFAB8F8143003F10053CA -:10356000053BDB000493D8F80C3003932821039B20 -:1035700013B1BAF1000F2CD1D8F8100040B1BAF154 -:10358000000F05D0009608AB5246691AFFF720FCE1 -:1035900038B2002FB8D066070AD00AAB03EBD401CB -:1035A000624211F8083C02F00702134101F8083C9E -:1035B000082C3CD9102C40F2B580202C40F2B7806A -:1035C000BBF1000F00F09C80082334E0BA460026CF -:1035D000C2E7049BE02B28BFE02306930B44AB42D9 -:1035E000059314D95A1B03980096924534BF52464E -:1035F000D2B2691A08AB04300792FFF7E9FB079AC9 -:103600001644AAEB020A1544F6B25FFA8AFA049B42 -:10361000069A05999B1A0493039B1B680393A6E7DC -:103620000093D8F8080008AB3A462946AEE7BBF14C -:10363000000F13D00123B4EBC30F6CD0082C12D8A9 -:103640009DF82030621E23FA02F2D50706D54FF00E -:10365000FF3202FA04F423438DF820309DF8203025 -:1036600089F8003051E7102C12D8BDF82030621EC6 -:1036700023FA02F2D10706D54FF0FF3202FA04F422 -:103680002343ADF82030BDF82030A9F800303CE7E6 -:10369000202C0FD80899631E21FA03F3DA0705D509 -:1036A0004FF0FF3202FA04F40C430894089BC9F867 -:1036B00000302AE7402C2BD0DDE90865611EC4F1FB -:1036C0002102A4F1210326FA01F105FA02F225FAFA -:1036D00003F311431943CB0712D50122A4F12003B0 -:1036E000C4F1200102FA03F322FA01F1A24052428E -:1036F00043EA010363EB430332432B43CDE9082341 -:10370000DDE90823C9E90023FFE66FF00100FCE6CC -:103710006FF00800F9E6082CA0D9102CB3D9202CA2 -:10372000EED8C3E7BBF1000FADD0022383E7BBF1B6 -:10373000000FBBD004237EE730B5012A144638BF02 -:103740000124402C85B028BF40240025012ACDE962 -:10375000025518D81B788DF8083063070AD004ABDF -:1037600003EBD405624215F8083C02F007029340CF -:1037700005F8083C009103462246002102A8FFF705 -:1037800027FB05B030BD082AE4D9102A03D81B88CE -:10379000ADF80830E1E7202A8DBFD3E900231B688C -:1037A0000293CDE90223D8E710B5CB681BB98B6033 -:1037B0000B618B8210BD04691A681C600361C38AA7 -:1037C000013BC382CA60F0E72DE9F04F93B0CDE929 -:1037D00003230B6804460D461806C3F3C01147BF08 -:1037E000C3F3C03BC3F306264FF0020B0E46002B7B -:1037F00080F2FF8113F0C04940F0FB812A7B002A50 -:1038000000F0F781BBF1020F03D02078B04240F006 -:10381000F381C3F30460079003F07F00059059B370 -:10382000C3F3074A2A44059B92F80380760646EACA -:103830000B4646EA834600220023CDE908235FEACF -:10384000D81346EA0A0602936AD0059B009367687C -:103850005B46524608A92046B847002800F0CF81B1 -:10386000276A87B9314604F10C00FFF715FB0746BC -:10387000C8B96FF0020057E0C3F30F2A590608BF1A -:103880000AF0030ACEE73B699E420DD03F68002F45 -:10389000F9D1314604F10C00FFF7FEFA0746002883 -:1038A000E7D0236A3B602762FE7D08F01F03C6F362 -:1038B0008406F01A1FFA80FC0028B8BF0CF1200023 -:1038C000D7E902210693A3EB06031FFA83FCB8BFD6 -:1038D00000B2002BBCBF0CF120031BB252EA010660 -:1038E00036D0039EDFF8D4C2B21A049E66EB010103 -:1038F0000026944576EB010C2AD395F80DE097F855 -:103900001AC0E64518D1029E002E79D001281FDC8E -:103910007868E8B9A84E964270EB010216D337E0FA -:10392000276A27B96FF00C0013B0BDE8F08F3B6930 -:103930009E42B9D03F68F4E79F48904276EB01027F -:1039400001D30020F0E7029A002AFAD00F2B18DCEE -:10395000FA7D4FEA880302F0030203F07C0313436D -:10396000FB7539462046FFF717FB6B7BBB76029B46 -:103970003BB9FB7DC3F38402013262F38603FB751E -:10398000D0E76A7BBB7E9A42DBD1029B002B37D00B -:103990004FEA9813022B33D0039BBB60049BFB6060 -:1039A000142200210DA8FDF78BFF039B0A93049BB3 -:1039B0000B932B1D0C932B7BADF83EA0013BDBB290 -:1039C000ADF83C30069B8DF84130079B8DF84230B6 -:1039D000059B8DF8433094F82C308DF840B083F07F -:1039E00001038DF844300AA9A36820469847FB7D5F -:1039F000C3F38403013303F01F039B02FB82A0E7A0 -:103A0000FB7DC8F34012B2EBD31F40F0FB80069A57 -:103A1000C3F38403934240F0F88002992B7B4FEA72 -:103A2000981200294DD0D2075DD4032B40F2F080CC -:103A3000039BBB60049BFB602B7BAE1D033BDBB297 -:103A40003246394604F10C00FFF7B8FA00280CDAC8 -:103A500039462046FFF7A0FAFB7DC3F38403013308 -:103A600003F01F039B02FB8203E7DDE90884AB88B8 -:103A70003B834FF6FF73C9F12000A9F1200228FA19 -:103A800009F104FA00F0014324FA02F21143184646 -:103A9000C9B2FFF7D5F909F10809B9F1400F03469A -:103AA000E9D1B8822A7B033AD2B23146FFF7DAF97C -:103AB000FB7DB882DA43C2F3C01262F3C713FB7511 -:103AC0003FE782B92E1D013BDBB23246394604F195 -:103AD0000C00FFF773FA0028BADB2A7BB88A013A98 -:103AE000D2B23146E2E7F98AC1F30901013B042968 -:103AF000DAB25CD8281D002307F11B069A4208D9C8 -:103B000010F801CB06F801C0013101330529DBB201 -:103B1000F4D103990A9104990B91934207F11B0187 -:103B20000C9138BF043379680D9134BF55FA83F393 -:103B300000230E93FB8AADF83EA0C3F309031A4499 -:103B4000069B8DF84130079B8DF84230059B8DF820 -:103B5000433094F82C30ADF83C2083F001038DF80D -:103B6000443000238DF840B07B602A7BB88A013A4C -:103B7000291DFFF777F93B8BB882834203D1A368F5 -:103B80000AA92046984720460AA9FFF70DFEFB7DAB -:103B9000BA8AC3F38403013303F01F039B02FB8241 -:103BA0003B8B9A420CBF00206FF01000BCE67B6894 -:103BB000002BAED0052005E040420F0080841E009F -:103BC0001C3033461E68002EFAD1091A081D2E1D1E -:103BD000184401EB090CBCF11B0F5FFA89F398D86C -:103BE0009A4296D916F8013B00F8013B09F1010908 -:103BF000EFE76FF0090097E66FF00A0094E66FF0C8 -:103C00000B0091E66FF00D008EE66FF00E008BE674 -:103C10006FF00F0088E600BFEFF3098305494A6B98 -:103C200022F001024A63683383F30988002383F397 -:103C30001188704700EF00E0302080F3118862B6F1 -:103C40000C4B0D4AD96821F4E0610904090C0A43C0 -:103C5000DA60D3F8FC20094942F08072C3F8FC20F6 -:103C60000A6842F001020A602022DA7783F8220013 -:103C7000704700BF00ED00E00003FA05001000E00F -:103C800010B5302383F311880E4B5B6813F4006387 -:103C900014D0F1EE103AEFF30984683C4FF08073D2 -:103CA000E361094BDB6B236684F3098800F076FB44 -:103CB00010B1064BA36110BD054BFBE783F31188E0 -:103CC000F9E700BF00ED00E000EF00E04306000868 -:103CD00046060008026843681143016003B11847B3 -:103CE00070470000024A136843F0C0031360704736 -:103CF0000038014013B50D4C204600F0B5FA04F130 -:103D000014000B4900940023202200F073F9094BA2 -:103D100009490094202204F1380000F0EDF9074A27 -:103D2000074BC4E9172302B010BD00BFEC380020D8 -:103D300058390020E53C000878390020003801405F -:103D4000007A030A30B5037C234C002918BF0C46C7 -:103D5000012B0FD1214B98420CD1214B1A6E42F40A -:103D600080421A66D3F8802042F48042C3F8802053 -:103D7000D3F880302268036EC16D846603EB520372 -:103D8000B3FBF2F36268150442BF23F0070503F0AA -:103D9000070343EA4503CB60A36843F040034B604D -:103DA000E36843F001038B6042F4967343F0010330 -:103DB0000B604FF0FF330B62510505D512F0102256 -:103DC00005D0B2F1805F04D080F8643030BD7F232D -:103DD000FAE73F23F8E700BF20530008EC38002043 -:103DE000001002402DE9F047C66D3768F46934626F -:103DF0002107054619D014F0080118BF4FF480714F -:103E0000E20748BF41F02001A30748BF41F040014D -:103E1000600748BF41F08001302383F31188281DDB -:103E2000FFF758FF002383F31188E2050AD53023FA -:103E300083F311884FF48061281DFFF74BFF0023A7 -:103E400083F311884FF030094FF0000A14F0200876 -:103E500038D13B0616D54FF0300905F1380A200657 -:103E600010D589F31188504600F07AF9002836DA27 -:103E70000821281DFFF72EFF27F080033360002361 -:103E800083F31188790614D5620612D5302383F3A3 -:103E90001188D5E913239A4208D12B6C33B1102134 -:103EA000281D27F04007FFF715FF3760002383F335 -:103EB0001188E30618D5AA6E1369ABB1BDE8F047C7 -:103EC0005069184789F31188736A95F86410284679 -:103ED000194000F0E3F98AF31188F469B6E7B0629B -:103EE00088F31188F469BAE7BDE8F0874FF0E02362 -:103EF000002258684FF0FF31930003F1604303F54F -:103F0000614301329042C3F88010C3F88011F3D2AC -:103F10007047000000F1604303F561430901C9B235 -:103F200083F80013012200F01F039A4043099B000D -:103F300003F1604303F56143C3F880211A607047C1 -:103F4000F8B5154682680669AA420B46816938BFF2 -:103F50008568761AB54204460BD218462A46FDF704 -:103F60009DFCA3692B44A361A3685B1BA360284647 -:103F7000F8BD0CD918463246FDF790FCAF1BE1683E -:103F80003A463044FDF78AFCE3683B44EBE71846C9 -:103F90002A46FDF783FCE368E5E700008368934267 -:103FA000F7B51546044638BF8568D0E90460361A6F -:103FB000B5420BD22A46FDF771FC63692B4463615D -:103FC000A36828465B1BA36003B0F0BD0DD9324641 -:103FD0000191FDF763FC0199E068AF1B3A4631445B -:103FE000FDF75CFCE3683B44E9E72A46FDF756FC35 -:103FF000E368E4E710B50A440024C361029B8460CF -:10400000C0E90000C0E90511C1600261036210BD92 -:1040100008B5D0E90532934201D1826882B982683D -:10402000013282605A1C42611970D0E904329A420E -:1040300024BFC3684361002100F078FA002008BD66 -:104040004FF0FF30FBE7000070B5302304460E460A -:1040500083F31188A568A5B1A368A269013BA36099 -:10406000531CA36115782269934224BFE368A361BE -:10407000E3690BB120469847002383F31188284653 -:1040800007E03146204600F041FA0028E2DA85F3E5 -:10409000118870BD2DE9F74F04460E461746984625 -:1040A000D0F81C904FF0300A8AF311884FF0000BC3 -:1040B000154665B12A4631462046FFF741FF0346C3 -:1040C00060B94146204600F021FA0028F1D00023D3 -:1040D00083F31188781B03B0BDE8F08FB9F1000FAE -:1040E00003D001902046C847019B8BF31188ED1A3D -:1040F0001E448AF31188DCE7C0E90511C160C36181 -:104100001144009B8260C0E90000016103627047B6 -:10411000F8B504460D461646302383F31188A76888 -:10412000A7B1A368013BA36063695A1C62611D705B -:10413000D4E904329A4224BFE3686361E3690BB1B6 -:1041400020469847002080F3118807E0314620463A -:1041500000F0DCF90028E2DA87F31188F8BD0000EE -:10416000D0E905239A4210B501D182687AB98268F4 -:10417000013282605A1C82611C7803699A4224BF12 -:10418000C3688361002100F0D1F9204610BD4FF0D3 -:10419000FF30FBE72DE9F74F04460E4617469846D9 -:1041A000D0F81C904FF0300A8AF311884FF0000BC2 -:1041B000154665B12A4631462046FFF7EFFE034615 -:1041C00060B94146204600F0A1F90028F1D0002353 -:1041D00083F31188781B03B0BDE8F08FB9F1000FAD -:1041E00003D001902046C847019B8BF31188ED1A3C -:1041F0001E448AF31188DCE70268436811430160BA -:1042000003B11847704700001430FFF743BF0000A8 -:104210004FF0FF331430FFF73DBF00003830FFF799 -:10422000B9BF00004FF0FF333830FFF7B3BF0000D5 -:104230001430FFF709BF00004FF0FF311430FFF7D3 -:1042400003BF00003830FFF763BF00004FF0FF32BC -:104250003830FFF75DBF0000012914BF6FF0130075 -:1042600000207047FFF746BD044B03600023C0E900 -:104270000233436001230374704700BF38530008C2 -:1042800010B53023044683F31188FFF75BFD02234A -:104290002374002080F3118810BD000038B5C36975 -:1042A00004460D461BB904210844FFF7A5FF294623 -:1042B00004F11400FFF7ACFE002806DA201D4FF4CD -:1042C0000061BDE83840FFF797BF38BD0023037594 -:1042D000826803691B6899689142FBD25A6803603F -:1042E000426010605860704700230375826803695C -:1042F0001B6899689142FBD85A680360426010605D -:104300005860704708B50846302383F311880B7D49 -:10431000032B05D0042B0DD02BB983F3118808BDD6 -:104320008B6900221A604FF0FF338361FFF7CEFFE5 -:104330000023F2E7D1E9003213605A60F3E700008E -:10434000FFF7C4BF054BD9680875186802681A6082 -:10435000536001220275D860FCF75EB998390020DD -:1043600030B50C4BDD684B1C87B004460FD02B4694 -:10437000094A684600F06CF92046FFF7E3FF009B0E -:1043800013B1684600F06EF9A86907B030BDFFF7B9 -:10439000D9FFF9E79839002005430008044B1A6853 -:1043A000DB6890689B68984294BF002001207047AA -:1043B00098390020084B10B51C68D86822681A602C -:1043C000536001222275DC60FFF78EFF0146204614 -:1043D000BDE81040FCF720B998390020044B1A685A -:1043E000DB6892689B689A4201D9FFF7E3BF704788 -:1043F0009839002038B5074C0749084801230025A3 -:104400002370656000F02EFC0223237085F3118871 -:1044100038BD00BFC03B002064530008983900201D -:1044200008B572B6044B186500F0E4FA00F09CFB86 -:10443000024B03221A70FEE798390020C03B00208F -:1044400000F046B9EFF3118020B9EFF30583302275 -:1044500082F311887047000010B530B9EFF305847E -:10446000C4F3080414B180F3118810BDFFF7B6FF40 -:1044700084F31188F9E700008B60022308618B82C6 -:10448000084670478368A3F1840243F8142C02693C -:1044900043F8442C426943F8402C094A43F8242C41 -:1044A000C26843F8182C022203F80C2C002203F8EF -:1044B0000B2C044A43F8102CA3F12000704700BFD6 -:1044C000310600089839002008B5FFF7DBFFBDE88A -:1044D0000840FFF735BF0000024BDB6898610F20F2 -:1044E000FFF730BF98390020302383F31188FFF79E -:1044F000F3BF000008B50146302383F3118808207C -:10450000FFF72EFF002383F3118808BD064BDB68FD -:1045100039B1426818605A60136043600420FFF7A5 -:104520001FBF4FF0FF307047983900200368984252 -:1045300006D01A680260506099611846FFF700BF04 -:104540007047000010B503689C68A2420CD85C68F4 -:104550008A600B604C602160596099688A1A9A6081 -:104560004FF0FF33836010BD1B68121BECE70000A7 -:104570000A2938BF0A2170B504460D460A2660197B -:1045800000F06AFB00F056FB041BA54203D8751C23 -:104590002E460446F3E70A2E04D9BDE870400120F8 -:1045A00000F0A0BB70BD0000F8B5144B0D46D961FA -:1045B00003F1100141600A2A1969826038BF0A229A -:1045C000016048601861A818144600F037FB0A27FC -:1045D00000F030FB431BA342064606D37C1C28197F -:1045E00000F03AFB27463546F2E70A2F04D9BDE82A -:1045F000F840012000F076BBF8BD00BF98390020DC -:10460000F8B506460D4600F015FB0F4A134653F861 -:10461000107F9F4206D12A4601463046BDE8F84049 -:10462000FFF7C2BFD169BB68441A2C1928BF2C46BA -:10463000A34202D92946FFF79BFF22463146034891 -:10464000BDE8F840FFF77EBF98390020A839002068 -:1046500010B4C0E9032300235DF8044B4361FFF766 -:10466000CFBF000010B5194C236998420DD0D0E996 -:104670000032816813605A609A680A449A60002385 -:1046800003604FF0FF33A36110BD2346026843F877 -:10469000102F53600022026022699A4203D1BDE8C4 -:1046A000104000F0D3BA936881680B44936000F027 -:1046B000C1FA2269E1699268441AA242E4D911441C -:1046C000BDE81040091AFFF753BF00BF983900201A -:1046D0002DE9F047DFF8BC8008F110072C4ED8F820 -:1046E000105000F0A7FAD8F81C40AA68031B9A42A1 -:1046F0003ED81444D5E900324FF00009C8F81C40F8 -:1047000013605A60C5F80090D8F81030B34201D158 -:1047100000F09CFA89F31188D5E9033128469847BF -:10472000302383F311886B69002BD8D000F082FA14 -:104730006A69A0EB04094A4582460DD2022000F0C6 -:10474000D1FA0022D8F81030B34208D15146284699 -:10475000BDE8F047FFF728BF121A2244F2E712EB38 -:10476000090938BF4A4629463846FFF7EBFEB5E748 -:10477000D8F81030B34208D01444211AC8F81C00ED -:10478000A960BDE8F047FFF7F3BEBDE8F08700BFC2 -:10479000A83900209839002000207047FEE700006B -:1047A000704700004FF0FF3070470000BFF34F8F9D -:1047B000024A1369DB03FCD4704700BF00200240AB -:1047C00008B5094B1B7873B9FFF7F0FF074B5A691F -:1047D000002ABFBF064A9A6002F188329A601A68BE -:1047E00022F480621A6008BDD83B002000200240FD -:1047F0002301674508B50B4B1B7893B9FFF7D6FF2C -:10480000094B5A6942F000425A611A6842F48052D8 -:104810001A601A6822F480521A601A6842F48062A0 -:104820001A6008BDD83B0020002002403F289ABFF4 -:1048300000F58030C0020020704700004FF4006097 -:1048400070470000402070473F2808B50BD8FFF79D -:10485000EDFF00F500630268013204D104308342A9 -:10486000F9D1012008BD0020FCE700003F2838B541 -:10487000044626D8FFF7E6FDFFF798FFFFF7A0FFF5 -:10488000114BF3221A6102225A615A6942EAC402A8 -:104890005A615A6942F480325A6105462046FFF750 -:1048A00085FF4FF40061FFF7C1FF00F059F928467A -:1048B000FFF7A0FFFFF7D0FD2046BDE83840FFF727 -:1048C000C3BF002038BD00BF0020024040EA020301 -:1048D00013F007032DE9F04705460C46164606D0AF -:1048E000344B40F231321A600020BDE8F087811865 -:1048F000314A91420CD92F4A40F236311160F3E728 -:104900002B1D1B686268934208D1083E08350834A5 -:10491000072E19D92A6823689A42F1D0FFF792FD31 -:10492000FFF74EFFFFF742FF04F10801234C4FF061 -:1049300001084FF00009012EA1F1080708D8FFF780 -:1049400059FFFFF789FD01E0002EE7D10120CCE7F8 -:10495000C4F81480AA4651F8083C4AF8043B51F8C0 -:10496000043C6B60FFF722FF236943F001032361DE -:10497000C4F814902A6851F8083C9A420ED00D4BA6 -:1049800040F25E321A600E4B1D600E4B1E600E4BE5 -:104990001F60FFF72FFFFFF75FFDA5E7DAF800A024 -:1049A00051F8043C9A4501F10801E8D1083E083568 -:1049B000C1E700BFD43B00200000020800200240F5 -:1049C000C83B0020D03B0020CC3B0020084908B564 -:1049D0000B7828B11BB9FFF7F3FE01230B7008BD5C -:1049E000002BFCD0BDE808400870FFF703BF00BFF4 -:1049F000D83B002008B54FF4B0414FF0005000F014 -:104A0000B1F8BDE808404FF420514FF0805000F05D -:104A1000A9B80000084600F0F3BB000070B582B0F2 -:104A2000FFF710FD0E4E054600F004F93268904283 -:104A300037BF0C4A0B49516814682EBFD1E90041B9 -:104A4000013151600419034641F1000128460191EA -:104A50003360FFF701FD0199204602B070BD00BF31 -:104A6000DC3B0020E03B002070B582B0FFF7EAFCA1 -:104A7000104E054600F0DEF83268904237BF0E4A0D -:104A80000D49516814682EBFD1E9004101315160D0 -:104A9000041941F100010346284601913360FFF7F4 -:104AA000DBFC01994FF47A7200232046FBF7A0FB50 -:104AB00002B070BDDC3B0020E03B00200244D2B2DB -:104AC000904200D17047431C800000F1804000F507 -:104AD0001450006841F8040BD8B2F1E7124B10B53E -:104AE000D3F89040240409D4D3F89040C3F8904000 -:104AF000D3F8904044F40044C3F890400B4C236832 -:104B0000024443F480732360D2B2904200D110BDBE -:104B1000431C800000F1804000F5145051F8044B14 -:104B20000460D8B2F1E700BF0010024000700040FE -:104B300007B5012201A90020FFF7C0FF019803B0CB -:104B40005DF804FB13B50446FFF7F2FFA04205D061 -:104B5000012201A900200194FFF7C0FF02B010BD9F -:104B6000704700007047000070470000074B45F297 -:104B700055521A6002225A6040F6FF729A604CF653 -:104B8000CC421A60024B01221A707047003000407C -:104B9000EC3B0020034B1B781BB1034B4AF6AA22C7 -:104BA0001A607047EC3B002000300040054B1A684B -:104BB00032B902F1804202F50432D2F894201A6030 -:104BC000704700BFE83B0020024B4FF40002C3F8DF -:104BD000942070470010024008B5FFF7E7FF024B32 -:104BE0001868C0F3407008BDE83B00207047000023 -:104BF000FEE700000A4B0B480B4A90420BD30B4BCD -:104C0000DA1C121AC11E22F003028B4238BF0022A6 -:104C10000021FCF755BE53F8041B40F8041BECE7D9 -:104C2000D4540008703C0020703C0020703C0020F0 -:104C300000F0C2B84FF08043586A70474FF080438D -:104C4000002258631A610222DA6070474FF08043F5 -:104C50000022DA60704700004FF0804358637047CD -:104C6000FEE7000070B51B4B01630025044686B0CB -:104C7000586085620E46FEF7DFFF04F11003C4E9B9 -:104C800004334FF0FF33C4E90635C4E90044A5609E -:104C9000E562FFF7CFFF2B460246C4E9082304F183 -:104CA00034010D4A256580232046FFF7E5FB0123EB -:104CB000E0600A4A0375009272680192B268CDE919 -:104CC0000223074B6846CDE90435FFF7FDFB06B02C -:104CD00070BD00BFC03B0020705300087553000832 -:104CE000614C0008024AD36A1843D062704700BF83 -:104CF000983900204B6843608B688360CB68C36041 -:104D00000B6943614B6903628B6943620B68036003 -:104D10007047000008B5204BDA6A42F07F02DA6281 -:104D2000DA6A22F07F02DA62DA6ADA6C42F07F0233 -:104D3000DA64DA6E42F07F02DA66184ADB6E1146F8 -:104D40004FF09040FFF7D6FF02F11C0100F58060A4 -:104D5000FFF7D0FF02F1380100F58060FFF7CAFFCE -:104D600002F1540100F58060FFF7C4FF02F1700109 -:104D700000F58060FFF7BEFF02F18C0100F5806056 -:104D8000FFF7B8FF02F1A80100F58060FFF7B2FF5E -:104D9000BDE8084000F050B8001002407C53000805 -:104DA00008B500F0FBF9FFF725FBBDE80840FFF769 -:104DB000FDBE0000704700000F4B9A6D42F00102EB -:104DC0009A659A6F42F001029A670C4A9B6F93684A -:104DD00043F0010393604FF08043A7229A624FF0A3 -:104DE000FF32DA6200229A615A63DA605A60012265 -:104DF0005A611A60704700BF00100240002004E0B2 -:104E00004FF0804208B51169D3680B40D9B2C9434D -:104E10009B07116107D5302383F31188FFF710FB3F -:104E2000002383F3118808BD08B5FFF75FF8BDE8DC -:104E3000084000F08BB900004E4B4FF0FF319A6AEA -:104E400099629A6A00229A62986AD86A60F07F0032 -:104E5000D862D86A00F07F00D862D86A186B1963EC -:104E6000186B1A63186B986B9963986B9A63986BBD -:104E7000D86BD963D86BDA63D86B186C1964196C6A -:104E80001A64196C196E41F001011966D3F880108B -:104E900021F00101C3F88010D3F88010996D41F022 -:104EA00080519965996F21F080519967996F3249C6 -:104EB0004FF400408860CA600A624A628A62CA622D -:104EC0000A634A638A63CA630A644A648A64CA6476 -:104ED0000A654A654A604FF48072C1F880204FF439 -:104EE00040720A604A6912F48062FBD1D3F89010D4 -:104EF00011F4407F1EBF4FF48031C3F89010C3F807 -:104F00009020D3F8982042F00102C3F89820D3F8FB -:104F100098209207FBD51A6842F480321A601A680A -:104F20009003FCD5D3F8902022F00322C3F8902000 -:104F3000124ADA601A6842F080721A601A689101A7 -:104F4000FCD50F490F4800229A60C3F888100E491B -:104F5000C3F89C20016002684A401207FBD19A689E -:104F600042F003029A609A6802F00C020C2AFAD10D -:104F7000704700BF0010024000700040232A61010A -:104F8000550100500020024004070400074A08B5FC -:104F9000536903F00103536123B1054A13680BB150 -:104FA00050689847BDE80840FEF76ABE000401401B -:104FB000F03B0020074A08B5536903F00203536130 -:104FC00023B1054A93680BB1D0689847BDE8084003 -:104FD000FEF756BE00040140F03B0020074A08B52A -:104FE000536903F00403536123B1054A13690BB1FC -:104FF00050699847BDE80840FEF742BE00040140F2 -:10500000F03B0020074A08B5536903F008035361D9 -:1050100023B1054A93690BB1D0699847BDE80840B0 -:10502000FEF72EBE00040140F03B0020074A08B501 -:10503000536903F01003536123B1054A136A0BB19E -:10504000506A9847BDE80840FEF71ABE00040140C8 -:10505000F03B0020164B10B55C6904F478725A617D -:10506000A30604D5134A936A0BB1D06A9847600629 -:1050700004D5104A136B0BB1506B9847210604D529 -:105080000C4A936B0BB1D06B9847E20504D5094AE3 -:10509000136C0BB1506C9847A30504D5054A936C6B -:1050A0000BB1D06C9847BDE81040FEF7E9BD00BFDA -:1050B00000040140F03B0020194B10B55C6904F47A -:1050C0007C425A61620504D5164A136D0BB1506DCE -:1050D0009847230504D5134A936D0BB1D06D9847BB -:1050E000E00404D50F4A136E0BB1506E9847A1042B -:1050F00004D50C4A936E0BB1D06E9847620404D568 -:10510000084A136F0BB1506F9847230404D5054A22 -:10511000936F0BB1D06F9847BDE81040FEF7B0BD5C -:1051200000040140F03B002008B50348FEF75AFE9A -:10513000BDE80840FEF7A4BDEC38002008B5FFF735 -:105140005FFEBDE80840FEF79BBD0000062108B5E4 -:105150000846FEF7DFFE06210720FEF7DBFE0621EC -:105160000820FEF7D7FE06210920FEF7D3FE062110 -:105170000A20FEF7CFFE06211720FEF7CBFE062100 -:105180002820FEF7C7FE07211C20FEF7C3FEBDE85E -:1051900008400C212520FEF7BDBE000008B5FFF732 -:1051A00043FE00F009F8FFF75DF8FFF703FEBDE8E6 -:1051B0000840FFF73DBD00000023054A19460133B2 -:1051C000102BC2E9001102F10802F8D1704700BFAC -:1051D000F03B00200B460146184600F003B80000E3 -:1051E00000F00EB810B5054C13462CB10A46014626 -:1051F0000220AFF3008010BD2046FCE70000000055 -:10520000024B01461868FFF705BC00BF28110020BB -:1052100010B501390244904201D1002005E0037825 -:1052200011F8014FA34201D0181B10BD0130F2E765 -:105230002DE9F041A3B1C91A17780144044603F1DE -:10524000FF3C8C42204601D9002009E00578BD4290 -:1052500004F10104F5D10CEB0405D618A54201D1E7 -:10526000BDE8F08115F8018D16F801EDF045F5D097 -:10527000E7E70000034611F8012B03F8012B002A91 -:10528000F9D170476F72672E6172647570696C6FC7 -:10529000742E48697465632D416972737065656425 -:1052A0000000000053544D333247343F3F000000AC -:1052B00040A2E4F1646891060041A3E5F2656992B9 -:1052C000070000004261642043414E496661636506 -:1052D00020696E6465782E00000000000000000068 -:1052E00061240008691F0008292B0008611F0008BD -:1052F00011200008F5210008D91F0008A11F00088F -:10530000A51F00087D1F0008651F0008B5210008C3 -:10531000891F0008652C0008951F000889210008D6 -:1053200000960000000000000000000000000000E7 -:1053300000000000000000000000000025420008FE -:10534000114200084D420008394200084542000859 -:10535000314200081D420008094200085942000875 -:105360006330000060530008F0390020C03B00208B -:105370006D61696E0069646C650000000010802A30 -:1053800000000000AAAAAAAA00000024BFFF000093 -:10539000000000000090090000A0000100000000D3 -:1053A000AAFAAAAA00500001FFFF0000000000773F -:1053B000000000000000000000000000AAAAAAAA45 -:1053C00000000000FFFF00000000000000000000DF -:1053D0000000000000000000AAAAAAAA0000000025 -:1053E000FFFF0000000000000000000000000000BF -:1053F00000000000AAAAAAAA00000000FFFF000007 -:10540000000000000000000000000000000000009C -:10541000AAAAAAAA00000000FFFF000000000000E6 -:10542000000000000000000000000000AAAAAAAAD4 -:1054300000000000FFFF000000000000000000006E -:10544000E0ADFF7F01000000160400000000000036 -:105450000098010000000000FE2A0100D2040000B4 -:10546000FF000000EC38002000000000A4520008FB -:105470002C110020000000000000000000000000CF -:10548000000000000000000000000000000000001C -:10549000000000000000000000000000000000000C -:1054A00000000000000000000000000000000000FC -:1054B00000000000000000000000000000000000EC -:1054C00000000000000000000000000000000000DC -:0454D00000000000D8 +:10063000002383F311882846A047002003F09AFA8C +:10064000FEE703F0FDF900DFFEE70000F8B500F07B +:1006500021FE03F085FD074603F0D6FD0546D0BB1D +:10066000294B9F4237D001339F4237D0274B27F089 +:10067000FF029A4235D1F8B200F044FC2E4642F215 +:10068000107400F045FC08B10024264601F0BAF8C9 +:1006900058B3032000F03EF80024264635B11C4B29 +:1006A0009F4203D003F0A8FD00242646002003F05B +:1006B00061FD0EB100F044F800F05CFC00F0ECFDD0 +:1006C00002F0DAF80546B4B900F09CFC4FF47A70F9 +:1006D00003F056FAF7E72E460024D2E70446012637 +:1006E000CFE706464FF47A74CBE7002CD6D04FF410 +:1006F0007A740126D2E702F0BFF8431BA342E3D984 +:1007000000F01EF8DCE700BF010007B0000008B0F1 +:10071000263A09B0084B187003280CD8DFE800F01F +:1007200008050208022000F013BE022000F008BEF7 +:10073000024B00225A607047801100208411002073 +:1007400038B501F05FF830B1254B03221A70254B04 +:1007500000225A6038BD244B244A19680131F9D06F +:1007600004339342F9D1224C1F4DD4F80428AA42F5 +:10077000F0D3204B9B6803F1006303F5D0439A420A +:10078000E8D203F00BFD03F01DFD002000F09EFDFC +:100790000220FFF7BFFF184B9A6D00229A65996FF0 +:1007A0009A67996FD96DDA65D96FDA67D96F196E63 +:1007B0001A66D3F88010C3F88020D3F8803072B660 +:1007C0004FF0E0233021C3F8085DD4F80038D4F8A6 +:1007D000042881F311889D4683F308881047B9E700 +:1007E00080110020841100200068000820680008A3 +:1007F000006000080011002000100240094A136840 +:1008000049F2690099B21B0C00FB01331360064BDF +:10081000186844F2506182B2000C01FB02001860BB +:1008200080B27047141100201011002010B5002173 +:100830001022044600F0A6FD034B03CB206061604C +:100840001868A06010BD00BF9075FF1F2DE9F04132 +:10085000ADF5507D0DF13C086EAC40F275120746C7 +:100860000D4610A80021C8F8001000F08BFD4FF4D1 +:10087000C4720021204600F085FD01F0FDFF254BEC +:100880004FF47A72B0FBF2F0186093E8070002238D +:1008900084E807000DF5ED702382FFF7C7FF41F2F2 +:1008A00004631D49238407A803F0ECFF1C2384F88C +:1008B00032310DF2EB226B440DF1340C1E4603CEA7 +:1008C000664510605160334602F10802F6D1306887 +:1008D000106041460122204600F0A0FD0023039352 +:1008E000AB7E029305F11903019380B20123CDE998 +:1008F00004800093E97E05A3D3E90023384602F083 +:1009000079FB0DF5507DBDE8F08100BF9E6AC421E2 +:10091000818A46EE8C110020944800082DE9F041B0 +:100920002C4C237ADAB080460D465BBB27A92846BB +:1009300000F084FE0746002842D19DF89D60C82E35 +:100940003ED801464FF4A662204600F01BFD4FF44E +:100950008073C4F8F8314FF40073C4F80C334FF4CB +:100960004073C4F8203432460DF19E0104F10900B1 +:1009700000F0F6FC26449DF89C30777223720BB988 +:10098000EB7E23728122002106AC27A800F0FAFC3E +:100990000122214627A800F08DFE00230393AB7EA1 +:1009A000029305F1190380B201932823CDE9044095 +:1009B0000093E97E05A3D3E90023404602F01AFB29 +:1009C0005AB0BDE8F08100BFAFF3008026417272DB +:1009D000DF25D7B788360020F0B5254E4FF48A754D +:1009E00005FB0065F1B096F8D83085F8DC300024BE +:1009F000D822214685F8E8403AA800F0C3FC06F169 +:100A0000090000F0B7FCD5F8E4308DF8F000C2B270 +:100A100006AF06F109010DF1F100CDE93A3400F01D +:100A20009FFC394601223AA800F070FE80B2CDE961 +:100A3000047008230127CDE9023706F1D80301939A +:100A400030230093317A0B4807A3D3E9002302F047 +:100A5000D1FAA04206DD01F00FFFC5F8E0003846EC +:100A600071B0F0BD2046FBE778F6339F93CACD8D79 +:100A700088360020A42100202DE9F0411D4D1E4E96 +:100A80001E4F86B0284602F0E1FA034658B3002410 +:100A9000CDE90344ADF81440027B8DF81420996829 +:100AA0004068029403AA03C21B68DFF8548043F035 +:100AB0000043029301F0E2FE821941F10003009429 +:100AC00002A9384601F0BAF8A04205DD284602F036 +:100AD000C1FA88F80040D5E798F80030072B05D810 +:100AE000013388F8003006B0BDE8F081014802F01B +:100AF000B1FAF8E7A421002040420F00D8210020DD +:100B0000BD3B002070B50D4614461E4602F0CEF9DE +:100B100050B9022E10D1012C0ED112A3D3E900231B +:100B2000C5E90023012007E0282C10D005D8012CAE +:100B300009D0052C0FD0002070BD302CFBD10BA3A9 +:100B4000D3E90023ECE70BA3D3E90023E8E70BA3E9 +:100B5000D3E90023E4E70BA3D3E90023E0E700BFD8 +:100B6000AFF30080401DA12026812A0B78F6339F29 +:100B700093CACD8D9E6AC421818A46EE2641727247 +:100B8000DF25D7B7F017304A39059E5638B50546E8 +:100B90000E4C0021013500F0BBFBA4F82C55B4F835 +:100BA0002C0500F09DFB78B1B4F82C0500F0A8FBF3 +:100BB000014648B9B4F82C0500F0AAFBB4F82C356E +:100BC0000133A4F82C35EAE738BD00BF8836002091 +:100BD00010B50A4B0A4A1A6003F5805393F848206F +:100BE0003AB95C6C2CB1204600F08AFE204603F036 +:100BF000FFFDBDE81040034800F082BED821002070 +:100C0000E4480008083200202DE9F04F8FB000AF13 +:100C100005460C4602F04AF9002849D1237E022BF2 +:100C20001BD1E38A012B18D101F026FE0646FFF7FF +:100C3000E5FD03464FF4C870DFF8C482B3FBF0F261 +:100C400006F5167602FB103316FA83F3C8F8003067 +:100C5000E37E33B9A34B00221A703C37BD46BDE892 +:100C6000F08F07F12401204600F0A6FC0028F4D103 +:100C700007F11400FFF7DAFD97F8264007F1140199 +:100C8000224607F1270003F0CBFD0028E2D10F2C0C +:100C900008D8944B1C70D8F80030A3F51673C8F828 +:100CA0000030DAE797F82410284602F0F7F8D4E786 +:100CB000E38A282B2BD010D8012B23D0052BCCD1A5 +:100CC000BFF34F8F8849894BCA6802F4E06213432F +:100CD000CB60BFF34F8F00BFFDE7302BBDD1844EFB +:100CE000E17E327A9142B8D1607E3146002291F89D +:100CF000DC50854200F0A5800132042A01F58A719A +:100D0000F5D1AAE721462846FFF7A0FDA5E7214631 +:100D10002846FFF703FEA0E7B2F8EC507B6005F130 +:100D200003094FEA99094FEA8902D11DC908A8EBC6 +:100D3000C1039D46EB460021584600F023FB04F119 +:100D4000EE012A463144584600F00AFB7B6813B98D +:100D5000012000F0BBFA96F8D20000F0C1FA044678 +:100D600030B9307200F0DCFA204600F0AFFAB1E0A2 +:100D7000D6F8D4203AB996F8D200B6F82C2582429B +:100D800001D8FFF703FFD6F8D4202A44944208D2B2 +:100D900096F8D200B6F82C250130824201D8FFF730 +:100DA000F5FE70685FFA89F2594600F0F3FA08B967 +:100DB000C54679E0726896F8D2002A447260D6F887 +:100DC000D42005EB0209C6F8D49000F089FA8145D9 +:100DD00009D396F8D220D6F8D4000132001B86F849 +:100DE000D220C6F8D400FF2D0FD80024347200F0B2 +:100DF00097FA204600F06AFA00F004FD3D4B188196 +:100E000008B9FFF79DFCC54627E7BB6896F8D900EF +:100E10000AFB0362FB68D2F8E41082F8E83001F5BF +:100E20008061C2F8E030C2F8E410FFF7D5FDFFF7AB +:100E300023FE96F8D920013202F0030286F8D92069 +:100E4000B6E74FF48A7A0AFB02F505F1EA0131446C +:100E5000204600F087FCF86000287FF4FEAE3544A1 +:100E6000012285F8E82001F007FDD5F8E020D6ED55 +:100E7000007ADFED216A801A192838BF192040F660 +:100E8000B832904228BF1046B8EE677A07EE900A53 +:100E9000F8EEE77A67EEA67ADFED186AE7EE267AD3 +:100EA000FCEEE77AC6ED007A96F8D930BB60BA68F6 +:100EB00073680AFB02F4321992F8E81059B1D2F8BB +:100EC000E4108B42E8463FF427AF002182F8E81097 +:100ED000C2F8E010C5467368064A9B0A01331381C5 +:100EE000BBE600BF9D21002000ED00E00400FA05F4 +:100EF000883600208C110020CDCCCC3D6666663F44 +:100F0000A0210020014B1870704700BF98110020ED +:100F100038B54FF00054134B22689A4220D1124B3F +:100F2000627D12481A70237D03724FF48073C0F8FB +:100F3000F8314FF40073C0F80C3300254FF44073C0 +:100F4000C0F820340A49C0F8E450C922093000F042 +:100F500007FAE0222946204600F014FA012038BDA5 +:100F60000020FCE79AAD44C5981100208836002087 +:100F70001600002037B500F045FC194D19492881AD +:100F800002236B7100220123174801F07FF8002330 +:100F90000193164B164900931648174B4FF4805295 +:100FA00001F054FF154B197811B1124801F076FF8A +:100FB00001F062FC0446FFF721FC4FF4C873B0FB5C +:100FC000F3F202FB130304F5167010FA83F00C4BD6 +:100FD000186003F019F908B10F232B8103B030BD5D +:100FE0008C11002040420F00D8210020050B000882 +:100FF0009C110020A4210020090C00089811002059 +:10100000A02100202DE9F04F2DED028B90A7D7E90C +:1010100000670FF24429D9E90089884C95B00DADDD +:101020009FED848BFFF728FDDFF834B200230C938B +:10103000ADF83C300D936B6000230DF125028DED72 +:10104000008B4FF0010A09A958468DF825308DF81C +:1010500024A001F079FB9DF824200023002A40F011 +:10106000AF80204601F022FF0546002847D1DFF877 +:10107000F4B101F001FCDBF8003098423FD301F0FD +:10108000FBFB0790FFF7BAFB079A4FF4C873B0FB5E +:10109000F3F101FB130302F5167010FA83F0CBF89D +:1010A0000000DFF8C4B19BF800100791002914BFBD +:1010B0002B46534610A88DF83030FFF7B7FB079941 +:1010C000C1F11002D2B2062A10AB28BF0622194481 +:1010D0000DF13100079200F043F9079A0CAB03932E +:1010E000182302930132564BD2B2CDE900A30492E9 +:1010F0003B463246204601F01FFF8BF8005001F0BE +:10110000BBFB504A504D1368C31AB3F57A7F32D3F4 +:10111000106001F0B3FB02460B46204601F0A4FF2D +:10112000204601F0C3FE30B32B7ADFF840A1002B3C +:1011300014BF032302238AF8053001F09DFB0DF153 +:10114000400B4FF47A730122B0FBF3F05946CAF812 +:101150000000504600F008FA182302933B4B01931D +:1011600080B240F25513CDE903B0009342464B469E +:10117000204601F0E1FE2B7AB3B101F07DFB4FF088 +:10118000000A83464FF48A7295F8D900504400F063 +:10119000030002FB005393F8E810002934D00AF151 +:1011A000010ABAF1040FEFD1C82002F0E9FC2B7A52 +:1011B000002B7FF434AF15B0BDEC028BBDE8F08F8F +:1011C0004FF0904110A84A6982F040024A611946E6 +:1011D000102200F0D7F80DF126030AAA0CA95846F0 +:1011E00000F01EFE95E8030011AB83E803009DF8B4 +:1011F0003C308DF84C300C9B109310A9DDE90A238C +:10120000204602F005F917E7D3F8E01049B12B6842 +:10121000FA2B38BFFA23ABEB01010533B1EB430FD7 +:10122000BDD3FFF7D9FB4FF48A720028B7D1BBE7D3 +:10123000AFF300800000000000000000A4210020A7 +:101240009C210020B83B002088360020BC3B0020B9 +:10125000401DA12026812A0BF1C6A7C1D068080F26 +:10126000D8210020A02100209D2100208C110020E9 +:1012700008B5054800F078FEBDE80840034A044977 +:10128000002003F0AFBA00BFD8210020F83B0020B7 +:10129000D10B00087047000070B502F0FDFD094E4B +:1012A000094D3080002428683388834208D902F031 +:1012B000EFFD2B6804440133B4F5D04F2B60F2D31B +:1012C00070BD00BFEC3B0020C03B002002F096BE8A +:1012D00000F10060920000F5D04002F019BE00005D +:1012E000054B1A68054B1B889B1A834202D9104490 +:1012F00002F0CEBD00207047C03B0020EC3B002038 +:10130000024B1B68184402F0C9BD00BFC03B00205F +:10131000024B1B68184402F0D3BD00BFC03B002045 +:10132000064991F8243033B10023086A81F824304B +:101330000822FFF7CDBF0120704700BFC43B00204B +:10134000022802BF4FF0904340229A61704700008C +:10135000022802BF4FF090434FF480029A61704719 +:1013600010B50023934203D0CC5CC4540133F9E799 +:1013700010BD000003460246D01A12F9011B0029D5 +:10138000FAD1704702440346934202D003F8011B8E +:10139000FAE770472DE9F8431F4D144695F82420CD +:1013A0000746884652BBDFF870909CB395F824300E +:1013B0002BB92022FF2148462F62FFF7E3FF95F863 +:1013C0002400C0F10802A24228BF2246D6B24146FC +:1013D000920005EB8000FFF7C3FF95F82430A41BB3 +:1013E0001E44F6B2082E17449044E4B285F82460F7 +:1013F000DBD1FFF795FF0028D7D108E02B6A03EB7C +:1014000082038342CFD0FFF78BFF0028CBD100208F +:10141000BDE8F8830120FBE7C43B00202DE9F0473D +:101420000D46044600219046284640F27912FFF707 +:10143000A9FF234620220021284601F08BFF231D0F +:1014400002222021284601F085FF631D032222216C +:10145000284601F07FFFA31D03222521284601F025 +:1014600079FF04F1080310222821284601F072FFB9 +:1014700004F1100308223821284601F06BFF04F123 +:10148000110308224021284601F064FF04F11203F1 +:1014900008224821284601F05DFF04F114032022B0 +:1014A0005021284601F056FF04F118034022702114 +:1014B000284601F04FFF04F120030822B0212846FE +:1014C00001F048FF04F121030822B821284601F069 +:1014D00041FF04F12207C0263B4631460822284638 +:1014E000083601F037FFB6F5A07F07F10107F3D109 +:1014F00004F1320308223146284601F02BFF002771 +:1015000004F1330A94F832304FEAC7099F4209F5D3 +:10151000A47615D3B8F1000F08D1314604F59973BC +:101520000722284601F016FF09F24F16274694F8C5 +:1015300032213B1B93420CD3F01DC008BDE8F0875D +:101540000AEB070308223146284601F003FF013762 +:10155000D8E707F2331331460822284601F0FAFE95 +:1015600008360137E3E7000013B5044608460021BA +:1015700001602346C0F803102022019001F0EAFE2A +:101580000198231D0222202101F0E4FE0198631D31 +:101590000322222101F0DEFE0198A31D0322252152 +:1015A00001F0D8FE019804F108031022282101F06F +:1015B000D1FE072002B010BDF7B50023047F0091D3 +:1015C0000E4607221946054601F088FD731C00935C +:1015D000012200230721284601F080FDC4B9B31C75 +:1015E0000093052223460821284601F077FD0D24AB +:1015F0003746B278BB1B934211D32B7FA88A07349E +:10160000E408BBB9844294BF0020012003B0F0BDC0 +:10161000AB8ADB00083BDB08B3700824E8E7FB1C5F +:101620000093214600230822284601F057FD083484 +:101630000137DEE7201A18BF0120E7E7F7B50023DE +:10164000047F00910E4608221946054601F046FD2A +:10165000731CC4B90822009311462346284601F0A2 +:101660003DFD1024012372785F1C013B934211D38E +:101670002B7FA88A0734E408BBB9844294BF0020BA +:10168000012003B0F0BDAB8ADB00083BDB087370C0 +:101690000824E7E7F319009321460023082228468F +:1016A00001F01CFD08343B46DDE7201A18BF01207D +:1016B000E7E70000F8B50E460546144600218122F2 +:1016C0003046FFF75FFE2B4608220021304601F02E +:1016D00041FE7CB96B1C07220821304601F03AFE1E +:1016E0000F2401236A785F1C013B934204D3E01D61 +:1016F000C008F8BD0824F4E7EB192146082230465B +:1017000001F028FE08343B46ECE70000F8B50E4631 +:10171000054614460021CE223046FFF733FE2B4605 +:1017200028220021304601F015FE7CB905F108039E +:1017300008222821304601F00DFE30242F462A7A57 +:101740007B1B934204D3E01DC008F8BD2824F5E7B5 +:1017500007F1090321460822304601F0FBFD083459 +:101760000137ECE7F7B5047F00910E460123102204 +:101770000021054601F0B2FCC4B9B31C0093092254 +:1017800023461021284601F0A9FC19243746728807 +:10179000BB1B9A4211D82B7FA88A0734E408BBB937 +:1017A000844294BF0020012003B0F0BDAB8ADB006F +:1017B000103BDB0873801024E8E73B1D00932146B3 +:1017C00000230822284601F089FC08340137DEE7AF +:1017D000201A18BF0120E7E730B5094D0A449142AD +:1017E0000DD011F8013B5840082340F30004013BA1 +:1017F0002C4013F0FF0384EA5000F6D1EFE730BD30 +:101800002083B8EDF7B5384A106851686B4603C3BA +:101810006A4636493648082303F012F80446002881 +:1018200033D10A25334A106851686B4603C36A46B0 +:1018300031492F48082303F003F80446002849D013 +:101840000369B3F5CC3F45D8B0F8661040F21642B4 +:1018500091423FD1294A024402F15C018B4239D3C3 +:101860005C3B234900209E1AFFF7B6FF324607462D +:1018700004F164010020FFF7AFFFA3689F4229D164 +:10188000E368984208BF002524E00369B3F5CC3F24 +:1018900027D8418B40F21642914220D1174A024488 +:1018A00002F110018B4218D3103B114900209D1A00 +:1018B000FFF792FF2A46064604F118010020FFF7C1 +:1018C0008BFFA3689E4202D1E368984201D00D25A8 +:1018D000A8E70025284603B0F0BD1025A2E70C2597 +:1018E000A0E70B259EE700BFB4480008DC97010085 +:1018F00000680008BD480008909701000898FFF7AD +:1019000010B5037C044613B9006802F081FF20463D +:1019100010BD00000023BFF35B8FC360BFF35B8F7C +:10192000BFF35B8F8360BFF35B8F7047BFF35B8F49 +:101930000068BFF35B8F704770B505460C30FFF74A +:10194000F5FF05F1080604463046FFF7EFFFA04219 +:1019500006D930466D68FFF7E9FF2544281A70BDA7 +:101960003046FFF7E3FF201AF9E7000070B505469F +:10197000406898B105F10800FFF7D8FF05F10C06A3 +:1019800004463046FFF7D2FF8442304694BF6D686C +:101990000025FFF7CBFF013C2C44201A70BD00004E +:1019A00038B50C460546FFF7C7FFA04210D305F136 +:1019B0000800FFF7BBFF04446868B4FBF0F100FBCC +:1019C0001144BFF35B8F0120AC60BFF35B8F38BD68 +:1019D0000020FCE72DE9F041144607460D46FFF7CD +:1019E000C5FF844228BF0446D4B1B84658F80C6BF2 +:1019F0004046FFF79BFF3044286040467E68FFF773 +:101A000095FF331A9C4203D86C600120BDE8F08139 +:101A10006B60A41B3B68AB602044E8600220F5E7E4 +:101A20002046F3E738B50C460546FFF79FFFA04276 +:101A300010D305F10C00FFF779FF04446868B4FB8C +:101A4000F0F100FB1144BFF35B8F0120EC60BFF3AA +:101A50005B8F38BD0020FCE72DE9FF4188466946D1 +:101A60000746FFF7B7FF6C4606B204EBC606002533 +:101A7000B44209D06268206808EB0501FFF770FCEA +:101A8000636808341D44F3E729463846FFF7CAFF68 +:101A9000284604B0BDE8F081F8B505460C300F4685 +:101AA000FFF744FF05F1080604463046FFF73EFF06 +:101AB000A042304688BF6C68FFF738FF201A3860B4 +:101AC00020B130462C68FFF731FF2044F8BD0000FC +:101AD00073B5144606460D46FFF72EFF844228BF15 +:101AE00004460190DCB101A93046FFF7D5FF019B08 +:101AF00033B93268C5E90233C5E9002401200CE09E +:101B00009C4238BF01942860019868608442F5D9EE +:101B10003368AB60241AEC60022002B070BD20462E +:101B2000FBE700002DE9FF410F466946FFF7D0FFB4 +:101B30006C4600B204EBC0050026AC4209D0D4F8D4 +:101B4000048054F8081BB8194246FFF709FC4644C4 +:101B5000F3E7304604B0BDE8F081000038B5054633 +:101B6000FFF7E0FF044601462846FFF719FF20462D +:101B700038BD0000302383F3118862B6704700003F +:101B8000002383F3118862B670470000012070477C +:101B90007047000010B41346026814680022A4467F +:101BA0005DF8044B6047000000F5805090F8590440 +:101BB0007047000000F5805090F852047047000014 +:101BC00000F5805090F9580470470000502070478D +:101BD00000F5805208B5FFF7CDFFD2F89834D2F85F +:101BE00094041844D2F890341844D2F87834184445 +:101BF000D2F888341844D2F884341844FFF7C0FF70 +:101C000008BD000038B5C26A936923F001039361EF +:101C1000044600F031FE0546E36A9B69DB0706D502 +:101C200000F02AFE431BFA2BF6D9002004E004F54D +:101C30008054012084F8520438BD00002DE9F04F93 +:101C40000C4600F5805185B01F4691F85234BDF81E +:101C50003890054690469BB1D1F874340133C1F8F1 +:101C6000743423689A0006D4237B082B0BD9627B3B +:101C70000AB10F2B07D9D1F878340133C1F8783481 +:101C80004FF0FF300FE0FFF775FFEB6AD3F8C42089 +:101C900012F4001A0AD0D1F87C340133C1F87C3434 +:101CA000FFF76EFF002005B0BDE8F08FD3F8C460E9 +:101CB00022686B6AC6F301464FF0480B002A1BFBF3 +:101CC000063BB4BF42F080429204CBF80020236868 +:101CD0005B0044BF42F00052CBF80020227B330669 +:101CE00043EA0243CBF80430607B720118B343F43B +:101CF0004013CBF80430D1F8A4340133C1F8A43434 +:101D0000AB1803F58353197B41F020011973207B35 +:101D1000039200F00DFE039A033080105FFA8AF3FD +:101D200083420AF1010A0DDA04EB83010BEB830312 +:101D300049689960F2E7AB1803F58353197B60F3A8 +:101D40004511E3E7EB6A0121B140C3F8CC10AB18B1 +:101D500003F58253C3E9048705EB461303F5825369 +:101D60002146183304F10C0051F804CB43F804CB9E +:101D70008142F9D1098819802A4441F26803284632 +:101D8000D65002F5805209F0030392F86C1043F02C +:101D9000100321F01F010B4382F86C30FFF7F0FEB7 +:101DA0004246CDF800903B46214600F087FD0120D9 +:101DB00079E7000013B500F580540191606CFFF7DE +:101DC000D5FD1F280AD90199606C2022FFF744FE37 +:101DD000A0F120035842584102B010BD0020FBE79B +:101DE00008B500F58050FFF7C5FE406CFFF792FD87 +:101DF000BDE80840FFF7C4BE002202608281426055 +:101E00008260704710B500220023C0E90023002340 +:101E1000044603810C30FFF7EFFF204610BD0000A1 +:101E20002DE9F047074688B007F5805468469A4682 +:101E30008846FFF79FFE9146FFF7E4FF606CFFF7CF +:101E40007BFD1F282CD9606C20226946FFF786FE97 +:101E5000202825D194F8523413B303AD444605AB82 +:101E60002E4603CE9E4220606160354604F1080490 +:101E7000F6D130682060B388A380DDE90023C9E98A +:101E80000023BDF80830AAF80030FFF779FE4A4673 +:101E900053464146384608B0BDE8F04700F0FCBC68 +:101EA000FFF76EFE002008B0BDE8F0872DE9F84F7F +:101EB00000230646C0E90133284B46F8303B00F5C5 +:101EC0008154054688463746103438462037FFF798 +:101ED00099FFA742F9D105F580544FF4805326634A +:101EE0000026C4E90D366764012305F5835705F51F +:101EF000A359E66384F8403084F84830103709F17C +:101F000010094FF0000A4FF0000B47E908ABA7F1AA +:101F10001800FFF771FF203747F8286C4F45F4D1C0 +:101F200084F85884A4F85A64A4F85C64A4F85E6445 +:101F300084F86064A4F86264A4F86464A4F8666435 +:101F400084F86864B8F1000F02D0054800F08EFCF8 +:101F5000044BEB622846BDE8F88F00BFE448000858 +:101F6000C84800080064004010B5044B19780446C6 +:101F70004A1C1A70FFF79AFF204610BDF53B00205F +:101F80002DE9F04300295FD03048314BB3FBF1F32A +:101F900081428CBF0A201120451EB3FBF0F700FBE5 +:101FA0001730ECB220B1022D2846F5D8002037E0DA +:101FB0007D1EB5F5806F33D2C4EBC40808F103036E +:101FC0004FEAE30EC3F3C703A4EB030C0EF10109C0 +:101FD0004FF47A705FFA8CF60EFB000E59FA8CFC07 +:101FE000BEFBFCFCBCF5617F1CDC1FFA8CF4581CAA +:101FF00056FA80F047431648B0FBF7F7B942D5D1FF +:10200000013BDBB20F2BD1D8711EC9B207294FF0AB +:10201000000005D810711480558053719171012012 +:10202000BDE8F08308F1FF334FEAE30CC3F3C703C5 +:10203000E41A0CF1010EE6B20CFB00005EFA84F427 +:10204000B0FBF4F4A4B2D2E70846E9E73F420F0040 +:1020500000366E010B4B10B54FF45472044600214C +:102060001846FFF78FF9084BA3614033E361D8337B +:102070002362F0336362E36A60610022C3F8C02028 +:1020800010BD00BF00A4004070A400402DE9F04F37 +:1020900000F58055994695F85834012B89B00446CF +:1020A0008A46904604D90027384609B0BDE8F08F2B +:1020B0008D4A52F8231009B942F823008B49C4F81D +:1020C0000CA00B7884F8109093B9FFF753FD884B60 +:1020D0009A6D42F000729A659A6B42F000729A63B0 +:1020E0009A6B22F000729A6301230B70FFF748FD90 +:1020F00095F8513473B903211520FFF73BFD01F02A +:1021000015FC0321162001F011FC012385F8513440 +:10211000FFF736FDFFF72EFDE26A936923F0100307 +:10212000936100F0A9FB0746E36A9E6916F0080672 +:1021300007D000F0A1FBC31BFA2BF5D9FFF720FD58 +:10214000B1E79A6942F001029A6100F095FB0746F7 +:10215000E36A9A69D00705D400F08EFBC31BFA2B03 +:10216000F6D9EBE79A6942F002029A61E36A002726 +:102170005F65FFF705FD686CFFF7CCFB04F5825B3C +:102180000BF1100B202200216846FFF7FBF802A894 +:10219000FFF732FE06976A460BEB06030DF1180EA9 +:1021A0009446BCE80300F44518605960624603F1A8 +:1021B0000803F5D1DCF80000186020369CF80420F4 +:1021C0001A71B6F5806FDDD1002304F5A25285F8AF +:1021D000503485F853341A3251462046FFF7D0FE6A +:1021E000074690B9E26A936923F00103936100F016 +:1021F00043FB0546E36A9B69D9077FF554AF00F0BE +:102200003BFB431BFA2BF5D94DE795F85F6495F836 +:102210005E24C5F86CA4360246EA426695F860244E +:10222000E36A1643B5F85C2446EA0246DE61B8F17B +:10223000000F29D004F5A352023241462046FFF791 +:102240009FFE90B9E26A936923F00103936100F065 +:1022500013FB0546E36A9B69DA077FF524AF00F0BC +:102260000BFB431BFA2BF5D91DE795F8683495F85D +:102270006714C5F870841B0143EA0123B5F86414A0 +:10228000E26A43EA0143D3602046FFF7E3FE0023FE +:1022900085F85934E36A6FF040421A65E36A154ADB +:1022A0005A65E36A44229A65E36A0722C3F8DC2090 +:1022B000E36A03229145DA653FF4F6AEE26A936978 +:1022C00023F00103936100F0D7FA0646E36A9B69A5 +:1022D000DB0705D500F0D0FA831BFA2BF6D9E2E62E +:1022E000012385F85234DFE6F03B0020F43B002068 +:1022F000001002409B0008002DE9F04F054689B010 +:1023000090469946002741F2680A00F58056EB6A2C +:10231000D3F8D430FB40D8074AD505EB47125244D6 +:102320004FEA471B1379190742D4D6F8803401339A +:10233000C6F8803413799A0648BFD6F8A83405EB5E +:102340000B0248BF0133524448BFC6F8A834137982 +:1023500043F008031371DB0722D596F85334FBB121 +:1023600005F58254183468465C44FFF74BFD03AB17 +:1023700004F1080C206861681A4603C208346445F9 +:102380001346F7D120681060A2889A800123ADF827 +:1023900008302B68CDE90089DB6B694628469847F1 +:1023A000D6F8543423B1D6F89C340133C6F89C34A3 +:1023B0000137202FABD109B0BDE8F08F2DE9F04FE8 +:1023C0008DB004460F4600F059FA82468946002F28 +:1023D00056D1E36AD3F89020920141BF04F58051B1 +:1023E000D1F894240132C1F89424D3F89020160730 +:1023F00003D100200DB0BDE8F08FD3F89050E6690E +:10240000C5F30125482303FB0566E8464046FFF770 +:10241000F3FC326851004ABF22F06043C2F38A43A2 +:1024200043F00043920048BF43F080430093736839 +:1024300013F400131FBF04F5805201238DF80D30F3 +:10244000D2F8AC340EBF8DF80D300133C2F8AC3485 +:10245000F38803F00F038DF80C304FF0000B9DF85C +:102460000C0000F065FA5FFA8BF3984220D9F2185D +:102470000CA90B44127A03F82C2C0BF1010BEEE79C +:10248000012FB6D1E36AD3F89820950141BF04F536 +:102490008051D1F894240132C1F89424D3F89820C3 +:1024A0001007A6D0D3F89850266AC5F30125A9E7EE +:1024B000EFB9E36AC3F8945004A8FFF7A3FC98E8C7 +:1024C0000F0007AD07C52B800023ADF81830236837 +:1024D0002046CDE904A9DB6B04A9984704F5805494 +:1024E00058B1D4F88C340133C4F88C3482E7012F0E +:1024F00004BFE36AC3F89C50DEE7D4F8903401339C +:10250000C4F89034012075E7F8B505460F4600F58C +:102510008054012639462846FFF750FF10B184F851 +:102520005364F7E7D4F8543423B1D4F89C3401331E +:10253000C4F89C34F8BD0000F0B5C36A1A6C12F4FC +:102540007F0F2BD000F580541B6CC4F8A03441F2EF +:102550006805002347194FF0010C00EB43122A4491 +:102560005E01117911F0020F15D0490713D4B95942 +:10257000C66AD6F8C8E00CFA01F111EA0E0F0AD0CB +:10258000C6F8D010117941F004011171D4F88824F3 +:102590000132C4F888240133202BDED1F0BD0000C5 +:1025A00010B5254C254B226802B338B31A6D1206BC +:1025B0000ED580221A6500F061F950EA01020B463F +:1025C00002D0013861F1000302462068FFF794FE53 +:1025D0001A4A136D1B032AD523684FF4002103F513 +:1025E00080531165012283F8592420E001221A65E5 +:1025F00008221A654FF480621A6510BD196DC8076C +:1026000002D4196D890705D50321196510460021EB +:10261000FFF77AFF094B1A6D100702D41A6DD10625 +:1026200005D518221A6520680121FFF76DFF206883 +:10263000BDE81040FFF780BFF03B00200064004081 +:1026400008B5FFF797FAFFF777FFBDE80840FFF7F7 +:1026500097BA0000C36AD3F8C40080F40010C0F336 +:102660004050704700F5805008B5FFF783FA406C82 +:10267000FFF762F9FFF784FA43090CBF012000203D +:1026800008BD000000F5805393F8592462B1C16A77 +:102690008A6922F001028A61D3F898240132C3F8D2 +:1026A0009824002283F85924704700002DE9F7434D +:1026B00000F5825198461031FFF75CFA002541F28F +:1026C000680E4FF0010900F5805C00EB451474447E +:1026D00023795E071CD4DB061AD5C36A8E69D3F84A +:1026E000C87009FA06F63E4212D04F6801970F688B +:1026F0009742019F77EB08070AD2C3F8D06023798D +:1027000043F004032371DCF884340133CCF88434BF +:102710000135202D01F12001D7D103B0BDE8F043F0 +:10272000FFF72EBAF8B51E46002313700F46054674 +:102730001446FFF797FF80F0010038701EB128465D +:10274000FFF788FF2070F8BD2DE9F04F85B099465E +:10275000DDE90EA30D4602931378019391F800B0C2 +:102760008046164600F08AF82B7804460F4613B9C7 +:102770003378002B42D022463B464046FFF796FF77 +:10278000FFF75EFFFFF77EFF4B4632462946FFF715 +:10279000C9FF2B7833B1BBF1000F03D0012005B086 +:1027A000BDE8F08F337813B1019B002BF6D108F50B +:1027B00080530393029B544577EB03031ED2039B84 +:1027C000D3F85404D0B10368AAEB0401DB6889B2E2 +:1027D00098474B46324629464046FFF7A3FF2B78E1 +:1027E00013B1BBF1000FD9D1337813B1019B002B8A +:1027F000D4D100F043F804460F46DBE70020CEE7D3 +:1028000008B50020FFF7CCFEBDE8084001F050B845 +:1028100008B50120FFF7C4FEBDE8084001F048B844 +:1028200000B59BB0EFF3098168226846FEF798FD7A +:10283000EFF30583014B9B6BFEE700BF00ED00E06B +:1028400008B5FFF7EDFF000000B59BB0EFF309817D +:1028500068226846FEF784FDEFF30583014B5B6B4E +:10286000FEE700BF00ED00E0FEE700000FB408B592 +:10287000029801F01BF9FEE701F00EBC01F0E6BB87 +:1028800013B56C4684E80600031D94E8030083E852 +:102890000500012002B010BD73B58568019155B1E6 +:1028A0001B885B0707D4D0E900369B6B9847019AD9 +:1028B000C1B23046A847012002B070BDF0B58668AD +:1028C00089B005460C465EB1BDF838305B070AD4C6 +:1028D000D0E900379B6B98472246C1B23846B047D3 +:1028E000012009B0F0BD00220023CDE90023002320 +:1028F000ADF808300A4603AB01F1080610685168CC +:102900001C4603C40832B2422346F7D11068206047 +:102910009288A280FFF7B2FF0423ADF808302B683D +:10292000CDE90001DB6B694628469847D8E70000EF +:10293000082817D909280CD00A280CD00B280CD04D +:102940000C280CD00D280CD00E2814BF40203020AD +:1029500070470C20704710207047142070471820D3 +:1029600070472020704700002DE9F041456A15B9F5 +:102970004162BDE8F0814B6823F06047C3F38A46AB +:102980004FEAD37EC3F3807816EA230638BF3E466B +:10299000AC462B465A68BEEBD27F22F060440AD088 +:1029A000002A18DAA40CB44217D19D420FD10D6051 +:1029B000DEE71346EEE7A74207D102F08044C2F3F8 +:1029C000807242450BD054B1EFE708D2EDE7CCF866 +:1029D00000100B60CDE7B44201D0B442E5D81A68CC +:1029E0009C46002AE5D11960C3E700002DE9F047B5 +:1029F000089D01F007044FEAD508224405F00705B9 +:102A000000EBD1004FF47F49944201D1BDE8F0873B +:102A100004F0070705F0070A57453E4638BF5646FB +:102A2000C6F10806111B8E4228BF0E46E10808EBCE +:102A3000D50E415C13F80EC0B94029FA06F721FA09 +:102A40000AF1FFB28CEA010147FA0AF739408CEA31 +:102A5000010C03F80EC034443544D5E780EA012068 +:102A6000082341F2210201B24000002980B203F1A3 +:102A7000FF33B8BF504013F0FF03F4D1704700009C +:102A800038B50C468D18A54200D138BD14F8011B8D +:102A9000FFF7E4FFF7E7000042684AB113684360BC +:102AA0004389818901339BB29942438138BF838135 +:102AB0001046704770B588B0202204460D4668461F +:102AC0000021FEF75FFC20460495FFF7E5FF024674 +:102AD00058B16B46054608AE1C4603CCB44228608C +:102AE0006960234605F10805F6D1104608B070BDAF +:102AF000082817D909280CD00A280CD00B280CD08C +:102B00000C280CD00D280CD00E2814BF40203020EB +:102B100070470C2070471020704714207047182011 +:102B20007047202070470000082817D90C280CD9BE +:102B300010280CD914280CD918280CD920280CD905 +:102B400030288CBF0F200E207047092070470A20C4 +:102B500070470B2070470C2070470D207047000015 +:102B60002DE9F843078C072F04461ED9D0E90298B7 +:102B700000254FF6FF73C5F12006A5F1200029FAC4 +:102B800005F108FA06F628FA00F031430143C9B20C +:102B90001846FFF763FF0835402D0346EBD1E16986 +:102BA0003A46BDE8F843FFF76BBF4FF6FF70BDE84C +:102BB000F883000010B54B6823B9CA8A63F3090291 +:102BC000CA8210BD04691A681C600361C38A013B94 +:102BD000C3824A60EFE700002DE9F84F1D46CB8A1B +:102BE0000F46C3F309010529814692460B4630D0B2 +:102BF0000020AAB207F11A049EB2042E1FFA80F830 +:102C00000FD8904503F1010306D3FB8A0A4462F30F +:102C10000903FB8201201AE01AF80060E654013033 +:102C2000EAE79045F1D2A1F1050B1C237C68BBFBC0 +:102C3000F3F203FB12BB1FFA8BF6002C45D148467A +:102C4000FFF72AFF044638B978606FF00200BDE84C +:102C5000F88F4FF00008E6E7002606607860ADB216 +:102C60004FF0000B454510D90AEB0803221D13F85D +:102C7000011B9155B1B208F101081B291FFA88F810 +:102C80002BD0454506F10106F1D8FB8AC3F30902B2 +:102C9000154465F30903BCE7013292B21C46236870 +:102CA000002BF9D16B1F0B441C21B3FBF1F3013353 +:102CB0009BB29A42D3D2BBF1000FD0D14846FFF766 +:102CC000EBFE20B9C4F800B0BFE70122E7E7C0F887 +:102CD00000B05E4620600446C1E74545D5D9484668 +:102CE000FFF7DAFE08B92060AFE7C0F800B00026B1 +:102CF00020600446B6E700002DE9F04F2DED028B71 +:102D00001C4683B05B69019207468846002B00F0A1 +:102D10009A80238C2BB1E269002A00F09480072B63 +:102D200035D807F10C00FFF7B7FE054638B96FF04C +:102D30000205284603B0BDEC028BBDE8F08F1422DB +:102D40000021FEF71FFB228CE16905F10800FEF768 +:102D500007FB208C013080B2FFF7E6FEFFF7C8FECC +:102D6000013880B22084013028746369228C1B787A +:102D70002A4403F01F0363F03F0348F0004113723D +:102D8000384669602946FFF7EFFD0125D1E700F1DC +:102D90000C034FF0000908EE103A4FF0800A4E463F +:102DA0004D4618EE100AFFF777FE83460028BED086 +:102DB00014220021FEF7E6FA002E3AD1019BABF86F +:102DC000083002220BF1080E1FFA82FC0CF1010000 +:102DD000BCF1060F218C80B201D88E422BD3FFF7B5 +:102DE000A3FEFFF785FE62691278013802F01F0228 +:102DF0008E4208BF4FF0400A42EA49121BFA80F1A6 +:102E00004AEA020A013048F0004281F808A08BF833 +:102E10001000CBF8042059463846FFF7A5FD238C57 +:102E20000135B3422DB289F001094FF0000AB8D143 +:102E30007FE70022C6E7E169895D0EF802100136DE +:102E4000B6B20132C0E76FF0010572E7F8B515467A +:102E50000E463022002104461F46FEF793FA069BD9 +:102E60006360B5F5001F079BA76034BF6A094FF682 +:102E7000FF72A36297B2E66104F1100000239A4248 +:102E800006D800230360A782E3822383E360F8BDB2 +:102E90000660013330462036F1E7000003781BB9A5 +:102EA0004BB2002BC8BF017070470000007870471C +:102EB000F8B50C46C969074611B9238C002B37D1E8 +:102EC000257E1F2D34D8387828BB228C072A2CD891 +:102ED000268A36F003032BD14FF6FF70FFF7D0FDA3 +:102EE00020F001003102400441EA0561400C41EA52 +:102EF00040254FF6FF72234629463846FFF7FCFE71 +:102F0000002807DD626913780133DBB21F2B88BF0D +:102F100000231370F8BD218A2D0645EA01250543DB +:102F20002046FFF71DFE0246E5E76FF00300F1E7DC +:102F30006FF00100EEE7000070B58AB00446164657 +:102F40000021282268461D46FEF71CFABDF83830DD +:102F5000ADF810300F9B05939DF840308DF8183078 +:102F6000119B07936946BDF84830ADF820302046E4 +:102F7000CDE90265FFF79CFF0AB070BD2DE9F04175 +:102F8000D36905460C4616460BB9138C5BBB377EDE +:102F90001F2F28D895F80080B8F1000F26D03046B2 +:102FA000FFF7DEFD3378210241EAC33141EA08012F +:102FB000338A41EA076141EA03410246334641F060 +:102FC00080012846FFF798FE00280ADD3378012BA0 +:102FD00007D1726913780133DBB21F2B88BF00233E +:102FE0001370BDE8F0816FF00100FAE76FF00300A5 +:102FF000F7E70000F0B58BB004460D4617460021F8 +:10300000282268461E46FEF7BDF99DF84C305A1E30 +:10301000534253418DF800309DF84030ADF81030E8 +:10302000119B05939DF848308DF81830149B079339 +:103030006A46BDF85430ADF8203029462046CDE927 +:103040000276FFF79BFF0BB0F0BD0000406A00B1B5 +:1030500004307047436A1A68426202691A60036169 +:10306000C38A013BC38270472DE9F041D0F820802C +:10307000194E14461D464146002709B9BDE8F081A6 +:10308000D1E90223A21A65EB0303964277EB03030F +:103090001ED2036A8B420DD1FFF78CFD036A1B68B9 +:1030A000036203690B60C38A0161016A013BC38249 +:1030B0008846E2E7FFF77EFD0B68C8F80030036939 +:1030C0000B60C38A0161013BC382D8F80010D4E7CA +:1030D00088460968D1E700BF80841E002DE9F04FC3 +:1030E0008BB00D46DDF8509014469B468046002874 +:1030F00000F01981B9F1000F00F01581531E3F2B2C +:1031000000F21181012A03D1BBF1000F40F00B81C5 +:103110000023CDE90833B8F81430B5EBC30F4FEAFC +:10312000C30703D300200BB0BDE8F08F2B199F42DB +:10313000D8F80C303ABF7F1BFFB227461BB9D8F82E +:103140001030002B7AD0272D4ED8C5F12806B74273 +:103150004FF000032CBFF6B23E4600932946D8F844 +:10316000080008AB3246FFF741FCA7EB060A3544DE +:103170005FFA8AFAB8F8143003F10053053BDB001C +:103180000493D8F80C3003932821039B13B1BAF1B0 +:10319000000F2CD1D8F8100040B1BAF1000F05D0C3 +:1031A000009608AB5246691AFFF720FC38B2002F90 +:1031B000B8D066070AD00AAB03EBD401624211F81B +:1031C000083C02F00702134101F8083C082C3CD9E6 +:1031D000102C40F2B580202C40F2B780BBF1000FDC +:1031E00000F09C80082334E0BA460026C2E7049B26 +:1031F000E02B28BFE02306930B44AB42059314D980 +:103200005A1B03980096924534BF5246D2B2691AAF +:1032100008AB04300792FFF7E9FB079A1644AAEBC4 +:10322000020A1544F6B25FFA8AFA049B069A0599D7 +:103230009B1A0493039B1B680393A6E70093D8F89B +:10324000080008AB3A462946AEE7BBF1000F13D0A1 +:103250000123B4EBC30F6CD0082C12D89DF820309A +:10326000621E23FA02F2D50706D54FF0FF3202FAAA +:1032700004F423438DF820309DF8203089F8003085 +:1032800051E7102C12D8BDF82030621E23FA02F24A +:10329000D10706D54FF0FF3202FA04F42343ADF80C +:1032A0002030BDF82030A9F800303CE7202C0FD8A2 +:1032B0000899631E21FA03F3DA0705D54FF0FF32B0 +:1032C00002FA04F40C430894089BC9F800302AE77A +:1032D000402C2BD0DDE90865611EC4F12102A4F168 +:1032E000210326FA01F105FA02F225FA03F311434C +:1032F0001943CB0712D50122A4F12003C4F1200108 +:1033000002FA03F322FA01F1A240524243EA010316 +:1033100063EB430332432B43CDE90823DDE9082364 +:10332000C9E90023FFE66FF00100FCE66FF008003A +:10333000F9E6082CA0D9102CB3D9202CEED8C3E77D +:10334000BBF1000FADD0022383E7BBF1000FBBD070 +:1033500004237EE730B5012A144638BF0124402CEF +:1033600085B028BF40240025012ACDE9025518D890 +:103370001B788DF8083063070AD004AB03EBD40543 +:10338000624215F8083C02F00702934005F8083C39 +:10339000009103462246002102A8FFF727FB05B053 +:1033A00030BD082AE4D9102A03D81B88ADF80830AC +:1033B000E1E7202A8DBFD3E900231B680293CDE902 +:1033C0000223D8E710B5CB681BB98B600B618B82E9 +:1033D00010BD04691A681C600361C38A013BC38283 +:1033E000CA60F0E703064CBFC0F3C030022070474C +:1033F00008B50246FFF7F6FF022806D15306C2F3CE +:103400000F2001D100F0030008BDC2F30740FBE725 +:103410002DE9F04F93B0CDE903230A680446104626 +:10342000FFF7E0FF022814BFC2F306260026002A99 +:103430000D46824680F2F28112F0C04940F0EE81E2 +:10344000097B002900F0EA81022803D02378B342E7 +:1034500040F0E781C2F304630693104602F07F0355 +:103460000593FFF7C5FF059B29444FEA834848EAC7 +:103470000A4848EA4668CE7800230022CDE90823AE +:10348000F309834648EA0008029367D0059B00933E +:1034900002466768534608A92046B847002800F04E +:1034A000C381276A4FB9414604F10C00FFF702FBC4 +:1034B000074690B96FF0020054E03B6998450DD083 +:1034C0003F68002FF9D1414604F10C00FFF7F2FAF2 +:1034D00007460028EED0236A3B60276297F817C0A2 +:1034E00006F01F08CCF3840CACEB08001FFA80FE3A +:1034F0000028B8BF0EF12000A8EB0C031FFA83FED2 +:10350000D7E90221B8BF00B2002B0793BEBF0EF16E +:1035100020031BB2079352EA010338D0039BDFF864 +:1035200024E39A1A049B4FF0000C63EB01019645CB +:103530007CEB01032BD36B7B97F81AE0734519D111 +:10354000029B002B78D0012821DC7868F8B9DFF8DD +:10355000F0C2944570EB010316D337E0276A27B910 +:103560006FF00C0013B0BDE8F08F3B699845B5D003 +:103570003F68F4E7B24890427CEB010301D300209E +:10358000F0E7029B002BFAD0079B0F2B17DCFA7D8C +:10359000B30002F0030203F07C031343FB753946CA +:1035A0002046FFF707FB6B7BBB76029B3BB9FB7D9D +:1035B000C3F38402013262F38603FB75D0E76A7BB2 +:1035C000BB7E9A42DBD1029B002B35D0B309022B84 +:1035D00032D0039BBB60049BFB60142200210DA82A +:1035E000FDF7D0FE039B0A93049B0B932B1D0C93BA +:1035F0002B7BADF83EB0013BDBB2ADF83C30069B17 +:103600008DF84230059B8DF8433094F82C308DF8BE +:1036100040A083F001038DF844308DF84180A36809 +:103620000AA920469847FB7DC3F38403013303F0C6 +:103630001F039B02FB82A2E7FB7DC6F34012B2EBA5 +:10364000D31F40F0F480C3F38403434540F0F2807D +:10365000029A2B7BB609002A4DD0F2075DD4032BCA +:1036600040F2EB80039BBB60049BFB602B7BAE1D99 +:10367000033BDBB23246394604F10C00FFF7ACFAEB +:1036800000280CDA39462046FFF794FAFB7DC3F395 +:103690008403013303F01F039B02FB820AE7DDE989 +:1036A0000884AB883B834FF6FF73C9F12000A9F172 +:1036B000200228FA09F104FA00F0014324FA02F288 +:1036C00011431846C9B2FFF7C9F909F10809B9F160 +:1036D000400F0346E9D1B8822A7B033AD2B2314681 +:1036E000FFF7CEF9FB7DB882DA43C2F3C01262F372 +:1036F000C713FB7543E786B92E1D013BDBB232468B +:10370000394604F10C00FFF767FA0028BADB2A7B80 +:10371000B88A013AD2B23146E2E7F98AC1F3090127 +:10372000013B0429DAB25BD8281D002307F11B06F0 +:103730009A4208D910F801CB06F801C001310133D3 +:103740000529DBB2F4D103990A9104990B919342B4 +:1037500007F11B010C9138BF043379680D9134BF18 +:1037600055FA83F300230E93FB8AADF83EB0C3F302 +:1037700009031A44069B8DF84230059B8DF84330AF +:1037800094F82C30ADF83C2083F001038DF84430E0 +:1037900000238DF840A08DF841807B602A7BB88A99 +:1037A000013A291DFFF76CF93B8BB882834203D1A4 +:1037B000A3680AA92046984720460AA9FFF702FEF7 +:1037C000FB7DBA8AC3F38403013303F01F039B021A +:1037D000FB823B8B9A420CBF00206FF01000C1E6C9 +:1037E0007B68002BAFD0052001E01C3033461E68FB +:1037F000002EFAD1091A081D2E1D184401EB090CE0 +:10380000BCF11B0F5FFA89F39DD89A429BD916F839 +:10381000013B00F8013B09F10109EFE76FF00900F6 +:10382000A0E66FF00A009DE66FF00B009AE66FF0DD +:103830000D0097E66FF00E0094E66FF00F0091E632 +:1038400040420F0080841E00EFF3098305494A6B54 +:1038500022F001024A63683383F30988002383F36B +:103860001188704700EF00E0302080F3118862B6C5 +:103870000C4B0D4AD96821F4E0610904090C0A4394 +:10388000DA60D3F8FC20094942F08072C3F8FC20CA +:103890000A6842F001020A602022DA7783F82200E7 +:1038A000704700BF00ED00E00003FA05001000E0E3 +:1038B00010B5302383F311880E4B5B6813F400635B +:1038C00014D0F1EE103AEFF30984683C4FF08073A6 +:1038D000E361094BDB6B236684F3098800F0A4F8ED +:1038E00010B1064BA36110BD054BFBE783F31188B4 +:1038F000F9E700BF00ED00E000EF00E0430600083C +:10390000460600084FF0E023002258684FF0FF31D0 +:10391000930003F1604303F5614301329042C3F821 +:103920008010C3F88011F3D27047000000F16043AB +:1039300003F561430901C9B283F80013012200F0C5 +:103940001F039A4043099B0003F1604303F5614361 +:10395000C3F880211A6070470023037582680369E9 +:103960001B6899689142FBD25A68036042601060FC +:103970005860704700230375826803691B68996863 +:103980009142FBD85A6803604260106058607047EB +:1039900008B50846302383F311880B7D032B05D02F +:1039A000042B0DD02BB983F3118808BD8B6900223D +:1039B0001A604FF0FF338361FFF7CEFF0023F2E779 +:1039C000D1E9003213605A60F3E70000FFF7C4BF8B +:1039D000054BD9680875186802681A60536001229F +:1039E0000275D860FCF718BE003C002030B50C4BC7 +:1039F000DD684B1C87B004460FD02B46094A684649 +:103A000000F050F92046FFF7E3FF009B13B1684632 +:103A100000F052F9A86907B030BDFFF7D9FFF9E708 +:103A2000003C002091390008044B1A68DB6890685C +:103A30009B68984294BF002001207047003C002002 +:103A4000084B10B51C68D86822681A6053600122C0 +:103A50002275DC60FFF78EFF01462046BDE810406E +:103A6000FCF7DABD003C0020044B1A68DB68926862 +:103A70009B689A4201D9FFF7E3BF7047003C0020E2 +:103A800038B5074C074908480123002523706560B5 +:103A900000F000FC0223237085F3118838BD00BFBD +:103AA000283E002028490008003C002008B572B6D6 +:103AB000044B186500F0B6FA00F06EFB024B0322CF +:103AC0001A70FEE7003C0020283E002000F02AB9D2 +:103AD000EFF3118020B9EFF30583302282F31188D0 +:103AE0007047000010B530B9EFF30584C4F3080443 +:103AF00014B180F3118810BDFFF7B6FF84F311886D +:103B0000F9E700008B60022308618B82084670474A +:103B10008368A3F1840243F8142C026943F8442C0F +:103B2000426943F8402C094A43F8242CC26843F800 +:103B3000182C022203F80C2C002203F80B2C044A48 +:103B400043F8102CA3F12000704700BF3106000895 +:103B5000003C002008B5FFF7DBFFBDE80840FFF799 +:103B600035BF0000024BDB6898610F20FFF730BFC4 +:103B7000003C0020302383F31188FFF7F3BF0000DF +:103B800008B50146302383F311880820FFF72EFF84 +:103B9000002383F3118808BD10B503689C68A24216 +:103BA0000CD85C688A600B604C6021605960996831 +:103BB0008A1A9A604FF0FF33836010BD1B68121B96 +:103BC000ECE700000A2938BF0A2170B504460D460B +:103BD0000A26601900F058FB00F044FB041BA542C4 +:103BE00003D8751C2E460446F3E70A2E04D9BDE817 +:103BF0007040012000F08EBB70BD0000F8B5144B82 +:103C00000D46D96103F1100141600A2A19698260E9 +:103C100038BF0A22016048601861A818144600F0F5 +:103C200025FB0A2700F01EFB431BA342064606D3D2 +:103C30007C1C281900F028FB27463546F2E70A2F9E +:103C400004D9BDE8F840012000F064BBF8BD00BF16 +:103C5000003C0020F8B506460D4600F003FB0F4A75 +:103C6000134653F8107F9F4206D12A46014630463C +:103C7000BDE8F840FFF7C2BFD169BB68441A2C19F0 +:103C800028BF2C46A34202D92946FFF79BFF2246B4 +:103C900031460348BDE8F840FFF77EBF003C0020F6 +:103CA000103C002010B4C0E9032300235DF8044B4E +:103CB0004361FFF7CFBF000010B5194C236998424C +:103CC0000DD0D0E90032816813605A609A680A44C6 +:103CD0009A60002303604FF0FF33A36110BD2346B9 +:103CE000026843F8102F53600022026022699A4252 +:103CF00003D1BDE8104000F0C1BA936881680B445D +:103D0000936000F0AFFA2269E1699268441AA24216 +:103D1000E4D91144BDE81040091AFFF753BF00BFB2 +:103D2000003C00202DE9F047DFF8BC8008F11007C7 +:103D30002C4ED8F8105000F095FAD8F81C40AA681C +:103D4000031B9A423ED81444D5E900324FF00009D3 +:103D5000C8F81C4013605A60C5F80090D8F81030BD +:103D6000B34201D100F08AFA89F31188D5E9033111 +:103D700028469847302383F311886B69002BD8D0ED +:103D800000F070FA6A69A0EB04094A4582460DD238 +:103D9000022000F0BFFA0022D8F81030B34208D158 +:103DA00051462846BDE8F047FFF728BF121A2244C3 +:103DB000F2E712EB090938BF4A4629463846FFF7B1 +:103DC000EBFEB5E7D8F81030B34208D01444211AFE +:103DD000C8F81C00A960BDE8F047FFF7F3BEBDE8D6 +:103DE000F08700BF103C0020003C002000207047FE +:103DF000FEE70000704700004FF0FF307047000002 +:103E0000BFF34F8F024A1369DB03FCD4704700BF36 +:103E10000020024008B5094B1B7873B9FFF7F0FF8B +:103E2000074B5A69002ABFBF064A9A6002F18832DE +:103E30009A601A6822F480621A6008BD403E002031 +:103E4000002002402301674508B50B4B1B7893B94E +:103E5000FFF7D6FF094B5A6942F000425A611A68CF +:103E600042F480521A601A6822F480521A601A686A +:103E700042F480621A6008BD403E002000200240EB +:103E80003F289ABF00F58030C00200207047000034 +:103E90004FF4006070470000402070473F2808B58D +:103EA0000BD8FFF7EDFF00F500630268013204D183 +:103EB00004308342F9D1012008BD0020FCE7000056 +:103EC0003F2810B504461FD8FFF79AFFFFF7A2FF5F +:103ED0000E4BF3221A6102225A615A6942EAC00269 +:103EE0005A615A6942F480325A61FFF789FF4FF4F0 +:103EF0000061FFF7C5FF00F04BF9FFF7A5FF204673 +:103F0000BDE81040FFF7CABF002010BD00200240EE +:103F10002DE9F84340EA020313F00703144606D0E4 +:103F2000304B40F231321A600020BDE8F88385182A +:103F30002D4A95420CD92B4A40F236311160F3E7F5 +:103F4000031D1B684A68934208D1083C08300831B9 +:103F5000072C14D902680B689A42F1D0FFF75AFF78 +:103F6000FFF74EFF214E08314FF001084FF00009D6 +:103F7000012CA1F1080706D8FFF766FF01E0002C2D +:103F8000ECD10120D1E7C6F81480054651F8083C71 +:103F900045F8043B51F8043C4360FFF731FF3369B7 +:103FA00043F001033361C6F81490026851F8083CED +:103FB0009A420CD00B4B40F25E321A600C4B1860E8 +:103FC0000C4B1C600C4B1F60FFF73EFFACE72D68ED +:103FD00051F8043C9D4201F10801EBD1083C083046 +:103FE000C6E700BF3C3E002000000208002002405F +:103FF000303E0020383E0020343E0020084908B5FD +:104000000B7828B11BB9FFF705FF01230B7008BD22 +:10401000002BFCD0BDE808400870FFF715BF00BFBB +:10402000403E002008B54FF4B0414FF0005000F082 +:10403000B1F8BDE808404FF420514FF0805000F037 +:10404000A9B80000084600F0E3BB000070B582B0DC +:10405000FFF73EFD0E4E054600F004F9326890422F +:1040600037BF0C4A0B49516814682EBFD1E9004193 +:10407000013151600419034641F1000128460191C4 +:104080003360FFF72FFD0199204602B070BD00BFDD +:10409000443E0020483E002070B582B0FFF718FD76 +:1040A000104E054600F0DEF83268904237BF0E4AE7 +:1040B0000D49516814682EBFD1E9004101315160AA +:1040C000041941F100010346284601913360FFF7CE +:1040D00009FD01994FF47A7200232046FCF788F815 +:1040E00002B070BD443E0020483E00200244D2B2DF +:1040F000904200D17047431C800000F1804000F5E1 +:104100001450006841F8040BD8B2F1E7124B10B517 +:10411000D3F89040240409D4D3F89040C3F89040D9 +:10412000D3F8904044F40044C3F890400B4C23680B +:10413000024443F480732360D2B2904200D110BD98 +:10414000431C800000F1804000F5145051F8044BEE +:104150000460D8B2F1E700BF0010024000700040D8 +:1041600007B5012201A90020FFF7C0FF019803B0A5 +:104170005DF804FB13B50446FFF7F2FFA04205D03B +:10418000012201A900200194FFF7C0FF02B010BD79 +:10419000704700007047000070470000074B45F271 +:1041A00055521A6002225A6040F6FF729A604CF62D +:1041B000CC421A60024B01221A7070470030004056 +:1041C000543E0020034B1B781BB1034B4AF6AA2236 +:1041D0001A607047543E002000300040054B1A68BA +:1041E00032B902F1804202F50432D2F894201A600A +:1041F000704700BF503E0020024B4FF40002C3F84E +:10420000942070470010024008B5FFF7E7FF024B0B +:104210001868C0F3407008BD503E00207047000091 +:10422000FEE700000A4B0B480B4A90420BD30B4BA6 +:10423000DA1C121AC11E22F003028B4238BF002280 +:104240000021FDF79FB853F8041B40F8041BECE76E +:104250008C4A0008D83E0020D83E0020D83E0020DE +:1042600000F0C2B84FF08043586A70474FF0804367 +:10427000002258631A610222DA6070474FF08043CF +:104280000022DA60704700004FF0804358637047A7 +:10429000FEE7000070B51B4B01630025044686B0A5 +:1042A000586085620E46FFF7DFFA04F11003C4E997 +:1042B00004334FF0FF33C4E90635C4E90044A56078 +:1042C000E562FFF7CFFF2B460246C4E9082304F15D +:1042D00034010D4A256580232046FFF713FC012396 +:1042E000E0600A4A0375009272680192B268CDE9F3 +:1042F0000223074B6846CDE90435FFF72BFC06B0D7 +:1043000070BD00BF283E002034490008394900082C +:1043100091420008024AD36A1843D062704700BF36 +:10432000003C00204B6843608B688360CB68C360AF +:104330000B6943614B6903628B6943620B680360DD +:104340007047000008B5204BDA6A42F07F02DA625B +:10435000DA6A22F07F02DA62DA6ADA6C42F07F020D +:10436000DA64DA6E42F07F02DA66184ADB6E1146D2 +:104370004FF09040FFF7D6FF02F11C0100F580607E +:10438000FFF7D0FF02F1380100F58060FFF7CAFFA8 +:1043900002F1540100F58060FFF7C4FF02F17001E3 +:1043A00000F58060FFF7BEFF02F18C0100F5806030 +:1043B000FFF7B8FF02F1A80100F58060FFF7B2FF38 +:1043C000BDE8084000F050B8001002404049000825 +:1043D00008B500F0EDF9FFF753FBBDE80840FFF723 +:1043E000FDBE0000704700000F4B9A6D42F00102C5 +:1043F0009A659A6F42F001029A670C4A9B6F936824 +:1044000043F0010393604FF08043A7229A624FF07C +:10441000FF32DA6200229A615A63DA605A6001223E +:104420005A611A60704700BF00100240002004E08B +:104430004FF0804208B51169D3680B40D9B2C94327 +:104440009B07116107D5302383F31188FFF73EFBEB +:10445000002383F3118808BD08B5FFF753FABDE8C0 +:10446000084000F081B900004E4B4FF0FF319A6ACE +:1044700099629A6A00229A62986AD86A60F07F000C +:10448000D862D86A00F07F00D862D86A186B1963C6 +:10449000186B1A63186B986B9963986B9A63986B97 +:1044A000D86BD963D86BDA63D86B186C1964196C44 +:1044B0001A64196C196E41F001011966D3F8801065 +:1044C00021F00101C3F88010D3F88010996D41F0FC +:1044D00080519965996F21F080519967996F3249A0 +:1044E0004FF400408860CA600A624A628A62CA6207 +:1044F0000A634A638A63CA630A644A648A64CA6450 +:104500000A654A654A604FF48072C1F880204FF412 +:1045100040720A604A6912F48062FBD1D3F89010AD +:1045200011F4407F1EBF4FF48031C3F89010C3F8E0 +:104530009020D3F8982042F00102C3F89820D3F8D5 +:1045400098209207FBD51A6842F480321A601A68E4 +:104550009003FCD5D3F8902022F00322C3F89020DA +:10456000124ADA601A6842F080721A601A68910181 +:10457000FCD50F490F4800229A60C3F888100E49F5 +:10458000C3F89C20016002684A401207FBD19A6878 +:1045900042F003029A609A6802F00C020C2AFAD1E7 +:1045A000704700BF0010024000700040232A6101E4 +:1045B000550100500020024004070400074A08B5D6 +:1045C000536903F00103536123B1054A13680BB12A +:1045D00050689847BDE80840FFF76AB900040140F9 +:1045E000583E0020074A08B5536903F0020353619F +:1045F00023B1054A93680BB1D0689847BDE80840DD +:10460000FFF756B900040140583E0020074A08B59C +:10461000536903F00403536123B1054A13690BB1D5 +:1046200050699847BDE80840FFF742B900040140CF +:10463000583E0020074A08B5536903F00803536148 +:1046400023B1054A93690BB1D0699847BDE808408A +:10465000FFF72EB900040140583E0020074A08B574 +:10466000536903F01003536123B1054A136A0BB178 +:10467000506A9847BDE80840FFF71AB900040140A6 +:10468000583E0020164B10B55C6904F478725A61EC +:10469000A30604D5134A936A0BB1D06A9847600603 +:1046A00004D5104A136B0BB1506B9847210604D503 +:1046B0000C4A936B0BB1D06B9847E20504D5094ABD +:1046C000136C0BB1506C9847A30504D5054A936C45 +:1046D0000BB1D06C9847BDE81040FFF7E9B800BFB8 +:1046E00000040140583E0020194B10B55C6904F4E9 +:1046F0007C425A61620504D5164A136D0BB1506DA8 +:104700009847230504D5134A936D0BB1D06D984794 +:10471000E00404D50F4A136E0BB1506E9847A10404 +:1047200004D50C4A936E0BB1D06E9847620404D541 +:10473000084A136F0BB1506F9847230404D5054AFC +:10474000936F0BB1D06F9847BDE81040FFF7B0B83A +:1047500000040140583E002008B5FFF769FEBDE89F +:104760000840FFF7A5B80000062108B50846FFF786 +:10477000DDF806210720FFF7D9F806210820FFF70A +:10478000D5F806210920FFF7D1F806210A20FFF706 +:10479000CDF806211720FFF7C9F806212820FFF7DA +:1047A000C5F8BDE8084007211C20FFF7BFB800008E +:1047B00008B5FFF751FE00F007F8FFF713FEBDE85C +:1047C0000840FFF74DBD00000023054A194601339C +:1047D000102BC2E9001102F10802F8D1704700BFA6 +:1047E000583E00200B460146184600F003B8000072 +:1047F00000F00EB810B5054C13462CB10A46014620 +:104800000220AFF3008010BD2046FCE7000000004E +:10481000024B01461868FFF715BC00BF18110020B5 +:1048200010B501390244904201D1002005E003781F +:1048300011F8014FA34201D0181B10BD0130F2E75F +:104840002DE9F041A3B1C91A17780144044603F1D8 +:10485000FF3C8C42204601D9002009E00578BD428A +:1048600004F10104F5D10CEB0405D618A54201D1E1 +:10487000BDE8F08115F8018D16F801EDF045F5D091 +:10488000E7E70000034611F8012B03F8012B002A8B +:10489000F9D170476F72672E6172647570696C6FC1 +:1048A000742E48697465632D41697273706565641F +:1048B0000000000040A2E4F1646891060041A3E515 +:1048C000F2656992070000004261642043414E494D +:1048D0006661636520696E6465782E0000000000E3 +:1048E000000000008D200008951B000849270008E3 +:1048F0008D1B00083D1C0008211E0008051C000837 +:10490000CD1B0008D11B0008A91B0008911B000843 +:10491000E11D0008B51B000881280008C11B000824 +:10492000B51D00086330000024490008583C0020F1 +:10493000283E00206D61696E0069646C65000000AE +:104940000010802A00000000AAAAAAAA00000024E1 +:10495000BFFF0000000000000090090000000001FF +:1049600000000000AAAAAAAA00000001FFFF0000A0 +:104970000000000000000000000000000000000037 +:10498000AAAAAAAA00000000FFFF00000000000081 +:10499000000000000000000000000000AAAAAAAA6F +:1049A00000000000FFFF0000000000000000000009 +:1049B0000000000000000000AAAAAAAA000000004F +:1049C000FFFF0000000000000000000000000000E9 +:1049D00000000000AAAAAAAA00000000FFFF000031 +:1049E00000000000000000000000000000000000C7 +:1049F000AAAAAAAA00000000FFFF00000000000011 +:104A0000000000001CB8FF7F010000000000000053 +:104A100016040000000000000098010000000000E3 +:104A2000FE2A0100D20400001C110020000000003A +:104A30000000000000000000000000000000000076 +:104A40000000000000000000000000000000000066 +:104A50000000000000000000000000000000000056 +:104A60000000000000000000000000000000000046 +:104A70000000000000000000000000000000000036 +:0C4A80000000000000000000000000002A :00000001FF diff --git a/Tools/bootloaders/HitecMosaic_bl.bin b/Tools/bootloaders/HitecMosaic_bl.bin index e9e621277e7b6f..055e5bd818531e 100755 Binary files a/Tools/bootloaders/HitecMosaic_bl.bin and b/Tools/bootloaders/HitecMosaic_bl.bin differ diff --git a/Tools/bootloaders/HitecMosaic_bl.elf b/Tools/bootloaders/HitecMosaic_bl.elf index 8bb8d21632cf22..3fe7c2f127917b 100755 Binary files a/Tools/bootloaders/HitecMosaic_bl.elf and b/Tools/bootloaders/HitecMosaic_bl.elf differ diff --git a/Tools/bootloaders/HitecMosaic_bl.hex b/Tools/bootloaders/HitecMosaic_bl.hex index 3b44f38eaa57a7..91872d56ef6c4e 100644 --- a/Tools/bootloaders/HitecMosaic_bl.hex +++ b/Tools/bootloaders/HitecMosaic_bl.hex @@ -1,979 +1,1217 @@ :020000040800F2 -:1000000000090020A5040008DD1400085D140008A4 -:10001000B51400085D14000889140008A70400083E -:10002000A7040008A7040008A70400087D350008FD -:10003000A7040008A7040008A7040008B53A0008B0 -:10004000A7040008A7040008A7040008A7040008E4 -:10005000A7040008A70400084D38000879380008F4 -:10006000A5380008D1380008FD380008A7040008AA -:10007000A7040008A7040008A7040008A7040008B4 -:10008000A7040008A7040008A70400082524000806 -:1000900091240008E52400083925000829390008C2 -:1000A000A7040008A7040008A7040008A704000884 -:1000B000A7040008A7040008A7040008A704000874 -:1000C000A7040008A7040008A7040008A704000864 -:1000D000A7040008A70400087D290008912900084A -:1000E00091390008A7040008A7040008A704000825 -:1000F000A7040008A7040008A7040008A704000834 -:10010000A7040008A7040008A7040008A704000823 -:10011000A7040008A7040008A7040008A704000813 -:10012000A7040008A7040008A7040008A704000803 -:10013000A7040008A7040008A7040008A7040008F3 -:10014000A7040008A7040008A7040008A7040008E3 -:10015000A7040008A7040008A7040008A7040008D3 -:10016000A7040008A7040008A7040008A7040008C3 -:10017000A7040008A7040008A7040008A7040008B3 -:10018000A7040008A7040008A7040008A7040008A3 -:10019000A7040008A7040008A7040008A704000893 -:1001A00053B94AB9002908BF00281CBF4FF0FF31DE -:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA -:1001C00000F006F8DDF804E0DDE9022304B0704732 -:1001D0002DE9F047089D04468E46002B4DD18A42FA -:1001E000944669D9B2FA82F252B101FA02F3C2F12D -:1001F000200120FA01F10CFA02FC41EA030E9440BE -:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE -:1002100016E341EA034306FB07F199420AD91CEBB6 -:10022000030306F1FF3080F01F81994240F21C81E8 -:10023000023E63445B1AA4B2B3FBF8F008FB103330 -:1002400044EA034400FB07F7A7420AD91CEB040465 -:1002500000F1FF3380F00A81A74240F20781644435 -:10026000023840EA0640E41B00261DB1D4400023BA -:10027000C5E900433146BDE8F0878B4209D9002D1E -:1002800000F0EF800026C5E9000130463146BDE8A8 -:10029000F087B3FA83F6002E4AD18B4202D3824212 -:1002A00000F2F980841A61EB030301209E46002DC1 -:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 -:1002C000002A40F09280A1EB0C014FEA1C471FFA74 -:1002D0008CFE0126200CB1FBF7F307FB131140EA5B -:1002E00001410EFB03F0884208D91CEB010103F128 -:1002F000FF3802D2884200F2CB804346091AA4B2EA -:10030000B1FBF7F007FB101144EA01440EFB00FEBD -:10031000A64508D91CEB040400F1FF3102D2A64522 -:1003200000F2BB800846A4EB0E0440EA03409CE7C1 -:10033000C6F12007B34022FA07FC4CEA030C20FA6E -:1003400007F401FA06F31C43F9404FEA1C4900FA8E -:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B -:1003600040EA014108FB0EF0884202FA06F20BD97E -:100370001CEB010108F1FF3A80F08880884240F2CE -:100380008580A8F102086144091AA4B2B1FBF9F012 -:1003900009FB101144EA014100FB0EFE8E4508D90D -:1003A0001CEB010100F1FF346CD28E456AD9023892 -:1003B000614440EA0840A0FB0294A1EB0E01A14277 -:1003C000C846A64656D353D05DB1B3EB080261EBE5 -:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF -:1003E000007100263146BDE8F087C2F12003D840F5 -:1003F0000CFA02FC21FA03F3914001434FEA1C4737 -:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 -:10041000064300FB0EF69E4204FA02F408D91CEBD8 -:10042000030300F1FF382FD29E422DD902386344D6 -:100430009B1B89B2B3FBF7F607FB163341EA034176 -:1004400006FB0EF38B4208D91CEB010106F1FF38C5 -:1004500016D28B4214D9023E6144C91A46EA0046BC -:1004600038E72E46284605E70646E3E61846F8E64E -:100470004B45A9D2B9EB020864EB0C0E0138A3E797 -:100480004646EAE7204694E74046D1E7D0467BE778 -:10049000023B614432E7304609E76444023842E7F0 -:1004A000704700BF02E000F000F8FEE772B63A487D -:1004B00080F30888394880F3098839484EF6085196 -:1004C000CEF20001086040F20000CCF200004EF6CF -:1004D0003471CEF200010860BFF34F8FBFF36F8F0E -:1004E00040F20000C0F2F0004EF68851CEF200015A -:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 -:10050000100A4EF63C71CEF200010860062080F31E -:100510001488BFF36F8F03F0B1F803F08DF803F088 -:10052000BFF84FF055301F491B4A91423CBF41F87C -:10053000040BFAE71C49194A91423CBF41F8040BED -:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C -:1005500042F8040BF8E700201749184A91423CBFC3 -:1005600041F8040BFAE703F06BF803F0D5F8144CEC -:10057000144DAC4203DA54F8041B8847F9E700F045 -:1005800041F8114C114DAC4203DA54F8041B884772 -:10059000F9E703F053B80000000900200011002023 -:1005A000000000080001002000090020F03C0008C5 -:1005B00000110020201100202011002028260020FA -:1005C000A0010008A0010008A0010008A001000887 -:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F -:1005E000BDEC108ABDE8F08F002383F31188284604 -:1005F000A047002002F04AFDFEE702F0CFFC00DF3A -:10060000FEE700002DE9F04102F060FF074602F02E -:10061000ABFF054600283FD12B4B9F423CD0013316 -:100620009F423CD0294B27F0FF029A423BD1F8B2BF -:1006300000F052FAA84642F2107400F057FC08B1DC -:100640000024A04600F04EFA064680B38CBB464616 -:1006500035B11F4B9F4203D002F07EFF0024264697 -:10066000002002F03DFF4FF090431B6913F0200380 -:1006700022D00EB100F02EF800F05CFC00F02EFE4F -:1006800000F02EFF0546CCB100F02AFF401BA0422F -:1006900014D900F01FF8F3E7A8460024CDE704467C -:1006A0004FF00108C9E780464FF47A74C5E7044665 -:1006B000CEE74FF47A74CBE71C46DDE700F0DAFCB6 -:1006C000012002F0E9FCDEE7010007B0000008B0FD -:1006D000263A09B038B51D4A1D4B1968013134D08E -:1006E00004339342F9D11B4C194DD4F80428AA4283 -:1006F0002BD3194B9B6803F1006303F5D0439A4257 -:1007000023D202F0FDFE02F00FFF002000F000FEF9 -:10071000124B0220187000F037FE114BDA690022EC -:10072000DA61D96999699A619B6972B64FF0E023E1 -:100730002021C3F8085DD4F80038D4F8042881F3E8 -:1007400011889D4683F30888104738BD206800084B -:10075000006800080060000800110020201100203F -:1007600000100240094A136849F2690099B21B0C53 -:1007700000FB01331360064B186844F2506182B2EB -:10078000000C01FB0200186080B270471C110020B1 -:100790001811002010B500211022044600F00EFEB2 -:1007A000034B03CB206061601868A06010BD00BFE0 -:1007B000ACF7FF1F2DE9F043224DBBB000F090FED7 -:1007C000AB6840F2ED22C31A934232D906AFA8605B -:1007D0002B4628220021384601F05EFB05F10E0071 -:1007E00000F0E4FD002604465FFA80F905F10E08EA -:1007F000F3B2F100994501F1280107D908EB06038E -:100800000822384601F048FB0136F1E708230122AF -:10081000CDE9023205340C4B0193A4B2302300938E -:10082000CDE9047405A3D3E90023297B074801F02F -:100830004BF93BB0BDE8F083AFF3008078F6339F0F -:1008400093CACD8D68210020752100203C21002015 -:1008500070B50D4614461E4601F0CCF850B9022E74 -:1008600010D1012C0ED112A3D3E90023C5E9002336 -:10087000012007E0282C10D005D8012C09D0052C28 -:100880000FD0002070BD302CFBD10BA3D3E9002387 -:10089000ECE70BA3D3E90023E8E70BA3D3E900239C -:1008A000E4E70BA3D3E90023E0E700BFAFF3008048 -:1008B000401DA12026812A0B78F6339F93CACD8D47 -:1008C0009E6AC421818A46EE26417272DF25D7B71F -:1008D000F017304A39059E5613B50446234608469C -:1008E00020220021019001F0D7FA22790198032AF1 -:1008F000234628BF032203F8042F2021022201F0FF -:10090000CBFA62790198072A234628BF072203F809 -:10091000052F2221032201F0BFFAA2790198072AAC -:10092000234628BF072203F8062F2521032201F0C2 -:10093000B3FA019804F108031022282101F0ACFA5F -:10094000382002B010BD00002DE9F04FADF5017D5B -:1009500021AD0EAE40F2751280460F4622A800214E -:10096000296000F02BFD48220021304600F026FDD2 -:1009700000F0B6FD564B4FF47A72B0FBF2F01860FF -:1009800093E80700012386E807000DF15A0033823F -:10099000FFF700FF4FF60303338407AB18464D49BA -:1009A00003F0C2F8192230642946304686F83C200C -:1009B000FFF792FF12AB044601460822284601F0D9 -:1009C0006BFA0822A1180DF14903284601F064FAD8 -:1009D0000DF14A03082204F11001284601F05CFAE7 -:1009E00013AB202204F11801284601F055FA14AB8C -:1009F000402204F13801284601F04EFA16AB0822D5 -:100A000004F17801284601F047FA0DF15903082254 -:100A100004F18001284601F03FFA04F1880A0DF143 -:100A20005A0904F5847B4B465146082228460AF1B0 -:100A3000080A01F031FAD34509F10109F3D11BABE2 -:100A400008225946284601F027FA04F588744FF029 -:100A5000000996F834304B450AD9B36B21464B4414 -:100A60000822284601F018FA083409F10109F0E7D4 -:100A70004FF0000996F83C304B4504EBC90108D90A -:100A8000336C08224B44284601F006FA09F10109AB -:100A9000F0E700230393BB7E0293073107F11903AC -:100AA0000193C1F3CF010123CDE904510093F97EF5 -:100AB00005A3D3E90023404601F006F80DF5017DBA -:100AC000BDE8F08FAFF300809E6AC421818A46EEB4 -:100AD00024110020383B0008014B1870704700BFFC -:100AE00030110020F0B5334B1C7B85B034B1324B54 -:100AF0000E221A810024204605B0F0BD2F4A10684E -:100B0000516802AB03C308232D492E480DEB0302A5 -:100B100002F0E8FF054630B9274B2B480A221A811C -:100B200000F098FCE6E70169B1F5663F06D9224B73 -:100B300026480B221A8100F08DFCDCE7438BB3F5CD -:100B40007E7F09D01C4A22480C2111814FF47E720D -:100B5000194600F07FFCCEE71E4A024402F1100362 -:100B6000994204D2144B1C4810221A81E3E7103931 -:100B70008E1A2046134900F0B7FC3246074605F1AD -:100B80001801204600F0B0FCAB689F4202D1EB6830 -:100B900098420AD0084B0D221A810090D5E9021222 -:100BA0003B460E4800F056FCA4E70D4800F052FC0E -:100BB0000124A0E76821002024110020E53B000863 -:100BC000DC97030000680008543B0008603B000805 -:100BD000723B00080898FFF7903B0008AD3B000807 -:100BE000D63B00082DE9F04FADB006AF80460C466D -:100BF00000F000FF054600285AD1237E022B1BD1AE -:100C0000E38A012B18D100F06BFC0646FFF7AAFD22 -:100C100003464FF4C870DFF8D092B3FBF0F206F54C -:100C2000167602FB103316FA83F3C9F80030E37E20 -:100C300033B9A84B00221A709C37BD46BDE8F08F2F -:100C4000A38AEEB2013BB34205F101050BD93B1D6E -:100C50001E44E90000960023082201F0F801204616 -:100C600000F0DEFFECE707F11400FFF793FD3246DA -:100C700007F11401381D02F025FF0028D9D10F2EED -:100C800008D8944B1E70D9F80030A3F51673C9F834 -:100C90000030D1E7FB1CF8700146009307220346A1 -:100CA000204600F0BDFFF978404600F09BFEC3E708 -:100CB000E38A282B26D010D8012B1ED0052BBBD1C0 -:100CC000BFF34F8F8449854BCA6802F4E062134337 -:100CD000CB60BFF34F8F00BFFDE7302BACD1637EFD -:100CE0007F4D01336A7BDBB29342E94603D1E27E5A -:100CF0002B7B9A4265D0CD469EE721464046FFF7C2 -:100D000023FE99E7A38A013B9BB2C92B94D8744D6B -:100D10002E7B26BB05F10C03009308223346314697 -:100D2000204600F07DFF731CF2B2D9001E46A38A54 -:100D3000013B9A4205DA0E322A440092002308222F -:100D4000EEE700230022C5E900230023AB6085F80D -:100D5000D730C5F8D8302B7B0BB9E37E2B73002539 -:100D600007F114093B1D082229464846C7E90155E9 -:100D7000FD6001F091F83B7A05F1010AAB424FEAC0 -:100D8000CA0608D9FB6808222B443146484601F0C0 -:100D900083F85546EFE7C6F3CF06E17ECDE904962A -:100DA00000230393A37E0293193428230093019414 -:100DB00046A3D3E90023404600F086FEFFF7FAFC85 -:100DC0003AE74FF0000807F11403A7F81480102247 -:100DD000009341460123204600F022FFA68A023EEE -:100DE000B6B2F31C9B109B000733DB08A9EBC303CF -:100DF0009D460DF1180A1FFA88F34FEAC801B34265 -:100E000001F110010AD20AEB080300930822002323 -:100E1000204600F005FF08F10108ECE795F8D7003F -:100E200000F080FAD5F8D83004461BB995F8D70001 -:100E300000F088FAD5F8D83033449C4204D295F8B3 -:100E4000D700013000F07EFA4FEA960B4FF0000811 -:100E50001FFA88F18B45D5E9003209D90AEB8801E0 -:100E600003EB8800012200F0B1FA08F10108EFE776 -:100E7000F31842F10002C5E90032D5F8D83095F8F0 -:100E8000D70006EB0308C5F8D88000F04BFA804580 -:100E900009D395F8D730D5F8D8000133001B85F871 -:100EA000D730C5F8D800FF2E08D800232B7300F0E8 -:100EB0005BFAFFF717FE08B1FFF70CFC2B68094A35 -:100EC0009B0A013313810023AB6014E72641727241 -:100ED000DF25D7B73521002000ED00E00400FA053A -:100EE00068210020241100203821002010B54FF087 -:100EF00000540C4B22689A4211D10B4B627D1A7040 -:100F00000A48237D03730A49C9220E3000F044FACF -:100F1000E0220021204600F051FA012010BD0020FF -:100F2000FCE700BF9AAD44C53011002068210020C5 -:100F3000160000202DE9FF41434C0223637100237A -:100F4000029324250A23581EB5FBF3F67343D3F10D -:100F50002402C1B23ED002280346F4D19DF80B30E2 -:100F60003A493B485A1E9DF80A30013B1B0443EAAC -:100F70000253BDF80820013A13434B6001F044FDD1 -:100F800000230193334B344900933448344B4FF4DE -:100F9000805200F001FD334B197811B12F4800F059 -:100FA00021FD00F09DFA0546FFF7DCFB4FF4C87306 -:100FB000B0FBF3F202FB130305F5167010FA83F091 -:100FC000294B186002F0D0FA08B10F23238104B036 -:100FD000BDE8F081C1EBC107FB1C4FEAE30EC3F390 -:100FE000C703A1EB030C0EF101084FF47A705FFA0E -:100FF0008CF50EFB000058FA8CFCB0FBFCF0B0F551 -:10100000617F07D97B1EC3F3C703C91ACDB2591E2E -:101010000F2916D86A1E072A8CBF002201225919EF -:1010200001FB06601149B1FBF0F11148814295D1F5 -:10103000002A93D0ADF808608DF80A308DF80B5077 -:101040008CE71346EBE700BF2411002010110020AD -:101050008022002051080008341100203C2100208B -:10106000E50B000830110020382100200051250236 -:1010700040420F002DE9F04F90A7D7E900670FF22B -:101080004429D9E90089874D93B0DFF840B2864CF6 -:10109000284600F07DFD0DF1300A079070B3102254 -:1010A0000021504600F08AF9079B197B4FF000029F -:1010B00061F303028DF83020586899680EAA03C2C4 -:1010C0001B680D9A63F31C029DF830300D9243F0BB -:1010D00020038DF83030002352461946584601F05F -:1010E000A3FC079028B9284600F056FD079B237003 -:1010F000CEE72378072B3CD8013323701822002138 -:10110000504600F05BF9DFF8C4B10023194652469F -:10111000584601F0B1FC014678BB102208A800F047 -:101120004DF94FF0904209AC536983F0400353618D -:1011300000F0D8F90B4612A9024611E9030084E831 -:1011400003009DF83410C1F3030089064CBF0E9CC8 -:10115000BDF838408DF82C0046BFC4F31C0444F0A1 -:101160000044C4F30A0408A92846089400F0DCFEF1 -:10117000CBE7284600F010FDC0E7284600F03AFC17 -:101180000446002848D1DFF848B100F0A9F9DBF89F -:101190000030984240D300F0A3F90790FFF7E2FA3D -:1011A000079A8DF8204003464FF4C87002F5167276 -:1011B000B3FBF0F101FB103312FA83F3CBF80030EC -:1011C000DFF810B19BF8001011B901238DF8203021 -:1011D00050460791FFF7DEFA0799C1F11004E4B217 -:1011E000062C28BF0624224651440DF1210000F0B0 -:1011F000D3F808AB03931823029301342B4B0193CC -:10120000E4B20123009304943B463246284600F0A2 -:10121000F3FB00238BF8003000F062F9244A254CE0 -:101220001368C31AB3F57A7F31D3106000F05AF90E -:1012300002460B46284600F0B9FC284600F0DAFBCF -:1012400028B3237BDFF890B0002B14BF03230223C5 -:101250008BF8053000F044F94FF47A735146B0FB37 -:10126000F3F0CBF800005846FFF736FB18230730A1 -:101270000293114B0193C0F3CF0040F25513CDE917 -:1012800003A0009342464B46284600F0B5FB237B63 -:101290002BB1FFF78FFA237B002B7FF4F6AE13B050 -:1012A000BDE8F08F3C2100204D2200203421002099 -:1012B00048220020682100204C220020401DA1204F -:1012C00026812A0BF1C6A7C1D068080F8022002012 -:1012D00038210020352100202411002070B501F0B4 -:1012E000B5FF094E094D30800024286833888342B9 -:1012F00008D901F0A7FF2B6804440133B4F5D04F9F -:101300002B60F2D370BD00BF7C2200205022002051 -:1013100002F03AB800F10060920000F5D04001F010 -:10132000D5BF0000054B1A68054B1B889B1A8342EA -:1013300002D9104401F086BF0020704750220020DF -:101340007C22002038B5074D04462868204401F06F -:101350007FFF28B928682044BDE8384001F08ABFE3 -:1013600038BD00BF50220020064991F8243033B127 -:101370000023086A81F824300822FFF7CBBF012040 -:10138000704700BF54220020022802BF4FF0904354 -:101390004FF480029A61704710B50023934203D046 -:1013A000CC5CC4540133F9E710BD0000034602468B -:1013B000D01A12F9011B0029FAD1704702440346E2 -:1013C000934202D003F8011BFAE770472DE9F84376 -:1013D0001F4D144695F824200746884652BBDFF877 -:1013E00070909CB395F824302BB92022FF214846F9 -:1013F0002F62FFF7E3FF95F82400C0F10802A24234 -:1014000028BF2246D6B24146920005EB8000FFF786 -:10141000C3FF95F82430A41B1E44F6B2082E1744CF -:101420009044E4B285F82460DBD1FFF79DFF0028EB -:10143000D7D108E02B6A03EB82038342CFD0FFF7BA -:1014400093FF0028CBD10020BDE8F8830120FBE703 -:10145000542200200FB4002004B0704700B59BB0A8 -:10146000EFF3098168226846FFF796FFEFF30583E3 -:10147000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6AC0 -:101480009B6AFEE700ED00E000B59BB0EFF3098139 -:1014900068226846FFF780FFEFF30583044B9A6BE1 -:1014A0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF7F -:1014B00000ED00E000B59BB0EFF3098168226846BB -:1014C000FFF76AFFEFF30583034B5A6B9A6A9A6A38 -:1014D0009A6A9A6A9B6AFEE700ED00E0FEE7000068 -:1014E00001F08EBF01F064BF30B5094D0A4491424E -:1014F0000DD011F8013B5840082340F30004013B94 -:101500002C4013F0FF0384EA5000F6D1EFE730BD22 -:101510002083B8ED2DE9F041C56915B9C161BDE879 -:10152000F0814B6823F06047C3F38A464FEAD37ECD -:10153000C3F3807816EA230638BF3E46AC462B46F6 -:101540005A68BEEBD27F22F060440AD0002A18DA33 -:10155000A40CB44217D19D420FD10D60DEE71346B3 -:10156000EEE7A74207D102F08044C2F38072424501 -:101570000BD054B1EFE708D2EDE7CCF800100B60C8 -:10158000CDE7B44201D0B442E5D81A689C46002A9F -:10159000E5D11960C3E700002DE9F047089D01F08F -:1015A00007044FEAD508224405F0070500EBD100F7 -:1015B0004FF47F49944201D1BDE8F08704F007075A -:1015C00005F0070A57453E4638BF5646C6F108069D -:1015D000111B8E4228BF0E46E10808EBD50E415C78 -:1015E00013F80EC0B94029FA06F721FA0AF1FFB242 -:1015F0008CEA010147FA0AF739408CEA010C03F83A -:101600000EC034443544D5E780EA0120082341F276 -:10161000210201B24000002980B203F1FF33B8BFBC -:10162000504013F0FF03F4D17047000038B50C466A -:101630008D18A54200D138BD14F8011BFFF7E4FF57 -:10164000F7E7000002684AB113680360C3880189A4 -:1016500001339BB29942C38038BF03811046704763 -:1016600070B588B0202204460D4668460021FFF779 -:10167000A5FE20460495FFF7E5FF024658B16B46EC -:10168000054608AE1C4603CCB44228606960234678 -:1016900005F10805F6D1104608B070BD082817D925 -:1016A00009280CD00A280CD00B280CD00C280CD000 -:1016B0000D280CD00E2814BF4020302070470C207D -:1016C0007047102070471420704718207047202062 -:1016D00070470000082817D90C280CD910280CD9FD -:1016E00014280CD918280CD920280CD930288CBFE4 -:1016F0000F200E207047092070470A2070470B20EA -:1017000070470C2070470D207047000010B54B68E3 -:1017100023B9CA8A63F30902CA8210BDC4681A6871 -:101720001C60C360438A013B43824A60EFE70000CC -:101730002DE9F84F1D46CB8A0F46C3F30901062950 -:10174000814692460B4630D00020AAB207F1190418 -:101750009EB2052E1FFA80F80FD8904503F10103C1 -:1017600006D3FB8A0A4462F30903FB8201201AE0D4 -:101770001AF80060E6540130EAE79045F1D2A1F191 -:10178000060B1C237C68BBFBF3F203FB12BB1FFAA6 -:101790008BF6002C45D14846FFF754FF044638B974 -:1017A00078606FF00200BDE8F88F4FF00008E6E7C0 -:1017B000002606607860ADB24FF0000B454510D9A9 -:1017C0000AEB0803221D13F8011B9155B1B208F171 -:1017D00001081B291FFA88F82BD0454506F10106A0 -:1017E000F1D8FB8AC3F30902154465F30903BCE78A -:1017F000013292B21C462368002BF9D1AB1F0B4477 -:101800001C21B3FBF1F301339BB29A42D3D2BBF15B -:10181000000FD0D14846FFF715FF20B9C4F800B03B -:10182000BFE70122E7E7C0F800B05E46206004464B -:10183000C1E74545D5D94846FFF704FF08B9206000 -:10184000AFE7C0F800B0002620600446B6E700000D -:101850002DE9F04F2DED028B83B0CDE90013BDF8DB -:101860003C5007469146002A00F092802DB10E9B15 -:10187000002B00F08D80072D32D807F10C00FFF708 -:10188000E1FE044638B96FF00204204603B0BDEC17 -:10189000028BBDE8F08F14220021FFF78FFD0E9917 -:1018A0002A4604F10800FFF777FD681CC0B2FFF775 -:1018B00011FFFFF7F3FE207499F80030013814FA95 -:1018C00080F003F01F0363F03F030372009B43F0BB -:1018D0000041616038462146FFF71CFE0124D4E731 -:1018E00000F10C034FF0000808EE103A4FF0800AA8 -:1018F0004646444618EE100AFFF7A4FE8346002829 -:10190000C1D014220021FFF759FDC6BB019BABF8E3 -:10191000083002200E9B00F1080299195BFA82F24E -:101920000130C0B2082801D0AE422AD3FFF7D2FE60 -:10193000FFF7B4FE99F80020009B411E02F01F0241 -:1019400042EA4812AE4208BF4FF0400A5BFA81F10A -:101950004AEA020A43F0004281F808A08BF810001E -:10196000CBF8042059463846FFF7D4FD0134AE4287 -:1019700024B288F001084FF0000ABBD185E70020AF -:10198000C8E711F801CB02F801CB0136B6B2C7E7C0 -:101990006FF0010479E70000F8B515460E462822DD -:1019A000002104461F46FFF709FD069B6360B5F55D -:1019B000001F079BA76034BF6A094FF6FF722362BE -:1019C00004F10C0097B200239A4205D8002303606B -:1019D00027826382A382F8BD066001333046203639 -:1019E000F2E7000003781BB94BB2002BC8BF0170AF -:1019F00070470000007870472DE9F74FDDF83C9004 -:101A0000BDF830500D9E9DF83840BDF840708046BE -:101A100092469B46B9F1000F01D1002F51D11F2CE6 -:101A20004FD898F80000B0B9072F47D835F0030316 -:101A300047D13A4649464FF6FF70FFF7F7FD20F0D1 -:101A400001002D02400445EA0464400C44EA4024AD -:101A50004FF6FF7321E040EA0520072F40EA0464B7 -:101A6000F6D900254FF6FF73C5F12000A5F120023D -:101A70002AFA05F10BFA00F001432BFA02F21143A6 -:101A80001846C9B2FFF7C0FD0835402D0346EBD11B -:101A90003A464946FFF7CAFD0346CDE9009732466C -:101AA00021464046FFF7D4FE33780133DBB21F2BCB -:101AB00088BF0023337003B0BDE8F08F6FF00300E0 -:101AC000F9E76FF00100F6E72DE9F04F85B0924697 -:101AD000DDF848800F9D9DF840209DF84490BDF8AA -:101AE0004C7006469B46B8F1000F01D1002F48D13B -:101AF0001F2A46D83378002B46D00C0244EA0264F1 -:101B00009DF8381044EAC93444EA01441C43072FC5 -:101B100044F0800432D900234FF6FF72C3F1200C49 -:101B2000A3F120002AFA03F10BFA0CFC41EA0C01A4 -:101B30002BFA00F00143C9B210460393FFF764FD8E -:101B4000039B0833402B0246E8D13A464146FFF753 -:101B50006DFD0346CDE900872A4621463046FFF752 -:101B600077FEB9F1010F06D12B780133DBB21F2BC1 -:101B700088BF00232B7005B0BDE8F08F4FF6FF73D0 -:101B8000E8E76FF00100F6E76FF00300F3E700000D -:101B9000C06900B104307047C3691A68C261C26885 -:101BA0001A60C360438A013B438270472DE9F041CC -:101BB000D0F81880194E14461D464146002709B931 -:101BC000BDE8F081D1E90223A21A65EB0303964236 -:101BD00077EB03031ED283698B420DD1FFF796FD8D -:101BE00083691B688361C3680B60438AC160816934 -:101BF000013B43828846E2E7FFF788FD0B68C8F89F -:101C00000030C3680B60438AC160013B4382D8F84F -:101C10000010D4E788460968D1E700BF80841E0021 -:101C20002DE9F04F8BB00D46DDF8509014469B46E1 -:101C30008046002800F01981B9F1000F00F01581ED -:101C4000531E3F2B00F21181012A03D1BBF1000F7B -:101C500040F00B810023CDE90833B8F81430B5EB20 -:101C6000C30F4FEAC30703D300200BB0BDE8F08FCA -:101C70002B199F42D8F80C303ABF7F1BFFB2274682 -:101C80001BB9D8F81030002B7AD02F2D4ED8C5F1C3 -:101C90003006B7424FF000032CBFF6B23E46009329 -:101CA0002946D8F8080008AB3246FFF775FCA7EBC9 -:101CB000060A35445FFA8AFAB8F8143003F1005383 -:101CC000063BDB000493D8F80C3003933021039BD0 -:101CD00013B1BAF1000F2CD1D8F8100040B1BAF10D -:101CE000000F05D0009608AB5246691AFFF754FC66 -:101CF00038B2002FB8D066070AD00AAB03EBD40184 -:101D0000624211F8083C02F00702134101F8083C56 -:101D1000082C3CD9102C40F2B580202C40F2B78022 -:101D2000BBF1000F00F09C80082334E0BA46002687 -:101D3000C2E7049BE02B28BFE02306930B44AB4291 -:101D4000059314D95A1B03980096924534BF524606 -:101D5000D2B2691A08AB04300792FFF71DFC079A4C -:101D60001644AAEB020A1544F6B25FFA8AFA049BFB -:101D7000069A05999B1A0493039B1B680393A6E795 -:101D80000093D8F8080008AB3A462946AEE7BBF105 -:101D9000000F13D00123B4EBC30F6CD0082C12D862 -:101DA0009DF82030621E23FA02F2D50706D54FF0C7 -:101DB000FF3202FA04F423438DF820309DF82030DE -:101DC00089F8003051E7102C12D8BDF82030621E7F -:101DD00023FA02F2D10706D54FF0FF3202FA04F4DB -:101DE0002343ADF82030BDF82030A9F800303CE79F -:101DF000202C0FD80899631E21FA03F3DA0705D5C2 -:101E00004FF0FF3202FA04F40C430894089BC9F81F -:101E100000302AE7402C2BD0DDE90865611EC4F1B3 -:101E20002102A4F1210326FA01F105FA02F225FAB2 -:101E300003F311431943CB0712D50122A4F1200368 -:101E4000C4F1200102FA03F322FA01F1A240524246 -:101E500043EA010363EB430332432B43CDE90823F9 -:101E6000DDE90823C9E90023FFE66FF00100FCE685 -:101E70006FF00800F9E6082CA0D9102CB3D9202C5B -:101E8000EED8C3E7BBF1000FADD0022383E7BBF16F -:101E9000000FBBD004237EE730B5012A144638BFBB -:101EA0000124402C85B028BF40240025012ACDE91B -:101EB000025518D81B788DF8083063070AD004AB98 -:101EC00003EBD405624215F8083C02F00702934088 -:101ED00005F8083C009103462246002102A8FFF7BE -:101EE0005BFB05B030BD082AE4D9102A03D81B8853 -:101EF000ADF80830E1E7202A8DBFD3E900231B6845 -:101F00000293CDE90223D8E710B5CB681BB98B60EB -:101F10000B618B8210BDC4681A681C60C360438A61 -:101F2000013B4382CA60F0E72DE9F04FD1F8008011 -:101F300093B018F0800FCDE90323C8F3C01219BF86 -:101F4000C8F3C03BC8F306264FF0020B1646B8F1A3 -:101F5000000F04460D4680F2D18118F0C04305936E -:101F600040F0CC810B7B002B00F0C881BBF1020F4D -:101F700003D00178B14240F0C48108F07F0106919E -:101F80006AB3C8F3074A2B44069A93F8039076067F -:101F900046EA0B4646EA82465FEAD91346EA0A0653 -:101FA000079300F0908000220023CDE90A23069BCE -:101FB000009367685B4652460AA92046B847002846 -:101FC0007ED0A7699FB9314604F10C00FFF748FBAA -:101FD0000746E0B96FF0020013B0BDE8F08FC8F318 -:101FE0000F2A18F07F0F08BF0AF0030ACBE73B69FE -:101FF0009E420DD03F68002FF9D1314604F10C000C -:10200000FFF72EFB07460028E4D0A3693B60A761D9 -:10201000DDE90A2300264FF6FF70C6F1200E22FAF2 -:1020200006F103FA0EFEA6F1200C23FA0CFC41EA9D -:102030000E0141EA0C01C9B2083609920893FFF774 -:10204000E3FA402EDDE90832E7D1B882FB7D09F0E2 -:102050001F06C3F384039B1BD7E9022198B2002B10 -:10206000BCBF00F120031BB252EA0100C8F30468B0 -:102070000FD00398821A049860EB0101A7489042A0 -:102080004FF000028A4104D3079A002A5BD0012B4B -:1020900023DDFA7D4FEA890302F0030203F07C039B -:1020A0001343FB7539462046FFF730FB079BA3B966 -:1020B000FB7DC3F38402013262F38603FB7504E007 -:1020C0006FF00B0088E7A76917B96FF00C0083E782 -:1020D0003B699E42BAD03F68F6E719F0400F32D014 -:1020E000039BBB60049BFB60142200210DA8FFF73B -:1020F00065F9039B0A93049B0B932B1D0C932B7B7D -:10210000ADF83EA0013BDBB2ADF83C30069B8DF84C -:10211000433094F824308DF840B083F001038DF8FB -:1021200044308DF84160A3688DF842800AA92046AA -:102130009847FB7DC3F38403013303F01F039B0225 -:10214000FB82002048E7FB7DC9F34012B2EBD31FAE -:1021500040F0DA80C3F38403B34240F0D88007999B -:102160002B7B4FEA9912002934D0D20741D4032B9C -:1021700040F2D080039BBB60049BFB602B7BAE1DB9 -:10218000033BDBB23246394604F10C00FFF7D0FACC -:1021900000280DDA20463946FFF7B8FAFB7DC3F375 -:1021A0008403013303F01F039B02FB82032013E728 -:1021B000AB883B832A7B033AB88AD2B23146FFF719 -:1021C00035FAFB7DB882DA43C2F3C01262F3C7135B -:1021D000FB75B6E76AB92E1D013BDBB232463946C4 -:1021E00004F10C00FFF7A4FA0028D3DB2A7B013AA4 -:1021F000E2E7F98AC1F30901013B0529DAB259D8AE -:10220000281D002307F11A0C9A4208D910F801EB97 -:102210000CF801E0013101330629DBB2F4D1039956 -:102220000A9104990B91934207F11A010C9138BF5E -:10223000043379680D9134BF55FA83F300230E936C -:10224000FB8AADF83EA0C3F309031A44069B8DF840 -:10225000433094F82430ADF83C2083F001038DF82E -:10226000443000238DF840B08DF841608DF84280F5 -:102270007B602A7BB88A013A291DFFF7D7F93B8B8F -:10228000B882834203D1A3680AA920469847204612 -:102290000AA9FFF739FEFB7DB88AC3F38403013333 -:1022A00003F01F039B02FB823B8B984214BF11205B -:1022B000002091E67B68002BB1D0062001E01C30A5 -:1022C0006346D3F800C0BCF1000FF8D1091A081D0D -:1022D00005F1040C00EB030905989DF8143001EB9F -:1022E000000EBEF11B0F9AD89A4298D91CF8013BF8 -:1022F00009F8013B059B01330593EDE76FF00900F9 -:102300006AE66FF00A0067E66FF00D0064E66FF0B2 -:102310000E0061E66FF00F005EE600BF80841E00D5 -:10232000F0B53D4D3D4FEB6943F00073EB61EB6958 -:102330003B4B9B6AD3F800623E4046F00106C3F86F -:102340000062D3F800423C4044EA002040F0010023 -:10235000C3F80002002951D00020C3F81C02064631 -:10236000C3F80402C3F80C02C3F8140203EBC00460 -:1023700001300E28C4F84062C4F84462F6D1002748 -:102380004FF0010C9678148816F0010F18BFD3F89F -:1023900004E20CFA04F01CBF40EA0E0EC3F804E29B -:1023A00016F0020F1EBFD3F80CE240EA0E0EC3F87F -:1023B0000CE2760742BFD3F814620643C3F81462F6 -:1023C00003EBC4045668C4F840629668C4F84462DB -:1023D000D3F81C4201372043B942C3F81C0202F172 -:1023E0000C02CFD1D3F8002222F00102C3F8002260 -:1023F000EB6923F00073EB61EB69F0BD0122C3F8D8 -:102400004012C3F84412C3F80412C3F81412C3F8FC -:102410000C22C3F81C22E5E7001002400000FFFF79 -:1024200080220020184A916A08B58B688B6013F0EF -:10243000010104D013F00C0F18BF4FF48031D80500 -:1024400006D513F4406F14BF41F4003141F002018E -:10245000D80306D513F4402F14BF41F4802141F076 -:102460000401D3690BB108489847202383F31188EE -:102470000648002100F038FE002383F31188BDE8F0 -:10248000084001F0AFB800BF802200208822002061 -:1024900038B5124CA36ADD68AA0712D05A6922F037 -:1024A00002025A61A36913B10121204698472023F3 -:1024B00083F311880A48002100F016FE002383F3FD -:1024C0001188EB0606D5A36A1021D960236A0BB1E7 -:1024D00002489847BDE8384001F084B880220020C7 -:1024E0009022002038B5124CA36A1D69AA0712D0A9 -:1024F0005A6922F010025A61A36913B102212046E1 -:102500009847202383F311880A48002100F0ECFD4E -:10251000002383F31188EB0606D5A36A1021196105 -:10252000236A0BB102489847BDE8384001F05AB819 -:10253000802200209022002038B50F4CA36A5D68ED -:102540005D602A070AD5042222701A6822F002026E -:102550001A60636A13B10021204698476B0706D5BD -:10256000A36A9969236A13B1034809049847BDE82F -:10257000384001F037B800BF8022002010B50E4C63 -:10258000204600F02FFA0D4BA3620B21132000F020 -:1025900009FA0B21142000F005FA0B21152000F098 -:1025A00001FA0B21162000F0FDF90022BDE81040D1 -:1025B00011460E20FFF7B4BE8022002000640040C8 -:1025C0000F4B984210B5044605D10E4BDA6942F024 -:1025D0000072DA61DB69A36A01221A60A36A5A6891 -:1025E000D20707D5626851681268D9611A60064A35 -:1025F0005A6110BD0121082000F06CFCEEE700BF1D -:1026000080220020001002405B87010003291AD8B5 -:10261000DFE801F0020A0F14836A9B6813F0E05FA1 -:1026200014BF012000207047836A9868C0F380605F -:102630007047836A9868C0F3C0607047836A98687F -:10264000C0F30070704700207047000010B50329E8 -:1026500025D8DFE801F00225292D836A9968C1F3A6 -:102660000161183103EB0113107884064CBF5468E4 -:102670009488C0F300114FEA410148BF41EAC40108 -:1026800000F00F004CBF41F0040141EA4451586092 -:1026900041F001019068D2689860DA60196010BD5D -:1026A000836A03F5C073DFE7836A03F5C873DBE76A -:1026B000836A03F5D073D7E701290AD002290FD026 -:1026C00081B9836ADA68920701D1186903E00120B1 -:1026D0007047836AD86810F0030018BF0120704764 -:1026E000836AF2E70020704710B539B9836AD96868 -:1026F00089071BD11B699C0704D110BD012915D086 -:102700000229FAD1816AD1F8C031D1F8C441D1F897 -:10271000C8011061D1F8CC0150612020086108691E -:10272000800717D1486940F0100012E0816AD1F8A3 -:10273000B031D1F8B441D1F8B8011061D1F8BC0181 -:1027400050612020C860C868800703D1486940F004 -:1027500002004861C3F34000C3F38001000140EA76 -:102760004111107920F030000143117189064BBFEF -:1027700091681189DB085B0D4CBF63F31C0163F3A7 -:102780000A01137948BF916064F3030313714FEAA0 -:1027900014234FEA144458BF118113705480ACE7DE -:1027A000026843681143016003B118477047000095 -:1027B000024A136843F0C0031360704700440040AE -:1027C000024A136843F0C00313607047004800409A -:1027D00037B51D4C1D4D204600F006FB009404F15A -:1027E00014001B490023202200F0C8F92022009485 -:1027F00004F13800174B184900F042FA174BC4E9AE -:102800001735174C0C21262000F0CCF8204600F09C -:10281000EBFA04F11400134900940023202200F085 -:10282000ADF904F13800104B10490094202200F05B -:1028300027FA0F4B0C212720C4E9173503B0BDE858 -:10284000304000F0AFB800BFAC220020005125029C -:1028500084230020B1270008C42300200044004046 -:1028600018230020A4230020C1270008E42300200F -:10287000004800402DE9F047C66D3768F4693462BE -:102880002107054618D014F0080118BF8021E2077F -:1028900048BF41F02001A30748BF41F04001600755 -:1028A00048BF41F48071202383F31188281DFFF76E -:1028B00077FF002383F31188E2050AD5202383F3F1 -:1028C00011884FF40071281DFFF76AFF002383F37E -:1028D00011884FF020094FF0000A14F0200838D179 -:1028E0003B0616D54FF0200905F1380A200610D511 -:1028F00089F31188504600F0F7F9002836DA0821EC -:10290000281DFFF74DFF27F080033360002383F37A -:102910001188790614D5620612D5202383F3118815 -:10292000D5E913239A4208D12B6C33B11021281D0D -:1029300027F04007FFF734FF3760002383F3118847 -:10294000E30619D5AA6E1369B3B1BDE8F047506923 -:10295000184789F31188B38C95F8641028461940FC -:1029600000F04EFA8AF31188F469B6E780B2308538 -:1029700088F31188F469B9E7BDE8F08708B5034822 -:10298000FFF778FFBDE8084000F02CBEAC22002025 -:1029900008B50348FFF76EFFBDE8084000F022BE0F -:1029A0001823002000F1604303F561430901C9B217 -:1029B00083F80013012200F01F039A4043099B0093 -:1029C00003F1604303F56143C3F880211A60704747 -:1029D00000F16040090100F56D40C9B20176704711 -:1029E000FFF7CCBD012300F10802C0E90222037009 -:1029F00000F110020023C0E90422C0E90633C0E957 -:102A0000083343607047000010B52023044683F369 -:102A10001188022303704160FFF7D2FD0423237065 -:102A2000002383F3118810BD2DE9F0411F460446B1 -:102A30000D461646202383F3118800F108082378F9 -:102A4000052B0DD029462046FFF7E0FD40B120467A -:102A500032462946FFF7FAFD002080F3118808E08E -:102A60003946404600F024FB0028E8D0002383F3D9 -:102A70001188BDE8F08100002DE9F0411F460446B1 -:102A80000D461646202383F3118800F110082378A1 -:102A9000052B0DD029462046FFF70EFE40B12046FB -:102AA00032462946FFF720FE002080F3118808E017 -:102AB0003946404600F0FCFA0028E8D0002383F3B2 -:102AC0001188BDE8F0810000F8B5154682680669F6 -:102AD000AA420B46816938BF8568761AB54204461A -:102AE0000BD218462A46FEF757FCA3692B44A36174 -:102AF000A3685B1BA3602846F8BD0CD91846324674 -:102B0000FEF74AFCAF1BE1683A463044FEF744FC4E -:102B1000E3683B44EBE718462A46FEF73DFCE368D2 -:102B2000E5E7000083689342F7B51546044638BFD1 -:102B30008568D0E90460361AB5420BD22A46FEF702 -:102B40002BFC63692B446361A36828465B1BA3606D -:102B500003B0F0BD0DD932460191FEF71DFC01997D -:102B6000E068AF1B3A463144FEF716FCE3683B448D -:102B7000E9E72A46FEF710FCE368E4E710B50A44EB -:102B80000024C361029B8460C0E90000C0E9051114 -:102B9000C1600261036210BD08B5D0E905329342FD -:102BA00001D1826882B98268013282605A1C426116 -:102BB0001970D0E904329A4224BFC36843610021EE -:102BC00000F086FA002008BD4FF0FF30FBE7000060 -:102BD00070B5202304460E4683F31188A568A5B17D -:102BE000A368A269013BA360531CA3611578226905 -:102BF000934224BFE368A361E3690BB12046984781 -:102C0000002383F31188284607E03146204600F070 -:102C10004FFA0028E2DA85F3118870BD2DE9F74FED -:102C200004460E4617469846D0F81C904FF0200AEE -:102C30008AF311884FF0000B154665B12A463146DC -:102C40002046FFF741FF034660B94146204600F0A9 -:102C50002FFA0028F1D0002383F31188781B03B0EA -:102C6000BDE8F08FB9F1000F03D001902046C847AE -:102C7000019B8BF31188ED1A1E448AF31188DCE75F -:102C8000C0E90511C160C3611144009B8260C0E9C5 -:102C90000000016103627047F8B504460D46164610 -:102CA000202383F31188A768A7B1A368013BA36021 -:102CB00063695A1C62611D70D4E904329A4224BFD0 -:102CC000E3686361E3690BB120469847002080F315 -:102CD000118807E03146204600F0EAF90028E2DAE0 -:102CE00087F31188F8BD0000D0E905239A4210B59A -:102CF00001D182687AB98268013282605A1C82618D -:102D00001C7803699A4224BFC3688361002100F0E4 -:102D1000DFF9204610BD4FF0FF30FBE72DE9F74FFC -:102D200004460E4617469846D0F81C904FF0200AED -:102D30008AF311884FF0000B154665B12A463146DB -:102D40002046FFF7EFFE034660B94146204600F0FB -:102D5000AFF90028F1D0002383F31188781B03B06A -:102D6000BDE8F08FB9F1000F03D001902046C847AD -:102D7000019B8BF31188ED1A1E448AF31188DCE75E -:102D8000026843681143016003B1184770470000AF -:102D90001430FFF743BF00004FF0FF331430FFF74C -:102DA0003DBF00003830FFF7B9BF00004FF0FF33E0 -:102DB0003830FFF7B3BF00001430FFF709BF000041 -:102DC0004FF0FF311430FFF703BF00003830FFF73A -:102DD00063BF00004FF0FF323830FFF75DBF0000E7 -:102DE00000207047FFF7F4BC044B03600023C0E9E8 -:102DF0000233436001230374704700BFF03B0008B7 -:102E000038B5C36904460D461BB904210844FFF7D1 -:102E1000B7FF294604F11400FFF7BEFE002806DACA -:102E2000201D4FF48061BDE83840FFF7A9BF38BDD1 -:102E3000024B0022C3E900339A607047042400204B -:102E4000002303748268054B1B6899689142FBD28A -:102E50005A68036042601060586070470424002084 -:102E600008B5202383F31188037C032B05D0042BA2 -:102E70000DD02BB983F3118808BD436900221A6075 -:102E80004FF0FF334361FFF7DBFF0023F2E7D0E9A8 -:102E9000003213605A60F3E7002303748268054B25 -:102EA0001B6899689142FBD85A68036042601060C1 -:102EB0005860704704240020054B1969087418688D -:102EC00002681A605360186101230374FDF780BB28 -:102ED0000424002030B54B1C0B4D87B0044610D0A5 -:102EE0002B690A4A01A800F01BF92046FFF7E4FF0E -:102EF000049B13B101A800F02FF92B69586907B0A2 -:102F000030BDFFF7D9FFF8E704240020612E000848 -:102F100038B50C4D41612B6981689A68914204462D -:102F200003D8BDE83840FFF78BBF1846FFF7B4FF62 -:102F300001232C61014623742046BDE83840FDF78B -:102F400047BB00BF04240020044B1A681B6990682B -:102F50009B68984294BF0020012070470424002001 -:102F600010B5084C236820691A6822605460012259 -:102F700023611A74FFF790FF01462069BDE81040F5 -:102F8000FDF726BB0424002008B5FFF7DDFF18B1CC -:102F9000BDE80840FFF7E4BF08BD0000FFF7E0BF51 -:102FA000FEE7000010B50C4CFFF742FF00F0AAF856 -:102FB0000A498022204600F031F8012344F8180C19 -:102FC000037400F0EBFA002383F3118862B604481F -:102FD000BDE8104000F042B82C240020183C000846 -:102FE000283C000800F0CAB8EFF3118020B9EFF3D5 -:102FF0000583202282F311887047000010B530B994 -:10300000EFF30584C4F3080414B180F3118810BDF4 -:10301000FFF7BAFF84F31188F9E70000826002220B -:10302000028270478368A3F17C0243F80C2C02698A -:1030300043F83C2C426943F8382C074A43F81C2CCF -:10304000C26843F8102C022203F8082C002203F86F -:10305000072CA3F118007047E905000810B52023DC -:1030600083F31188FFF7DEFF00210446FFF750FFCE -:10307000002383F31188204610BD0000024B1B691A -:1030800058610F20FFF718BF04240020202383F38A -:103090001188FFF7F3BF000008B50146202383F332 -:1030A00011880820FFF716FF002383F3118808BD5D -:1030B00049B1064B42681B6918605A60136043604F -:1030C0000420FFF707BF4FF0FF30704704240020B3 -:1030D0000368984206D01A68026050605961184629 -:1030E000FFF7AEBE7047000038B504460D462068B5 -:1030F000844200D138BD036823605C604561FFF7FE -:103100009FFEF4E7054B03F11402C3E905224FF0DB -:10311000FF32DA6100221A62704700BF04240020E7 -:1031200010B5C0E903230B4A136A53699C68A14296 -:103130000CD85C68816003604460206058609868C7 -:10314000411A99604FF0FF33D36110BD1B68091B12 -:10315000ECE700BF04240020036881689A680A44F1 -:103160009A60426813605A600023C360024B4FF0BC -:10317000FF32DA61704700BF0424002038B50F4CDD -:10318000236A22460133236252F8143F934206D049 -:103190009A68013A9A60202563699A6802B138BD3D -:1031A000D3E9001001604860D968DA6082F31188C1 -:1031B0001869884785F31188EEE700BF04240020D2 -:1031C00000207047FEE70000704700004FF0FF301E -:1031D00070470000BFF34F8F024AD368DB07FCD46F -:1031E000704700BF0020024008B5074B1B7853B959 -:1031F000FFF7F0FF054B1A69120641BF044A5A60F7 -:1032000002F188325A6008BD90250020002002405B -:103210002301674508B5054B1B7833B9FFF7DAFF83 -:10322000034A136943F08003136108BD9025002011 -:10323000002002407F289ABF00F58030C0020020A5 -:10324000704700004FF40060704700008020704716 -:103250007F2808B50BD8FFF7EDFF00F50063026883 -:10326000013204D104308342F9D1012008BD00208D -:10327000FCE700007F2838B5044623D8FFF7B4FEEA -:10328000FFF7A8FFFFF7B0FF0F4BF322DA6002222F -:103290001A6105462046FFF7CDFF58611A6942F0D2 -:1032A00040021A614FF40061FFF794FF00F026F925 -:1032B0002846FFF7AFFFFFF7A1FE2046BDE83840E4 -:1032C000FFF7C6BF002038BD0020024012F0010306 -:1032D0002DE9F04704460E46154606D0244B40F231 -:1032E000BD221A600020BDE8F0878118214A914272 -:1032F00004D91F4A40F2C2211160F3E7FFF774FEC0 -:10330000FFF772FFFFF766FFDFF8789031464FF066 -:10331000010AA61B012D06EB0107884605D8FFF719 -:1033200079FFFFF76BFE0120DDE7B8F80030C9F840 -:1033300010A03B800024FFF74DFFC9F810403B88E8 -:1033400031F8022B9BB29A420FD0094B40F2D9229E -:103350001A60094B1F60094B1D60094BC3F80080C0 -:10336000FFF758FFFFF74AFEBCE7023DD2E700BF78 -:103370008C250020000004088025002088250020DE -:103380008425002000200240084908B50B7828B1A8 -:103390001BB9FFF729FF01230B7008BD002BFCD0E0 -:1033A000BDE808400870FFF735BF00BF902500203A -:1033B00030B583B0FFF718FE0E4B0F4D1B6A2A681D -:1033C0004FF47A7101FB03F3934237BF0B4A0B4969 -:1033D000516814682B602EBFD1E900410131516062 -:1033E0001C1941F100010191FFF708FE01992046E7 -:1033F00003B030BD0424002094250020982500202F -:1034000030B583B0FFF7F0FD114B124D1B6A2A68EF -:103410004FF47A7101FB03F3934237BF0E4A0E4912 -:10342000516814682B602EBFD1E900410131516011 -:103430001C1941F100010191FFF7E0FD01994FF4E2 -:103440007A7200232046FCF7ABFE03B030BD00BF0C -:1034500004240020942500209825002010B5024463 -:10346000064BD2B2904200D110BD441C00B253F8BA -:10347000200041F8040BE0B2F4E700BF5028004000 -:103480000F4B30B51C6A240407D41C6A44F4407402 -:103490001C621C6A44F400441C620A4C236843F416 -:1034A000807323600244084BD2B2904200D130BDF9 -:1034B000441C00B251F8045B43F82050E0B2F4E73A -:1034C00000100240007000405028004007B5012263 -:1034D00001A90020FFF7C2FF019803B05DF804FBCB -:1034E00013B50446FFF7F2FFA04205D0012201A95F -:1034F00000200194FFF7C4FF02B010BD7047000028 -:10350000074B45F255521A6002225A6040F6FF728C -:103510009A604CF6CC421A60024B01221A70704736 -:1035200000300040A4250020034B1B781BB1034B47 -:103530004AF6AA221A607047A425002000300040F5 -:10354000044B1A682AB902F1804202F50432526A29 -:103550001A607047A0250020024B4FF080725A621B -:10356000704700BF0010024008B5FFF7E9FF024BAB -:103570001868C0F3407008BDA0250020EFF3098350 -:1035800005494A6B22F001024A63683383F30988D4 -:10359000002383F31188704700EF00E0202080F3C0 -:1035A000118862B60C4B0D4AD96821F4E061090418 -:1035B000090C0A43DA60D3F8FC20094942F0807212 -:1035C000C3F8FC200A6842F001020A601022DA7790 -:1035D00083F82200704700BF00ED00E00003FA0509 -:1035E000001000E010B5202383F311880E4B5B68B8 -:1035F00013F4006314D0F1EE103AEFF30984683C41 -:103600004FF08073E361094BDB6B236684F3098819 -:10361000FFF79AFC10B1064BA36110BD054BFBE709 -:1036200083F31188F9E700BF00ED00E000EF00E050 -:10363000FB050008FE05000870470000FEE70000DB -:103640000A4B0B480B4A90420BD30B4BDA1C121A55 -:10365000C11E22F003028B4238BF00220021FDF779 -:10366000ADBE53F8041B40F8041BECE7103D000806 -:103670002826002028260020282600207047000049 -:103680004B6843608B688360CB68C3600B694361A0 -:103690004B6903628B6943620B68036070470000EB -:1036A00008B51B4B9A6A42F4FC029A629A6A22F4A9 -:1036B000FC029A629A6A5A6942F4FC025A61154AFB -:1036C0005B6911464FF09040FFF7DAFF02F11C01F1 -:1036D00000F58060FFF7D4FF02F1380100F580604B -:1036E000FFF7CEFF02F1540100F58060FFF7C8FF3D -:1036F00002F1700100F58060FFF7C2FF02F18C015A -:1037000000F58060FFF7BCFFBDE8084000F05AB844 -:1037100000100240403C000808B500F093F9FFF7A4 -:1037200041FCBDE80840FFF70BBF000070470000F8 -:1037300010B5214CA36A63F4FC03A362A36A03F4EB -:10374000FC03A3624FF0FF32A36A2369226123695D -:10375000002323612169E168E260E268E360E268D6 -:10376000E269164942F08052E261E2690A6842F475 -:1037700080720A60226A02F44072B2F5407F1EBF76 -:103780004FF4803222622362236A1B0407D4236A27 -:1037900043F440732362236A43F40043236200F03E -:1037A00031F9A369064A43F00103A361A3691368D1 -:1037B00043F02003136010BD001002400070004071 -:1037C000000001401E4B1A6842F001021A601A689C -:1037D0009007FCD55A6822F003025A605A6812F02A -:1037E0000C02FBD1196801F0F90119605A601A68DE -:1037F00042F480321A601A689103FCD5114A5A606B -:103800004FF40452DA6230221A631A6842F080726E -:103810001A601A689201FCD50B4912220A600A68E4 -:1038200002F00702022AFAD15A6842F002025A60F4 -:103830005A6802F00C02082AFAD11A6B1A63704710 -:10384000001002400024050000200240084A08B58C -:10385000516913680B4003F00103536123B1054A1A -:1038600013680BB150689847BDE80840FFF7BABE2F -:1038700000040140A8250020084A08B551691368D2 -:103880000B4003F00203536123B1054A93680BB167 -:10389000D0689847BDE80840FFF7A4BE0004014087 -:1038A000A8250020084A08B5516913680B4003F0A9 -:1038B0000403536123B1054A13690BB1506998475A -:1038C000BDE80840FFF78EBE00040140A825002097 -:1038D000084A08B5516913680B4003F008035361A7 -:1038E00023B1054A93690BB1D0699847BDE80840F8 -:1038F000FFF778BE00040140A8250020084A08B55B -:10390000516913680B4003F01003536123B1054A5A -:10391000136A0BB1506A9847BDE80840FFF762BED2 -:1039200000040140A8250020174B10B55A691C68F7 -:10393000144004F478725A61A30604D5134A936ABA -:103940000BB1D06A9847600604D5104A136B0BB1CF -:10395000506B9847210604D50C4A936B0BB1D06B82 -:103960009847E20504D5094A136C0BB1506C98478F -:10397000A30504D5054A936C0BB1D06C9847BDE8FC -:103980001040FFF72FBE00BF00040140A825002013 -:103990001A4B10B55A691C68144004F47C425A61F1 -:1039A000620504D5164A136D0BB1506D9847230577 -:1039B00004D5134A936D0BB1D06D9847E00404D53C -:1039C0000F4A136E0BB1506E9847A10404D50C4AF0 -:1039D000936E0BB1D06E9847620404D5084A136FFA -:1039E0000BB1506F9847230404D5054A936F0BB170 -:1039F000D06F9847BDE81040FFF7F4BD00040140C8 -:103A0000A8250020062108B50846FEF7CBFF0621B1 -:103A10000720FEF7C7FF06210820FEF7C3FF062197 -:103A20000920FEF7BFFF06210A20FEF7BBFF062193 -:103A30001720FEF7B7FFBDE8084006212820FEF753 -:103A4000B1BF000008B5FFF773FE00F00DF8FEF7F8 -:103A5000C7FFFFF7C7F9FFF769FEBDE8084000F0B0 -:103A600001B8000000F00EB80023054A19460133E2 -:103A7000102BC2E9001102F10802F8D1704700BF13 -:103A8000A82500204FF0E023044A5A6100229A61E1 -:103A900007221A6108210B20FEF79ABF3F19010087 -:103AA00008B5202383F31188FFF79CFA002383F3E2 -:103AB000118808BD08B5FFF7F3FFBDE80840FFF720 -:103AC00091BD000010B501390244904201D100209F -:103AD00005E0037811F8014FA34201D0181B10BD77 -:103AE0000130F2E72DE9F041A3B1C91A177801447A -:103AF000044603F1FF3C8C42204601D9002009E036 -:103B00000578BD4204F10104F5D10CEB0405D6188B -:103B1000A54201D1BDE8F08115F8018D16F801ED3F -:103B2000F045F5D0E7E70000034611F8012B03F854 -:103B3000012B002AF9D170476F72672E617264758C -:103B400070696C6F742E48697465634D6F73616939 -:103B5000630000004E6F20617070207369670A0077 -:103B6000426164206677206C656E677468202575F5 -:103B70000A0042616420626F6172645F696420259B -:103B8000752073686F756C642062652025750A0066 -:103B90004261642066772064657363726970746F34 -:103BA00072206C656E6774682025750A0042616436 -:103BB0002061707020435243203078253038783AA5 -:103BC000307825303878203078253038783A307899 -:103BD000253038780A00476F6F64206669726D7708 -:103BE0006172650A0040A2E4F16468910600000079 -:103BF00000000000AD2D0008992D0008D52D00080B -:103C0000C12D0008CD2D0008B92D0008A52D0008F4 -:103C1000912D0008E12D00086D61696E0000000023 -:103C200069646C6500000000203C00084824002006 -:103C30008025002001000000A12F000800000000E6 -:103C4000A010002800000000FAAAAAAA500400242C -:103C5000BFFF000000770000000000001410AA0061 -:103C600000000000AAAAFAAA04005000FBFF00000E -:103C70000000000099770000000000000000000034 -:103C8000AAAAAAAA00000000FFFF0000000000008E -:103C9000000000000000000000000000AAAAAAAA7C -:103CA00000000000FFFF0000000000000000000016 -:103CB0000000000000000000AAAAAAAA000000005C -:103CC000FFFF0000000000000000000000000000F6 -:103CD00000000000AAAAAAAA00000000FFFF00003E -:103CE0000000000000000000E8C4FF7F01000000A9 -:103CF000F80300000000000000980300000000002E -:103D00006400000000000000FE2A0100D204000050 +:1000000000090020B5040008CD250008852500085A +:10001000AD25000885250008A5250008B7040008BF +:10002000B7040008B7040008B7040008C135000889 +:10003000B7040008B7040008B704000875430008B7 +:10004000B7040008B7040008B7040008B7040008A4 +:10005000B7040008B70400085940000885400008AC +:10006000B1400008DD40000809410008B70400085D +:10007000B7040008B7040008B7040008B704000874 +:10008000B7040008B7040008B704000839250008C1 +:100090006525000875250008B704000835410008EB +:1000A000B7040008B7040008B7040008B704000844 +:1000B000B7040008B7040008B7040008B704000834 +:1000C000B7040008B7040008B7040008B704000824 +:1000D000B7040008B7040008654500087945000822 +:1000E0009D410008B7040008B7040008B7040008E1 +:1000F000B7040008B7040008B7040008B7040008F4 +:10010000B7040008B7040008B7040008B7040008E3 +:10011000B7040008B7040008B7040008B7040008D3 +:10012000B7040008B7040008B7040008B7040008C3 +:10013000B7040008B7040008B7040008B7040008B3 +:10014000B7040008B7040008B7040008B7040008A3 +:10015000B7040008B7040008B7040008B704000893 +:10016000B7040008B7040008B7040008B704000883 +:10017000B7040008B7040008B7040008B704000873 +:10018000B7040008B7040008B7040008B704000863 +:10019000B7040008B7040008B7040008B704000853 +:1001A0002112000800000000000000000000000014 +:1001B00053B94AB9002908BF00281CBF4FF0FF31CE +:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA +:1001D00000F006F8DDF804E0DDE9022304B0704722 +:1001E0002DE9F047089D04468E46002B4DD18A42EA +:1001F000944669D9B2FA82F252B101FA02F3C2F11D +:10020000200120FA01F10CFA02FC41EA030E9440AD +:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE +:1002200016E341EA034306FB07F199420AD91CEBA6 +:10023000030306F1FF3080F01F81994240F21C81D8 +:10024000023E63445B1AA4B2B3FBF8F008FB103320 +:1002500044EA034400FB07F7A7420AD91CEB040455 +:1002600000F1FF3380F00A81A74240F20781644425 +:10027000023840EA0640E41B00261DB1D4400023AA +:10028000C5E900433146BDE8F0878B4209D9002D0E +:1002900000F0EF800026C5E9000130463146BDE898 +:1002A000F087B3FA83F6002E4AD18B4202D3824202 +:1002B00000F2F980841A61EB030301209E46002DB1 +:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 +:1002D000002A40F09280A1EB0C014FEA1C471FFA64 +:1002E0008CFE0126200CB1FBF7F307FB131140EA4B +:1002F00001410EFB03F0884208D91CEB010103F118 +:10030000FF3802D2884200F2CB804346091AA4B2D9 +:10031000B1FBF7F007FB101144EA01440EFB00FEAD +:10032000A64508D91CEB040400F1FF3102D2A64512 +:1003300000F2BB800846A4EB0E0440EA03409CE7B1 +:10034000C6F12007B34022FA07FC4CEA030C20FA5E +:1003500007F401FA06F31C43F9404FEA1C4900FA7E +:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB +:1003700040EA014108FB0EF0884202FA06F20BD96E +:100380001CEB010108F1FF3A80F08880884240F2BE +:100390008580A8F102086144091AA4B2B1FBF9F002 +:1003A00009FB101144EA014100FB0EFE8E4508D9FD +:1003B0001CEB010100F1FF346CD28E456AD9023882 +:1003C000614440EA0840A0FB0294A1EB0E01A14267 +:1003D000C846A64656D353D05DB1B3EB080261EBD5 +:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF +:1003F000007100263146BDE8F087C2F12003D840E5 +:100400000CFA02FC21FA03F3914001434FEA1C4726 +:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 +:10042000064300FB0EF69E4204FA02F408D91CEBC8 +:10043000030300F1FF382FD29E422DD902386344C6 +:100440009B1B89B2B3FBF7F607FB163341EA034166 +:1004500006FB0EF38B4208D91CEB010106F1FF38B5 +:1004600016D28B4214D9023E6144C91A46EA0046AC +:1004700038E72E46284605E70646E3E61846F8E63E +:100480004B45A9D2B9EB020864EB0C0E0138A3E787 +:100490004646EAE7204694E74046D1E7D0467BE768 +:1004A000023B614432E7304609E76444023842E7E0 +:1004B000704700BF02E000F000F8FEE772B6374870 +:1004C00080F30888364880F3098836483649086042 +:1004D00040F20000CCF200004EF63471CEF2000182 +:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 +:1004F000F0004EF68851CEF200010860BFF34F8F36 +:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 +:10051000CEF200010860062080F31488BFF36F8FCD +:1005200003F04EFC03F0C2FC4FF055301F491B4A4C +:1005300091423CBF41F8040BFAE71D49184A914229 +:100540003CBF41F8040BFAE71A491B4A1B4B9A427D +:100550003EBF51F8040B42F8040BF8E7002018499D +:10056000184A91423CBF41F8040BFAE703F02CFC17 +:1005700003F0D8FC144C154DAC4203DA54F8041BBC +:100580008847F9E700F042F8114C124DAC4203DA0B +:1005900054F8041B8847F9E703F014BC0009002055 +:1005A000001100200000000808ED00E0000100201C +:1005B00000090020704B0008001100207C11002071 +:1005C00080110020583C0020A0010008A401000870 +:1005D000A4010008A40100082DE9F04F2DED108AB8 +:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 +:1005F000002383F311882846A047002003F06AF9FE +:10060000FEE703F0CDF800DFFEE70000F8B500F0EC +:1006100019FE03F079FB074603F0C8FB05460028E6 +:1006200041D12D4B9F423ED001339F423ED02B4BB8 +:1006300027F0FF029A423CD1F8B200F03FFC2E4670 +:1006400042F2107400F040FC08B10024264601F08C +:10065000B1F890B3032000F045F80024264635B1E8 +:100660001F4B9F4203D003F099FB00242646002035 +:1006700003F054FB4FF090431B6913F0200322D08A +:100680000EB100F045F800F051FC00F0DDFD01F086 +:10069000A5FF0546CCB101F0A1FF401BA04214D933 +:1006A00000F036F8F3E72E460024CBE70446012697 +:1006B000C8E706464FF47A74C4E7002CCFD04FF455 +:1006C0007A740126CBE71C46DDE700F077FC0120B9 +:1006D00003F006F9DEE700BF010007B0000008B034 +:1006E000263A09B0084B187003280CD8DFE800F050 +:1006F00008050208022000F003BE022000F0F8BD49 +:10070000024B00225A6070478011002084110020A3 +:1007100038B501F04FF830B11F4B03221A701F4B50 +:1007200000225A6038BD1E4B1E4A19680131F9D0AB +:1007300004339342F9D11C4C194DD4F80428AA4231 +:10074000F0D31A4B9B6803F1006303F5D0439A4240 +:10075000E8D203F0F7FA03F009FB002000F08EFD69 +:100760000220FFF7BFFF124BDA690022DA61D96974 +:1007700099699A619B6972B64FF0E0233021C3F802 +:10078000085DD4F80038D4F8042881F311889D4618 +:1007900083F308881047C5E78011002084110020EA +:1007A00000680008206800080060000800110020B0 +:1007B00000100240094A136849F2690099B21B0C03 +:1007C00000FB01331360064B186844F2506182B29B +:1007D000000C01FB0200186080B270471411002069 +:1007E0001011002010B500211022044600F0A2FDD7 +:1007F000034B03CB206061601868A06010BD00BF90 +:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 +:100810006CAC40F2751207460D460EA80021C8F8D0 +:10082000001000F087FD4FF4C4720021204600F054 +:1008300081FD01F0D3FE254B4FF47A72B0FBF2F04C +:10084000186093E80700022384E807000DF5E970BB +:100850002382FFF7C7FF4FF603031D49238406A831 +:1008600004F0B6F8192384F832310DF2E32206AB16 +:100870000DF1300C1E4603CE6645106051603346C4 +:1008800002F10802F6D13378137041460122204666 +:1008900000F09CFD00230393AB7E029305F1190346 +:1008A000019380B20123CDE904800093E97E05A382 +:1008B000D3E90023384602F059FA0DF54E7DBDE824 +:1008C000F08100BF9E6AC421818A46EE8C1100200F +:1008D000E04900082DE9F0412C4C237ADAB080463B +:1008E0000D465BBB27A9284600F080FE074600287E +:1008F00042D19DF89D60C82E3ED801464FF4A662B5 +:10090000204600F017FD4FF48073C4F8F8314FF41F +:100910000073C4F80C334FF44073C4F820343246EB +:100920000DF19E0104F1090000F0F2FC26449DF84F +:100930009C30777223720BB9EB7E237281220021E7 +:1009400006AC27A800F0F6FC0122214627A800F0FB +:1009500089FE00230393AB7E029305F1190380B255 +:1009600001932823CDE904400093E97E05A3D3E950 +:100970000023404602F0FAF95AB0BDE8F08100BF0A +:10098000AFF3008026417272DF25D7B7A83200206E +:10099000F0B5254E4FF48A7505FB0065F1B096F869 +:1009A000D83085F8DC300024D822214685F8E8408C +:1009B0003AA800F0BFFC06F1090000F0B3FCD5F83E +:1009C000E4308DF8F000C2B206AF06F109010DF176 +:1009D000F100CDE93A3400F09BFC394601223AA8F7 +:1009E00000F06CFE80B2CDE9047008230127CDE948 +:1009F000023706F1D803019330230093317A0B4874 +:100A000007A3D3E9002302F0B1F9A04206DD01F00B +:100A1000E5FDC5F8E000384671B0F0BD2046FBE7C3 +:100A200078F6339F93CACD8DA8320020A4210020F0 +:100A30002DE9F0411D4D1E4E1E4F86B0284602F096 +:100A4000C1F9034658B30024CDE90344ADF814407E +:100A5000027B8DF8142099684068029403AA03C2AF +:100A60001B68DFF8548043F00043029301F0B8FDA7 +:100A7000821941F10003009402A9384601F07CF884 +:100A8000A04205DD284602F0A1F988F80040D5E72C +:100A900098F80030072B05D8013388F8003006B0ED +:100AA000BDE8F081014802F091F9F8E7A4210020A7 +:100AB00040420F00D8210020DD37002070B50D46E0 +:100AC00014461E4602F0AEF850B9022E10D1012C89 +:100AD0000ED112A3D3E90023C5E90023012007E0CA +:100AE000282C10D005D8012C09D0052C0FD00020BF +:100AF00070BD302CFBD10BA3D3E90023ECE70BA393 +:100B0000D3E90023E8E70BA3D3E90023E4E70BA331 +:100B1000D3E90023E0E700BFAFF30080401DA12030 +:100B200026812A0B78F6339F93CACD8D9E6AC42105 +:100B3000818A46EE26417272DF25D7B7F017304A18 +:100B400039059E5638B505460E4C0021013500F09A +:100B5000B7FBA4F82C55B4F82C0500F099FB78B13C +:100B6000B4F82C0500F0A4FB014648B9B4F82C05F4 +:100B700000F0A6FBB4F82C350133A4F82C35EAE7D5 +:100B800038BD00BFA832002010B50A4B0A4A1A60CF +:100B900003F5805393F860203AB9DC6D2CB1204600 +:100BA00000F082FE204603F053FEBDE810400348EB +:100BB00000F07ABED8210020384A000820320020F8 +:100BC0002DE9F04F8FB000AF05460C4602F02AF831 +:100BD000002849D1237E022B1BD1E38A012B18D197 +:100BE00001F0FCFC0646FFF7E5FD03464FF4C87034 +:100BF000DFF8C482B3FBF0F206F5167602FB103381 +:100C000016FA83F3C8F80030E37E33B9A34B002211 +:100C10001A703C37BD46BDE8F08F07F1240120462D +:100C200000F0A2FC0028F4D107F11400FFF7DAFD70 +:100C300097F8264007F11401224607F1270003F038 +:100C400051FE0028E2D10F2C08D8944B1C70D8F824 +:100C50000030A3F51673C8F80030DAE797F82410CF +:100C6000284601F0D7FFD4E7E38A282B2BD010D8F1 +:100C7000012B23D0052BCCD1BFF34F8F8849894B53 +:100C8000CA6802F4E0621343CB60BFF34F8F00BF2A +:100C9000FDE7302BBDD1844EE17E327A9142B8D14E +:100CA000607E3146002291F8DC50854200F0A5803C +:100CB0000132042A01F58A71F5D1AAE721462846B6 +:100CC000FFF7A0FDA5E721462846FFF703FEA0E7B2 +:100CD000B2F8EC507B6005F103094FEA99094FEA3D +:100CE0008902D11DC908A8EBC1039D46EB4600212E +:100CF000584600F01FFB04F1EE012A4631445846E5 +:100D000000F006FB7B6813B9012000F0B7FA96F8F3 +:100D1000D20000F0BDFA044630B9307200F0D8FAC3 +:100D2000204600F0ABFAB1E0D6F8D4203AB996F8F4 +:100D3000D200B6F82C25824201D8FFF703FFD6F87F +:100D4000D4202A44944208D296F8D200B6F82C2532 +:100D50000130824201D8FFF7F5FE70685FFA89F230 +:100D6000594600F0EFFA08B9C54679E0726896F87E +:100D7000D2002A447260D6F8D42005EB0209C6F8E6 +:100D8000D49000F085FA814509D396F8D220D6F8A0 +:100D9000D4000132001B86F8D220C6F8D400FF2D03 +:100DA0000FD80024347200F093FA204600F066FA5F +:100DB00000F000FD3D4B188108B9FFF7A9FCC546BE +:100DC00027E7BB6896F8D9000AFB0362FB68D2F8F4 +:100DD000E41082F8E83001F58061C2F8E030C2F832 +:100DE000E410FFF7D5FDFFF723FE96F8D920013276 +:100DF00002F0030286F8D920B6E74FF48A7A0AFB9C +:100E000002F505F1EA013144204600F083FCF86068 +:100E100000287FF4FEAE3544012285F8E82001F079 +:100E2000DDFBD5F8E020D6ED007ADFED216A801AEF +:100E3000192838BF192040F6B832904228BF104612 +:100E4000B8EE677A07EE900AF8EEE77A67EEA67AD0 +:100E5000DFED186AE7EE267AFCEEE77AC6ED007A57 +:100E600096F8D930BB60BA6873680AFB02F432198D +:100E700092F8E81059B1D2F8E4108B42E8463FF4FA +:100E800027AF002182F8E810C2F8E010C546736869 +:100E9000064A9B0A01331381BBE600BF9D21002057 +:100EA00000ED00E00400FA05A83200208C110020BB +:100EB000CDCCCC3D6666663FA0210020014B18706A +:100EC000704700BF9811002038B54FF00054134B05 +:100ED00022689A4220D1124B627D12481A70237DFB +:100EE00003724FF48073C0F8F8314FF40073C0F808 +:100EF0000C3300254FF44073C0F820340A49C0F881 +:100F0000E450C922093000F003FAE02229462046C5 +:100F100000F010FA012038BD0020FCE79AAD44C56E +:100F200098110020A83200201600002037B500F0EC +:100F300041FC194D194928810223012218486B717F +:100F400001F0EAF900230193164B17490093174863 +:100F5000174B4FF4805201F035FE164B197811B142 +:100F6000124801F057FE01F039FB0446FFF722FC5E +:100F70004FF4C873B0FBF3F202FB130304F51670D1 +:100F800010FA83F00C4B186002F010FF08B10F2329 +:100F90002B8103B030BD00BF8C11002040420F00F8 +:100FA000D8210020BD0A00089C110020A4210020A7 +:100FB000C10B000898110020A02100202DE9F04F5E +:100FC0002DED028B8EA7D7E900670FF23C29D9E9F6 +:100FD0000089864C95B00DAD9FED828BFFF728FD03 +:100FE000DFF82CB200230C93ADF83C300D936B600E +:100FF00000230DF125028DED008B4FF0010A09A9A8 +:1010000058468DF825308DF824A001F035F99DF86B +:1010100024200023002A40F0AB80204601F002FE8D +:101020000546002847D1DFF8ECB101F0D7FADBF82C +:10103000003098423FD301F0D1FA0790FFF7BAFB96 +:10104000079A4FF4C873B0FBF3F101FB130302F5E9 +:10105000167010FA83F0CBF80000DFF8BCB19BF8F3 +:1010600000100791002914BF2B46534610A88DF895 +:101070003030FFF7B7FB0799C1F11002D2B2062A50 +:1010800010AB28BF062219440DF13100079200F081 +:101090003FF9079A0CAB0393182302930132544B88 +:1010A000D2B2CDE900A304923B463246204601F07D +:1010B000FFFD8BF8005001F091FA4E4A4E4D136837 +:1010C000C31AB3F57A7F32D3106001F089FA024671 +:1010D0000B46204601F084FE204601F0A3FD30B30C +:1010E0002B7ADFF838A1002B14BF032302238AF8E0 +:1010F000053001F073FA0DF1400B4FF47A730122C1 +:10110000B0FBF3F05946CAF80000504600F004FA6C +:1011100018230293394B019380B240F25513CDE965 +:1011200003B0009342464B46204601F0C1FD2B7AA6 +:10113000CBB101F053FA4FF0000A83464FF48A72A4 +:1011400095F8D900504400F0030002FB005393F8D7 +:10115000E81089B30AF1010ABAF1040FF0D12B7A31 +:10116000002B7FF438AF15B0BDEC028BBDE8F08FDB +:101170004FF0904110A84A6982F040024A61194636 +:10118000102200F0D7F80DF126030AAA0CA9584640 +:1011900000F0F0FD95E8030011AB83E803009DF833 +:1011A0003C308DF84C300C9B109310A9DDE90A23DC +:1011B000204601F0E9FF1BE7D3F8E01049B12B68A6 +:1011C000FA2B38BFFA23ABEB01010533B1EB430F28 +:1011D000C0D3FFF7DDFB4FF48A720028BAD1BEE717 +:1011E000AFF300800000000000000000A4210020F8 +:1011F0009C210020D8370020A8320020DC370020B6 +:10120000401DA12026812A0BF1C6A7C1D068080F76 +:10121000D8210020A02100209D2100208C11002039 +:1012200008B5054800F040FEBDE80840034A0449FF +:10123000002003F007BB00BFD82100201838002091 +:10124000890B00087047000070B502F013FC094ECE +:10125000094D3080002428683388834208D902F081 +:1012600005FC2B6804440133B4F5D04F2B60F2D356 +:1012700070BD00BF0C380020E037002002F086BCB3 +:1012800000F10060920000F5D04002F02DBC00009B +:10129000054B1A68054B1B889B1A834202D91044E0 +:1012A00002F0E4BB00207047E03700200C3800203B +:1012B000024B1B68184402F0DFBB00BFE037002080 +:1012C000024B1B68184402F0E9BB00BFE037002066 +:1012D000064991F8243033B10023086A81F824309C +:1012E0000822FFF7CDBF0120704700BFE437002080 +:1012F000022802BF4FF0904340229A6170470000DD +:10130000022802BF4FF090434FF480029A61704769 +:1013100010B50023934203D0CC5CC4540133F9E7E9 +:1013200010BD000003460246D01A12F9011B002925 +:10133000FAD1704702440346934202D003F8011BDE +:10134000FAE770472DE9F8431F4D144695F824201D +:101350000746884652BBDFF870909CB395F824305E +:101360002BB92022FF2148462F62FFF7E3FF95F8B3 +:101370002400C0F10802A24228BF2246D6B241464C +:10138000920005EB8000FFF7C3FF95F82430A41B03 +:101390001E44F6B2082E17449044E4B285F8246047 +:1013A000DBD1FFF795FF0028D7D108E02B6A03EBCC +:1013B00082038342CFD0FFF78BFF0028CBD10020E0 +:1013C000BDE8F8830120FBE7E43700202DE9F04772 +:1013D0000D46044600219046284640F27912FFF758 +:1013E000A9FF234620220021284601F06FFE231D7D +:1013F00002222021284601F069FE631D03222221DA +:10140000284601F063FEA31D03222521284601F092 +:101410005DFE04F1080310222821284601F056FE43 +:1014200004F1100308223821284601F04FFE04F190 +:10143000110308224021284601F048FE04F112035E +:1014400008224821284601F041FE04F1140320221D +:101450005021284601F03AFE04F118034022702181 +:10146000284601F033FE04F120030822B02128466B +:1014700001F02CFE04F121030822B821284601F0D6 +:1014800025FE04F12207C0263B46314608222846A5 +:10149000083601F01BFEB6F5A07F07F10107F3D176 +:1014A00004F1320308223146284601F00FFE0027DE +:1014B00004F1330A94F832304FEAC7099F4209F524 +:1014C000A47615D3B8F1000F08D1314604F599730D +:1014D0000722284601F0FAFD09F24F16274694F834 +:1014E00032213B1B93420CD3F01DC008BDE8F087AE +:1014F0000AEB070308223146284601F0E7FD0137D1 +:10150000D8E707F2331331460822284601F0DEFD02 +:1015100008360137E3E7000013B50446084600210A +:1015200001602346C0F803102022019001F0CEFD97 +:101530000198231D0222202101F0C8FD0198631D9E +:101540000322222101F0C2FD0198A31D03222521BF +:1015500001F0BCFD019804F108031022282101F0DC +:10156000B5FD072002B010BDF7B50023047F009140 +:101570000E4607221946054601F06CFC731C0093C9 +:10158000012200230721284601F064FCC4B9B31CE2 +:101590000093052223460821284601F05BFC0D2418 +:1015A0003746B278BB1B934211D32B7FA88A0734EE +:1015B000E408BBB9844294BF0020012003B0F0BD11 +:1015C000AB8ADB00083BDB08B3700824E8E7FB1CB0 +:1015D0000093214600230822284601F03BFC0834F2 +:1015E0000137DEE7201A18BF0120E7E7F7B500232F +:1015F000047F00910E4608221946054601F02AFC98 +:10160000731CC4B90822009311462346284601F0F2 +:1016100021FC1024012372785F1C013B934211D3FB +:101620002B7FA88A0734E408BBB9844294BF00200A +:10163000012003B0F0BDAB8ADB00083BDB08737010 +:101640000824E7E7F31900932146002308222846DF +:1016500001F000FC08343B46DDE7201A18BF0120EA +:10166000E7E70000F8B50E46054614460021812242 +:101670003046FFF75FFE2B4608220021304601F07E +:1016800025FD7CB96B1C07220821304601F01EFDA8 +:101690000F2401236A785F1C013B934204D3E01DB1 +:1016A000C008F8BD0824F4E7EB19214608223046AB +:1016B00001F00CFD08343B46ECE70000F8B50E469F +:1016C000054614460021CE223046FFF733FE2B4656 +:1016D00028220021304601F0F9FC7CB905F108030D +:1016E00008222821304601F0F1FC30242F462A7AC6 +:1016F0007B1B934204D3E01DC008F8BD2824F5E706 +:1017000007F1090321460822304601F0DFFC0834C6 +:101710000137ECE7F7B5047F00910E460123102254 +:101720000021054601F096FBC4B9B31C00930922C1 +:1017300023461021284601F08DFB19243746728874 +:10174000BB1B9A4211D82B7FA88A0734E408BBB987 +:10175000844294BF0020012003B0F0BDAB8ADB00BF +:10176000103BDB0873801024E8E73B1D0093214603 +:1017700000230822284601F06DFB08340137DEE71C +:10178000201A18BF0120E7E730B5094D0A449142FD +:101790000DD011F8013B5840082340F30004013BF1 +:1017A0002C4013F0FF0384EA5000F6D1EFE730BD80 +:1017B0002083B8EDF7B5364A106851686B4603C30D +:1017C0006A4634493448082303F09CF8044690BB29 +:1017D0000A25324A106851686B4603C36A4630498D +:1017E0002D48082303F08EF80446002847D00369EB +:1017F000B3F5663F43D8B0F86620B2F57E7F3ED1A0 +:10180000284A024402F15C018B4238D35C3B2249F6 +:1018100000209E1AFFF7B8FF3246074604F1640124 +:101820000020FFF7B1FFA3689F4228D1E3689842E8 +:1018300008BF002523E00369B3F5663F26D8428B35 +:10184000B2F57E7F20D1174A024402F110018B428B +:1018500018D3103B104900209D1AFFF795FF2A4628 +:10186000064604F118010020FFF78EFFA3689E4290 +:1018700002D1E368984201D00D25AAE70025284649 +:1018800003B0F0BD1025A4E70C25A2E70B25A0E7C7 +:10189000FC490008DC97030000680008054A0008BE +:1018A000909703000898FFF710B5037C044613B91E +:1018B000006803F00FF8204610BD00000023BFF3BE +:1018C0005B8FC360BFF35B8FBFF35B8F8360BFF33E +:1018D0005B8F7047BFF35B8F0068BFF35B8F704710 +:1018E00070B505460C30FFF7F5FF05F10806044614 +:1018F0003046FFF7EFFFA04206D930466D68FFF78C +:10190000E9FF2544281A70BD3046FFF7E3FF201A8F +:10191000F9E7000070B50546406898B105F1080088 +:10192000FFF7D8FF05F10C0604463046FFF7D2FF5B +:101930008442304694BF6D680025FFF7CBFF013C21 +:101940002C44201A70BD000038B50C460546FFF740 +:10195000C7FFA04210D305F10800FFF7BBFF044406 +:101960006868B4FBF0F100FB1144BFF35B8F01200A +:10197000AC60BFF35B8F38BD0020FCE72DE9F04180 +:10198000144607460D46FFF7C5FF844228BF0446AC +:10199000D4B1B84658F80C6B4046FFF79BFF304473 +:1019A000286040467E68FFF795FF331A9C4203D8B3 +:1019B0006C600120BDE8F0816B60A41B3B68AB60EC +:1019C0002044E8600220F5E72046F3E738B50C46EE +:1019D0000546FFF79FFFA04210D305F10C00FFF76B +:1019E00079FF04446868B4FBF0F100FB1144BFF3D5 +:1019F0005B8F0120EC60BFF35B8F38BD0020FCE7FC +:101A00002DE9FF41884669460746FFF7B7FF6C4658 +:101A100006B204EBC6060025B44209D0626820680D +:101A200008EB0501FFF774FC636808341D44F3E715 +:101A300029463846FFF7CAFF284604B0BDE8F081C2 +:101A4000F8B505460C300F46FFF744FF05F10806D0 +:101A500004463046FFF73EFFA042304688BF6C6820 +:101A6000FFF738FF201A386020B130462C68FFF7A6 +:101A700031FF2044F8BD000073B5144606460D46FC +:101A8000FFF72EFF844228BF04460190DCB101A974 +:101A90003046FFF7D5FF019B33B93268C5E9023301 +:101AA000C5E9002401200CE09C4238BF0194286065 +:101AB000019868608442F5D93368AB60241AEC6001 +:101AC000022002B070BD2046FBE700002DE9FF4177 +:101AD0000F466946FFF7D0FF6C4600B204EBC00525 +:101AE0000026AC4209D0D4F8048054F8081BB81979 +:101AF0004246FFF70DFC4644F3E7304604B0BDE82C +:101B0000F081000038B50546FFF7E0FF04460146C6 +:101B10002846FFF719FF204638BD0000302383F325 +:101B2000118862B670470000002383F3118862B603 +:101B30007047000010B4026854681A4623465DF8E6 +:101B4000044B184701207047002070470020704761 +:101B500070470000002070470E20704700F580504D +:101B600090F8C800C0F340007047000000F58050B6 +:101B700090F9C90070470000F7B50C68BDF82070F7 +:101B800014F000541E466FD10B7B082B6CD8FFF766 +:101B9000C5FF4569AB685B010CD4AB681B0108D479 +:101BA000AC6814F080545DD1FFF7BEFF204603B04F +:101BB000F0BD01240B6804F1180C002BB8BFDB004A +:101BC0004FEA0C1CB4BF43F004035B0545F80C302E +:101BD0000B680FFA84FC13F0804F18BF05EB0C1E46 +:101BE00005EB0C1C1EBFDEF8803143F00203CEF87B +:101BF00080310B7BCCF8843105EB04158B68C5F87C +:101C00008C314B68C5F88831DCF8803143F0010332 +:101C1000CCF8803100EB441541F268031D4403EB1E +:101C200044130344C5E9002608330D4601F10C0CAA +:101C300055F804EB43F804EB6545F9D184342D885D +:101C40001D8000EB441407F00303257925F00B05F4 +:101C50002B432371FFF768FF0097334600F0E0FC49 +:101C60000120A4E70224A5E74FF0FF309FE7000022 +:101C700013B500F580540191E06DFFF74BFE1F286E +:101C80000AD90199E06D2022FFF7BAFEA0F12003E6 +:101C90005842584102B010BD0020FBE708B500F5DE +:101CA0008050FFF73BFFC06DFFF708FEBDE808401E +:101CB000FFF73ABF00220260828142608260704773 +:101CC00010B500220023C0E900230023044603814D +:101CD0000C30FFF7EFFF204610BD0000F0B50546C1 +:101CE00000F580500C4690F8C83013F0040FC3F391 +:101CF000800108BF114661F3820304F1840680F875 +:101D0000C83005EB461389B01B79D8072ED57AB3B6 +:101D100019072DD46846FFF7D3FF05EB441303F5ED +:101D2000835303F1180703AA10331868596814463F +:101D300003C40833BB422246F7D1186820609B8851 +:101D4000A380DDE90E23CDE900230123ADF808309F +:101D50002B686946DB6B2846984705EB46152B79BF +:101D60001A075CBF43F008032B7101E0002AF4D18D +:101D700009B0F0BD2DE9F047074688B007F580545B +:101D800068469A468846FFF7C9FE9146FFF798FFD6 +:101D9000E06DFFF7A5FD1F2829D9E06D20226946D7 +:101DA000FFF7B0FE202822D103AD444605AB2E46F6 +:101DB00003CE9E4220606160354604F10804F6D1EE +:101DC00030682060B388A380DDE90023C9E90023DF +:101DD000BDF80830AAF80030FFF7A6FE4A46534681 +:101DE0004146384608B0BDE8F04700F007BCFFF7B1 +:101DF0009BFE002008B0BDE8F08700002DE9F84FF9 +:101E00000023C0E90133254B044640F8183B0F4638 +:101E1000FFF750FF04F12800FFF752FF04F14808D4 +:101E200004F582554646083530462036FFF748FF10 +:101E3000AE42F9D104F580554FF480534FF00009BC +:101E4000C5E91339C5F848800123EE6504F58758C4 +:101E500004F58456C5F8549085F8583085F86030FC +:101E6000083608F108084FF0000A4FF0000B46E969 +:101E700008ABA6F11800FFF71DFF203646F8289C96 +:101E80004645F4D185F8C97017B1054800F0A0FBAC +:101E9000044B63612046BDE8F88F00BF384A000854 +:101EA000104A00080064004010B5044B197804463D +:101EB0004A1C1A70FFF7A2FF204610BD14380020FC +:101EC0002DE9F047002950D0294B2A4FB7FBF1F5F7 +:101ED00099428CBF0A231123581EB5FBF3FC03FB68 +:101EE0001C53C4B22BB102280346F5D80020BDE82C +:101EF000F0870CF1FF36B6F5806FF7D2C4EBC40E55 +:101F00000EF103034FEAE309C3F3C703A4EB03088D +:101F100009F1010A4FF47A755FFA88F009FB05555B +:101F20005AFA88F8B5FBF8F5B5F5617FC1BF0EF137 +:101F3000FF33C3F3C703E01AC0B25C1C50FA84F449 +:101F40000CFB04F4B7FBF4F4A142CFD1013BDBB2AC +:101F50000F2BCBD80138C0B20728C7D80021107189 +:101F600016809170D3700120C1E70846BFE700BF1B +:101F70003F420F000051250270B505460E464FF452 +:101F80007A746B695B6803F00103B3424FF00100A0 +:101F900004D001F0A5FC013CF3D1204670BD000047 +:101FA00030B54269936913F0700F16D000230B4CC3 +:101FB000936103F1840200EB421211794D0709D5B8 +:101FC000890707D5416954F823508D60117941F094 +:101FD000040111710133032BEBD130BD244A0008F9 +:101FE00073B51D46436916469A68D207044609D55B +:101FF0009A6801219960C2F34002CDE90065002191 +:10200000FFF76CFE63699A68D1050BD59A684FF4A7 +:1020100080719960C2F34022CDE90065012120461C +:10202000FFF75CFE63699A68D2030BD59A684FF498 +:1020300080319960C2F34042CDE90065022120461B +:10204000FFF74CFE204602B0BDE87040FFF7A8BF86 +:10205000F8B50446466900296CD106F10C073868CA +:1020600080076AD006EB01153868D5F8B00110F08A +:10207000040FD5F8B0011ABFC00840F00040400D71 +:10208000A061D5F8B0C11CF0020F1CBF40F0804029 +:10209000A061D5F8B40106EB011100F00F0084F83F +:1020A0002400D1F8B8012077D1F8B801000A607790 +:1020B000D1F8B801000CA077D1F8B801000EE07794 +:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 +:1020D0002100D1F8BC01000C84F82200D1F8BC1119 +:1020E000090E84F823103821396004F1340004F11A +:1020F000180104F1240551F8046B40F8046BA9425F +:10210000F9D109880180C4E90A23214600232386E6 +:1021100051F8283B2046DB6B984704F58052204657 +:1021200092F8C83043F0040382F8C830BDE8F840A4 +:10213000FFF736BF06F1100791E7F8BD10B504466A +:1021400000F04EFA02460B4652EA030102D0013A71 +:1021500063F100030449086820B12146BDE810403E +:10216000FFF776BF10BD00BF10380020F8B500F5AE +:1021700083511E46FFF7D2FCDFF844C0083100242B +:1021800004F1840500EB45152B795F070ED4DB06BF +:102190000CD5D1E900739742B34107D243695CF88B +:1021A00024709F602B7943F004032B710134032CBE +:1021B00001F12001E4D1BDE8F840FFF7B5BC00BF54 +:1021C000244A000808B5FFF7A9FCFFF7E9FEBDE8BF +:1021D0000840FFF7A9BC0000F8B5436905469868B8 +:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C +:1021F00095FC05F583541034002606F1840305EBA5 +:1022000043131B791A0706D50136032E04F1200467 +:10221000F3D1012007E05B07F6D42146384600F0F1 +:1022200039FA0028F0D1FFF77FFCF8BD0120FCE768 +:1022300000F5805008B5FFF771FCC06DFFF750FB4B +:10224000FFF772FC43090CBF0120002008BD00000D +:10225000F8B51D46002313700F4606461446FFF7D7 +:10226000E7FF80F00100387025B129463046FFF7BE +:10227000B3FF2070F8BD00002DE9B8410C461546AB +:102280001F46804600F0ACF90B462178024609B99A +:10229000287850B14046FFF769FFFFF793FF3B46B0 +:1022A0002A462146FFF7D4FF0120BDE8B88100008F +:1022B00010B5FFF733FC174BDA6942F00072DA61B0 +:1022C0001A6942F000721A611A6900F5805422F00E +:1022D00000721A61FFF728FC94F8C830DB0718D4A5 +:1022E000B9B103211320FFF719FC01F0C7F903214D +:1022F000142001F0C3F90321152001F0BFF994F86F +:10230000C83043F0010384F8C830BDE81040FFF73F +:102310000BBC10BD001002402DE9F04700F58055C0 +:1023200088B095F8C930012B0446884616467FD8F8 +:10233000804F57F823200AB947F82300D7F800A0A8 +:10234000C4F80C802674BAF1000F63D095F8C93038 +:10235000012B6FD001212046FFF7AAFFFFF7DEFB1C +:102360006269136823F0020313606269136843F023 +:1023700001031360636900275F6101212046FFF7B5 +:10238000D3FBFFF7F9FD002800F09580E86DFFF71B +:1023900095FA04F58359BA4609F10809202200216B +:1023A0006846FEF7C7FF02A8FFF784FCCDF818A027 +:1023B0006A4609EB07030DF1180E9446BCE80300CA +:1023C000F44518605960624603F10803F5D1DCF862 +:1023D0000000186020379CF804201A71602FDDD1AE +:1023E00095F8C8306FF38203002785F8C8306A4635 +:1023F00041462046ADF80070ADF802708DF80470CB +:10240000FFF75EFD636948BB4FF400421A6008B0F5 +:10241000BDE8F08741F2D00002F01CFA814610B10D +:102420005146FFF7EBFCC7F80090B9F1000F8DD1D2 +:102430000020ECE7386803681B6B984701460028CA +:1024400088D13868FFF734FF3868036832465B6824 +:102450004146984700287FF47DAFE9E761221A6082 +:102460009DF802309DF803201B06120402F470222E +:1024700003F040731343BDF80020C2F30902134375 +:102480009DF804201205022E02F4E0020CBF4FF06A +:1024900000410021134362690B43D3616369132236 +:1024A0005A616269136823F00103136039462046BC +:1024B000FFF762FD08B96369A6E795F8C93093BBD9 +:1024C0006169D1F8002242F00102C1F8002261697D +:1024D000D1F8002222F47C5222F00E02C1F8002230 +:1024E0006169D1F8002242F46062C1F80022626999 +:1024F000C2F814326269C2F80432626941F6FF71AF +:10250000C2F80C126269C2F840326269C2F8443201 +:1025100063690122C3F81C226269D2F8003223F0F9 +:102520000103C2F8003295F8C83043F0020385F881 +:10253000C8306CE71038002008B500F051F850EAB8 +:102540000103024602D0421E61F10001044B1868EB +:1025500010B10B46FFF744FDBDE8084001F064B838 +:102560001038002008B50020FFF7E8FDBDE808405E +:1025700001F05AB808B50120FFF7E0FDBDE80840BA +:1025800001F052B800B59BB0EFF3098168226846AC +:10259000FEF7BEFEEFF30583014B9B6BFEE700BF2A +:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF +:1025B000EFF3098168226846FEF7AAFEEFF3058370 +:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 +:1025D0000FB408B5029801F019F9FEE701F02EBB1F +:1025E00001F004BB13B56C4684E80600031D94E8B3 +:1025F000030083E80500012002B010BD73B58568B3 +:10260000019155B11B885B0707D4D0E900369B6B5D +:102610009847019AC1B23046A847012002B070BD68 +:10262000F0B5866889B005460C465EB1BDF8383015 +:102630005B070AD4D0E900379B6B98472246C1B2AA +:102640003846B047012009B0F0BD00220023CDE993 +:1026500000230023ADF808300A4603AB01F1080659 +:10266000106851681C4603C40832B2422346F7D1B1 +:10267000106820609288A280FFF7B2FF0423ADF8B3 +:1026800008302B68CDE90001DB6B69462846984786 +:10269000D8E7000030B503680968DD0FB5EBD17FDE +:1026A00023F0604421F060424FEAD1700BD0002B40 +:1026B000B8BFA40C0029B8BF920C944202D034BF1A +:1026C0000120002030BD944205D1C1F38070C3F3D6 +:1026D00080738342F6D194422CBF00200120F1E7A1 +:1026E0002DE9F041456A15B94162BDE8F0814B68BA +:1026F00023F06047C3F38A464FEAD37EC3F3807862 +:1027000016EA230638BF3E46AC462B465A68BEEB57 +:10271000D27F22F060440AD0002A18DAA40CB44216 +:1027200017D19D420FD10D60DEE71346EEE7A742B9 +:1027300007D102F08044C2F3807242450BD054B1FD +:10274000EFE708D2EDE7CCF800100B60CDE7B4421C +:1027500001D0B442E5D81A689C46002AE5D1196038 +:10276000C3E700002DE9F047089D01F007044FEA98 +:10277000D508224405F0070500EBD1004FF47F494E +:10278000944201D1BDE8F08704F0070705F0070A7D +:1027900057453E4638BF5646C6F10806111B8E42C5 +:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 +:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 +:1027C00047FA0AF739408CEA010C03F80EC034448A +:1027D0003544D5E780EA0120082341F2210201B205 +:1027E0004000002980B203F1FF33B8BF504013F01E +:1027F000FF03F4D17047000038B50C468D18A54290 +:1028000000D138BD14F8011BFFF7E4FFF7E7000023 +:1028100042684AB1136843604389818901339BB29E +:102820009942438138BF83811046704770B588B0A4 +:10283000202204460D4668460021FEF77BFD204617 +:102840000495FFF7E5FF024658B16B46054608AE12 +:102850001C4603CCB44228606960234605F1080594 +:10286000F6D1104608B070BD082817D909280CD039 +:102870000A280CD00B280CD00C280CD00D280CD01A +:102880000E2814BF4020302070470C2070471020C5 +:1028900070471420704718207047202070470000B0 +:1028A000082817D90C280CD910280CD914280CD9B1 +:1028B00018280CD920280CD930288CBF0F200E20C6 +:1028C0007047092070470A2070470B2070470C2082 +:1028D00070470D20704700002DE9F843078C072F43 +:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 +:1028F0002006A5F1200029FA05F108FA06F628FAC3 +:1029000000F031430143C9B21846FFF763FF0835B1 +:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 +:102920006BBF4FF6FF70BDE8F883000010B54B6831 +:1029300023B9CA8A63F30902CA8210BD04691A68FE +:102940001C600361C38A013BC3824A60EFE7000059 +:102950002DE9F84F1D46CB8A0F46C3F3090105291F +:10296000814692460B4630D00020AAB207F11A04E5 +:102970009EB2042E1FFA80F80FD8904503F1010390 +:1029800006D3FB8A0A4462F30903FB8201201AE0A2 +:102990001AF80060E6540130EAE79045F1D2A1F15F +:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 +:1029B0008BF6002C45D14846FFF72AFF044638B96C +:1029C00078606FF00200BDE8F88F4FF00008E6E78E +:1029D000002606607860ADB24FF0000B454510D977 +:1029E0000AEB0803221D13F8011B9155B1B208F13F +:1029F00001081B291FFA88F82BD0454506F101066E +:102A0000F1D8FB8AC3F30902154465F30903BCE757 +:102A1000013292B21C462368002BF9D16B1F0B4484 +:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 +:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 +:102A4000BFE70122E7E7C0F800B05E462060044619 +:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 +:102A6000AFE7C0F800B0002620600446B6E70000DB +:102A70002DE9F04F2DED028B1C4683B05B6901926E +:102A800007468846002B00F09A80238C2BB1E26920 +:102A9000002A00F09480072B35D807F10C00FFF7CF +:102AA000B7FE054638B96FF00205284603B0BDEC05 +:102AB000028BBDE8F08F14220021FEF73BFC228C34 +:102AC000E16905F10800FEF723FC208C013080B29B +:102AD000FFF7E6FEFFF7C8FE013880B22084013020 +:102AE00028746369228C1B782A4403F01F0363F067 +:102AF0003F0348F000411372384669602946FFF7EA +:102B0000EFFD0125D1E700F10C034FF0000908EEBD +:102B1000103A4FF0800A4E464D4618EE100AFFF765 +:102B200077FE83460028BED014220021FEF702FC67 +:102B3000002E3AD1019BABF8083002220BF1080EAF +:102B40001FFA82FC0CF10100BCF1060F218C80B24F +:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 +:102B60001278013802F01F028E4208BF4FF0400A6F +:102B700042EA49121BFA80F14AEA020A013048F09F +:102B8000004281F808A08BF81000CBF804205946C9 +:102B90003846FFF7A5FD238C0135B3422DB289F0ED +:102BA00001094FF0000AB8D17FE70022C6E7E169CA +:102BB000895D0EF802100136B6B20132C0E76FF03F +:102BC000010572E7F8B515460E463022002104468D +:102BD0001F46FEF7AFFB069B6360B5F5001F079B22 +:102BE000A76034BF6A094FF6FF72A36297B2E6612D +:102BF00004F1100000239A4206D800230360A78244 +:102C0000E3822383E360F8BD06600133304620365B +:102C1000F1E7000003781BB94BB2002BC8BF01706D +:102C20007047000000787047F8B50C46C969074640 +:102C300011B9238C002B37D1257E1F2D34D838783D +:102C400028BB228C072A2CD8268A36F003032BD1E6 +:102C50004FF6FF70FFF7D0FD20F001003102400475 +:102C600041EA0561400C41EA40254FF6FF722346D8 +:102C700029463846FFF7FCFE002807DD6269137815 +:102C80000133DBB21F2B88BF00231370F8BD218AEC +:102C90002D0645EA012505432046FFF71DFE0246A5 +:102CA000E5E76FF00300F1E76FF00100EEE70000E9 +:102CB00070B58AB0044616460021282268461D4693 +:102CC000FEF738FBBDF83830ADF810300F9B059398 +:102CD0009DF840308DF81830119B07936946BDF878 +:102CE0004830ADF820302046CDE90265FFF79CFF63 +:102CF0000AB070BD2DE9F041D36905460C46164671 +:102D00000BB9138C5BBB377E1F2F28D895F800803A +:102D1000B8F1000F26D03046FFF7DEFD33782102F0 +:102D200041EAC33141EA0801338A41EA076141EAD5 +:102D300003410246334641F080012846FFF798FEE2 +:102D400000280ADD3378012B07D17269137801332B +:102D5000DBB21F2B88BF00231370BDE8F0816FF03A +:102D60000100FAE76FF00300F7E70000F0B58BB061 +:102D700004460D4617460021282268461E46FEF7E7 +:102D8000D9FA9DF84C305A1E534253418DF8003009 +:102D90009DF84030ADF81030119B05939DF84830F8 +:102DA0008DF81830149B07936A46BDF85430ADF87F +:102DB000203029462046CDE90276FFF79BFF0BB075 +:102DC000F0BD0000406A00B104307047436A1A68E1 +:102DD000426202691A600361C38A013BC382704781 +:102DE0002DE9F041D0F82080194E14461D46414689 +:102DF000002709B9BDE8F081D1E90223A21A65EBE9 +:102E00000303964277EB03031ED2036A8B420DD174 +:102E1000FFF78CFD036A1B68036203690B60C38ABA +:102E20000161016A013BC3828846E2E7FFF77EFD4C +:102E30000B68C8F8003003690B60C38A0161013B6D +:102E4000C382D8F80010D4E788460968D1E700BFEC +:102E500080841E002DE9F04F8BB00D46DDF85090B8 +:102E600014469B468046002800F01981B9F1000FF6 +:102E700000F01581531E3F2B00F21181012A03D16E +:102E8000BBF1000F40F00B810023CDE90833B8F807 +:102E90001430B5EBC30F4FEAC30703D300200BB0C8 +:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A +:102EB000FFB227461BB9D8F81030002B7AD0272D47 +:102EC0004ED8C5F12806B7424FF000032CBFF6B22A +:102ED0003E4600932946D8F8080008AB3246FFF773 +:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 +:102EF00003F10053053BDB000493D8F80C30039337 +:102F00002821039B13B1BAF1000F2CD1D8F810007F +:102F100040B1BAF1000F05D0009608AB5246691ACD +:102F2000FFF720FC38B2002FB8D066070AD00AABF2 +:102F300003EBD401624211F8083C02F0070213418E +:102F400001F8083C082C3CD9102C40F2B580202C0C +:102F500040F2B780BBF1000F00F09C80082334E002 +:102F6000BA460026C2E7049BE02B28BFE023069365 +:102F70000B44AB42059314D95A1B03980096924513 +:102F800034BF5246D2B2691A08AB04300792FFF739 +:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 +:102FA0008AFA049B069A05999B1A0493039B1B6853 +:102FB0000393A6E70093D8F8080008AB3A462946E1 +:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD +:102FD000082C12D89DF82030621E23FA02F2D50781 +:102FE00006D54FF0FF3202FA04F423438DF8203067 +:102FF0009DF8203089F8003051E7102C12D8BDF828 +:103000002030621E23FA02F2D10706D54FF0FF32BC +:1030100002FA04F42343ADF82030BDF82030A9F8BB +:1030200000303CE7202C0FD80899631E21FA03F3E7 +:10303000DA0705D54FF0FF3202FA04F40C43089486 +:10304000089BC9F800302AE7402C2BD0DDE9086541 +:10305000611EC4F12102A4F1210326FA01F105FA4F +:1030600002F225FA03F311431943CB0712D50122CB +:10307000A4F12003C4F1200102FA03F322FA01F1C2 +:10308000A240524243EA010363EB430332432B4322 +:10309000CDE90823DDE90823C9E90023FFE66FF045 +:1030A0000100FCE66FF00800F9E6082CA0D9102C0E +:1030B000B3D9202CEED8C3E7BBF1000FADD002236B +:1030C00083E7BBF1000FBBD004237EE730B5012AB4 +:1030D000144638BF0124402C85B028BF4024002569 +:1030E000012ACDE9025518D81B788DF808306307FE +:1030F0000AD004AB03EBD405624215F8083C02F099 +:103100000702934005F8083C00910346224600213F +:1031100002A8FFF727FB05B030BD082AE4D9102A22 +:1031200003D81B88ADF80830E1E7202A8DBFD3E92A +:1031300000231B680293CDE90223D8E710B5CB68C2 +:103140001BB98B600B618B8210BD04691A681C600F +:103150000361C38A013BC382CA60F0E703064CBF28 +:10316000C0F3C0300220704708B50246FFF7F6FFF3 +:10317000022806D15306C2F30F2001D100F003004C +:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E +:1031900003230A6804461046FFF7E0FF022814BF25 +:1031A000C2F306260026002A0D46824680F2F281EE +:1031B00012F0C04940F0EE81097B002900F0EA815D +:1031C000022803D02378B34240F0E781C2F30463BE +:1031D0000693104602F07F030593FFF7C5FF059B9A +:1031E00029444FEA834848EA0A4848EA4668CE78C4 +:1031F00000230022CDE90823F309834648EA0008AA +:10320000029367D0059B009302466768534608A95E +:103210002046B847002800F0C381276A4FB94146CD +:1032200004F10C00FFF702FB074690B96FF00200B3 +:1032300054E03B6998450DD03F68002FF9D14146D5 +:1032400004F10C00FFF7F2FA07460028EED0236ADB +:103250003B60276297F817C006F01F08CCF3840C78 +:10326000ACEB08001FFA80FE0028B8BF0EF120006A +:10327000A8EB0C031FFA83FED7E90221B8BF00B206 +:10328000002B0793BEBF0EF120031BB2079352EA37 +:10329000010338D0039BDFF824E39A1A049B4FF014 +:1032A000000C63EB010196457CEB01032BD36B7B98 +:1032B00097F81AE0734519D1029B002B78D00128AA +:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF +:1032D00016D337E0276A27B96FF00C0013B0BDE8AA +:1032E000F08F3B699845B5D03F68F4E7B24890420B +:1032F0007CEB010301D30020F0E7029B002BFAD006 +:10330000079B0F2B17DCFA7DB30002F0030203F0DA +:103310007C031343FB7539462046FFF707FB6B7BA5 +:10332000BB76029B3BB9FB7DC3F38402013262F39F +:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A +:10334000002B35D0B309022B32D0039BBB60049B0A +:10335000FB60142200210DA8FDF7ECFF039B0A93EC +:10336000049B0B932B1D0C932B7BADF83EB0013BC4 +:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 +:10338000433094F82C308DF840A083F001038DF881 +:1033900044308DF84180A3680AA920469847FB7DF8 +:1033A000C3F38403013303F01F039B02FB82A2E7F4 +:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 +:1033C0008403434540F0F280029A2B7BB609002A21 +:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 +:1033E000049BFB602B7BAE1D033BDBB232463946B0 +:1033F00004F10C00FFF7ACFA00280CDA394620463D +:10340000FFF794FAFB7DC3F38403013303F01F033A +:103410009B02FB820AE7DDE90884AB883B834FF619 +:10342000FF73C9F12000A9F1200228FA09F104FA7A +:1034300000F0014324FA02F211431846C9B2FFF723 +:10344000C9F909F10809B9F1400F0346E9D1B88279 +:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 +:10346000DA43C2F3C01262F3C713FB7543E786B9B0 +:103470002E1D013BDBB23246394604F10C00FFF74A +:1034800067FA0028BADB2A7BB88A013AD2B2314601 +:10349000E2E7F98AC1F30901013B0429DAB25BD8FA +:1034A000281D002307F11B069A4208D910F801CB0A +:1034B00006F801C0013101330529DBB2F4D10399CB +:1034C0000A9104990B91934207F11B010C9138BFAB +:1034D000043379680D9134BF55FA83F300230E93BA +:1034E000FB8AADF83EB0C3F309031A44069B8DF87E +:1034F0004230059B8DF8433094F82C30ADF83C20D9 +:1035000083F001038DF8443000238DF840A08DF83E +:1035100041807B602A7BB88A013A291DFFF76CF94C +:103520003B8BB882834203D1A3680AA920469847FF +:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 +:10354000013303F01F039B02FB823B8B9A420CBFAB +:1035500000206FF01000C1E67B68002BAFD0052083 +:1035600001E01C3033461E68002EFAD1091A081DEE +:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 +:103580009DD89A429BD916F8013B00F8013B09F1FE +:103590000109EFE76FF00900A0E66FF00A009DE671 +:1035A0006FF00B009AE66FF00D0097E66FF00E00DB +:1035B00094E66FF00F0091E640420F0080841E00F9 +:1035C000EFF3098305494A6B22F001024A6368332D +:1035D00083F30988002383F31188704700EF00E02C +:1035E000302080F3118862B60C4B0D4AD96821F463 +:1035F000E0610904090C0A43DA60D3F8FC200949A8 +:1036000042F08072C3F8FC200A6842F001020A60AE +:103610002022DA7783F82200704700BF00ED00E037 +:103620000003FA05001000E010B5302383F3118881 +:103630000E4B5B6813F4006314D0F1EE103AEFF315 +:103640000984683C4FF08073E361094BDB6B2366B0 +:1036500084F3098800F098F810B1064BA36110BDFF +:10366000054BFBE783F31188F9E700BF00ED00E0AD +:1036700000EF00E0030600080606000800F16043C2 +:1036800003F561430901C9B283F80013012200F078 +:103690001F039A4043099B0003F1604303F5614314 +:1036A000C3F880211A60704700F16040090100F5FD +:1036B0006D40C9B2017670470023037582680369C3 +:1036C0001B6899689142FBD25A680360426010609F +:1036D0005860704700230375826803691B68996806 +:1036E0009142FBD85A68036042601060586070478E +:1036F00008B50846302383F311880B7D032B05D0D2 +:10370000042B0DD02BB983F3118808BD8B690022DF +:103710001A604FF0FF338361FFF7CEFF0023F2E71B +:10372000D1E9003213605A60F3E70000FFF7C4BF2D +:10373000054BD9680875186802681A605360012241 +:103740000275D860FCF748BF2038002030B50C4B1C +:10375000DD684B1C87B004460FD02B46094A6846EB +:1037600000F0FEF82046FFF7E3FF009B13B1684628 +:1037700000F000F9A86907B030BDFFF7D9FFF9E7FD +:1037800020380020F1360008044B1A68DB68906886 +:103790009B68984294BF0020012070472038002089 +:1037A000084B10B51C68D86822681A605360012263 +:1037B0002275DC60FFF78EFF01462046BDE8104011 +:1037C000FCF70ABF20380020044B1A68DB689268B7 +:1037D0009B689A4201D9FFF7E3BF70472038002069 +:1037E00038B5074C07490848012300252370656058 +:1037F00000F00AFB0223237085F3118838BD00BF57 +:10380000483A00207C4A00082038002008B572B6EB +:10381000044B186500F0CEF900F092FA024B032237 +:103820001A70FEE720380020483A002000F0B4B8B3 +:10383000EFF3118020B9EFF30583302282F3118872 +:103840007047000010B530B9EFF30584C4F30804E5 +:1038500014B180F3118810BDFFF7B6FF84F311880F +:10386000F9E700008B60022308618B8208467047ED +:103870008368A3F1840243F8142C026943F8442CB2 +:10388000426943F8402C094A43F8242CC26843F8A3 +:10389000182C022203F80C2C002203F80B2C044AEB +:1038A00043F8102CA3F12000704700BFF105000879 +:1038B0002038002008B5FFF7DBFFBDE80840FFF720 +:1038C00035BF0000024BDB6898610F20FFF730BF67 +:1038D00020380020302383F31188FFF7F3BF000066 +:1038E00008B50146302383F311880820FFF72EFF27 +:1038F000002383F3118808BD064BDB6839B14268A9 +:1039000018605A60136043600420FFF71FBF4FF038 +:10391000FF307047203800200368984206D01A68AC +:103920000260506099611846FFF700BF70470000C1 +:1039300010B50A4C23699A6891420CD85A68816084 +:103940000360426010609A685860511A99604FF0A5 +:10395000FF33A36110BD1B68891AECE720380020F3 +:1039600010B4C0E9032300235DF8044B4361FFF763 +:10397000DFBF0000036881689A680A449A60426861 +:1039800013605A6000230360024B4FF0FF329A61CC +:10399000704700BF2038002070B5124DEB692A46F1 +:1039A0000133EB6152F8103F934206D09A68013A16 +:1039B0009A6030262C69A36803B170BDD4E9002158 +:1039C0000A605160236083F31188D4E903312046F3 +:1039D000984786F3118861690029EBD02046FFF7EC +:1039E000A7FFE7E72038002000207047FEE700002F +:1039F000704700004FF0FF3070470000BFF34F8F5B +:103A0000024AD368DB07FCD4704700BF00200240A5 +:103A100008B5074B1B7853B9FFF7F0FF054B1A6940 +:103A2000120641BF044A5A6002F188325A6008BD4A +:103A3000603A0020002002402301674508B5054B8D +:103A40001B7833B9FFF7DAFF034A136943F08003A9 +:103A5000136108BD603A0020002002407F289ABF11 +:103A600000F58030C0020020704700004FF4006075 +:103A700070470000802070477F2808B50BD8FFF7FB +:103A8000EDFF00F500630268013204D10430834287 +:103A9000F9D1012008BD0020FCE700007F2810B507 +:103AA00004461CD8FFF7AAFFFFF7B2FF0D4BF32225 +:103AB000DA6002221A61FFF7D1FF58611A6942F0F9 +:103AC00040021A614FF40061FFF798FF00F034F9EB +:103AD000FFF7B4FF2046BDE81040FFF7CDBF002040 +:103AE00010BD00BF002002402DE9F84312F0010391 +:103AF000144606D01F4B40F2F3221A600020BDE8A6 +:103B0000F88385181C4A954204D91A4A4FF43E712D +:103B10001160F3E7FFF77CFFFFF770FFDFF86880C5 +:103B2000451A4FF00109012C05EB01060F4603D899 +:103B3000FFF784FF0120E2E73B88C8F8109033804C +:103B40000020FFF75BFFC8F81000338831F8022B24 +:103B50009BB29A420CD0074B40F20F321A60074BCF +:103B60001E60074B1C60074B1F60FFF767FFC6E72F +:103B7000023CD8E75C3A002000000408503A0020DC +:103B8000583A0020543A002000200240084908B565 +:103B90000B7828B11BB9FFF73BFF01230B7008BD61 +:103BA000002BFCD0BDE808400870FFF747BF00BFFE +:103BB000603A002008B54FF420414FF0005000F06B +:103BC000BDF8BDE808404FF400514FF0805000F0C0 +:103BD000B5B800000846114600F05EBE012000F0B6 +:103BE0005BBE0000084600F075BE000030B583B033 +:103BF000FFF71EFE0E4B0F4DDB692A684FF47A71FA +:103C000001FB03F3934237BF0B4A0B495168146819 +:103C10002B602EBFD1E90041013151601C1941F1E7 +:103C200000010191FFF70EFE0199204603B030BD5F +:103C300020380020643A0020683A002030B583B074 +:103C4000FFF7F6FD114B124DDB692A684FF47A71CC +:103C500001FB03F3934237BF0E4A0E4951681468C3 +:103C60002B602EBFD1E90041013151601C1941F197 +:103C700000010191FFF7E6FD01994FF47A720023EC +:103C80002046FCF795FA03B030BD00BF2038002075 +:103C9000643A0020683A002010B50244064BD2B2C4 +:103CA000904200D110BD441C00B253F8200041F8EE +:103CB000040BE0B2F4E700BF502800400F4B30B5D2 +:103CC0001C6A240407D41C6A44F440741C621C6AF5 +:103CD00044F400441C620A4C236843F4807323605C +:103CE0000244084BD2B2904200D130BD441C00B215 +:103CF00051F8045B43F82050E0B2F4E700100240B2 +:103D0000007000405028004007B5012201A90020A2 +:103D1000FFF7C2FF019803B05DF804FB13B504463A +:103D2000FFF7F2FFA04205D0012201A90020019473 +:103D3000FFF7C4FF02B010BD7047000070470000DD +:103D400070470000074B45F255521A6002225A6034 +:103D500040F6FF729A604CF6CC421A60024B012288 +:103D60001A70704700300040743A0020034B1B78F3 +:103D70001BB1034B4AF6AA221A607047743A00201E +:103D800000300040044B1A682AB902F1804202F563 +:103D90000432526A1A607047703A0020024B4FF0AA +:103DA00080725A62704700BF0010024008B5FFF7EA +:103DB000E9FF024B1868C0F3407008BD703A00205C +:103DC00070470000FEE700000A4B0B480B4A904288 +:103DD0000BD30B4BDA1C121AC11E22F003028B42CA +:103DE00038BF00220021FDF7A5BA53F8041B40F8A4 +:103DF000041BECE7EC4B0008583C0020583C00202A +:103E0000583C0020FEE7000070B51B4B0163002505 +:103E1000044686B0586085620E46FFF7E1FB04F168 +:103E20001003C4E904334FF0FF33A361134BE56182 +:103E3000D969A5600A462B46C4E9082304F1340178 +:103E4000C4E900440E4AE562256580232046FFF759 +:103E500009FD0123E0600B4A03750092726801922C +:103E6000B268CDE90223084B6846CDE90435FFF777 +:103E700021FD06B070BD00BF483A00202038002068 +:103E8000884A00088D4A0008053E00084B684360D8 +:103E90008B688360CB68C3600B6943614B690362C5 +:103EA0008B6943620B6803607047000008B51B4BC9 +:103EB0009A6A42F4FC029A629A6A22F4FC029A62BA +:103EC0009A6A5A6942F4FC025A61154A5B691146C2 +:103ED0004FF09040FFF7DAFF02F11C0100F580601F +:103EE000FFF7D4FF02F1380100F58060FFF7CEFF45 +:103EF00002F1540100F58060FFF7C8FF02F1700184 +:103F000000F58060FFF7C2FF02F18C0100F58060D0 +:103F1000FFF7BCFFBDE8084000F05AB800100240AF +:103F2000944A000808B500F093F9FFF759FCBDE882 +:103F30000840FFF727BF00007047000010B5214C74 +:103F4000A36A63F4FC03A362A36A03F4FC03A36201 +:103F50004FF0FF32A36A23692261236900232361A2 +:103F60002169E168E260E268E360E268E2691649BB +:103F700042F08052E261E2690A6842F480720A60AB +:103F8000226A02F44072B2F5407F1EBF4FF48032C5 +:103F900022622362236A1B0407D4236A43F440731A +:103FA0002362236A43F40043236200F031F9A369DA +:103FB000064A43F00103A361A369136843F0200399 +:103FC000136010BD0010024000700040000001406E +:103FD0001E4B1A6842F001021A601A689007FCD55D +:103FE0005A6822F003025A605A6812F00C02FBD1A0 +:103FF000196801F0F90119605A601A6842F48032B8 +:104000001A601A689103FCD5114A5A604FF40452A1 +:10401000DA6230221A631A6842F080721A601A68F3 +:104020009201FCD50B4912220A600A6802F00702CD +:10403000022AFAD15A6842F002025A605A6802F023 +:104040000C02082AFAD11A6B1A637047001002405A +:104050000024050000200240084A08B55169136891 +:104060000B4003F00103536123B1054A13680BB100 +:1040700050689847BDE80840FFF7D6BA00040140F1 +:10408000783A0020084A08B5516913680B4003F0DC +:104090000203536123B1054A93680BB1D068984776 +:1040A000BDE80840FFF7C0BA00040140783A00209C +:1040B000084A08B5516913680B4003F004035361C3 +:1040C00023B1054A13690BB150699847BDE8084010 +:1040D000FFF7AABA00040140783A0020084A08B560 +:1040E000516913680B4003F00803536123B1054A7B +:1040F00093690BB1D0699847BDE80840FFF794BABF +:1041000000040140783A0020084A08B55169136854 +:104110000B4003F01003536123B1054A136A0BB13E +:10412000506A9847BDE80840FFF77EBA0004014096 +:10413000783A0020174B10B55A691C68144004F4F3 +:1041400078725A61A30604D5134A936A0BB1D06AF8 +:104150009847600604D5104A136B0BB1506B984713 +:10416000210604D50C4A936B0BB1D06B9847E2053E +:1041700004D5094A136C0BB1506C9847A30504D5BC +:10418000054A936C0BB1D06C9847BDE81040FFF71F +:104190004BBA00BF00040140783A00201A4B10B51A +:1041A0005A691C68144004F47C425A61620504D5C3 +:1041B000164A136D0BB1506D9847230504D5134A69 +:1041C000936D0BB1D06D9847E00404D50F4A136E80 +:1041D0000BB1506E9847A10404D50C4A936E0BB1F5 +:1041E000D06E9847620404D5084A136F0BB1506F24 +:1041F0009847230404D5054A936F0BB1D06F9847B5 +:10420000BDE81040FFF710BA00040140783A0020E2 +:10421000062108B50846FFF731FA06210720FFF707 +:104220002DFA06210820FFF729FA06210920FFF7B9 +:1042300025FA06210A20FFF721FA06211720FFF7A9 +:104240001DFABDE8084006212820FFF717BA000034 +:1042500008B5FFF773FE00F067F800F03DF8FFF7D0 +:104260006BFEBDE8084000F05DB8000002684368DE +:104270001143016003B1184770470000143000F08B +:104280002FBA00004FF0FF33143000F029BA0000BD +:10429000383000F0A5BA00004FF0FF33383000F09E +:1042A0009FBA0000143000F0F5B900004FF0FF3164 +:1042B000143000F0EFB90000383000F04FBA0000C1 +:1042C0004FF0FF32383000F049BA0000012914BF26 +:1042D0006FF013000020704700F06CB8044B0360CF +:1042E0000023C0E90233436001230374704700BF19 +:1042F0003C4B000838B5C36904460D461BB9042180 +:104300000844FFF7B3FF294604F1140000F0A6F9B2 +:10431000002806DA201D4FF40061BDE83840FFF7A1 +:10432000A5BF38BD00F00EB80023054A1946013379 +:10433000102BC2E9001102F10802F8D1704700BF4A +:10434000783A00204FF0E023044A5A6100229A6133 +:1043500007221A6108210B20FFF7A6B93F190100B7 +:1043600008B5302383F31188FFF760FA002383F345 +:10437000118808BD08B5FFF7F3FFBDE80840FFF757 +:1043800053B90000026843681143016003B1184744 +:1043900070470000024A136843F0C003136070477F +:1043A00000440040024A136843F0C00313607047A2 +:1043B0000048004037B51D4C1D4D2046FFF78EFFCD +:1043C000009404F114001B490023202200F038F966 +:1043D0002022009404F13800174B184900F0B2F97C +:1043E000174BC4E91735174C0C212620FFF746F967 +:1043F0002046FFF773FF04F11400134900940023D3 +:10440000202200F01DF904F13800104B10490094EF +:10441000202200F097F90F4B0C212720C4E9173513 +:1044200003B0BDE83040FFF729B900BFF83A0020DB +:1044300000512502D03B002095430008103C00208D +:1044400000440040643B0020F03B0020A5430008EE +:10445000303C0020004800402DE9F047C66D376829 +:10446000F46934622107054619D014F0080118BF19 +:104470004FF48071E20748BF41F02001A30748BF15 +:1044800041F04001600748BF41F08001302383F3D1 +:104490001188281DFFF776FF002383F31188E205BA +:1044A0000AD5302383F311884FF48061281DFFF76C +:1044B00069FF002383F311884FF030094FF0000AA1 +:1044C00014F0200838D13B0616D54FF0300905F11D +:1044D000380A200610D589F31188504600F066F995 +:1044E000002836DA0821281DFFF74CFF27F080034B +:1044F0003360002383F31188790614D5620612D540 +:10450000302383F31188D5E913239A4208D12B6C09 +:1045100033B11021281D27F04007FFF733FF376024 +:10452000002383F31188E30619D5AA6E1369B3B18A +:10453000BDE8F0475069184789F31188B38C95F8A6 +:10454000641028461940FFF7D5FE8AF31188F469F4 +:10455000B6E780B2308588F31188F469B9E7BDE821 +:10456000F087000008B50348FFF776FFBDE8084074 +:10457000FFF75AB8F83A002008B50348FFF76CFF78 +:10458000BDE80840FFF750B8643B0020F8B5154679 +:1045900082680669AA420B46816938BF8568761A27 +:1045A000B54204460BD218462A46FCF7B1FEA36971 +:1045B0002B44A361A3685B1BA3602846F8BD0CD9FC +:1045C00018463246FCF7A4FEAF1BE1683A46304479 +:1045D000FCF79EFEE3683B44EBE718462A46FCF7EF +:1045E00097FEE368E5E7000083689342F7B5154658 +:1045F000044638BF8568D0E90460361AB5420BD24C +:104600002A46FCF785FE63692B446361A36828464C +:104610005B1BA36003B0F0BD0DD932460191FCF7DE +:1046200077FE0199E068AF1B3A463144FCF770FE13 +:10463000E3683B44E9E72A46FCF76AFEE368E4E7FF +:1046400010B50A440024C361029B8460C0E90000E5 +:10465000C0E90511C1600261036210BD08B5D0E96F +:104660000532934201D1826882B982680132826048 +:104670005A1C42611970D0E904329A4224BFC368BF +:1046800043610021FFF748F9002008BD4FF0FF30DB +:10469000FBE7000070B5302304460E4683F3118813 +:1046A000A568A5B1A368A269013BA360531CA361DF +:1046B00015782269934224BFE368A361E3690BB1D3 +:1046C00020469847002383F31188284607E03146A7 +:1046D0002046FFF711F90028E2DA85F3118870BD52 +:1046E0002DE9F74F04460E4617469846D0F81C9021 +:1046F0004FF0300A8AF311884FF0000B154665B170 +:104700002A4631462046FFF741FF034660B941463D +:104710002046FFF7F1F80028F1D0002383F3118839 +:10472000781B03B0BDE8F08FB9F1000F03D0019002 +:104730002046C847019B8BF31188ED1A1E448AF36B +:104740001188DCE7C0E90511C160C3611144009B19 +:104750008260C0E90000016103627047F8B5044659 +:104760000D461646302383F31188A768A7B1A368C6 +:10477000013BA36063695A1C62611D70D4E9043275 +:104780009A4224BFE3686361E3690BB1204698470E +:10479000002080F3118807E031462046FFF7ACF88F +:1047A0000028E2DA87F31188F8BD0000D0E905237C +:1047B0009A4210B501D182687AB98268013282606A +:1047C0005A1C82611C7803699A4224BFC3688361C2 +:1047D0000021FFF7A1F8204610BD4FF0FF30FBE7A6 +:1047E0002DE9F74F04460E4617469846D0F81C9020 +:1047F0004FF0300A8AF311884FF0000B154665B16F +:104800002A4631462046FFF7EFFE034660B941468F +:104810002046FFF771F80028F1D0002383F31188B8 +:10482000781B03B0BDE8F08FB9F1000F03D0019001 +:104830002046C847019B8BF31188ED1A1E448AF36A +:104840001188DCE70B460146184600F02DB8000041 +:1048500000F040B8012838BF012010B504462046BA +:1048600000F030F830B900F007F808B900F00CF8A3 +:104870008047F4E710BD0000024B1868BFF35B8F60 +:10488000704700BF503C002008B5062000F084F8B7 +:104890000120FFF7ABF80000024B0A4601461868FA +:1048A000FFF798B91811002010B5054C13462CB12C +:1048B0000A4601460220AFF3008010BD2046FCE707 +:1048C00000000000024B01461868FFF787B900BFDF +:1048D00018110020024B01461868FFF783B900BF8A +:1048E0001811002010B501390244904201D1002076 +:1048F00005E0037811F8014FA34201D0181B10BD49 +:104900000130F2E72DE9F041A3B1C91A177801444B +:10491000044603F1FF3C8C42204601D9002009E007 +:104920000578BD4204F10104F5D10CEB0405D6185D +:10493000A54201D1BDE8F08115F8018D16F801ED11 +:10494000F045F5D0E7E700001F2938B504460D46CD +:1049500004D9162303604FF0FF3038BD426C12B10A +:1049600052F821304BB9204600F030F82A46014673 +:104970002046BDE8384000F017B8012B0AD0591C7A +:1049800003D1162303600120E7E7002442F8254005 +:10499000284698470020E0E7024B01461868FFF7D9 +:1049A000D3BF00BF1811002038B5074D00230446BF +:1049B000084611462B60FFF71DF8431C02D12B68F7 +:1049C00003B1236038BD00BF543C0020FFF70CB892 +:1049D000034611F8012B03F8012B002AF9D1704787 +:1049E0006F72672E6172647570696C6F742E48699E +:1049F0007465634D6F7361696300000040A2E4F168 +:104A0000646891060041A3E5F26569920700000021 +:104A10004261642043414E496661636520696E646A +:104A200065782E00800000000080000000008000FB +:104A30000000000000000000351B000819230008DA +:104A400079220008451B0008791B0008751D000825 +:104A5000491B0008591B00084D1B0008551B000886 +:104A6000511B00089D1C00085D1B0008E52500087F +:104A70006D1B0008711C000863300000784A0008B4 +:104A800078380020483A00206D61696E0069646CD6 +:104A900065000000A010002800000000FAAAAAAAE1 +:104AA00050040024BFFF0000007700000000000059 +:104AB0001410AA0000000000AAAAFAAA04005000DC +:104AC000FBFF0000000000009977000000000000DC +:104AD00000000000AAAAAAAA00000000FFFF000030 +:104AE00000000000000000000000000000000000C6 +:104AF000AAAAAAAA00000000FFFF00000000000010 +:104B0000000000000000000000000000AAAAAAAAFD +:104B100000000000FFFF0000000000000000000097 +:104B20000000000000000000AAAAAAAA00000000DD +:104B3000FFFF000000000000000000000000000077 +:104B40009942000885420008C1420008AD420008B1 +:104B5000B9420008A5420008914200087D420008C1 +:104B6000CD4200087CB6FF7F01000000000000007D +:104B7000F80300000000000000980300000000009F +:104B8000FE2A0100D20400001C11002000000000D9 +:104B90000000000000000000000000000000000015 +:104BA0000000000000000000000000000000000005 +:104BB00000000000000000000000000000000000F5 +:104BC00000000000000000000000000000000000E5 +:104BD00000000000000000000000000000000000D5 +:0C4BE000000000000000000000000000C9 :00000001FF diff --git a/Tools/bootloaders/HolybroG4_Compass_bl.bin b/Tools/bootloaders/HolybroG4_Compass_bl.bin index c6cee547010430..1fae62e434005d 100755 Binary files a/Tools/bootloaders/HolybroG4_Compass_bl.bin and b/Tools/bootloaders/HolybroG4_Compass_bl.bin differ diff --git a/Tools/bootloaders/HolybroG4_GPS_bl.bin b/Tools/bootloaders/HolybroG4_GPS_bl.bin index 59d33b5fbf38c3..6889581a3b3206 100755 Binary files a/Tools/bootloaders/HolybroG4_GPS_bl.bin and b/Tools/bootloaders/HolybroG4_GPS_bl.bin differ diff --git a/Tools/bootloaders/HolybroG4_GPS_bl.elf b/Tools/bootloaders/HolybroG4_GPS_bl.elf index a0432c3ec6b22a..66b34a15b100fb 100755 Binary files a/Tools/bootloaders/HolybroG4_GPS_bl.elf and b/Tools/bootloaders/HolybroG4_GPS_bl.elf differ diff --git a/Tools/bootloaders/HolybroG4_GPS_bl.hex b/Tools/bootloaders/HolybroG4_GPS_bl.hex index 07b2562c97e6ae..b8ae6e861be360 100644 --- a/Tools/bootloaders/HolybroG4_GPS_bl.hex +++ b/Tools/bootloaders/HolybroG4_GPS_bl.hex @@ -1,19 +1,19 @@ :020000040800F2 -:1000000000070020F5040008552D00080D2D0008FC -:10001000352D00080D2D00082D2D0008F7040008CF -:10002000F7040008F7040008F7040008253D00085D +:1000000000070020F504000899300008513000086E +:10001000793000085130000871300008F7040008FA +:10002000F7040008F7040008F70400087940000806 :10003000F7040008F7040008F7040008F7040008B4 :10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F704000899500008C150000890 -:10006000E95000081151000839510008F704000850 +:10005000F7040008F7040008C9530008F15300082A +:10006000195400084154000869540008F7040008B6 :10007000F7040008F7040008F7040008F704000874 :10008000F7040008F7040008F7040008F704000864 -:10009000F7040008BD2C0008D12C000861510008AD +:10009000F7040008013000081530000891540008EA :1000A000F7040008F7040008F7040008F704000844 -:1000B00049520008F7040008F7040008F704000894 +:1000B00079550008F7040008F7040008F704000861 :1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F704000835520008F704000888 -:1000E000C5510008F7040008F7040008F7040008E9 +:1000D000F7040008F704000865550008F704000855 +:1000E000F5540008F7040008F7040008F7040008B6 :1000F000F7040008F7040008F7040008F7040008F4 :10010000F7040008F7040008F7040008F7040008E3 :10011000F7040008F7040008F7040008F7040008D3 @@ -24,12 +24,12 @@ :10016000F7040008F7040008F7040008F704000883 :10017000F7040008F7040008F7040008F704000873 :10018000F7040008F7040008F7040008F704000863 -:10019000F7040008F7040008E52C0008F92C000813 +:10019000F7040008F7040008293000083D30000883 :1001A000F7040008F7040008F7040008F704000843 :1001B000F7040008F7040008F7040008F704000833 :1001C000F7040008F7040008F7040008F704000823 :1001D000F7040008F7040008F7040008F704000813 -:1001E000D116000800000000000000000000000020 +:1001E00045180008000000000000000000000000AA :1001F00053B94AB9002908BF00281CBF4FF0FF318E :100200004FF0FF3000F074B9ADF1080C6DE904CE89 :1002100000F006F8DDF804E0DDE9022304B07047E1 @@ -85,1293 +85,1344 @@ :10053000F0004EF68851CEF200010860BFF34F8FF5 :10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 :10055000CEF200010860062080F31488BFF36F8F8D -:1005600004F0CAFB04F05CFC4FF055301F491B4AF5 +:1005600004F062FD04F0F4FD4FF055301F491B4AC2 :1005700091423CBF41F8040BFAE71D49184A9142E9 :100580003CBF41F8040BFAE71A491B4A1B4B9A423D :100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE704F0A8FB5B -:1005B00004F07CFC144C154DAC4203DA54F8041BD7 +:1005A000184A91423CBF41F8040BFAE704F040FDC1 +:1005B00004F014FE144C154DAC4203DA54F8041B3D :1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E704F090BB000700209B +:1005D00054F8041B8847F9E704F028BD0007002001 :1005E000002300200000000808ED00E000010020CA -:1005F0000007002060550008002300208C23002005 -:100600009023002028650020E0010008E401000894 +:1005F0000007002090580008002300208C230020D2 +:100600009023002078690020E0010008E401000840 :10061000E4010008E40100082DE9F04F2DED108AF7 :10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F0D8FF49 -:10064000FEE703F03BFF00DFFEE70000F8B504F033 -:10065000F5FA074604F046FB0546B8BB204B9F421F -:1006600034D001339F4234D01E4B27F0FF029A4210 -:1006700032D1F8B200F052FE2E4642F2107400F071 -:1006800053FE08B10024264601F0D6FA20B103201B -:1006900000F07CF80024264635B1134B9F4203D06E -:1006A00004F018FB00242646002004F0D1FA0EB115 -:1006B00000F082F801F08AF900F05AFE01F07AF8B1 -:1006C000204600F0D1F800F077F8F9E72E46002434 -:1006D000D5E704460126D2E7064640F6C414CEE725 -:1006E000010007B0000008B0263A09B008B501F0D3 -:1006F0002DF8A0F120035842584108BD07B541F23A -:100700001203022101A8ADF8043001F03DF803B056 -:100710005DF804FB38B5302383F31188174803686C -:100720000BB104F023F8164A144800234FF47A71F1 -:1007300004F012F8002383F31188124C236813B1DC -:100740002368013B2360636813B16368013B636006 -:100750000D4D2B7833B963687BB9022001F0C4F8E2 -:10076000322363602B78032B07D163682BB90220F7 -:1007700001F0BAF84FF47A73636038BD902300201B -:1007800015070008B0240020A8230020084B18708B -:1007900003280CD8DFE800F008050208022001F069 -:1007A00099B8022001F08CB8024B00225A607047C1 -:1007B000A8230020B024002010B501F03DFA30B18C -:1007C000234B03221A70234B00225A6010BD224B88 -:1007D000224A1C4619680131F8D004339342F9D1FA -:1007E0006268A242F2D31E4B9B6803F1006303F5DB -:1007F00010439A42EAD204F03FFA04F051FA002082 -:1008000000F0F2FF0220FFF7C1FF164B9A6D0022A5 -:100810009A65996F9A67996FD96DDA65D96FDA67BA -:10082000D96F196E1A66D3F88010C3F88020D3F8F8 -:10083000803072B64FF0E0233021C3F8084DD4E980 -:10084000003281F311889D4683F308881047BDE785 -:10085000A8230020B0240020009000082090000869 -:1008600000230020001002402DE9F04F93B0AC4B64 -:1008700000902022FF210AA89D6801F051F8A94AA2 -:100880001378A3B9A848012103601170302383F3C2 -:10089000118803680BB103F069FFA44AA248002342 -:1008A0004FF47A7103F058FF002383F31188009B03 -:1008B00013B19F4B009A1A609E4A009C1378032B39 -:1008C0001EBF002313709A4A4FF0000A18BF5360EE -:1008D000D3465646D146012000F0FCFF24B1944B8C -:1008E0001B68002B00F01582002000F02FFF039002 -:1008F000039B002B01DA00F08FFD039B002BEDDB47 -:10090000012000F0DDFF039B213B162BE3D801A261 -:1009100052F823F071090008990900082D0A00080F -:10092000D7080008D7080008D7080008B70A000849 -:10093000870C0008A10B0008030C00082B0C000812 -:10094000510C0008D7080008630C0008D7080008FD -:10095000D50C0008110A0008D7080008190D000876 -:100960007D090008110A0008D7080008030C0008D8 -:100970000220FFF7BBFE002840F0F581009B02211A -:10098000BAF1000F08BF1C4605A841F21233ADF8BA -:10099000143000F0F9FE9EE74FF47A7000F0D6FEB6 -:1009A000071EEBDB0220FFF7A1FE0028E6D0013F87 -:1009B000052F00F2DA81DFE807F0030A0D10133685 -:1009C00005230593042105A800F0DEFE17E0544836 -:1009D0000421F9E758480421F6E758480421F3E7D1 -:1009E0004FF01C08404600F001FF08F10408059094 -:1009F000042105A800F0C8FEB8F12C0FF2D10120A7 -:100A000000FA07F747EA0B0B5FFA8BFB4FF0000980 -:100A100000F0D2FF26B10BF00B030B2B08BF002414 -:100A2000FFF76CFE57E746480421CDE7002EA5D01E -:100A30000BF00B030B2BA1D10220FFF757FE07464B -:100A400000289BD0012000F0CFFE0220FFF79EFE81 -:100A500000265FFA86F8404600F0D6FE044690B1C4 -:100A60000021404600F0E0FE01360028F1D1BA46F0 -:100A7000044641F21213022105A8ADF814303E4697 -:100A800000F082FE27E70120FFF780FE2546244B79 -:100A90009B68AB4207D9284600F0A8FE013040F021 -:100AA00067810435F3E7234B00251D70204BBA46C0 -:100AB0005D603E46ACE7002E3FF460AF0BF00B03E9 -:100AC0000B2B7FF45BAF0220FFF760FE322000F0BB -:100AD0003DFEB0F10008FFF651AF18F003077FF4B8 -:100AE0004DAF0F4A926808EB050393423FF646AFBD -:100AF000B8F5807F3FF742AF124B0193B84523DD35 -:100B00004FF47A7000F022FE0390039A002AFFF659 -:100B100035AF019B039A03F8012B0137EDE700BFC6 -:100B200000230020AC24002090230020150700089B -:100B3000B0240020A8230020042300200823002044 -:100B40000C230020AC230020C820FFF7CFFD074670 -:100B500000283FF413AF1F2D11D8C5F120024245E4 -:100B60000AAB25F0030028BF42468349019218448E -:100B700000F0C4FE019A8048FF2100F0D1FE4FEA48 -:100B8000A8037D490193C8F38702284600F0D0FEF0 -:100B9000064600283FF46DAF019B05EB830537E760 -:100BA0000220FFF7A3FD00283FF4E8AE00F04EFE60 -:100BB00000283FF4E3AE0027B846704B9B68BB4269 -:100BC00018D91F2F11D80A9B01330ED027F0030329 -:100BD00012AA134453F8203C05934046042205A969 -:100BE00001F014F804378046E7E7384600F0FEFDD0 -:100BF0000590F2E7CDF81480042105A800F0C4FDAB -:100C000006E70023642104A8049300F0B3FD002844 -:100C10007FF4B4AE0220FFF769FD00283FF4AEAECA -:100C2000049800F009FE0590E6E70023642104A87B -:100C3000049300F09FFD00287FF4A0AE0220FFF790 -:100C400055FD00283FF49AAE049800F0F7FDEAE75E -:100C50000220FFF74BFD00283FF490AE00F006FEA7 -:100C6000E1E70220FFF742FD00283FF487AE05A927 -:100C7000142000F001FE04210746049004A800F0AF -:100C800083FD3946B9E7322000F060FD071EFFF60C -:100C900075AEBB077FF472AE384A926807EB090362 -:100CA00093423FF66BAE0220FFF720FD00283FF491 -:100CB00065AE27F003074F44B9453FF4A9AE484657 -:100CC00000F094FD0421059005A800F05DFD09F1F8 -:100CD0000409F1E74FF47A70FFF708FD00283FF4AC -:100CE0004DAE00F0B3FD002844D00A9B01330BD079 -:100CF00008220AA9002000F01BFE00283AD020227A -:100D0000FF210AA800F00CFEFFF7F8FC1C4803F0D6 -:100D100075FC13B0BDE8F08F002E3FF42FAE0BF042 -:100D20000B030B2B7FF42AAE0023642105A8059347 -:100D300000F020FD074600287FF420AE0220FFF7D8 -:100D4000D5FC804600283FF419AEFFF7D7FC41F2EE -:100D5000883003F053FC059800F044FE464600F04E -:100D60002BFE3C46B7E5064652E64FF0000905E685 -:100D7000BA467EE637467CE6AC23002000230020FE -:100D8000A0860100094A136849F2690099B21B0C58 -:100D900000FB01331360064B186844F2506182B2C5 -:100DA000000C01FB0200186080B270471423002081 -:100DB0001023002010B500211022044600F0B0FDE1 -:100DC000034B03CB206061601868A06010BD00BFBA -:100DD0009075FF1F2DE9F041ADF54E7D0DF1340802 -:100DE0006CAC40F2751207460D460EA80021C8F8FB -:100DF000001000F095FD4FF4C4720021204600F071 -:100E00008FFD01F0AFFF274B4FF47A72B0FBF2F089 -:100E1000186093E80700012384E807000DF5E970E6 -:100E20002382FFF7C7FF41F604531F49238406A816 -:100E300004F0A6FA1B2384F832310DF2E32206AB4C -:100E40000DF1300C1E4603CE6645106051603346EE -:100E500002F10802F6D13188B378937011802046F0 -:100E60004146012200F0D8FD00230393AB7E02939C -:100E700005F11903019380B20123CDE904800093A9 -:100E8000E97E06A3D3E90023384602F02BFB0DF5DB -:100E90004E7DBDE8F08100BFAFF300809E6AC421A3 -:100EA000818A46EEB8240020905300082DE9F043D3 -:100EB000224DBBB001F056FFAB6840F2ED22C31AE1 -:100EC000934232D906AFA8602B462822002138462B -:100ED00002F0B8FC05F10E0000F01AFD00260446F1 -:100EE0005FFA80F905F10E08F3B2F100994501F1BE -:100EF000280107D908EB06030822384602F0A2FCB5 -:100F00000136F1E708230122CDE9023205340C4B0A -:100F10000193A4B230230093CDE9047405A3D3E96F -:100F20000023297B074802F0DDFA3BB0BDE8F083DF -:100F3000AFF3008078F6339F93CACD8D605E0020BA -:100F40006D5E0020D0340020F0B58B8A013B9BB24F -:100F5000C92BC9B006460C4647D8274D2F7B27BB67 -:100F600005F10C03009308223B463946204602F067 -:100F70002DFB7B1CFAB2D9001F46A38A013B9A4283 -:100F800005DA0E322A44009200230822EEE70023FD -:100F90000022C5E900230023AB6085F8D730C5F8EF -:100FA000D8302B7B0BB9E37E2B738122002106AD59 -:100FB00027A800F0B5FC0122294627A800F0FAFD79 -:100FC00000230393A37E029304F1190380B20193DB -:100FD0002823CDE90450E17E0093304604A3D3E9F1 -:100FE000002302F07FFAFFF761FF49B0F0BD00BFB8 -:100FF00026417272DF25D7B7605E002070B50D46BE -:1010000014461E4602F0CAF950B9022E10D1012C26 -:101010000ED112A3D3E90023C5E90023012007E084 -:10102000282C10D005D8012C09D0052C0FD0002079 -:1010300070BD302CFBD10BA3D3E90023ECE70BA34D -:10104000D3E90023E8E70BA3D3E90023E4E70BA3EC -:10105000D3E90023E0E700BFAFF30080401DA120EB -:1010600026812A0B78F6339F93CACD8D9E6AC421C0 -:10107000818A46EE26417272DF25D7B7F017304AD3 -:1010800039059E562DE9F04F8DB002AF80460D46D2 -:1010900002F084F9044600285CD12B7E022B1BD180 -:1010A000EB8A012B18D101F05DFE0646FFF76AFEC0 -:1010B00003464FF4C870DFF81C92B3FBF0F206F55C -:1010C000167602FB103316FA83F3C9F80030EB7E74 -:1010D00033B97B4B00221A702C37BD46BDE8F08F28 -:1010E000AB8AE6B2013BB34204F101040CD907F12B -:1010F00008031E44E10000960023082201F0F801D5 -:10110000284602F063FAEBE707F11800FFF752FEFA -:10111000324607F1180107F1080004F0FFF8002833 -:10112000D7D10F2E08D8664B1E70D9F80030A3F522 -:101130001673C9F80030CFE7FB1DF8710146009324 -:1011400007220346284602F041FAF979404602F0A8 -:101150001DF9C1E7EB8A282B26D010D8012B1ED011 -:10116000052BB9D1BFF34F8F5649574BCA6802F4CC -:10117000E0621343CB60BFF34F8F00BFFDE7302B1E -:10118000AAD16B7E514C0133627BDBB29342E946BC -:1011900003D1EA7E237B9A420BD0CD469CE72946B9 -:1011A0004046FFF717FE97E729464046FFF7CCFE7B -:1011B00092E74FF0000807F11803A7F818801022F3 -:1011C000009341460123284602F000FAAE8A023E0F -:1011D000B6B2F31C9B109B000733DB08A9EBC303DB -:1011E0009D460DF1080A1FFA88F34FEAC8019E4296 -:1011F00001F110010AD90AEB080300930822002329 -:10120000284602F0E3F908F10108ECE794F8D7006A -:1012100000F0FAFAD4F8D810054619B994F8D700B6 -:1012200000F002FBD4F8D83033449D4205D294F844 -:10123000D7000021013000F0F7FA4FEA960B4FF08B -:1012400000081FFA88F18B45D4E9003209D90AEB6E -:10125000880103EB8800012200F06AFB08F1010815 -:10126000EFE7F31842F10002C4E90032D4F8D830B5 -:1012700094F8D70006EB0308C4F8D88000F0C4FA4D -:10128000804509D394F8D730D4F8D8000133401BF7 -:1012900084F8D730C4F8D800FF2E0D4D09D80023AC -:1012A000237300F0D3FA00F0C7FC288108B9FFF7D8 -:1012B00083FA23689B0A01332B810023A3606CE728 -:1012C000C934002000ED00E00400FA05605E002053 -:1012D000B8240020CC340020F8B50E4C0E4F022666 -:1012E000A4F5805343F8307C237E3BB965692DB16A -:1012F000284600F01FFD284603F0F8FF204600F0C6 -:1013000019FDA4F5A554012EA4F1100400D1F8BDD7 -:101310000126E5E7E0590020F8530008014B18705A -:10132000704700BFC424002010B54FF000540C4B90 -:1013300022689A4211D10B4B627D1A700A48237DB4 -:1013400003730A49C9220E3000F0D8FAE0220021C6 -:10135000204600F0E5FA012010BD0020FCE700BFA8 -:101360009AAD44C5C4240020605E00201600002011 -:1013700037B500F061FC1F4C1F4D20492881022326 -:101380006B712368204604F580545B6801229847FE -:10139000D4F8B03419495B68012204F59660984787 -:1013A00000230193164B174900931748174B4FF42E -:1013B000805201F0C3FF164B197811B1124801F0A9 -:1013C000E5FF01F0CFFC0446FFF7DCFC4FF4C873E7 -:1013D000B0FBF3F202FB130304F5167010FA83F06E -:1013E0000C4B186003F07EFC08B10F232B8103B077 -:1013F00030BD00BF00350020B824002040420F005F -:10140000FD0F0008C8240020D034002085100008FB -:10141000C4240020CC3400202DE9F04F2DED028BA8 -:101420009F4D93B0DFF8A0A29E4F284602F086F8A9 -:10143000034600283ED00024CDE90F440E94ADF8B9 -:101440004440027B8DF8442099684068964E0FAA6C -:1014500003C21B6843F000430E93A046A1463368C5 -:10146000D3F810B001F080FC10EB0A0241F1000348 -:101470003046CDF800900EA9D84704F22C5440F61F -:1014800058230028C8BF48F0010806F5A5569C421D -:1014900006F11006E3D1B8F1000F05D0284602F09E -:1014A00051F887F80090C0E73B78072B00F2E68000 -:1014B00001333B700DF12C089FED738B0023DFF897 -:1014C0000C920A93ADF834300B93C8F80430002620 -:1014D000754C374601238DF81C3023688DED008B49 -:1014E0004FF0000BD3F808A08DF81DB05B460DF14E -:1014F0001D0207A92046D0479DF81CA0BAF1000F95 -:1015000024D0D9F8143083F48063C9F81430102241 -:1015100059460EA800F004FA236808AA5F690AA9D0 -:101520000DF11E032046B84798E803000FAB83E88F -:1015300003009DF834308DF844300A9B0E930EA9B9 -:10154000DDE90823284602F0C5F9574606F22C5675 -:1015500040F6582304F5A5549E4204F11004B9D175 -:10156000002FB4D1284601F019FF002840D14F4E7A -:1015700001F0F8FB336898423AD301F0F3FB0446DC -:10158000FFF700FC4FF4C87304F51674B0FBF3F2D8 -:1015900002FB130314FA83F33360454E8DF8287071 -:1015A000377817B901238DF82830C7F11004E4B259 -:1015B0000EA8FFF7FFFB062C28BF06240EAB224621 -:1015C000D9190DF1290000F099F90AAB03931823FA -:1015D00002930134374B0193E4B201230093049446 -:1015E0002BA3D3E90023284601F01EFF002333700C -:1015F00001F0B8FB304A314C1368C31AB3F57A7F57 -:101600002FD3106001F0B0FB02460B46284601F0D4 -:10161000A3FF284601F0C2FE18B3237B284E002BFF -:1016200014BF03230223737101F09CFB0EAF4FF430 -:101630007A730122B0FBF3F039463060304600F097 -:1016400091FA182302931F4B019380B240F2551375 -:10165000CDE90370009328460FA3D3E9002301F0DE -:10166000E3FE237B2BB1FFF721FC237B002B7FF4D0 -:10167000D9AE13B0BDEC028BBDE8F08F284601F067 -:1016800061FF17E7AFF300800000000000000000DA -:10169000401DA12026812A0BF1C6A7C1D068080FE2 -:1016A000D0340020455F002000350020CC340020DD -:1016B000C9340020C8340020405F0020605E002054 -:1016C000B8240020445F002040420F00000800487A -:1016D00008B5064800F064FE054800F061FEBDE86C -:1016E0000840044A0449002003F0FABD00350020F8 -:1016F000B04900209C5F0020D912000870B5104B43 -:101700001B780133DBB2012B0C4612D80D4B1D6840 -:1017100029684FF47A730E6AA2FB0332014622460F -:101720002846B047844204D1074B00221A7001209A -:1017300070BD4FF4FA7002F061FF0020F8E700BFBF -:10174000182300201C2300208C5F002007B50023F5 -:10175000024601210DF107008DF80730FFF7CEFF9B -:1017600020B19DF8070003B05DF804FB4FF0FF3097 -:10177000F9E700000A4608B50421FFF7BFFF80F033 -:101780000100C0B2404208BD30B4074B0A46197888 -:10179000064B53F821402368DD69054B0146AC46F2 -:1017A000204630BC604700BF8C5F00201C23002017 -:1017B000A086010070B503F0C9F8094E094D3080CC -:1017C000002428683388834208D903F0BBF82B68CB -:1017D00004440133B4F5104F2B60F2D370BD00BF49 -:1017E0008E5F0020485F002003F076B900F10060B2 -:1017F00000F510400068704700F10060920000F5AD -:10180000104003F0E9B80000054B1A68054B1B882F -:101810009B1A834202D9104403F094B80020704709 -:10182000485F00208E5F0020024B1B68184403F0C5 -:10183000A3B800BF485F00200020704700F10050AF -:10184000A0F51040D0F8900570470000064991F8C7 -:10185000243033B10023086A81F824300822FFF7CE -:10186000CBBF0120704700BF4C5F0020014B1868C0 -:10187000704700BF002004E030B50F4B0F4C1B68D1 -:101880002288C3F30B030138934208440BD16468E8 -:101890000A46013C824213460BD214F9015F2DB176 -:1018A00002F8015BF6E781420B4602D22C2203F8D4 -:1018B000012B581A30BD00BF002004E02023002077 -:1018C000022802BF024B4FF080629A61704700BF4E -:1018D00000080048022802BF024B4FF480629A6160 -:1018E000704700BF00080048022801BF024A536940 -:1018F00083F48063536170470008004810B50023EB -:10190000934203D0CC5CC4540133F9E710BD00000E -:1019100003460246D01A12F9011B0029FAD170477A -:1019200002440346934202D003F8011BFAE77047D2 -:101930002DE9F8431F4D144695F8242007468846A4 -:1019400052BBDFF870909CB395F824302BB920225D -:10195000FF2148462F62FFF7E3FF95F82400C0F10E -:101960000802A24228BF2246D6B24146920005EBA9 -:101970008000FFF7C3FF95F82430A41B1E44F6B285 -:10198000082E17449044E4B285F82460DBD1FFF7B9 -:101990005DFF0028D7D108E02B6A03EB8203834266 -:1019A000CFD0FFF753FF0028CBD10020BDE8F8834C -:1019B0000120FBE74C5F0020024B1A78024B1A70A3 -:1019C000704700BF8C5F00201823002003494FF4AC -:1019D00061430B60024B186802F0D6BC745F0020B4 -:1019E0001C230020094B10B518220446002118467C -:1019F000FFF796FF064A074B127804600146BDE8E0 -:101A0000104053F8220002F0BFBC00BF745F0020FA -:101A10008C5F00201C2300202DE9F0470D46044672 -:101A200000219046284640F27912FFF779FF2346BD -:101A300020220021284601F005FF231D022220213B -:101A4000284601F0FFFE631D03222221284601F0F3 -:101A5000F9FEA31D03222521284601F0F3FE04F11F -:101A6000080310222821284601F0ECFE04F110039F -:101A700008223821284601F0E5FE04F1110308226E -:101A80004021284601F0DEFE04F11203082248211D -:101A9000284601F0D7FE04F11403202250212846E5 -:101AA00001F0D0FE04F1180340227021284601F015 -:101AB000C9FE04F120030822B021284601F0C2FE2D -:101AC00004F121030822B821284601F0BBFE04F1ED -:101AD0002207C0263B46314608222846083601F038 -:101AE000B1FEB6F5A07F07F10107F3D104F132038F -:101AF00008223146284601F0A5FE002704F1330AEA -:101B000094F832304FEAC7099F4209F5A47615D3FD -:101B1000B8F1000F08D1314604F599730722284621 -:101B200001F090FE09F24F16274694F832213B1B34 -:101B300093420CD3F01DC008BDE8F0870AEB070301 -:101B400008223146284601F07DFE0137D8E707F22A -:101B5000331331460822284601F074FE0836013757 -:101B6000E3E7000013B50446084600210160234660 -:101B7000C0F803102022019001F064FE0198231D9B -:101B80000222202101F05EFE0198631D0322222122 -:101B900001F058FE0198A31D0322252101F052FEF9 -:101BA000019804F108031022282101F04BFE0720C0 -:101BB00002B010BDF8B50E4605461446002181223C -:101BC0003046FFF7ADFE2B4608220021304601F0DB -:101BD00039FE7CB96B1C07220821304601F032FE29 -:101BE0000F2401236A785F1C013B934204D3E01D5C -:101BF000C008F8BD0824F4E7EB1921460822304656 -:101C000001F020FE08343B46ECE7000030B5094DFA -:101C10000A4491420DD011F8013B5840082340F38B -:101C20000004013B2C4013F0FF0384EA5000F6D17E -:101C3000EFE730BD2083B8ED73B5384A10685168BE -:101C40006B4603C36A4636493648082303F076FBE1 -:101C5000044670B9344A106851686B4603C36A463B -:101C600032493048082303F069FB044630BB0A20A0 -:101C700022E00369B3F5EE2FECD8418B40F21D4210 -:101C80009142E7D12A4A024402F110018B42E1D38A -:101C9000103B244900209D1AFFF7B8FF2A4606464C -:101CA00004F118010020FFF7B1FFA3689E42D1D1D3 -:101CB000E3689842CED1002002B070BD0369B3F54D -:101CC000EE2F22D8B0F8661040F21D4291421ED18C -:101CD000174A024402F15C018B421AD35C3B114962 -:101CE00000209D1AFFF792FF2A46064604F1640180 -:101CF0000020FFF78BFFA268964203460BD1E068F5 -:101D0000834214BF0D200020D6E70B20D4E70C201F -:101D1000D2E71020D0E70D20CEE700BFB85300086F -:101D2000DC6F070000900008C1530008906F0700A7 -:101D30000870FFF710B5037C044613B9006803F080 -:101D4000E5FA204610BD00000023BFF35B8FC3609F -:101D5000BFF35B8FBFF35B8F8360BFF35B8F704715 -:101D6000BFF35B8F0068BFF35B8F704770B50546AC -:101D70000C30FFF7F5FF05F1080604463046FFF783 -:101D8000EFFFA04206D930466D68FFF7E9FF254412 -:101D9000281A70BD3046FFF7E3FF201AF9E700006C -:101DA00070B50546406898B105F10800FFF7D8FF07 -:101DB00005F10C0604463046FFF7D2FF8442304658 -:101DC00094BF6D680025FFF7CBFF013C2C44201A1F -:101DD00070BD000038B50C460546FFF7C7FFA042AE -:101DE00010D305F10800FFF7BBFF04446868B4FB9B -:101DF000F0F100FB1144BFF35B8F0120AC60BFF337 -:101E00005B8F38BD0020FCE72DE9F0411446074602 -:101E10000D46FFF7C5FF844228BF0446D4B1B8463B -:101E200058F80C6B4046FFF79BFF30442860404653 -:101E30007E68FFF795FF331A9C4203D86C6001203F -:101E4000BDE8F0816B60A41B3B68AB602044E86098 -:101E50000220F5E72046F3E738B50C460546FFF7C4 -:101E60009FFFA04210D305F10C00FFF779FF044457 -:101E70006868B4FBF0F100FB1144BFF35B8F0120F5 -:101E8000EC60BFF35B8F38BD0020FCE72DE9FF411C -:101E9000884669460746FFF7B7FF6C4606B204EB73 -:101EA000C6060025B44209D06268206808EB050127 -:101EB000FFF724FD636808341D44F3E729463846DC -:101EC000FFF7CAFF284604B0BDE8F081F8B5054623 -:101ED0000C300F46FFF744FF05F108060446304674 -:101EE000FFF73EFFA042304688BF6C68FFF738FF1F -:101EF000201A386020B130462C68FFF731FF2044AB -:101F0000F8BD000073B5144606460D46FFF72EFFD8 -:101F1000844228BF04460190DCB101A93046FFF796 -:101F2000D5FF019B33B93268C5E90233C5E9002406 -:101F300001200CE09C4238BF019428600198686041 -:101F40008442F5D93368AB60241AEC60022002B0F9 -:101F500070BD2046FBE700002DE9FF410F466946B2 -:101F6000FFF7D0FF6C4600B204EBC0050026AC4280 -:101F700009D0D4F8048054F8081BB8194246FFF77A -:101F8000BDFC4644F3E7304604B0BDE8F0810000F4 -:101F900038B50546FFF7E0FF044601462846FFF73F -:101FA00019FF204638BD0000302383F3118862B644 -:101FB00070470000002383F3118862B67047000069 -:101FC000012070477047000010B41346026814687F -:101FD0000022A4465DF8044B6047000000F58050E5 -:101FE00090F859047047000000F5805090F85204B2 -:101FF0007047000000F5805090F9580470470000C9 -:102000005020704700F5805208B5FFF7CDFFD2F899 -:102010009834D2F894041844D2F890341844D2F882 -:1020200078341844D2F888341844D2F884341844E8 -:10203000FFF7C0FF08BD000038B5C26A936923F0FE -:1020400001039361044600F08DFE0546E36A9B6937 -:10205000DB0706D500F086FE431BFA2BF6D90020DD -:1020600004E004F58054012084F8520438BD0000D7 -:102070002DE9F04F0C4600F5805185B01F4691F8D0 -:102080005234BDF83890054690469BB1D1F874346F -:102090000133C1F8743423689A0006D4237B082BDB -:1020A0000BD9627B0AB10F2B07D9D1F878340133F1 -:1020B000C1F878344FF0FF300FE0FFF775FFEB6A9F -:1020C000D3F8C42012F4001A0AD0D1F87C340133BA -:1020D000C1F87C34FFF76EFF002005B0BDE8F08F3B -:1020E000D3F8C46022686B6AC6F301464FF0480B10 -:1020F000002A1BFB063BB4BF42F080429204CBF89F -:10210000002023685B0044BF42F00052CBF800205F -:10211000227B330643EA0243CBF80430607B720132 -:1021200018B343F44013CBF80430D1F8A43401338E -:10213000C1F8A434AB1803F58353197B41F0200197 -:102140001973207B039200F06BFE039A033080101A -:102150005FFA8AF383420AF1010A0DDA04EB830184 -:102160000BEB830349689960F2E7AB1803F58353DF -:10217000197B60F34511E3E7EB6A0121B140C3F835 -:10218000CC10AB1803F58253C3E9048705EB461363 -:1021900003F582532146183304F10C0051F804CBA7 -:1021A00043F804CB8142F9D1098819802A4441F2CD -:1021B00068032846D65002F5805209F0030392F8CE -:1021C0006C1043F0100321F01F010B4382F86C30B8 -:1021D000FFF7F0FE4246CDF800903B46214600F066 -:1021E000E5FD012079E7000013B500F58054019169 -:1021F000606CFFF7D5FD1F280AD90199606C202279 -:10220000FFF744FEA0F120035842584102B010BD30 -:102210000020FBE708B500F58050FFF7C5FE406CD5 -:10222000FFF792FDBDE80840FFF7C4BE0022026040 -:10223000828142608260704710B500220023C0E9AD -:1022400000230023044603810C30FFF7EFFF2046F4 -:1022500010BD00002DE9F047074688B007F580540F -:1022600068469A468846FFF79FFE9146FFF7E4FFCF -:10227000606CFFF77BFD1F282CD9606C202269461B -:10228000FFF786FE202825D194F8523413B303AD0E -:10229000444605AB2E4603CE9E4220606160354623 -:1022A00004F10804F6D130682060B388A380DDE92A -:1022B0000023C9E90023BDF80830AAF80030FFF771 -:1022C00079FE4A4653464146384608B0BDE8F047D5 -:1022D00000F05ABDFFF76EFE002008B0BDE8F087A1 -:1022E0002DE9F84F00230646C0E90133294B46F893 -:1022F000303B00F581540546884637461034384651 -:102300002037FFF799FFA742F9D105F580544FF424 -:10231000805326630026C4E90D366764012305F562 -:10232000835705F5A359E66384F8403084F84830B4 -:10233000103709F110094FF0000A4FF0000B47E980 -:1023400008ABA7F11800FFF771FF203747F8286C9A -:102350004F45F4D1B8F1010F84F85884A4F85A64B9 -:10236000A4F85C64A4F85E6484F86064A4F8626411 -:10237000A4F86464A4F8666484F8686402D9064822 -:1023800000F0EAFC054B53F82830EB622846BDE824 -:10239000F88F00BFF8530008CC530008E85300083A -:1023A00010B5044B197804464A1C1A70FFF798FFC1 -:1023B000204610BD995F00202DE9F04300295FD031 -:1023C0003048314BB3FBF1F381428CBF0A2011201E -:1023D000451EB3FBF0F700FB1730ECB220B1022D25 -:1023E0002846F5D8002037E07D1EB5F5806F33D242 -:1023F000C4EBC40808F103034FEAE30EC3F3C703B9 -:10240000A4EB030C0EF101094FF47A705FFA8CF61D -:102410000EFB000E59FA8CFCBEFBFCFCBCF5617F88 -:102420001CDC1FFA8CF4581C56FA80F047431648FF -:10243000B0FBF7F7B942D5D1013BDBB20F2BD1D8B6 -:10244000711EC9B207294FF0000005D81071148021 -:102450005580537191710120BDE8F08308F1FF337D -:102460004FEAE30CC3F3C703E41A0CF1010EE6B222 -:102470000CFB00005EFA84F4B0FBF4F4A4B2D2E7E3 -:102480000846E9E73F420F000024F40038B500F5A4 -:102490008053114A93F85834D55C4FF45472554325 -:1024A00005F1804303F52443044600211846FFF755 -:1024B00037FA0A4B60612B44A361094B2B44E3615B -:1024C000084B2B442362084B2B446362E36A0022CF -:1024D000C3F8C02038BD00BFE053000870A400401E -:1024E000B0A4004088A5004078A600402DE9F04F38 -:1024F00000F58055994695F85834022B89B004466A -:102500008A46904604D90027384609B0BDE8F08FC6 -:102510009C4A52F8231009B942F823009A49C4F89A -:102520000CA00B7884F8109093B9FFF73DFD974B02 -:102530009A6D42F000729A659A6B42F000729A634B -:102540009A6B22F000729A6301230B70FFF732FD41 -:1025500095F85134BBB9FFF727FD8D4A95F85834EB -:10256000D35C012B26D0022B2BD03BB903211520A5 -:1025700001F054FD0321162001F050FD012385F8E0 -:102580005134FFF717FDFFF70FFDE26A936923F05F -:102590001003936100F0E6FB0746E36A9E6916F0BC -:1025A000080615D000F0DEFBC31BFA2BF5D9FFF7A8 -:1025B00001FDA8E70321562001F030FD032157203B -:1025C000DAE70321582001F029FD03215920D3E740 -:1025D0009A6942F001029A6100F0C4FB0746E36A7F -:1025E0009A69D00705D400F0BDFBC31BFA2BF6D9BE -:1025F000DDE79A6942F002029A61E36A00275F65AB -:10260000FFF7D8FC686CFFF79FFB04F5825B0BF1CA -:10261000100B202200216846FFF782F902A8FFF77D -:1026200005FE06976A460BEB06030DF1180E94465D -:10263000BCE80300F44518605960624603F10803E2 -:10264000F5D1DCF80000186020369CF804201A71DF -:10265000B6F5806FDDD1002304F5A25285F8503421 -:1026600085F853341A3251462046FFF7A5FE074637 -:1026700090B9E26A936923F00103936100F072FB61 -:102680000546E36A9B69D9077FF53DAF00F06AFB19 -:10269000431BFA2BF5D936E795F85F6495F85E246D -:1026A000C5F86CA4360246EA426695F86024E36AEF -:1026B0001643B5F85C2446EA0246DE61B8F1000F25 -:1026C00029D004F5A352023241462046FFF774FE9A -:1026D00090B9E26A936923F00103936100F042FB31 -:1026E0000546E36A9B69DA077FF50DAF00F03AFB18 -:1026F000431BFA2BF5D906E795F8683495F867146B -:10270000C5F870841B0143EA0123B5F86414E26A3A -:1027100043EA0143D3602046FFF7B8FE002385F863 -:102720005934E36A6FF040421A65E36A194A5A6500 -:10273000E36A44229A65E36A0722C3F8DC20E36A6D -:102740000322DA65E26A9369B9F1030F43F4407337 -:1027500093613FF4D9AEE26A936923F00103936178 -:1027600000F000FB0646E36A9B69DB0705D500F035 -:10277000F9FA831BFA2BF6D9C5E6012385F8523402 -:10278000C2E600BF905F0020985F0020001002406A -:10279000E05300089B0008002DE9F04F054689B082 -:1027A00090469946002741F2680A00F58056EB6A88 -:1027B000D3F8D430FB40D8074AD505EB4712524432 -:1027C0004FEA471B1379190742D4D6F880340133F6 -:1027D000C6F8803413799A0648BFD6F8A83405EBBA -:1027E0000B0248BF0133524448BFC6F8A8341379DE -:1027F00043F008031371DB0722D596F85334FBB17D -:1028000005F58254183468465C44FFF715FD03ABA8 -:1028100004F1080C206861681A4603C20834644554 -:102820001346F7D120681060A2889A800123ADF882 -:1028300008302B68CDE90089DB6B6946284698474C -:10284000D6F8543423B1D6F89C340133C6F89C34FE -:102850000137202FABD109B0BDE8F08F2DE9F04F43 -:102860008DB004460F4600F07FFA82468946002F5D -:1028700056D1E36AD3F89020920141BF04F580510C -:10288000D1F894240132C1F89424D3F8902016078B -:1028900003D100200DB0BDE8F08FD3F89050E66969 -:1028A000C5F30125482303FB0566E8464046FFF7CC -:1028B000BDFC326851004ABF22F06043C2F38A4334 -:1028C00043F00043920048BF43F080430093736895 -:1028D00013F400131FBF04F5805201238DF80D304F -:1028E000D2F8AC340EBF8DF80D300133C2F8AC34E1 -:1028F000F38803F00F038DF80C304FF0000B9DF8B8 -:102900000C0000F08DFA5FFA8BF3984220D9F21890 -:102910000CA90B44127A03F82C2C0BF1010BEEE7F7 -:10292000012FB6D1E36AD3F89820950141BF04F591 -:102930008051D1F894240132C1F89424D3F898201E -:102940001007A6D0D3F89850266AC5F30125A9E749 -:10295000EFB9E36AC3F8945004A8FFF76DFC98E858 -:102960000F0007AD07C52B800023ADF81830236892 -:102970002046CDE904A9DB6B04A9984704F58054EF -:1029800058B1D4F88C340133C4F88C3482E7012F69 -:1029900004BFE36AC3F89C50DEE7D4F890340133F7 -:1029A000C4F89034012075E7F8B505460F4600F5E8 -:1029B0008054012639462846FFF750FF10B184F8AD -:1029C0005364F7E7D4F8543423B1D4F89C3401337A -:1029D000C4F89C34F8BD0000F0B5C36A1A6C12F458 -:1029E0007F0F2BD000F580541B6CC4F8A03441F24B -:1029F0006805002347194FF0010C00EB43122A44ED -:102A00005E01117911F0020F15D0490713D4B9599D -:102A1000C66AD6F8C8E00CFA01F111EA0E0F0AD026 -:102A2000C6F8D010117941F004011171D4F888244E -:102A30000132C4F888240133202BDED1F0BD000020 -:102A40002B4B70B51E561B5C012B2FD8294D2A4AE3 -:102A500055F8233052F826400BB341B3236D1A06C4 -:102A60000FD58023236500F07FF950EA01020B4661 -:102A700002D0013861F10003024655F82600FFF745 -:102A80008BFE236D1B032CD555F826304FF4002206 -:102A900003F580532265012283F8592421E00123A4 -:102AA0002365082323654FF48063236570BD236D80 -:102AB000DA0702D4236D9B0706D5032355F82600B9 -:102AC00023650021FFF770FF236D180702D4236DE3 -:102AD000D90606D5182355F8260023650121FFF7EE -:102AE00063FF55F82600BDE87040FFF775BF00BFD3 -:102AF000E4530008905F0020E853000808B5FFF792 -:102B000053FAFFF769FFBDE80840FFF753BA00002A -:102B1000C36AD3F8C40080F40010C0F3405070477B -:102B200000F5805008B5FFF73FFA406CFFF71EF93B -:102B3000FFF740FA43090CBF0120002008BD000048 -:102B400000F5805393F8592462B1C16A8A6922F072 -:102B500001028A61D3F898240132C3F89824002234 -:102B600083F85924704700002DE9F74300F582519E -:102B700098461031FFF718FA002541F2680E4FF021 -:102B8000010900F5805C00EB4514744423795E076D -:102B90001CD4DB061AD5C36A8E69D3F8C87009FA4B -:102BA00006F63E4212D04F6801970F689742019F88 -:102BB00077EB08070AD2C3F8D060237943F0040307 -:102BC0002371DCF884340133CCF884340135202DB2 -:102BD00001F12001D7D103B0BDE8F043FFF7EAB916 -:102BE000F8B51E46002313700F4605461446FFF73E -:102BF00097FF80F0010038701EB12846FFF788FF6C -:102C00002070F8BD2DE9F04F85B09946DDE90EA39F -:102C10000D4602931378019391F800B08046164652 -:102C200000F0A2F82B7804460F4613B93378002B36 -:102C300042D022463B464046FFF796FFFFF75EFF35 -:102C4000FFF77EFF4B4632462946FFF7C9FF2B7838 -:102C500033B1BBF1000F03D0012005B0BDE8F08F08 -:102C6000337813B1019B002BF6D108F58053039301 -:102C7000029B544577EB03031ED2039BD3F8540405 -:102C8000D0B10368AAEB0401DB6889B298474B46D0 -:102C9000324629464046FFF7A3FF2B7813B1BBF11C -:102CA000000FD9D1337813B1019B002BD4D100F0A0 -:102CB0005BF804460F46DBE70020CEE708B50021AD -:102CC0000846FFF7BDFEBDE8084001F05FB8000010 -:102CD00008B501210020FFF7B3FEBDE8084001F070 -:102CE00055B8000008B500210120FFF7A9FEBDE896 -:102CF000084001F04BB8000008B501210846FFF775 -:102D00009FFEBDE8084001F041B8000000B59BB04F -:102D1000EFF3098168226846FEF7F0FDEFF30583C3 -:102D2000014B9B6BFEE700BF00ED00E008B5FFF72D -:102D3000EDFF000000B59BB0EFF309816822684603 -:102D4000FEF7DCFDEFF30583014B5B6BFEE700BF95 -:102D500000ED00E0FEE700000FB408B5029801F0B6 -:102D6000E3FBFEE701F006BF01F0DEBE01F0DCBED2 -:102D700013B56C4684E80600031D94E8030083E85D -:102D80000500012002B010BD73B58568019155B1F1 -:102D90001B885B0707D4D0E900369B6B9847019AE4 -:102DA000C1B23046A847012002B070BDF0B58668B8 -:102DB00089B005460C465EB1BDF838305B070AD4D1 -:102DC000D0E900379B6B98472246C1B23846B047DE -:102DD000012009B0F0BD00220023CDE9002300232B -:102DE000ADF808300A4603AB01F1080610685168D7 -:102DF0001C4603C40832B2422346F7D11068206053 -:102E00009288A280FFF7B2FF0423ADF808302B6848 -:102E1000CDE90001DB6B694628469847D8E70000FA -:102E2000082817D909280CD00A280CD00B280CD058 -:102E30000C280CD00D280CD00E2814BF40203020B8 -:102E400070470C20704710207047142070471820DE -:102E500070472020704700002DE9F041456A15B900 -:102E60004162BDE8F0814B6823F06047C3F38A46B6 -:102E70004FEAD37EC3F3807816EA230638BF3E4676 -:102E8000AC462B465A68BEEBD27F22F060440AD093 -:102E9000002A18DAA40CB44217D19D420FD10D605C -:102EA000DEE71346EEE7A74207D102F08044C2F303 -:102EB000807242450BD054B1EFE708D2EDE7CCF871 -:102EC00000100B60CDE7B44201D0B442E5D81A68D7 -:102ED0009C46002AE5D11960C3E700002DE9F047C0 -:102EE000089D01F007044FEAD508224405F00705C4 -:102EF00000EBD1004FF47F49944201D1BDE8F08747 -:102F000004F0070705F0070A57453E4638BF564606 -:102F1000C6F10806111B8E4228BF0E46E10808EBD9 -:102F2000D50E415C13F80EC0B94029FA06F721FA14 -:102F30000AF1FFB28CEA010147FA0AF739408CEA3C -:102F4000010C03F80EC034443544D5E780EA012073 -:102F5000082341F2210201B24000002980B203F1AE -:102F6000FF33B8BF504013F0FF03F4D170470000A7 -:102F700038B50C468D18A54200D138BD14F8011B98 -:102F8000FFF7E4FFF7E7000042684AB113684360C7 -:102F90004389818901339BB29942438138BF838140 -:102FA0001046704770B588B0202204460D4668462A -:102FB0000021FEF7B5FC20460495FFF7E5FF024629 -:102FC00058B16B46054608AE1C4603CCB442286097 -:102FD0006960234605F10805F6D1104608B070BDBA -:102FE000082817D909280CD00A280CD00B280CD097 -:102FF0000C280CD00D280CD00E2814BF40203020F7 -:1030000070470C207047102070471420704718201C -:103010007047202070470000082817D90C280CD9C9 -:1030200010280CD914280CD918280CD920280CD910 -:1030300030288CBF0F200E207047092070470A20CF -:1030400070470B2070470C2070470D207047000020 -:103050002DE9F843078C072F04461ED9D0E90298C2 -:1030600000254FF6FF73C5F12006A5F1200029FACF -:1030700005F108FA06F628FA00F031430143C9B217 -:103080001846FFF763FF0835402D0346EBD1E16991 -:103090003A46BDE8F843FFF76BBF4FF6FF70BDE857 -:1030A000F883000010B54B6823B9CA8A63F309029C -:1030B000CA8210BD04691A681C600361C38A013B9F -:1030C000C3824A60EFE700002DE9F84F1D46CB8A26 -:1030D0000F46C3F309010529814692460B4630D0BD -:1030E0000020AAB207F11A049EB2042E1FFA80F83B -:1030F0000FD8904503F1010306D3FB8A0A4462F31B -:103100000903FB8201201AE01AF80060E65401303E -:10311000EAE79045F1D2A1F1050B1C237C68BBFBCB -:10312000F3F203FB12BB1FFA8BF6002C45D1484685 -:10313000FFF72AFF044638B978606FF00200BDE857 -:10314000F88F4FF00008E6E7002606607860ADB221 -:103150004FF0000B454510D90AEB0803221D13F868 -:10316000011B9155B1B208F101081B291FFA88F81B -:103170002BD0454506F10106F1D8FB8AC3F30902BD -:10318000154465F30903BCE7013292B21C4623687B -:10319000002BF9D16B1F0B441C21B3FBF1F301335E -:1031A0009BB29A42D3D2BBF1000FD0D14846FFF771 -:1031B000EBFE20B9C4F800B0BFE70122E7E7C0F892 -:1031C00000B05E4620600446C1E74545D5D9484673 -:1031D000FFF7DAFE08B92060AFE7C0F800B00026BC -:1031E00020600446B6E700002DE9F04F2DED028B7C -:1031F0001C4683B05B69019207468846002B00F0AD -:103200009A80238C2BB1E269002A00F09480072B6E -:1032100035D807F10C00FFF7B7FE054638B96FF057 -:103220000205284603B0BDEC028BBDE8F08F1422E6 -:103230000021FEF775FB228CE16905F10800FEF71D -:103240005DFB208C013080B2FFF7E6FEFFF7C8FE81 -:10325000013880B22084013028746369228C1B7885 -:103260002A4403F01F0363F03F0348F00041137248 -:10327000384669602946FFF7EFFD0125D1E700F1E7 -:103280000C034FF0000908EE103A4FF0800A4E464A -:103290004D4618EE100AFFF777FE83460028BED091 -:1032A00014220021FEF73CFB002E3AD1019BABF823 -:1032B000083002220BF1080E1FFA82FC0CF101000B -:1032C000BCF1060F218C80B201D88E422BD3FFF7C0 -:1032D000A3FEFFF785FE62691278013802F01F0233 -:1032E0008E4208BF4FF0400A42EA49121BFA80F1B1 -:1032F0004AEA020A013048F0004281F808A08BF83F -:103300001000CBF8042059463846FFF7A5FD238C62 -:103310000135B3422DB289F001094FF0000AB8D14E -:103320007FE70022C6E7E169895D0EF802100136E9 -:10333000B6B20132C0E76FF0010572E7F8B5154685 -:103340000E463022002104461F46FEF7E9FA069B8E -:103350006360B5F5001F079BA76034BF6A094FF68D -:10336000FF72A36297B2E66104F1100000239A4253 -:1033700006D800230360A782E3822383E360F8BDBD -:103380000660013330462036F1E7000003781BB9B0 -:103390004BB2002BC8BF0170704700000078704727 -:1033A000F8B50C46C969074611B9238C002B37D1F3 -:1033B000257E1F2D34D8387828BB228C072A2CD89C -:1033C000268A36F003032BD14FF6FF70FFF7D0FDAE -:1033D00020F001003102400441EA0561400C41EA5D -:1033E00040254FF6FF72234629463846FFF7FCFE7C -:1033F000002807DD626913780133DBB21F2B88BF19 -:1034000000231370F8BD218A2D0645EA01250543E6 -:103410002046FFF71DFE0246E5E76FF00300F1E7E7 -:103420006FF00100EEE7000070B58AB00446164662 -:103430000021282268461D46FEF772FABDF8383092 -:10344000ADF810300F9B05939DF840308DF8183083 -:10345000119B07936946BDF84830ADF820302046EF -:10346000CDE90265FFF79CFF0AB070BD2DE9F04180 -:10347000D36905460C4616460BB9138C5BBB377EE9 -:103480001F2F28D895F80080B8F1000F26D03046BD -:10349000FFF7DEFD3378210241EAC33141EA08013A -:1034A000338A41EA076141EA03410246334641F06B -:1034B00080012846FFF798FE00280ADD3378012BAB -:1034C00007D1726913780133DBB21F2B88BF002349 -:1034D0001370BDE8F0816FF00100FAE76FF00300B0 -:1034E000F7E70000F0B58BB004460D461746002103 -:1034F000282268461E46FEF713FA9DF84C305A1EE5 -:10350000534253418DF800309DF84030ADF81030F3 -:10351000119B05939DF848308DF81830149B079344 -:103520006A46BDF85430ADF8203029462046CDE932 -:103530000276FFF79BFF0BB0F0BD0000406A00B1C0 -:1035400004307047436A1A68426202691A60036174 -:10355000C38A013BC38270472DE9F041D0F8208037 -:10356000194E14461D464146002709B9BDE8F081B1 -:10357000D1E90223A21A65EB0303964277EB03031A -:103580001ED2036A8B420DD1FFF78CFD036A1B68C4 -:10359000036203690B60C38A0161016A013BC38254 -:1035A0008846E2E7FFF77EFD0B68C8F80030036944 -:1035B0000B60C38A0161013BC382D8F80010D4E7D5 -:1035C00088460968D1E700BF80841E002DE9F04FCE -:1035D0008BB00D46DDF8509014469B46804600287F -:1035E00000F01981B9F1000F00F01581531E3F2B37 -:1035F00000F21181012A03D1BBF1000F40F00B81D1 -:103600000023CDE90833B8F81430B5EBC30F4FEA07 -:10361000C30703D300200BB0BDE8F08F2B199F42E6 -:10362000D8F80C303ABF7F1BFFB227461BB9D8F839 -:103630001030002B7AD0272D4ED8C5F12806B7427E -:103640004FF000032CBFF6B23E4600932946D8F84F -:10365000080008AB3246FFF741FCA7EB060A3544E9 -:103660005FFA8AFAB8F8143003F10053053BDB0027 -:103670000493D8F80C3003932821039B13B1BAF1BB -:10368000000F2CD1D8F8100040B1BAF1000F05D0CE -:10369000009608AB5246691AFFF720FC38B2002F9B -:1036A000B8D066070AD00AAB03EBD401624211F826 -:1036B000083C02F00702134101F8083C082C3CD9F1 -:1036C000102C40F2B580202C40F2B780BBF1000FE7 -:1036D00000F09C80082334E0BA460026C2E7049B31 -:1036E000E02B28BFE02306930B44AB42059314D98B -:1036F0005A1B03980096924534BF5246D2B2691ABB -:1037000008AB04300792FFF7E9FB079A1644AAEBCF -:10371000020A1544F6B25FFA8AFA049B069A0599E2 -:103720009B1A0493039B1B680393A6E70093D8F8A6 -:10373000080008AB3A462946AEE7BBF1000F13D0AC -:103740000123B4EBC30F6CD0082C12D89DF82030A5 -:10375000621E23FA02F2D50706D54FF0FF3202FAB5 -:1037600004F423438DF820309DF8203089F8003090 -:1037700051E7102C12D8BDF82030621E23FA02F255 -:10378000D10706D54FF0FF3202FA04F42343ADF817 -:103790002030BDF82030A9F800303CE7202C0FD8AD -:1037A0000899631E21FA03F3DA0705D54FF0FF32BB -:1037B00002FA04F40C430894089BC9F800302AE785 -:1037C000402C2BD0DDE90865611EC4F12102A4F173 -:1037D000210326FA01F105FA02F225FA03F3114357 -:1037E0001943CB0712D50122A4F12003C4F1200113 -:1037F00002FA03F322FA01F1A240524243EA010322 -:1038000063EB430332432B43CDE90823DDE908236F -:10381000C9E90023FFE66FF00100FCE66FF0080045 -:10382000F9E6082CA0D9102CB3D9202CEED8C3E788 -:10383000BBF1000FADD0022383E7BBF1000FBBD07B -:1038400004237EE730B5012A144638BF0124402CFA -:1038500085B028BF40240025012ACDE9025518D89B -:103860001B788DF8083063070AD004AB03EBD4054E -:10387000624215F8083C02F00702934005F8083C44 -:10388000009103462246002102A8FFF727FB05B05E -:1038900030BD082AE4D9102A03D81B88ADF80830B7 -:1038A000E1E7202A8DBFD3E900231B680293CDE90D -:1038B0000223D8E710B5CB681BB98B600B618B82F4 -:1038C00010BD04691A681C600361C38A013BC3828E -:1038D000CA60F0E72DE9F04F93B0CDE903230B6800 -:1038E00004460D461806C3F3C01147BFC3F3C03BDF -:1038F000C3F306264FF0020B0E46002B80F2FF8129 -:1039000013F0C04940F0FB812A7B002A00F0F781C8 -:10391000BBF1020F03D02078B04240F0F381C3F333 -:103920000460079003F07F00059059B3C3F3074A82 -:103930002A44059B92F80380760646EA0B4646EA3F -:10394000834600220023CDE908235FEAD81346EA24 -:103950000A0602936AD0059B009367685B4652464D -:1039600008A92046B847002800F0CF81276A87B908 -:10397000314604F10C00FFF715FB0746C8B96FF09C -:10398000020057E0C3F30F2A590608BF0AF0030AE2 -:10399000CEE73B699E420DD03F68002FF9D13146FA -:1039A00004F10C00FFF7FEFA07460028E7D0236A6F -:1039B0003B602762FE7D08F01F03C6F38406F01A01 -:1039C0001FFA80FC0028B8BF0CF12000D7E90221C3 -:1039D0000693A3EB06031FFA83FCB8BF00B2002BCB -:1039E000BCBF0CF120031BB252EA010636D0039E85 -:1039F000DFF8D4C2B21A049E66EB0101002694459A -:103A000076EB010C2AD395F80DE097F81AC0E6453D -:103A100018D1029E002E79D001281FDC7868E8B901 -:103A2000A84E964270EB010216D337E0276A27B9F9 -:103A30006FF00C0013B0BDE8F08F3B699E42B9D027 -:103A40003F68F4E79F48904276EB010201D30020E3 -:103A5000F0E7029A002AFAD00F2B18DCFA7D4FEA21 -:103A6000880302F0030203F07C031343FB7539461D -:103A70002046FFF717FB6B7BBB76029B3BB9FB7DB8 -:103A8000C3F38402013262F38603FB75D0E76A7BDD -:103A9000BB7E9A42DBD1029B002B37D04FEA9813B2 -:103AA000022B33D0039BBB60049BFB6014220021DC -:103AB0000DA8FDF735FF039B0A93049B0B932B1D69 -:103AC0000C932B7BADF83EA0013BDBB2ADF83C3054 -:103AD000069B8DF84130079B8DF84230059B8DF891 -:103AE000433094F82C308DF840B083F001038DF80A -:103AF00044300AA9A36820469847FB7DC3F384039A -:103B0000013303F01F039B02FB82A0E7FB7DC8F398 -:103B10004012B2EBD31F40F0FB80069AC3F384033C -:103B2000934240F0F88002992B7B4FEA98120029CB -:103B30004DD0D2075DD4032B40F2F080039BBB60D5 -:103B4000049BFB602B7BAE1D033BDBB23246394648 -:103B500004F10C00FFF7B8FA00280CDA39462046C9 -:103B6000FFF7A0FAFB7DC3F38403013303F01F03C7 -:103B70009B02FB8203E7DDE90884AB883B834FF6B9 -:103B8000FF73C9F12000A9F1200228FA09F104FA13 -:103B900000F0014324FA02F211431846C9B2FFF7BC -:103BA000D5F909F10809B9F1400F0346E9D1B88206 -:103BB0002A7B033AD2B23146FFF7DAF9FB7DB882AD -:103BC000DA43C2F3C01262F3C713FB753FE782B951 -:103BD0002E1D013BDBB23246394604F10C00FFF7E3 -:103BE00073FA0028BADB2A7BB88A013AD2B231468E -:103BF000E2E7F98AC1F30901013B0429DAB25CD892 -:103C0000281D002307F11B069A4208D910F801CBA2 -:103C100006F801C0013101330529DBB2F4D1039963 -:103C20000A9104990B91934207F11B010C9138BF43 -:103C3000043379680D9134BF55FA83F300230E9352 -:103C4000FB8AADF83EA0C3F309031A44069B8DF826 -:103C50004130079B8DF84230059B8DF8433094F836 -:103C60002C30ADF83C2083F001038DF84430002364 -:103C70008DF840B07B602A7BB88A013A291DFFF796 -:103C800077F93B8BB882834203D1A3680AA9204607 -:103C9000984720460AA9FFF70DFEFB7DBA8AC3F3B9 -:103CA0008403013303F01F039B02FB823B8B9A4288 -:103CB0000CBF00206FF01000BCE67B68002BAED07C -:103CC000052005E040420F0080841E001C30334672 -:103CD0001E68002EFAD1091A081D2E1D184401EB8A -:103CE000090CBCF11B0F5FFA89F398D89A4296D958 -:103CF00016F8013B00F8013B09F10109EFE76FF00D -:103D0000090097E66FF00A0094E66FF00B0091E669 -:103D10006FF00D008EE66FF00E008BE66FF00F0077 -:103D200088E600BFEFF3098305494A6B22F00102E0 -:103D30004A63683383F30988002383F3118870474B -:103D400000EF00E0302080F3118862B60C4B0D4A82 -:103D5000D96821F4E0610904090C0A43DA60D3F858 -:103D6000FC20094942F08072C3F8FC200A6842F046 -:103D700001020A602022DA7783F82200704700BF30 -:103D800000ED00E00003FA05001000E010B530235C -:103D900083F311880E4B5B6813F4006314D0F1EECB -:103DA000103AEFF30984683C4FF08073E361094BEC -:103DB000DB6B236684F3098800F074FB10B1064BBB -:103DC000A36110BD054BFBE783F31188F9E700BF42 -:103DD00000ED00E000EF00E04306000846060008A2 -:103DE000026843681143016003B11847704700003F -:103DF000024A136843F0C003136070470044004058 -:103E000013B50E4C204600F0B3FA04F114000C492F -:103E1000009400234FF4807200F070F9094B0A49B6 -:103E200000944FF4807204F1380000F0E9F9074A79 -:103E3000074BC4E9172302B010BD00BFA05F0020EC -:103E40000C600020F13D00080C610020004400409F -:103E5000007A030A30B5037C214C002918BF0C46B8 -:103E6000012B0CD11F4B984209D11F4B9A6D42F484 -:103E700000329A659A6F42F400329A679B6F22680B -:103E8000036EC16D846603EB5203B3FBF2F3626809 -:103E9000150442BF23F0070503F0070343EA450377 -:103EA000CB60A36843F040034B60E36843F0010339 -:103EB0008B6042F4967343F001030B604FF0FF33C5 -:103EC0000B62510505D512F0102205D0B2F1805FCA -:103ED00004D080F8643030BD7F23FAE73F23F8E751 -:103EE00038540008A05F0020001002402DE9F04780 -:103EF000C66D3768F46934622107054619D014F09D -:103F0000080118BF4FF48071E20748BF41F020015B -:103F1000A30748BF41F04001600748BF41F080015E -:103F2000302383F31188281DFFF75AFF002383F302 -:103F30001188E2050AD5302383F311884FF480619C -:103F4000281DFFF74DFF002383F311884FF0300940 -:103F50004FF0000A14F0200838D13B0616D54FF078 -:103F6000300905F1380A200610D589F3118850462A -:103F700000F07AF9002836DA0821281DFFF730FF13 -:103F800027F080033360002383F31188790614D56A -:103F9000620612D5302383F31188D5E913239A42A0 -:103FA00008D12B6C33B11021281D27F04007FFF7F3 -:103FB00017FF3760002383F31188E30618D5AA6E34 -:103FC0001369ABB1BDE8F0475069184789F3118810 -:103FD000736A95F864102846194000F0E3F98AF3F3 -:103FE0001188F469B6E7B06288F31188F469BAE71A -:103FF000BDE8F0874FF0E023002258684FF0FF3112 -:10400000930003F1604303F5614301329042C3F82A -:104010008010C3F88011F3D27047000000F16043B4 -:1040200003F561430901C9B283F80013012200F0CE -:104030001F039A4043099B0003F1604303F561436A -:10404000C3F880211A607047F8B515468268066982 -:10405000AA420B46816938BF8568761AB542044684 -:104060000BD218462A46FDF749FCA3692B44A361ED -:10407000A3685B1BA3602846F8BD0CD918463246DE -:10408000FDF73CFCAF1BE1683A463044FDF736FCD7 -:10409000E3683B44EBE718462A46FDF72FFCE3684C -:1040A000E5E7000083689342F7B51546044638BF3C -:1040B0008568D0E90460361AB5420BD22A46FDF76E -:1040C0001DFC63692B446361A36828465B1BA360E6 -:1040D00003B0F0BD0DD932460191FDF70FFC0199F7 -:1040E000E068AF1B3A463144FDF708FCE3683B4407 -:1040F000E9E72A46FDF702FCE368E4E710B50A4465 -:104100000024C361029B8460C0E90000C0E905117E -:10411000C1600261036210BD08B5D0E90532934267 -:1041200001D1826882B98268013282605A1C426180 -:104130001970D0E904329A4224BFC3684361002158 -:1041400000F078FA002008BD4FF0FF30FBE70000D8 -:1041500070B5302304460E4683F31188A568A5B1D7 -:10416000A368A269013BA360531CA361157822696F -:10417000934224BFE368A361E3690BB120469847EB -:10418000002383F31188284607E03146204600F0DB -:1041900041FA0028E2DA85F3118870BD2DE9F74F66 -:1041A00004460E4617469846D0F81C904FF0300A49 -:1041B0008AF311884FF0000B154665B12A46314647 -:1041C0002046FFF741FF034660B94146204600F014 -:1041D00021FA0028F1D0002383F31188781B03B063 -:1041E000BDE8F08FB9F1000F03D001902046C84719 -:1041F000019B8BF31188ED1A1E448AF31188DCE7CA -:10420000C0E90511C160C3611144009B8260C0E92F -:104210000000016103627047F8B504460D4616467A -:10422000302383F31188A768A7B1A368013BA3607B -:1042300063695A1C62611D70D4E904329A4224BF3A -:10424000E3686361E3690BB120469847002080F37F -:10425000118807E03146204600F0DCF90028E2DA58 -:1042600087F31188F8BD0000D0E905239A4210B504 -:1042700001D182687AB98268013282605A1C8261F7 -:104280001C7803699A4224BFC3688361002100F04F -:10429000D1F9204610BD4FF0FF30FBE72DE9F74F75 -:1042A00004460E4617469846D0F81C904FF0300A48 -:1042B0008AF311884FF0000B154665B12A46314646 -:1042C0002046FFF7EFFE034660B94146204600F066 -:1042D000A1F90028F1D0002383F31188781B03B0E3 -:1042E000BDE8F08FB9F1000F03D001902046C84718 -:1042F000019B8BF31188ED1A1E448AF31188DCE7C9 -:10430000026843681143016003B118477047000019 -:104310001430FFF743BF00004FF0FF331430FFF7B6 -:104320003DBF00003830FFF7B9BF00004FF0FF334A -:104330003830FFF7B3BF00001430FFF709BF0000AB -:104340004FF0FF311430FFF703BF00003830FFF7A4 -:1043500063BF00004FF0FF323830FFF75DBF000051 -:10436000012914BF6FF0130000207047FFF748BD0C -:10437000044B03600023C0E902334360012303744C -:10438000704700BF5054000810B53023044683F333 -:104390001188FFF75FFD02232374002080F311884A -:1043A00010BD000038B5C36904460D461BB9042191 -:1043B0000844FFF7A5FF294604F11400FFF7ACFEFF -:1043C000002806DA201D4FF40061BDE83840FFF7F1 -:1043D00097BF38BD00230375826803691B6899681D -:1043E0009142FBD25A680360426010605860704787 -:1043F00000230375826803691B6899689142FBD8A2 -:104400005A680360426010605860704708B50846FB -:10441000302383F311880B7D032B05D0042B0DD0A3 -:104420002BB983F3118808BD8B6900221A604FF005 -:10443000FF338361FFF7CEFF0023F2E7D1E90032BB -:1044400013605A60F3E70000FFF7C4BF054BD9685B -:104450000875186802681A60536001220275D860F6 -:10446000FCF7DAB81062002030B50C4BDD684B1C4D -:1044700087B004460FD02B46094A684600F06CF915 -:104480002046FFF7E3FF009B13B1684600F06EF98A -:10449000A86907B030BDFFF7D9FFF9E71062002027 -:1044A0000D440008044B1A68DB6890689B689842CA -:1044B00094BF00200120704710620020084B10B507 -:1044C0001C68D86822681A60536001222275DC607B -:1044D000FFF78EFF01462046BDE81040FCF79CB870 -:1044E00010620020044B1A68DB6892689B689A424D -:1044F00001D9FFF7E3BF70471062002038B5074CC1 -:1045000007490848012300252370656000F030FC4E -:104510000223237085F3118838BD00BF7864002022 -:104520007C5400081062002008B572B6044B186570 -:1045300000F0E6FA00F09EFB024B03221A70FEE741 -:10454000106200207864002000F046B9EFF311807B -:1045500020B9EFF30583302282F311887047000001 -:1045600010B530B9EFF30584C4F3080414B180F337 -:10457000118810BDFFF7B6FF84F31188F9E700003A -:104580008B60022308618B82084670478368A3F121 -:10459000840243F8142C026943F8442C426943F81E -:1045A000402C094A43F8242CC26843F8182C0222F4 -:1045B00003F80C2C002203F80B2C044A43F8102CAF -:1045C000A3F12000704700BF3106000810620020F0 -:1045D00008B5FFF7DBFFBDE80840FFF735BF000077 -:1045E000024BDB6898610F20FFF730BF106200209C -:1045F000302383F31188FFF7F3BF000008B50146AD -:10460000302383F311880820FFF72EFF002383F364 -:10461000118808BD064BDB6839B1426818605A60E2 -:10462000136043600420FFF71FBF4FF0FF30704757 -:10463000106200200368984206D01A680260506039 -:1046400099611846FFF700BF7047000010B5036876 -:104650009C68A2420CD85C688A600B604C60216048 -:10466000596099688A1A9A604FF0FF33836010BDD1 -:104670001B68121BECE700000A2938BF0A2170B53D -:1046800004460D460A26601900F06CFB00F058FB4A -:10469000041BA54203D8751C2E460446F3E70A2ED8 -:1046A00004D9BDE87040012000F0A2BB70BD00003D -:1046B000F8B5144B0D46D96103F1100141600A2A87 -:1046C0001969826038BF0A22016048601861A81821 -:1046D000144600F039FB0A2700F032FB431BA342CB -:1046E000064606D37C1C281900F03CFB27463546BD -:1046F000F2E70A2F04D9BDE8F840012000F078BBAA -:10470000F8BD00BF10620020F8B506460D4600F067 -:1047100017FB0F4A134653F8107F9F4206D12A46D3 -:1047200001463046BDE8F840FFF7C2BFD169BB681B -:10473000441A2C1928BF2C46A34202D92946FFF758 -:104740009BFF224631460348BDE8F840FFF77EBF95 -:10475000106200202062002010B4C0E9032300236F -:104760005DF8044B4361FFF7CFBF000010B5194C53 -:10477000236998420DD0D0E90032816813605A60F5 -:104780009A680A449A60002303604FF0FF33A361E4 -:1047900010BD2346026843F8102F536000220260C8 -:1047A00022699A4203D1BDE8104000F0D5BA93685F -:1047B00081680B44936000F0C3FA2269E169926852 -:1047C000441AA242E4D91144BDE81040091AFFF787 -:1047D00053BF00BF106200202DE9F047DFF8BC8016 -:1047E00008F110072C4ED8F8105000F0A9FAD8F8AC -:1047F0001C40AA68031B9A423ED81444D5E90032F3 -:104800004FF00009C8F81C4013605A60C5F80090CA -:10481000D8F81030B34201D100F09EFA89F3118824 -:10482000D5E9033128469847302383F311886B6913 -:10483000002BD8D000F084FA6A69A0EB04094A453D -:1048400082460DD2022000F0D3FA0022D8F81030B0 -:10485000B34208D151462846BDE8F047FFF728BFCC -:10486000121A2244F2E712EB090938BF4A462946D8 -:104870003846FFF7EBFEB5E7D8F81030B34208D062 -:104880001444211AC8F81C00A960BDE8F047FFF7DE -:10489000F3BEBDE8F08700BF206200201062002058 -:1048A00000207047FEE70000704700004FF0FF3027 -:1048B00070470000BFF34F8F024A1369DB03FCD43B -:1048C000704700BF0020024008B5094B1B7873B940 -:1048D000FFF7F0FF074B5A69002ABFBF064A9A60EC -:1048E00002F188329A601A6822F480621A6008BD68 -:1048F00090640020002002402301674508B50B4B5F -:104900001B7893B9FFF7D6FF094B5A6942F0004272 -:104910005A611A6842F480521A601A6822F480526E -:104920001A601A6842F480621A6008BD9064002020 -:1049300000200240FF289ABF00F58030C00200200E -:10494000704700004FF40060704700004FF4807023 -:1049500070470000FF2808B50BD8FFF7EBFF00F504 -:1049600000630268013204D104308342F9D101208E -:1049700008BD0020FCE70000FF2838B5044626D813 -:10498000FFF7E4FDFFF796FFFFF79EFF114BF322C1 -:104990001A6102225A615A6942EAC4025A615A698A -:1049A00042F480325A6105462046FFF783FF4FF4F8 -:1049B0000061FFF7BFFF00F059F92846FFF79EFF9F -:1049C000FFF7CEFD2046BDE83840FFF7C3BF00200B -:1049D00038BD00BF0020024040EA020313F0070385 -:1049E0002DE9F04705460C46164606D0344B40F2FA -:1049F00031321A600020BDE8F0878118314A9142B7 -:104A00000CD92F4A40F236311160F3E72B1D1B6899 -:104A10006268934208D1083E08350834072E19D938 -:104A20002A6823689A42F1D0FFF790FDFFF74CFF08 -:104A3000FFF740FF04F10801234C4FF001084FF04D -:104A40000009012EA1F1080708D8FFF757FFFFF76B -:104A500087FD01E0002EE7D10120CCE7C4F81480E7 -:104A6000AA4651F8083C4AF8043B51F8043C6B60F4 -:104A7000FFF720FF236943F001032361C4F814907A -:104A80002A6851F8083C9A420ED00D4B40F25E3233 -:104A90001A600E4B1D600E4B1E600E4B1F60FFF721 -:104AA0002DFFFFF75DFDA5E7DAF800A051F8043C03 -:104AB0009A4501F10801E8D1083E0835C1E700BF79 -:104AC0008C64002000000808002002408064002060 -:104AD0008864002084640020084908B50B7828B158 -:104AE0001BB9FFF7F1FE01230B7008BD002BFCD0B2 -:104AF000BDE808400870FFF701BF00BF90640020C8 -:104B000008B54FF4C0314FF0005000F0B1F8BDE8E7 -:104B100008404FF400414FF0805000F0A9B8000069 -:104B2000084600F0F3BB000070B582B0FFF70EFD41 -:104B30000E4E054600F004F93268904237BF0C4A29 -:104B40000B49516814682EBFD1E900410131516011 -:104B50000419034641F10001284601913360FFF733 -:104B6000FFFC0199204602B070BD00BF9464002094 -:104B70009864002070B582B0FFF7E8FC104E05463F -:104B800000F0DEF83268904237BF0E4A0D49516896 -:104B900014682EBFD1E9004101315160041941F17F -:104BA00000010346284601913360FFF7D9FC0199C3 -:104BB0004FF47A7200232046FBF71AFB02B070BD57 -:104BC00094640020986400200244D2B2904200D144 -:104BD0007047431C800000F1804000F514500068CD -:104BE00041F8040BD8B2F1E7124B10B5D3F890405E -:104BF000240409D4D3F89040C3F89040D3F89040EF -:104C000044F40044C3F890400B4C2368024443F43E -:104C100080732360D2B2904200D110BD431C80004B -:104C200000F1804000F5145051F8044B0460D8B2F4 -:104C3000F1E700BF001002400070004007B50122FC -:104C400001A90020FFF7C0FF019803B05DF804FB45 -:104C500013B50446FFF7F2FFA04205D0012201A9D7 -:104C600000200194FFF7C0FF02B010BD70470000A4 -:104C70007047000070470000074B45F255521A601C -:104C800002225A6040F6FF729A604CF6CC421A60DB -:104C9000024B01221A70704700300040A4640020CB -:104CA000034B1B781BB1034B4AF6AA221A607047CC -:104CB000A464002000300040054B1A6832B902F1AC -:104CC000804202F50432D2F894201A60704700BF87 -:104CD000A0640020024B4FF40002C3F894207047F8 -:104CE0000010024008B5FFF7E7FF024B1868C0F359 -:104CF000407008BDA064002070470000FEE700007F -:104D00000A4B0B480B4A90420BD30B4BDA1C121A7E -:104D1000C11E22F003028B4238BF00220021FCF7A3 -:104D2000FFBD53F8041B40F8041BECE7EC550008EA -:104D300028650020286500202865002000F0C2B802 -:104D40004FF08043586A70474FF080430022586309 -:104D50001A610222DA6070474FF080430022DA6065 -:104D6000704700004FF0804358637047FEE7000033 -:104D700070B51B4B01630025044686B05860856200 -:104D80000E46FEF7DFFF04F11003C4E904334FF0D1 -:104D9000FF33C4E90635C4E90044A560E562FFF7C6 -:104DA000CFFF2B460246C4E9082304F134010D4A23 -:104DB000256580232046FFF7E3FB0123E0600A4AD4 -:104DC0000375009272680192B268CDE90223074B25 -:104DD0006846CDE90435FFF7FBFB06B070BD00BFA8 -:104DE00078640020885400088D5400086D4D000838 -:104DF000024AD36A1843D062704700BF1062002095 -:104E00004B6843608B688360CB68C3600B69436108 -:104E10004B6903628B6943620B6803607047000053 -:104E200008B5204BDA6A42F07F02DA62DA6A22F0D1 -:104E30007F02DA62DA6ADA6C42F07F02DA64DA6EF2 -:104E400042F07F02DA66184ADB6E11464FF090405E -:104E5000FFF7D6FF02F11C0100F58060FFF7D0FFDD -:104E600002F1380100F58060FFF7CAFF02F154013A -:104E700000F58060FFF7C4FF02F1700100F580606B -:104E8000FFF7BEFF02F18C0100F58060FFF7B8FF6D -:104E900002F1A80100F58060FFF7B2FFBDE808400D -:104EA00000F050B8001002409454000808B500F01B -:104EB000FBF9FFF723FBBDE80840FFF7FDBE00004C -:104EC000704700000F4B9A6D42F001029A659A6F8D -:104ED00042F001029A670C4A9B6F936843F001030A -:104EE00093604FF08043A7229A624FF0FF32DA625C -:104EF00000229A615A63DA605A6001225A611A608C -:104F0000704700BF00100240002004E04FF08042D4 -:104F100008B51169D3680B40D9B2C9439B07116129 -:104F200007D5302383F31188FFF70EFB002383F3AB -:104F3000118808BD08B5FFF75DF8BDE8084000F02E -:104F40008BB900004E4B4FF0FF319A6A99629A6A12 -:104F500000229A62986AD86A60F07F00D862D86AA4 -:104F600000F07F00D862D86A186B1963186B1A6357 -:104F7000186B986B9963986B9A63986BD86BD9632D -:104F8000D86BDA63D86B186C1964196C1A64196CD5 -:104F9000196E41F001011966D3F8801021F001016A -:104FA000C3F88010D3F88010996D41F08051996555 -:104FB000996F21F080519967996F32494FF4004001 -:104FC0008860CA600A624A628A62CA620A634A6385 -:104FD0008A63CA630A644A648A64CA640A654A6561 -:104FE0004A604FF48072C1F880204FF440720A602A -:104FF0004A6912F48062FBD1D3F8901011F4407F1B -:105000001EBF4FF48031C3F89010C3F89020D3F83E -:10501000982042F00102C3F89820D3F89820920714 -:10502000FBD51A6842F480321A601A689003FCD5E6 -:10503000D3F8902022F00322C3F89020124ADA60BD -:105040001A6842F080721A601A689101FCD50F4903 -:105050000F4800229A60C3F888100E49C3F89C20BC -:10506000016002684A401207FBD19A6842F00302CD -:105070009A609A6802F00C020C2AFAD1704700BFBD -:105080000010024000700040132A610155010050D9 -:105090000020024004070400074A08B5536903F0E2 -:1050A0000103536123B1054A13680BB15068984757 -:1050B000BDE80840FEF76ABE00040140A864002075 -:1050C000074A08B5536903F00203536123B1054A47 -:1050D00093680BB1D0689847BDE80840FEF756BE0C -:1050E00000040140A8640020074A08B5536903F092 -:1050F0000403536123B1054A13690BB15069984702 -:10510000BDE80840FEF742BE00040140A86400204C -:10511000074A08B5536903F00803536123B1054AF0 -:1051200093690BB1D0699847BDE80840FEF72EBEE1 -:1051300000040140A8640020074A08B5536903F041 -:105140001003536123B1054A136A0BB1506A9847A3 -:10515000BDE80840FEF71ABE00040140A864002024 -:10516000164B10B55C6904F478725A61A30604D535 -:10517000134A936A0BB1D06A9847600604D5104A67 -:10518000136B0BB1506B9847210604D50C4A936BF7 -:105190000BB1D06B9847E20504D5094A136C0BB1EB -:1051A000506C9847A30504D5054A936C0BB1D06C9D -:1051B0009847BDE81040FEF7E9BD00BF000401407C -:1051C000A8640020194B10B55C6904F47C425A6154 -:1051D000620504D5164A136D0BB1506D984723052F -:1051E00004D5134A936D0BB1D06D9847E00404D5F4 -:1051F0000F4A136E0BB1506E9847A10404D50C4AA8 -:10520000936E0BB1D06E9847620404D5084A136FB1 -:105210000BB1506F9847230404D5054A936F0BB127 -:10522000D06F9847BDE81040FEF7B0BD00040140C4 -:10523000A864002008B50348FEF758FEBDE8084002 -:10524000FEF7A4BDA05F002008B5FFF75FFEBDE834 -:105250000840FEF79BBD0000062108B50846FEF792 -:10526000DDFE06210720FEF7D9FE06210820FEF705 -:10527000D5FE06210920FEF7D1FE06210A20FEF701 -:10528000CDFE06211720FEF7C9FE06212820FEF7D5 -:10529000C5FE07211C20FEF7C1FEBDE808400C2119 -:1052A0002620FEF7BBBE000008B5FFF743FE00F066 -:1052B00009F8FFF75BF8FFF703FEBDE80840FFF7CA -:1052C0003DBD00000023054A19460133102BC2E9F9 -:1052D000001102F10802F8D1704700BFA864002055 -:1052E0000B460146184600F003B8000000F00EB867 -:1052F00010B5054C13462CB10A4601460220AFF307 -:10530000008010BD2046FCE700000000024B014673 -:105310001868FFF705BC00BF2823002010B501392D -:105320000244904201D1002005E0037811F8014FBA -:10533000A34201D0181B10BD0130F2E72DE9F04166 -:10534000A3B1C91A17780144044603F1FF3C8C420B -:10535000204601D9002009E00578BD4204F101048E -:10536000F5D10CEB0405D618A54201D1BDE8F081BA -:1053700015F8018D16F801EDF045F5D0E7E70000CE -:10538000034611F8012B03F8012B002AF9D17047CD -:105390006F72672E6172647570696C6F742E486FDE -:1053A0006C7962726F47345F4750530053544D33EA -:1053B0003247343F3F00000040A2E4F164689106A8 -:1053C0000041A3E5F2656992070000004261642094 -:1053D00043414E496661636520696E6465782E00BD -:1053E000000100000001FF00006400400068004070 -:1053F0000000000000000000ED240008C91F0008A4 -:10540000052C0008C11F0008712000085522000863 -:10541000392000080120000805200008DD1F0008D1 -:10542000C51F000815220008E91F0008712D00089B -:10543000F51F0008E92100080096000000000000A8 -:10544000000000000000000000000000000000005C -:10545000000000002D4300081943000855430008D0 -:10546000414300084D430008394300082543000824 -:1054700011430008614300086330000078540008BD -:1054800068620020786400206D61696E0069646C58 -:1054900065000000A000802A00000000AAAAAAAAB5 -:1054A00050000024FFFF000000770000009009007A -:1054B0000400005A00000000AAAAAA9A04000000F2 -:1054C000FFBF000000000000000099000011101450 -:1054D00000000000AAAAAAA600010010FFDF000039 -:1054E00000000000000000000000000000000000BC -:1054F000AAAAAAAA00000000FFFF00000000000006 -:10550000000000000000000000000000AAAAAAAAF3 -:1055100000000000FFFF000000000000000000008D -:105520000000000000000000AAAAAAAA00000000D3 -:10553000FFFF00000000000000000000000000006D -:1055400000000000AAAAAAAA00000000FFFF0000B5 -:105550000000000000000000C8ACFF7F0100000058 -:105560001D040000000000000070070000000000A3 -:10557000FE2A0100D2040000FF000000A05F00200E -:1055800000000000AC5300082C23002000000000A5 -:10559000000000000000000000000000000000000B -:1055A00000000000000000000000000000000000FB -:1055B00000000000000000000000000000000000EB -:1055C00000000000000000000000000000000000DB -:1055D00000000000000000000000000000000000CB -:0C55E000000000000000000000000000BF +:10063000002383F311882846A047002004F082F9A4 +:10064000FEE704F0E5F800DFFEE70000F8B501F092 +:100650000FF904F08BFC074604F0DCFC0546B8BB40 +:10066000204B9F4234D001339F4234D01E4B27F0A1 +:10067000FF029A4232D1F8B200F028FF2E4642F231 +:10068000107400F029FF08B10024264601F07CFC1C +:1006900020B1032000F07CF80024264635B1134B2E +:1006A0009F4203D004F0AEFC00242646002004F054 +:1006B00067FC0EB100F082F801F04CFA00F03EFF4A +:1006C00001F034F9204600F0D1F800F077F8F9E7AE +:1006D0002E460024D5E704460126D2E7064640F61A +:1006E000C414CEE7010007B0000008B0263A09B0F4 +:1006F00008B501F0E7F8A0F120035842584108BDC1 +:1007000007B541F21203022101A8ADF8043001F04F +:10071000F7F803B05DF804FB38B5302383F3118894 +:10072000174803680BB104F0CBF9164A14480023AC +:100730004FF47A7104F0BAF9002383F31188124C54 +:10074000236813B12368013B2360636813B16368B6 +:10075000013B63600D4D2B7833B963687BB9022090 +:1007600001F086F9322363602B78032B07D163688D +:100770002BB9022001F07CF94FF47A73636038BD25 +:100780009023002019070008B0240020A82300208F +:10079000084B187003280CD8DFE800F008050208A1 +:1007A000022001F05BB9022001F04EB9024B002299 +:1007B0005A607047A8230020B024002010B501F033 +:1007C000E3FB30B1234B03221A70234B00225A6003 +:1007D00010BD224B224A1C4619680131F8D004335F +:1007E0009342F9D16268A242F2D31E4B9B6803F197 +:1007F000006303F510439A42EAD204F0D5FB04F0FB +:10080000E7FB002001F0ACF80220FFF7C1FF164B18 +:100810009A6D00229A65996F9A67996FD96DDA651A +:10082000D96FDA67D96F196E1A66D3F88010C3F8DA +:100830008020D3F8803072B64FF0E0233021C3F827 +:10084000084DD4E9003281F311889D4683F308886E +:100850001047BDE7A8230020B02400200090000826 +:100860002090000800230020001002402DE9F04FE6 +:1008700093B0AC4B00902022FF210AA89D6801F0A4 +:1008800013F9A94A1378A3B9A8480121036011708C +:10089000302383F3118803680BB104F011F9A44AE3 +:1008A000A24800234FF47A7104F000F9002383F387 +:1008B0001188009B13B19F4B009A1A609E4A009CBE +:1008C0001378032B1EBF002313709A4A4FF0000ABF +:1008D00018BF5360D3465646D146012001F0BEF8FA +:1008E00024B1944B1B68002B00F01582002000F00F +:1008F000E9FF0390039B002B01DA00F073FE039BDA +:10090000002BEDDB012001F09FF8039B213B162B10 +:10091000E3D801A252F823F0750900089D090008E8 +:10092000310A0008DB080008DB080008DB080008C3 +:10093000BB0A00088B0C0008A50B0008070C000878 +:100940002F0C0008550C0008DB080008670C000895 +:10095000DB080008D90C0008150A0008DB080008AD +:100960001D0D000881090008150A0008DB080008B1 +:10097000070C00080220FFF7BBFE002840F0F581BD +:10098000009B0221BAF1000F08BF1C4605A841F2E6 +:100990001233ADF8143000F0B3FF9EE74FF47A70D5 +:1009A00000F090FF071EEBDB0220FFF7A1FE0028FE +:1009B000E6D0013F052F00F2DA81DFE807F0030AF5 +:1009C0000D10133605230593042105A800F098FFA8 +:1009D00017E054480421F9E758480421F6E758483D +:1009E0000421F3E74FF01C08404600F0BBFF08F17C +:1009F00004080590042105A800F082FFB8F12C0F2F +:100A0000F2D1012000FA07F747EA0B0B5FFA8BFBE4 +:100A10004FF0000901F094F826B10BF00B030B2BFB +:100A200008BF0024FFF76CFE57E746480421CDE7D6 +:100A3000002EA5D00BF00B030B2BA1D10220FFF74A +:100A400057FE074600289BD0012000F089FF0220B6 +:100A5000FFF79EFE00261FFA86F8404600F090FF42 +:100A6000044690B10021404600F0A2FF0136002864 +:100A7000F1D1BA46044641F21213022105A8ADF89D +:100A800014303E4600F03CFF27E70120FFF780FED0 +:100A90002546244B9B68AB4207D9284600F062FFED +:100AA000013040F067810435F3E7234B00251D70CA +:100AB000204BBA465D603E46ACE7002E3FF460AF87 +:100AC0000BF00B030B2B7FF45BAF0220FFF760FEF4 +:100AD000322000F0F7FEB0F10008FFF651AF18F039 +:100AE00003077FF44DAF0F4A926808EB050393426A +:100AF0003FF646AFB8F5807F3FF742AF124B019308 +:100B0000B84523DD4FF47A7000F0DCFE0390039AC1 +:100B1000002AFFF635AF019B039A03F8012B01373A +:100B2000EDE700BF00230020AC240020902300202C +:100B300019070008B0240020A82300200423002067 +:100B4000082300200C230020AC230020C820FFF73E +:100B5000CFFD074600283FF413AF1F2D11D8C5F174 +:100B6000200242450AAB25F0030028BF42468349D4 +:100B70000192184400F086FF019A8048FF2100F09E +:100B800093FF4FEAA8037D490193C8F387022846E3 +:100B900000F092FF064600283FF46DAF019B05EB85 +:100BA000830537E70220FFF7A3FD00283FF4E8AEF6 +:100BB00000F010FF00283FF4E3AE0027B846704B6A +:100BC0009B68BB4218D91F2F11D80A9B01330ED046 +:100BD00027F0030312AA134453F8203C0593404620 +:100BE000042205A901F0BAF904378046E7E7384640 +:100BF00000F0B8FE0590F2E7CDF81480042105A8B6 +:100C000000F07EFE06E70023642104A8049300F0B0 +:100C10006DFE00287FF4B4AE0220FFF769FD0028C6 +:100C20003FF4AEAE049800F0CBFE0590E6E700235B +:100C3000642104A8049300F059FE00287FF4A0AEBC +:100C40000220FFF755FD00283FF49AAE049800F00B +:100C5000B9FEEAE70220FFF74BFD00283FF490AE13 +:100C600000F0C8FEE1E70220FFF742FD00283FF454 +:100C700087AE05A9142000F0C3FE042107460490A6 +:100C800004A800F03DFE3946B9E7322000F01AFE14 +:100C9000071EFFF675AEBB077FF472AE384A926846 +:100CA00007EB090393423FF66BAE0220FFF720FDEE +:100CB00000283FF465AE27F003074F44B9453FF4E1 +:100CC000A9AE484600F04EFE0421059005A800F0AC +:100CD00017FE09F10409F1E74FF47A70FFF708FDF8 +:100CE00000283FF44DAE00F075FE002844D00A9B6A +:100CF00001330BD008220AA9002000F0DDFE0028F5 +:100D00003AD02022FF210AA800F0CEFEFFF7F8FC1F +:100D10001C4803F01DFE13B0BDE8F08F002E3FF419 +:100D20002FAE0BF00B030B2B7FF42AAE00236421B4 +:100D300005A8059300F0DAFD074600287FF420AEF1 +:100D40000220FFF7D5FC804600283FF419AEFFF7DC +:100D5000D7FC41F2883003F0FBFD059800F006FF58 +:100D6000464600F0EDFE3C46B7E5064652E64FF03B +:100D7000000905E6BA467EE637467CE6AC2300204D +:100D800000230020A0860100094A136849F2690087 +:100D900099B21B0C00FB01331360064B186844F238 +:100DA000506182B2000C01FB0200186080B27047F3 +:100DB000142300201023002010B500211022044627 +:100DC00000F072FE034B03CB206061601868A060E6 +:100DD00010BD00BF9075FF1F2DE9F041ADF54E7DB0 +:100DE0000DF134086CAC40F2751207460D460EA8A2 +:100DF0000021C8F8001000F057FE4FF4C472002123 +:100E0000204600F051FE02F04FF9274B4FF47A7262 +:100E1000B0FBF2F0186093E80700022384E80700B3 +:100E20000DF5E9702382FFF7C7FF41F604531F4910 +:100E3000238406A804F03CFC1B2384F832310DF215 +:100E4000E32206AB0DF1300C1E4603CE6645106062 +:100E50005160334602F10802F6D13188B3789370BD +:100E6000118020464146012200F09AFE00230393A0 +:100E7000AB7E029305F11903019380B20123CDE902 +:100E800004800093E97E06A3D3E90023384602F0EC +:100E9000C9FC0DF54E7DBDE8F08100BFAFF30080C9 +:100EA0009E6AC421818A46EEB8240020C0560008FC +:100EB0002DE9F0412C4C237ADAB080460D465BBB1D +:100EC00027A9284600F07CFF0746002842D19DF85C +:100ED0009D60C82E3ED801464FF4A662204600F021 +:100EE000E3FD4FF48073C4F8F8314FF40073C4F895 +:100EF0000C334FF44073C4F8203432460DF19E0198 +:100F000004F1090000F0BEFD26449DF89C30777284 +:100F100023720BB9EB7E23728122002106AC27A835 +:100F200000F0C2FD0122214627A800F085FF002322 +:100F30000393AB7E029305F1190380B2019328233A +:100F4000CDE904400093E97E05A3D3E900234046A0 +:100F500002F068FC5AB0BDE8F08100BFAFF300803A +:100F600026417272DF25D7B7605E0020F0B5254EAE +:100F70004FF48A7505FB0065F1B096F8D83085F816 +:100F8000DC300024D822214685F8E8403AA800F059 +:100F90008BFD06F1090000F07FFDD5F8E4308DF8F7 +:100FA000F000C2B206AF06F109010DF1F100CDE982 +:100FB0003A3400F067FD394601223AA800F068FF94 +:100FC00080B2CDE9047008230127CDE9023706F18C +:100FD000D803019330230093317A0B4807A3D3E958 +:100FE000002302F01FFCA04206DD02F05DF8C5F808 +:100FF000E000384671B0F0BD2046FBE778F6339F3D +:1010000093CACD8D605E0020D03400202DE9F04FD2 +:10101000274FDFF8A880274E87B0384602F02EFC15 +:10102000034600283DD00024CDE90344ADF8144028 +:10103000027B8DF8142099684068029403AA03C2C9 +:101040001B681D4D43F000430293A146A2462B6846 +:10105000D3F810B002F02AF810EB080241F10003B7 +:101060002846CDF800A002A9D84704F22C5440F637 +:1010700058230028C8BF49F0010905F5A5559C4231 +:1010800005F11005E3D1B9F1000F05D0384602F0A3 +:10109000F9FB86F800A0C0E73378072B04D80133AA +:1010A000337007B0BDE8F08F014802F0EBFBF8E7C2 +:1010B000D0340020956300200035002040420F000E +:1010C00070B50D4614461E4602F008FB50B9022EBC +:1010D00010D1012C0ED112A3D3E90023C5E90023BE +:1010E000012007E0282C10D005D8012C09D0052CB0 +:1010F0000FD0002070BD302CFBD10BA3D3E900230F +:10110000ECE70BA3D3E90023E8E70BA3D3E9002323 +:10111000E4E70BA3D3E90023E0E700BFAFF30080CF +:10112000401DA12026812A0B78F6339F93CACD8DCE +:101130009E6AC421818A46EE26417272DF25D7B7A6 +:10114000F017304A39059E5638B505460E4C002139 +:10115000013500F02DFCA4F82C55B4F82C0500F056 +:101160000FFC78B1B4F82C0500F01AFC014648B920 +:10117000B4F82C0500F01CFCB4F82C350133A4F8AD +:101180002C35EAE738BD00BF605E0020F8B50E4C94 +:101190000E4F0226A4F5805343F8307C237E3BB9E2 +:1011A00065692DB1284600F06DFF284604F036FA37 +:1011B000204600F067FFA4F5A554012EA4F1100409 +:1011C00000D1F8BD0126E5E7E059002028570008C6 +:1011D0002DE9F04F8FB000AF05460C4602F07EFAC5 +:1011E000002849D1237E022B1BD1E38A012B18D181 +:1011F00001F05AFF0646FFF7C7FD03464FF4C870DB +:10120000DFF8C482B3FBF0F206F5167602FB10336A +:1012100016FA83F3C8F80030E37E33B9A34B0022FB +:101220001A703C37BD46BDE8F08F07F12401204617 +:1012300000F084FD0028F4D107F11400FFF7BCFD95 +:1012400097F8264007F11401224607F1270004F021 +:10125000FDF90028E2D10F2C08D8944B1C70D8F867 +:101260000030A3F51673C8F80030DAE797F82410B9 +:10127000284602F02BFAD4E7E38A282B2BD010D88B +:10128000012B23D0052BCCD1BFF34F8F8849894B3D +:10129000CA6802F4E0621343CB60BFF34F8F00BF14 +:1012A000FDE7302BBDD1844EE17E327A9142B8D138 +:1012B000607E3146002291F8DC50854200F0A58026 +:1012C0000132042A01F58A71F5D1AAE721462846A0 +:1012D000FFF782FDA5E721462846FFF7E9FDA0E7D5 +:1012E000B2F8EC507B6005F103094FEA99094FEA27 +:1012F0008902D11DC908A8EBC1039D46EB46002118 +:10130000584600F0D1FB04F1EE012A46314458461C +:1013100000F0B8FB7B6813B9012000F021FB96F8C0 +:10132000D20000F02DFB044630B9307200F052FBC1 +:10133000204600F015FBB1E0D6F8D4203AB996F873 +:10134000D200B6F82C25824201D8FFF7FDFED6F870 +:10135000D4202A44944208D296F8D200B6F82C251C +:101360000130824201D8FFF7EFFE70685FFA89F220 +:10137000594600F0A1FB08B9C54679E0726896F8B5 +:10138000D2002A447260D6F8D42005EB0209C6F8D0 +:10139000D49000F0F5FA814509D396F8D220D6F81A +:1013A000D4000132001B86F8D220C6F8D400FF2DED +:1013B0000FD80024347200F00DFB204600F0D0FA64 +:1013C00000F0E2FD3D4B188108B9FFF7F7F9C5467B +:1013D00027E7BB6896F8D9000AFB0362FB68D2F8DE +:1013E000E41082F8E83001F58061C2F8E030C2F81C +:1013F000E410FFF7BBFDFFF709FE96F8D920013294 +:1014000002F0030286F8D920B6E74FF48A7A0AFB85 +:1014100002F505F1EA013144204600F065FDF8606F +:1014200000287FF4FEAE3544012285F8E82001F063 +:101430003BFED5F8E020D6ED007ADFED216A801A78 +:10144000192838BF192040F6B832904228BF1046FC +:10145000B8EE677A07EE900AF8EEE77A67EEA67ABA +:10146000DFED186AE7EE267AFCEEE77AC6ED007A41 +:1014700096F8D930BB60BA6873680AFB02F4321977 +:1014800092F8E81059B1D2F8E4108B42E8463FF4E4 +:1014900027AF002182F8E810C2F8E010C546736853 +:1014A000064A9B0A01331381BBE600BFC934002002 +:1014B00000ED00E00400FA05605E0020B824002082 +:1014C000CDCCCC3D6666663FCC340020014B187015 +:1014D000704700BFC424002038B54FF00054134BB0 +:1014E00022689A4220D1124B627D12481A70237DE5 +:1014F00003724FF48073C0F8F8314FF40073C0F8F2 +:101500000C3300254FF44073C0F820340A49C0F86A +:10151000E450C922093000F0B5FAE02229462046FD +:1015200000F0C2FA012038BD0020FCE79AAD44C5A6 +:10153000C4240020605E00201600002037B500F0B3 +:1015400023FD1F4C1F4D2049288102236B71236806 +:10155000204604F580545B6801229847D4F8B034E3 +:1015600019495B68012204F59660984700230193AE +:10157000164B174900931748174B4FF4805202F04F +:101580007DF8164B197811B1124802F09FF801F05E +:101590008BFD0446FFF7F8FB4FF4C873B0FBF3F282 +:1015A00002FB130304F5167010FA83F00C4B18605D +:1015B00003F030FD08B10F232B8103B030BD00BF15 +:1015C00000350020B824002040420F00C110000860 +:1015D000C8240020D0340020D1110008C4240020E9 +:1015E000CC3400202DE9F04F2DED028B002593B077 +:1015F0000DF12C089FED838BDFF84492FFF706FD79 +:101600000A95ADF834500B95C8F804500026834C69 +:10161000DFF80CB2374601238DF81C3023688DF8B3 +:101620001D508DED008B0DF11D02D3F808A007A908 +:1016300000232046D0479DF81CA0BAF1000F24D00B +:10164000D9F8143083F48063C9F8143010220021D3 +:101650000EA800F029FA236808AA5F690AA90DF10B +:101660001E032046B84798E803000FAB83E8030049 +:101670009DF834308DF844300A9B0E930EA9DDE9B5 +:101680000823584602F0DCFA574606F22C5640F67C +:10169000582304F5A5549E4204F11004BBD1002F39 +:1016A000B4D15F4802F01AF800283FD15D4E01F036 +:1016B000FBFC3368984239D301F0F6FC0446FFF78F +:1016C00063FB4FF4C873B0FBF3F202FB130304F5A2 +:1016D000167010FA83F03060534E8DF8287037780A +:1016E00017B901238DF82830C7F11004E4B20EA811 +:1016F000FFF762FB062C28BF06240EAB2246D91941 +:101700000DF1290000F0BEF90AAB039318230293F0 +:101710000134464B0193E4B2012300934048049402 +:101720003AA3D3E9002302F01FF8357001F0BCFCA6 +:101730003F4A404C1368C31AB3F57A7F2FD3106029 +:1017400001F0B4FC02460B46354802F0A5F83448D7 +:1017500001F0C4FF18B3237A374E002B14BF0323C4 +:101760000223737101F0A0FC0EAF4FF47A730122D3 +:10177000B0FBF3F039463060304600F0B7FA18237A +:1017800002932E4B019380B240F25513CDE90370C2 +:10179000009323481FA3D3E9002301F0E5FF237A38 +:1017A00093B101F081FC002607464FF48A7894F843 +:1017B000D900304400F0030008FB004393F8E82010 +:1017C00072B10136042EF2D1C82003F0C1F8237A99 +:1017D000002B7FF40DAF13B0BDEC028BBDE8F08F92 +:1017E000D3F8E02042B12368FA2B38BFFA23BA1AA3 +:1017F0000533B2EB430FE4D3FFF7B8FB0028E0D189 +:10180000E2E700BF0000000000000000401DA12032 +:1018100026812A0BF1C6A7C1D068080F0035002029 +:10182000D0340020CC340020C9340020C83400203B +:1018300090630020605E0020B824002094630020A4 +:101840000008004808B5064800F052FF054800F0BF +:101850004FFFBDE80840044A0449002003F0D8BE09 +:1018600000350020B0490020EC6300208D110008F5 +:101870007047000070B5104B1B780133DBB2012BB1 +:101880000C4612D80D4B1D6829684FF47A730E6A06 +:10189000A2FB0332014622462846B047844204D1C7 +:1018A000074B00221A70012070BD4FF4FA7003F04C +:1018B0004FF80020F8E700BF182300201C23002069 +:1018C000DC63002007B50023024601210DF107006B +:1018D0008DF80730FFF7CEFF20B19DF8070003B069 +:1018E0005DF804FB4FF0FF30F9E700000A4608B549 +:1018F0000421FFF7BFFF80F00100C0B2404208BDE5 +:1019000030B4074B0A461978064B53F82140236838 +:10191000DD69054B0146AC46204630BC604700BF40 +:10192000DC6300201C230020A086010070B503F0BA +:10193000B7F9094E094D3080002428683388834266 +:1019400008D903F0A9F92B6804440133B4F5104F0A +:101950002B60F2D370BD00BFDE63002098630020CF +:1019600003F052BA00F1006000F5104000687047C3 +:1019700000F10060920000F5104003F0CFB90000C4 +:10198000054B1A68054B1B889B1A834202D91044E9 +:1019900003F082B90020704798630020DE630020C6 +:1019A000024B1B68184403F07FB900BF9863002006 +:1019B000024B1B68184403F089B900BF98630020EC +:1019C0000020704700F10050A0F51040D0F89005BD +:1019D00070470000064991F8243033B10023086AAB +:1019E00081F824300822FFF7C3BF0120704700BFF1 +:1019F0009C630020014B1868704700BF002004E082 +:101A000030B50F4B0F4C1B682288C3F30B03013812 +:101A1000934208440BD164680A46013C8242134653 +:101A20000BD214F9015F2DB102F8015BF6E7814298 +:101A30000B4602D22C2203F8012B581A30BD00BFEE +:101A4000002004E020230020022802BF024B4FF0B8 +:101A500080629A61704700BF00080048022802BFF8 +:101A6000024B4FF480629A61704700BF0008004843 +:101A7000022801BF024A536983F4806353617047AF +:101A80000008004810B50023934203D0CC5CC45436 +:101A90000133F9E710BD000003460246D01A12F9DF +:101AA000011B0029FAD1704702440346934202D039 +:101AB00003F8011BFAE770472DE9F8431F4D144660 +:101AC00095F824200746884652BBDFF870909CB3F7 +:101AD00095F824302BB92022FF2148462F62FFF7CA +:101AE000E3FF95F82400C0F10802A24228BF224675 +:101AF000D6B24146920005EB8000FFF7C3FF95F890 +:101B00002430A41B1E44F6B2082E17449044E4B2BD +:101B100085F82460DBD1FFF75DFF0028D7D108E00E +:101B20002B6A03EB82038342CFD0FFF753FF0028D9 +:101B3000CBD10020BDE8F8830120FBE79C630020A7 +:101B4000024B1A78024B1A70704700BFDC6300200A +:101B50001823002003494FF461430B60024B1868BF +:101B600002F0BCBDC46300201C230020094B10B54B +:101B70001822044600211846FFF796FF064A074B35 +:101B8000127804600146BDE8104053F8220002F0CC +:101B9000A5BD00BFC4630020DC6300201C2300201F +:101BA0002DE9F0470D46044600219046284640F2B4 +:101BB0007912FFF779FF234620220021284601F001 +:101BC000E1FF231D02222021284601F0DBFF631DD7 +:101BD00003222221284601F0D5FFA31D032225213F +:101BE000284601F0CFFF04F10803102228212846DF +:101BF00001F0C8FF04F1100308223821284601F043 +:101C0000C1FF04F1110308224021284601F0BAFF68 +:101C100004F1120308224821284601F0B3FF04F121 +:101C2000140320225021284601F0ACFF04F11803D0 +:101C300040227021284601F0A5FF04F1200308226C +:101C4000B021284601F09EFF04F121030822B821AB +:101C5000284601F097FF04F12207C0263B46314693 +:101C600008222846083601F08DFFB6F5A07F07F15F +:101C70000107F3D104F1320308223146284601F06E +:101C800081FF002704F1330A94F832304FEAC70984 +:101C90009F4209F5A47615D3B8F1000F08D131465B +:101CA00004F599730722284601F06CFF09F24F16DC +:101CB000274694F832213B1B93420CD3F01DC008F9 +:101CC000BDE8F0870AEB070308223146284601F0F9 +:101CD00059FF0137D8E707F2331331460822284667 +:101CE00001F050FF08360137E3E7000013B5044662 +:101CF0000846002101602346C0F80310202201900D +:101D000001F040FF0198231D0222202101F03AFF3B +:101D10000198631D0322222101F034FF0198A31DC5 +:101D20000322252101F02EFF019804F1080310225F +:101D3000282101F027FF072002B010BDF7B50023CE +:101D4000047F00910E4607221946054601F0DEFD8C +:101D5000731C0093012200230721284601F0D6FDC1 +:101D6000C4B9B31C0093052223460821284601F07C +:101D7000CDFD0D243746B278BB1B934211D32B7F88 +:101D8000A88A0734E408BBB9844294BF002001202C +:101D900003B0F0BDAB8ADB00083BDB08B37008245E +:101DA000E8E7FB1C0093214600230822284601F0A7 +:101DB000ADFD08340137DEE7201A18BF0120E7E740 +:101DC000F7B50023047F00910E4608221946054608 +:101DD00001F09CFD731CC4B90822009311462346F0 +:101DE000284601F093FD1024012372785F1C013B0B +:101DF000934211D32B7FA88A0734E408BBB98442ED +:101E000094BF0020012003B0F0BDAB8ADB00083B8B +:101E1000DB0873700824E7E7F319009321460023D9 +:101E20000822284601F072FD08343B46DDE7201AFF +:101E300018BF0120E7E70000F8B50E460546144636 +:101E4000002181223046FFF72FFE2B460822002179 +:101E5000304601F097FE7CB96B1C07220821304602 +:101E600001F090FE0F2401236A785F1C013B93422E +:101E700004D3E01DC008F8BD0824F4E7EB1921469F +:101E80000822304601F07EFE08343B46ECE70000B5 +:101E9000F8B50E46054614460021CE223046FFF71F +:101EA00003FE2B4628220021304601F06BFE7CB950 +:101EB00005F1080308222821304601F063FE302492 +:101EC0002F462A7A7B1B934204D3E01DC008F8BD3D +:101ED0002824F5E707F1090321460822304601F0DE +:101EE00051FE08340137ECE7F7B5047F00910E4648 +:101EF000012310220021054601F008FDC4B9B31CDE +:101F00000093092223461021284601F0FFFC1924E2 +:101F100037467288BB1B9A4211D82B7FA88A073498 +:101F2000E408BBB9844294BF0020012003B0F0BD97 +:101F3000AB8ADB00103BDB0873801024E8E73B1D15 +:101F40000093214600230822284601F0DFFC0834D4 +:101F50000137DEE7201A18BF0120E7E730B5094D49 +:101F60000A4491420DD011F8013B5840082340F338 +:101F70000004013B2C4013F0FF0384EA5000F6D12B +:101F8000EFE730BD2083B8EDF7B5384A10685168E7 +:101F90006B4603C36A4636493648082303F066FB9E +:101FA0000446002833D10A25334A106851686B462D +:101FB00003C36A4631492F48082303F057FB044600 +:101FC000002849D00369B3F5EE2F45D8B0F8661064 +:101FD00040F21D4291423FD1294A024402F15C0184 +:101FE0008B4239D35C3B234900209E1AFFF7B6FF92 +:101FF0003246074604F164010020FFF7AFFFA368F3 +:102000009F4229D1E368984208BF002524E0036974 +:10201000B3F5EE2F27D8418B40F21D42914220D1DB +:10202000174A024402F110018B4218D3103B1149A8 +:1020300000209D1AFFF792FF2A46064604F1180178 +:102040000020FFF78BFFA3689E4202D1E36898420D +:1020500001D00D25A8E70025284603B0F0BD1025C6 +:10206000A2E70C25A0E70B259EE700BFE856000875 +:10207000DC6F070000900008F1560008906F070021 +:102080000870FFF710B5037C044613B9006803F02D +:10209000D5FA204610BD00000023BFF35B8FC3605C +:1020A000BFF35B8FBFF35B8F8360BFF35B8F7047C2 +:1020B000BFF35B8F0068BFF35B8F704770B5054659 +:1020C0000C30FFF7F5FF05F1080604463046FFF730 +:1020D000EFFFA04206D930466D68FFF7E9FF2544BF +:1020E000281A70BD3046FFF7E3FF201AF9E7000019 +:1020F00070B50546406898B105F10800FFF7D8FFB4 +:1021000005F10C0604463046FFF7D2FF8442304604 +:1021100094BF6D680025FFF7CBFF013C2C44201ACB +:1021200070BD000038B50C460546FFF7C7FFA0425A +:1021300010D305F10800FFF7BBFF04446868B4FB47 +:10214000F0F100FB1144BFF35B8F0120AC60BFF3E3 +:102150005B8F38BD0020FCE72DE9F04114460746AF +:102160000D46FFF7C5FF844228BF0446D4B1B846E8 +:1021700058F80C6B4046FFF79BFF30442860404600 +:102180007E68FFF795FF331A9C4203D86C600120EC +:10219000BDE8F0816B60A41B3B68AB602044E86045 +:1021A0000220F5E72046F3E738B50C460546FFF771 +:1021B0009FFFA04210D305F10C00FFF779FF044404 +:1021C0006868B4FBF0F100FB1144BFF35B8F0120A2 +:1021D000EC60BFF35B8F38BD0020FCE72DE9FF41C9 +:1021E000884669460746FFF7B7FF6C4606B204EB20 +:1021F000C6060025B44209D06268206808EB0501D4 +:10220000FFF740FC636808341D44F3E7294638466D +:10221000FFF7CAFF284604B0BDE8F081F8B50546CF +:102220000C300F46FFF744FF05F108060446304620 +:10223000FFF73EFFA042304688BF6C68FFF738FFCB +:10224000201A386020B130462C68FFF731FF204457 +:10225000F8BD000073B5144606460D46FFF72EFF85 +:10226000844228BF04460190DCB101A93046FFF743 +:10227000D5FF019B33B93268C5E90233C5E90024B3 +:1022800001200CE09C4238BF0194286001986860EE +:102290008442F5D93368AB60241AEC60022002B0A6 +:1022A00070BD2046FBE700002DE9FF410F4669465F +:1022B000FFF7D0FF6C4600B204EBC0050026AC422D +:1022C00009D0D4F8048054F8081BB8194246FFF727 +:1022D000D9FB4644F3E7304604B0BDE8F081000086 +:1022E00038B50546FFF7E0FF044601462846FFF7EC +:1022F00019FF204638BD0000302383F3118862B6F1 +:1023000070470000002383F3118862B67047000015 +:10231000012070477047000010B41346026814682B +:102320000022A4465DF8044B6047000000F5805091 +:1023300090F859047047000000F5805090F852045E +:102340007047000000F5805090F958047047000075 +:102350005020704700F5805208B5FFF7CDFFD2F846 +:102360009834D2F894041844D2F890341844D2F82F +:1023700078341844D2F888341844D2F88434184495 +:10238000FFF7C0FF08BD000038B5C26A936923F0AB +:1023900001039361044600F087FE0546E36A9B69EA +:1023A000DB0706D500F080FE431BFA2BF6D9002090 +:1023B00004E004F58054012084F8520438BD000084 +:1023C0002DE9F04F0C4600F5805185B01F4691F87D +:1023D0005234BDF83890054690469BB1D1F874341C +:1023E0000133C1F8743423689A0006D4237B082B88 +:1023F0000BD9627B0AB10F2B07D9D1F8783401339E +:10240000C1F878344FF0FF300FE0FFF775FFEB6A4B +:10241000D3F8C42012F4001A0AD0D1F87C34013366 +:10242000C1F87C34FFF76EFF002005B0BDE8F08FE7 +:10243000D3F8C46022686B6AC6F301464FF0480BBC +:10244000002A1BFB063BB4BF42F080429204CBF84B +:10245000002023685B0044BF42F00052CBF800200C +:10246000227B330643EA0243CBF80430607B7201DF +:1024700018B343F44013CBF80430D1F8A43401333B +:10248000C1F8A434AB1803F58353197B41F0200144 +:102490001973207B039200F063FE039A03308010CF +:1024A0005FFA8AF383420AF1010A0DDA04EB830131 +:1024B0000BEB830349689960F2E7AB1803F583538C +:1024C000197B60F34511E3E7EB6A0121B140C3F8E2 +:1024D000CC10AB1803F58253C3E9048705EB461310 +:1024E00003F582532146183304F10C0051F804CB54 +:1024F00043F804CB8142F9D1098819802A4441F27A +:1025000068032846D65002F5805209F0030392F87A +:102510006C1043F0100321F01F010B4382F86C3064 +:10252000FFF7F0FE4246CDF800903B46214600F012 +:10253000DDFD012079E7000013B500F5805401911D +:10254000606CFFF7D5FD1F280AD90199606C202225 +:10255000FFF744FEA0F120035842584102B010BDDD +:102560000020FBE708B500F58050FFF7C5FE406C82 +:10257000FFF792FDBDE80840FFF7C4BE00220260ED +:10258000828142608260704710B500220023C0E95A +:1025900000230023044603810C30FFF7EFFF2046A1 +:1025A00010BD00002DE9F047074688B007F58054BC +:1025B00068469A468846FFF79FFE9146FFF7E4FF7C +:1025C000606CFFF77BFD1F282CD9606C20226946C8 +:1025D000FFF786FE202825D194F8523413B303ADBB +:1025E000444605AB2E4603CE9E42206061603546D0 +:1025F00004F10804F6D130682060B388A380DDE9D7 +:102600000023C9E90023BDF80830AAF80030FFF71D +:1026100079FE4A4653464146384608B0BDE8F04781 +:1026200000F052BDFFF76EFE002008B0BDE8F08755 +:102630002DE9F84F00230646C0E90133294B46F83F +:10264000303B00F5815405468846374610343846FD +:102650002037FFF799FFA742F9D105F580544FF4D1 +:10266000805326630026C4E90D366764012305F50F +:10267000835705F5A359E66384F8403084F8483061 +:10268000103709F110094FF0000A4FF0000B47E92D +:1026900008ABA7F11800FFF771FF203747F8286C47 +:1026A0004F45F4D1B8F1010F84F85884A4F85A6466 +:1026B000A4F85C64A4F85E6484F86064A4F86264BE +:1026C000A4F86464A4F8666484F8686402D90648CF +:1026D00000F0E4FC054B53F82830EB622846BDE8D7 +:1026E000F88F00BF28570008FC560008185700084C +:1026F00010B5044B197804464A1C1A70FFF798FF6E +:10270000204610BDE96300202DE9F04300295FD089 +:102710003048314BB3FBF1F381428CBF0A201120CA +:10272000451EB3FBF0F700FB1730ECB220B1022DD1 +:102730002846F5D8002037E07D1EB5F5806F33D2EE +:10274000C4EBC40808F103034FEAE30EC3F3C70365 +:10275000A4EB030C0EF101094FF47A705FFA8CF6CA +:102760000EFB000E59FA8CFCBEFBFCFCBCF5617F35 +:102770001CDC1FFA8CF4581C56FA80F047431648AC +:10278000B0FBF7F7B942D5D1013BDBB20F2BD1D863 +:10279000711EC9B207294FF0000005D810711480CE +:1027A0005580537191710120BDE8F08308F1FF332A +:1027B0004FEAE30CC3F3C703E41A0CF1010EE6B2CF +:1027C0000CFB00005EFA84F4B0FBF4F4A4B2D2E790 +:1027D0000846E9E73F420F000024F40038B500F551 +:1027E0008053114A93F85834D55C4FF454725543D2 +:1027F00005F1804303F52443044600211846FFF702 +:1028000053F90A4B60612B44A361094B2B44E361EC +:10281000084B2B442362084B2B446362E36A00227B +:10282000C3F8C02038BD00BF1057000870A4004096 +:10283000B0A4004088A5004078A600402DE9F04FE4 +:1028400000F58055994695F85834022B89B0044616 +:102850008A46904604D90027384609B0BDE8F08F73 +:10286000994A52F8231009B942F823009749C4F84D +:102870000CA00B7884F8109093B9FFF73DFD944BB2 +:102880009A6D42F000729A659A6B42F000729A63F8 +:102890009A6B22F000729A6301230B70FFF732FDEE +:1028A00095F85134BBB9FFF727FD8A4A95F858349B +:1028B000D35C012B26D0022B2BD03BB90321152052 +:1028C00001F056FD0321162001F052FD012385F889 +:1028D0005134FFF717FDFFF70FFDE26A936923F00C +:1028E0001003936100F0E0FB0746E36A9E6916F06F +:1028F000080615D000F0D8FBC31BFA2BF5D9FFF75B +:1029000001FDA8E70321562001F032FD03215720E5 +:10291000DAE70321582001F02BFD03215920D3E7EA +:102920009A6942F001029A6100F0BEFB0746E36A31 +:102930009A69D00705D400F0B7FBC31BFA2BF6D970 +:10294000DDE79A6942F002029A61E36A00275F6557 +:10295000FFF7D8FC686CFFF79FFB04F5825B0BF177 +:10296000100B202200216846FFF79EF802A8FFF70F +:1029700005FE06976A460BEB06030DF1180E94460A +:10298000BCE80300F44518605960624603F108038F +:10299000F5D1DCF80000186020369CF804201A718C +:1029A000B6F5806FDDD1002304F5A25285F85034CE +:1029B00085F853341A3251462046FFF7A5FE0746E4 +:1029C00090B9E26A936923F00103936100F06CFB14 +:1029D0000546E36A9B69D9077FF53DAF00F064FBCC +:1029E000431BFA2BF5D936E795F85F6495F85E241A +:1029F000C5F86CA4360246EA426695F86024E36A9C +:102A00001643B5F85C2446EA0246DE61B8F1000FD1 +:102A100029D004F5A352023241462046FFF774FE46 +:102A200090B9E26A936923F00103936100F03CFBE3 +:102A30000546E36A9B69DA077FF50DAF00F034FBCA +:102A4000431BFA2BF5D906E795F8683495F8671417 +:102A5000C5F870841B0143EA0123B5F86414E26AE7 +:102A600043EA0143D3602046FFF7B8FE002385F810 +:102A70005934E36A6FF040421A65E36A164A5A65B0 +:102A8000E36A44229A65E36A0722C3F8DC20E36A1A +:102A900003229145DA653FF4DFAEE26A936923F0E1 +:102AA0000103936100F000FB0646E36A9B69DB07C4 +:102AB00005D500F0F9FA831BFA2BF6D9CBE60123F2 +:102AC00085F85234C8E600BFE0630020E8630020C8 +:102AD00000100240105700089B0008002DE9F04F3D +:102AE000054689B090469946002741F2680A00F5EC +:102AF0008056EB6AD3F8D430FB40D8074AD505EBB3 +:102B0000471252444FEA471B1379190742D4D6F8AB +:102B100080340133C6F8803413799A0648BFD6F85A +:102B2000A83405EB0B0248BF0133524448BFC6F836 +:102B3000A834137943F008031371DB0722D596F804 +:102B40005334FBB105F58254183468465C44FFF7F2 +:102B50001BFD03AB04F1080C206861681A4603C230 +:102B6000083464451346F7D120681060A2889A8023 +:102B70000123ADF808302B68CDE90089DB6B69468D +:102B800028469847D6F8543423B1D6F89C340133FC +:102B9000C6F89C340137202FABD109B0BDE8F08FC7 +:102BA0002DE9F04F8DB004460F4600F07FFA8246C3 +:102BB0008946002F56D1E36AD3F89020920141BF95 +:102BC00004F58051D1F894240132C1F89424D3F84B +:102BD0009020160703D100200DB0BDE8F08FD3F888 +:102BE0009050E669C5F30125482303FB0566E846D6 +:102BF0004046FFF7C3FC326851004ABF22F06043F1 +:102C0000C2F38A4343F00043920048BF43F080433D +:102C10000093736813F400131FBF04F5805201235F +:102C20008DF80D30D2F8AC340EBF8DF80D30013375 +:102C3000C2F8AC34F38803F00F038DF80C304FF07A +:102C4000000B9DF80C0000F08BFA5FFA8BF39842B2 +:102C500020D9F2180CA90B44127A03F82C2C0BF192 +:102C6000010BEEE7012FB6D1E36AD3F89820950166 +:102C700041BF04F58051D1F894240132C1F8942465 +:102C8000D3F898201007A6D0D3F89850266AC5F339 +:102C90000125A9E7EFB9E36AC3F8945004A8FFF748 +:102CA00073FC98E80F0007AD07C52B800023ADF833 +:102CB000183023682046CDE904A9DB6B04A99847A6 +:102CC00004F5805458B1D4F88C340133C4F88C34F2 +:102CD00082E7012F04BFE36AC3F89C50DEE7D4F813 +:102CE00090340133C4F89034012075E7F8B50546F7 +:102CF0000F4600F58054012639462846FFF750FF5D +:102D000010B184F85364F7E7D4F8543423B1D4F8FD +:102D10009C340133C4F89C34F8BD0000F0B5C36A9C +:102D20001A6C12F47F0F2BD000F580541B6CC4F882 +:102D3000A03441F26805002347194FF0010C00EB65 +:102D400043122A445E01117911F0020F15D0490790 +:102D500013D4B959C66AD6F8C8E00CFA01F111EAE1 +:102D60000E0F0AD0C6F8D010117941F0040111718C +:102D7000D4F888240132C4F888240133202BDED112 +:102D8000F0BD00002B4B70B51E561B5C012B2FD8DD +:102D9000294D2A4A55F8233052F826400BB341B347 +:102DA000236D1A060FD58023236500F07FF950EAC2 +:102DB00001020B4602D0013861F10003024655F8CA +:102DC0002600FFF78BFE236D1B032CD555F826300C +:102DD0004FF4002203F580532265012283F8592421 +:102DE00021E001232365082323654FF480632365D5 +:102DF00070BD236DDA0702D4236D9B0706D503232C +:102E000055F8260023650021FFF770FF236D180792 +:102E100002D4236DD90606D5182355F8260023655C +:102E20000121FFF763FF55F82600BDE87040FFF76A +:102E300075BF00BF14570008E06300201857000852 +:102E400008B5FFF759FAFFF769FFBDE80840FFF73B +:102E500059BA0000C36AD3F8C40080F40010C0F36C +:102E60004050704700F5805008B5FFF745FA406CB8 +:102E7000FFF724F9FFF746FA43090CBF01200020B1 +:102E800008BD000000F5805393F8592462B1C16A6F +:102E90008A6922F001028A61D3F898240132C3F8CA +:102EA0009824002283F85924704700002DE9F74345 +:102EB00000F5825198461031FFF71EFA002541F2C5 +:102EC000680E4FF0010900F5805C00EB4514744476 +:102ED00023795E071CD4DB061AD5C36A8E69D3F842 +:102EE000C87009FA06F63E4212D04F6801970F6883 +:102EF0009742019F77EB08070AD2C3F8D060237985 +:102F000043F004032371DCF884340133CCF88434B7 +:102F10000135202D01F12001D7D103B0BDE8F043E8 +:102F2000FFF7F0B9F8B51E46002313700F460546AB +:102F30001446FFF797FF80F0010038701EB1284655 +:102F4000FFF788FF2070F8BD2DE9F04F85B0994656 +:102F5000DDE90EA30D4602931378019391F800B0BA +:102F60008046164600F0A2F82B7804460F4613B9A7 +:102F70003378002B42D022463B464046FFF796FF6F +:102F8000FFF75EFFFFF77EFF4B4632462946FFF70D +:102F9000C9FF2B7833B1BBF1000F03D0012005B07E +:102FA000BDE8F08F337813B1019B002BF6D108F503 +:102FB00080530393029B544577EB03031ED2039B7C +:102FC000D3F85404D0B10368AAEB0401DB6889B2DA +:102FD00098474B46324629464046FFF7A3FF2B78D9 +:102FE00013B1BBF1000FD9D1337813B1019B002B82 +:102FF000D4D100F05BF804460F46DBE70020CEE7B3 +:1030000008B500210846FFF7BDFEBDE8084001F005 +:1030100067B8000008B501210020FFF7B3FEBDE846 +:10302000084001F05DB8000008B500210120FFF75D +:10303000A9FEBDE8084001F053B8000008B5012121 +:103040000846FFF79FFEBDE8084001F049B80000C0 +:1030500000B59BB0EFF3098168226846FEF712FDC8 +:10306000EFF30583014B9B6BFEE700BF00ED00E033 +:1030700008B5FFF7EDFF000000B59BB0EFF3098145 +:1030800068226846FEF7FEFCEFF30583014B5B6B9D +:10309000FEE700BF00ED00E0FEE700000FB408B55A +:1030A000029801F0EBFBFEE701F0FCBE01F0D4BE9C +:1030B00013B56C4684E80600031D94E8030083E81A +:1030C0000500012002B010BD73B58568019155B1AE +:1030D0001B885B0707D4D0E900369B6B9847019AA1 +:1030E000C1B23046A847012002B070BDF0B5866875 +:1030F00089B005460C465EB1BDF838305B070AD48E +:10310000D0E900379B6B98472246C1B23846B0479A +:10311000012009B0F0BD00220023CDE900230023E7 +:10312000ADF808300A4603AB01F108061068516893 +:103130001C4603C40832B2422346F7D1106820600F +:103140009288A280FFF7B2FF0423ADF808302B6805 +:10315000CDE90001DB6B694628469847D8E70000B7 +:10316000082817D909280CD00A280CD00B280CD015 +:103170000C280CD00D280CD00E2814BF4020302075 +:1031800070470C207047102070471420704718209B +:1031900070472020704700002DE9F041456A15B9BD +:1031A0004162BDE8F0814B6823F06047C3F38A4673 +:1031B0004FEAD37EC3F3807816EA230638BF3E4633 +:1031C000AC462B465A68BEEBD27F22F060440AD050 +:1031D000002A18DAA40CB44217D19D420FD10D6019 +:1031E000DEE71346EEE7A74207D102F08044C2F3C0 +:1031F000807242450BD054B1EFE708D2EDE7CCF82E +:1032000000100B60CDE7B44201D0B442E5D81A6893 +:103210009C46002AE5D11960C3E700002DE9F0477C +:10322000089D01F007044FEAD508224405F0070580 +:1032300000EBD1004FF47F49944201D1BDE8F08703 +:1032400004F0070705F0070A57453E4638BF5646C3 +:10325000C6F10806111B8E4228BF0E46E10808EB96 +:10326000D50E415C13F80EC0B94029FA06F721FAD1 +:103270000AF1FFB28CEA010147FA0AF739408CEAF9 +:10328000010C03F80EC034443544D5E780EA012030 +:10329000082341F2210201B24000002980B203F16B +:1032A000FF33B8BF504013F0FF03F4D17047000064 +:1032B00038B50C468D18A54200D138BD14F8011B55 +:1032C000FFF7E4FFF7E7000042684AB11368436084 +:1032D0004389818901339BB29942438138BF8381FD +:1032E0001046704770B588B0202204460D466846E7 +:1032F0000021FEF7D9FB20460495FFF7E5FF0246C3 +:1033000058B16B46054608AE1C4603CCB442286053 +:103310006960234605F10805F6D1104608B070BD76 +:10332000082817D909280CD00A280CD00B280CD053 +:103330000C280CD00D280CD00E2814BF40203020B3 +:1033400070470C20704710207047142070471820D9 +:103350007047202070470000082817D90C280CD986 +:1033600010280CD914280CD918280CD920280CD9CD +:1033700030288CBF0F200E207047092070470A208C +:1033800070470B2070470C2070470D2070470000DD +:103390002DE9F843078C072F04461ED9D0E902987F +:1033A00000254FF6FF73C5F12006A5F1200029FA8C +:1033B00005F108FA06F628FA00F031430143C9B2D4 +:1033C0001846FFF763FF0835402D0346EBD1E1694E +:1033D0003A46BDE8F843FFF76BBF4FF6FF70BDE814 +:1033E000F883000010B54B6823B9CA8A63F3090259 +:1033F000CA8210BD04691A681C600361C38A013B5C +:10340000C3824A60EFE700002DE9F84F1D46CB8AE2 +:103410000F46C3F309010529814692460B4630D079 +:103420000020AAB207F11A049EB2042E1FFA80F8F7 +:103430000FD8904503F1010306D3FB8A0A4462F3D7 +:103440000903FB8201201AE01AF80060E6540130FB +:10345000EAE79045F1D2A1F1050B1C237C68BBFB88 +:10346000F3F203FB12BB1FFA8BF6002C45D1484642 +:10347000FFF72AFF044638B978606FF00200BDE814 +:10348000F88F4FF00008E6E7002606607860ADB2DE +:103490004FF0000B454510D90AEB0803221D13F825 +:1034A000011B9155B1B208F101081B291FFA88F8D8 +:1034B0002BD0454506F10106F1D8FB8AC3F309027A +:1034C000154465F30903BCE7013292B21C46236838 +:1034D000002BF9D16B1F0B441C21B3FBF1F301331B +:1034E0009BB29A42D3D2BBF1000FD0D14846FFF72E +:1034F000EBFE20B9C4F800B0BFE70122E7E7C0F84F +:1035000000B05E4620600446C1E74545D5D948462F +:10351000FFF7DAFE08B92060AFE7C0F800B0002678 +:1035200020600446B6E700002DE9F04F2DED028B38 +:103530001C4683B05B69019207468846002B00F069 +:103540009A80238C2BB1E269002A00F09480072B2B +:1035500035D807F10C00FFF7B7FE054638B96FF014 +:103560000205284603B0BDEC028BBDE8F08F1422A3 +:103570000021FEF799FA228CE16905F10800FEF7B7 +:1035800081FA208C013080B2FFF7E6FEFFF7C8FE1B +:10359000013880B22084013028746369228C1B7842 +:1035A0002A4403F01F0363F03F0348F00041137205 +:1035B000384669602946FFF7EFFD0125D1E700F1A4 +:1035C0000C034FF0000908EE103A4FF0800A4E4607 +:1035D0004D4618EE100AFFF777FE83460028BED04E +:1035E00014220021FEF760FA002E3AD1019BABF8BD +:1035F000083002220BF1080E1FFA82FC0CF10100C8 +:10360000BCF1060F218C80B201D88E422BD3FFF77C +:10361000A3FEFFF785FE62691278013802F01F02EF +:103620008E4208BF4FF0400A42EA49121BFA80F16D +:103630004AEA020A013048F0004281F808A08BF8FB +:103640001000CBF8042059463846FFF7A5FD238C1F +:103650000135B3422DB289F001094FF0000AB8D10B +:103660007FE70022C6E7E169895D0EF802100136A6 +:10367000B6B20132C0E76FF0010572E7F8B5154642 +:103680000E463022002104461F46FEF70DFA069B27 +:103690006360B5F5001F079BA76034BF6A094FF64A +:1036A000FF72A36297B2E66104F1100000239A4210 +:1036B00006D800230360A782E3822383E360F8BD7A +:1036C0000660013330462036F1E7000003781BB96D +:1036D0004BB2002BC8BF01707047000000787047E4 +:1036E000F8B50C46C969074611B9238C002B37D1B0 +:1036F000257E1F2D34D8387828BB228C072A2CD859 +:10370000268A36F003032BD14FF6FF70FFF7D0FD6A +:1037100020F001003102400441EA0561400C41EA19 +:1037200040254FF6FF72234629463846FFF7FCFE38 +:10373000002807DD626913780133DBB21F2B88BFD5 +:1037400000231370F8BD218A2D0645EA01250543A3 +:103750002046FFF71DFE0246E5E76FF00300F1E7A4 +:103760006FF00100EEE7000070B58AB0044616461F +:103770000021282268461D46FEF796F9BDF838302C +:10378000ADF810300F9B05939DF840308DF8183040 +:10379000119B07936946BDF84830ADF820302046AC +:1037A000CDE90265FFF79CFF0AB070BD2DE9F0413D +:1037B000D36905460C4616460BB9138C5BBB377EA6 +:1037C0001F2F28D895F80080B8F1000F26D030467A +:1037D000FFF7DEFD3378210241EAC33141EA0801F7 +:1037E000338A41EA076141EA03410246334641F028 +:1037F00080012846FFF798FE00280ADD3378012B68 +:1038000007D1726913780133DBB21F2B88BF002305 +:103810001370BDE8F0816FF00100FAE76FF003006C +:10382000F7E70000F0B58BB004460D4617460021BF +:10383000282268461E46FEF737F99DF84C305A1E7E +:10384000534253418DF800309DF84030ADF81030B0 +:10385000119B05939DF848308DF81830149B079301 +:103860006A46BDF85430ADF8203029462046CDE9EF +:103870000276FFF79BFF0BB0F0BD0000406A00B17D +:1038800004307047436A1A68426202691A60036131 +:10389000C38A013BC38270472DE9F041D0F82080F4 +:1038A000194E14461D464146002709B9BDE8F0816E +:1038B000D1E90223A21A65EB0303964277EB0303D7 +:1038C0001ED2036A8B420DD1FFF78CFD036A1B6881 +:1038D000036203690B60C38A0161016A013BC38211 +:1038E0008846E2E7FFF77EFD0B68C8F80030036901 +:1038F0000B60C38A0161013BC382D8F80010D4E792 +:1039000088460968D1E700BF80841E002DE9F04F8A +:103910008BB00D46DDF8509014469B46804600283B +:1039200000F01981B9F1000F00F01581531E3F2BF3 +:1039300000F21181012A03D1BBF1000F40F00B818D +:103940000023CDE90833B8F81430B5EBC30F4FEAC4 +:10395000C30703D300200BB0BDE8F08F2B199F42A3 +:10396000D8F80C303ABF7F1BFFB227461BB9D8F8F6 +:103970001030002B7AD0272D4ED8C5F12806B7423B +:103980004FF000032CBFF6B23E4600932946D8F80C +:10399000080008AB3246FFF741FCA7EB060A3544A6 +:1039A0005FFA8AFAB8F8143003F10053053BDB00E4 +:1039B0000493D8F80C3003932821039B13B1BAF178 +:1039C000000F2CD1D8F8100040B1BAF1000F05D08B +:1039D000009608AB5246691AFFF720FC38B2002F58 +:1039E000B8D066070AD00AAB03EBD401624211F8E3 +:1039F000083C02F00702134101F8083C082C3CD9AE +:103A0000102C40F2B580202C40F2B780BBF1000FA3 +:103A100000F09C80082334E0BA460026C2E7049BED +:103A2000E02B28BFE02306930B44AB42059314D947 +:103A30005A1B03980096924534BF5246D2B2691A77 +:103A400008AB04300792FFF7E9FB079A1644AAEB8C +:103A5000020A1544F6B25FFA8AFA049B069A05999F +:103A60009B1A0493039B1B680393A6E70093D8F863 +:103A7000080008AB3A462946AEE7BBF1000F13D069 +:103A80000123B4EBC30F6CD0082C12D89DF8203062 +:103A9000621E23FA02F2D50706D54FF0FF3202FA72 +:103AA00004F423438DF820309DF8203089F800304D +:103AB00051E7102C12D8BDF82030621E23FA02F212 +:103AC000D10706D54FF0FF3202FA04F42343ADF8D4 +:103AD0002030BDF82030A9F800303CE7202C0FD86A +:103AE0000899631E21FA03F3DA0705D54FF0FF3278 +:103AF00002FA04F40C430894089BC9F800302AE742 +:103B0000402C2BD0DDE90865611EC4F12102A4F12F +:103B1000210326FA01F105FA02F225FA03F3114313 +:103B20001943CB0712D50122A4F12003C4F12001CF +:103B300002FA03F322FA01F1A240524243EA0103DE +:103B400063EB430332432B43CDE90823DDE908232C +:103B5000C9E90023FFE66FF00100FCE66FF0080002 +:103B6000F9E6082CA0D9102CB3D9202CEED8C3E745 +:103B7000BBF1000FADD0022383E7BBF1000FBBD038 +:103B800004237EE730B5012A144638BF0124402CB7 +:103B900085B028BF40240025012ACDE9025518D858 +:103BA0001B788DF8083063070AD004AB03EBD4050B +:103BB000624215F8083C02F00702934005F8083C01 +:103BC000009103462246002102A8FFF727FB05B01B +:103BD00030BD082AE4D9102A03D81B88ADF8083074 +:103BE000E1E7202A8DBFD3E900231B680293CDE9CA +:103BF0000223D8E710B5CB681BB98B600B618B82B1 +:103C000010BD04691A681C600361C38A013BC3824A +:103C1000CA60F0E703064CBFC0F3C0300220704713 +:103C200008B50246FFF7F6FF022806D15306C2F395 +:103C30000F2001D100F0030008BDC2F30740FBE7ED +:103C40002DE9F04F93B0CDE903230A6804461046EE +:103C5000FFF7E0FF022814BFC2F306260026002A61 +:103C60000D46824680F2F28112F0C04940F0EE81AA +:103C7000097B002900F0EA81022803D02378B342AF +:103C800040F0E781C2F304630693104602F07F031D +:103C90000593FFF7C5FF059B29444FEA834848EA8F +:103CA0000A4848EA4668CE7800230022CDE9082376 +:103CB000F309834648EA0008029367D0059B009306 +:103CC00002466768534608A92046B847002800F016 +:103CD000C381276A4FB9414604F10C00FFF702FB8C +:103CE000074690B96FF0020054E03B6998450DD04B +:103CF0003F68002FF9D1414604F10C00FFF7F2FABA +:103D000007460028EED0236A3B60276297F817C069 +:103D100006F01F08CCF3840CACEB08001FFA80FE01 +:103D20000028B8BF0EF12000A8EB0C031FFA83FE99 +:103D3000D7E90221B8BF00B2002B0793BEBF0EF136 +:103D400020031BB2079352EA010338D0039BDFF82C +:103D500024E39A1A049B4FF0000C63EB0101964593 +:103D60007CEB01032BD36B7B97F81AE0734519D1D9 +:103D7000029B002B78D0012821DC7868F8B9DFF8A5 +:103D8000F0C2944570EB010316D337E0276A27B9D8 +:103D90006FF00C0013B0BDE8F08F3B699845B5D0CB +:103DA0003F68F4E7B24890427CEB010301D3002066 +:103DB000F0E7029B002BFAD0079B0F2B17DCFA7D54 +:103DC000B30002F0030203F07C031343FB75394692 +:103DD0002046FFF707FB6B7BBB76029B3BB9FB7D65 +:103DE000C3F38402013262F38603FB75D0E76A7B7A +:103DF000BB7E9A42DBD1029B002B35D0B309022B4C +:103E000032D0039BBB60049BFB60142200210DA8F1 +:103E1000FDF74AFE039B0A93049B0B932B1D0C9307 +:103E20002B7BADF83EB0013BDBB2ADF83C30069BDE +:103E30008DF84230059B8DF8433094F82C308DF886 +:103E400040A083F001038DF844308DF84180A368D1 +:103E50000AA920469847FB7DC3F38403013303F08E +:103E60001F039B02FB82A2E7FB7DC6F34012B2EB6D +:103E7000D31F40F0F480C3F38403434540F0F28045 +:103E8000029A2B7BB609002A4DD0F2075DD4032B92 +:103E900040F2EB80039BBB60049BFB602B7BAE1D61 +:103EA000033BDBB23246394604F10C00FFF7ACFAB3 +:103EB00000280CDA39462046FFF794FAFB7DC3F35D +:103EC0008403013303F01F039B02FB820AE7DDE951 +:103ED0000884AB883B834FF6FF73C9F12000A9F13A +:103EE000200228FA09F104FA00F0014324FA02F250 +:103EF00011431846C9B2FFF7C9F909F10809B9F128 +:103F0000400F0346E9D1B8822A7B033AD2B2314648 +:103F1000FFF7CEF9FB7DB882DA43C2F3C01262F339 +:103F2000C713FB7543E786B92E1D013BDBB2324652 +:103F3000394604F10C00FFF767FA0028BADB2A7B48 +:103F4000B88A013AD2B23146E2E7F98AC1F30901EF +:103F5000013B0429DAB25BD8281D002307F11B06B8 +:103F60009A4208D910F801CB06F801C0013101339B +:103F70000529DBB2F4D103990A9104990B9193427C +:103F800007F11B010C9138BF043379680D9134BFE0 +:103F900055FA83F300230E93FB8AADF83EB0C3F3CA +:103FA00009031A44069B8DF84230059B8DF8433077 +:103FB00094F82C30ADF83C2083F001038DF84430A8 +:103FC00000238DF840A08DF841807B602A7BB88A61 +:103FD000013A291DFFF76CF93B8BB882834203D16C +:103FE000A3680AA92046984720460AA9FFF702FEBF +:103FF000FB7DBA8AC3F38403013303F01F039B02E2 +:10400000FB823B8B9A420CBF00206FF01000C1E690 +:104010007B68002BAFD0052001E01C3033461E68C2 +:10402000002EFAD1091A081D2E1D184401EB090CA7 +:10403000BCF11B0F5FFA89F39DD89A429BD916F801 +:10404000013B00F8013B09F10109EFE76FF00900BE +:10405000A0E66FF00A009DE66FF00B009AE66FF0A5 +:104060000D0097E66FF00E0094E66FF00F0091E6FA +:1040700040420F0080841E00EFF3098305494A6B1C +:1040800022F001024A63683383F30988002383F333 +:104090001188704700EF00E0302080F3118862B68D +:1040A0000C4B0D4AD96821F4E0610904090C0A435C +:1040B000DA60D3F8FC20094942F08072C3F8FC2092 +:1040C0000A6842F001020A602022DA7783F82200AF +:1040D000704700BF00ED00E00003FA05001000E0AB +:1040E00010B5302383F311880E4B5B6813F4006323 +:1040F00014D0F1EE103AEFF30984683C4FF080736E +:10410000E361094BDB6B236684F3098800F074FBE1 +:1041100010B1064BA36110BD054BFBE783F311887B +:10412000F9E700BF00ED00E000EF00E04306000803 +:1041300046060008026843681143016003B118474E +:1041400070470000024A136843F0C00313607047D1 +:104150000044004013B50E4C204600F0B3FA04F1C1 +:1041600014000C49009400234FF4807200F070F9A1 +:10417000094B0A4900944FF4807204F1380000F0B2 +:10418000E9F9074A074BC4E9172302B010BD00BF85 +:10419000F06300205C640020454100085C6500205D +:1041A00000440040007A030A30B5037C214C00290A +:1041B00018BF0C46012B0CD11F4B984209D11F4B45 +:1041C0009A6D42F400329A659A6F42F400329A670F +:1041D0009B6F2268036EC16D846603EB5203B3FBD1 +:1041E000F2F36268150442BF23F0070503F00703EA +:1041F00043EA4503CB60A36843F040034B60E368A8 +:1042000043F001038B6042F4967343F001030B60AB +:104210004FF0FF330B62510505D512F0102205D087 +:10422000B2F1805F04D080F8643030BD7F23FAE7BC +:104230003F23F8E768570008F063002000100240B1 +:104240002DE9F047C66D3768F469346221070546E9 +:1042500019D014F0080118BF4FF48071E20748BF6D +:1042600041F02001A30748BF41F04001600748BF6B +:1042700041F08001302383F31188281DFFF75AFF96 +:10428000002383F31188E2050AD5302383F31188D4 +:104290004FF48061281DFFF74DFF002383F3118841 +:1042A0004FF030094FF0000A14F0200838D13B06D7 +:1042B00016D54FF0300905F1380A200610D589F3DC +:1042C0001188504600F07AF9002836DA0821281DB6 +:1042D000FFF730FF27F080033360002383F311885A +:1042E000790614D5620612D5302383F31188D5E9F7 +:1042F00013239A4208D12B6C33B11021281D27F0CB +:104300004007FFF717FF3760002383F31188E306A8 +:1043100018D5AA6E1369ABB1BDE8F04750691847CC +:1043200089F31188736A95F864102846194000F0E3 +:10433000E3F98AF31188F469B6E7B06288F311886B +:10434000F469BAE7BDE8F0874FF0E023002258682F +:104350004FF0FF31930003F1604303F561430132F5 +:104360009042C3F88010C3F88011F3D27047000068 +:1043700000F1604303F561430901C9B283F80013FA +:10438000012200F01F039A4043099B0003F16043A0 +:1043900003F56143C3F880211A607047F8B51546EC +:1043A00082680669AA420B46816938BF8568761A19 +:1043B000B54204460BD218462A46FDF763FBA369B3 +:1043C0002B44A361A3685B1BA3602846F8BD0CD9EE +:1043D00018463246FDF756FBAF1BE1683A463044BB +:1043E000FDF750FBE3683B44EBE718462A46FDF730 +:1043F00049FBE368E5E7000083689342F7B515469B +:10440000044638BF8568D0E90460361AB5420BD23D +:104410002A46FDF737FB63692B446361A36828468E +:104420005B1BA36003B0F0BD0DD932460191FDF7CF +:1044300029FB0199E068AF1B3A463144FDF722FBA6 +:10444000E3683B44E9E72A46FDF71CFBE368E4E741 +:1044500010B50A440024C361029B8460C0E90000D7 +:10446000C0E90511C1600261036210BD08B5D0E961 +:104470000532934201D1826882B98268013282603A +:104480005A1C42611970D0E904329A4224BFC368B1 +:104490004361002100F078FA002008BD4FF0FF30A2 +:1044A000FBE7000070B5302304460E4683F3118805 +:1044B000A568A5B1A368A269013BA360531CA361D1 +:1044C00015782269934224BFE368A361E3690BB1C5 +:1044D00020469847002383F31188284607E0314699 +:1044E000204600F041FA0028E2DA85F3118870BD19 +:1044F0002DE9F74F04460E4617469846D0F81C9013 +:104500004FF0300A8AF311884FF0000B154665B161 +:104510002A4631462046FFF741FF034660B941462F +:10452000204600F021FA0028F1D0002383F31188FF +:10453000781B03B0BDE8F08FB9F1000F03D00190F4 +:104540002046C847019B8BF31188ED1A1E448AF35D +:104550001188DCE7C0E90511C160C3611144009B0B +:104560008260C0E90000016103627047F8B504464B +:104570000D461646302383F31188A768A7B1A368B8 +:10458000013BA36063695A1C62611D70D4E9043267 +:104590009A4224BFE3686361E3690BB12046984700 +:1045A000002080F3118807E03146204600F0DCF956 +:1045B0000028E2DA87F31188F8BD0000D0E905236E +:1045C0009A4210B501D182687AB98268013282605C +:1045D0005A1C82611C7803699A4224BFC3688361B4 +:1045E000002100F0D1F9204610BD4FF0FF30FBE76D +:1045F0002DE9F74F04460E4617469846D0F81C9012 +:104600004FF0300A8AF311884FF0000B154665B160 +:104610002A4631462046FFF7EFFE034660B9414681 +:10462000204600F0A1F90028F1D0002383F311887F +:10463000781B03B0BDE8F08FB9F1000F03D00190F3 +:104640002046C847019B8BF31188ED1A1E448AF35C +:104650001188DCE7026843681143016003B1184721 +:10466000704700001430FFF743BF00004FF0FF33E6 +:104670001430FFF73DBF00003830FFF7B9BF00002E +:104680004FF0FF333830FFF7B3BF00001430FFF7AF +:1046900009BF00004FF0FF311430FFF703BF0000E7 +:1046A0003830FFF763BF00004FF0FF323830FFF7BC +:1046B0005DBF0000012914BF6FF013000020704798 +:1046C000FFF748BD044B03600023C0E90233436099 +:1046D00001230374704700BF8057000810B53023D2 +:1046E000044683F31188FFF75FFD02232374002043 +:1046F00080F3118810BD000038B5C36904460D462B +:104700001BB904210844FFF7A5FF294604F1140052 +:10471000FFF7ACFE002806DA201D4FF40061BDE86B +:104720003840FFF797BF38BD0023037582680369DF +:104730001B6899689142FBD25A680360426010601E +:104740005860704700230375826803691B68996885 +:104750009142FBD85A68036042601060586070470D +:1047600008B50846302383F311880B7D032B05D051 +:10477000042B0DD02BB983F3118808BD8B6900225F +:104780001A604FF0FF338361FFF7CEFF0023F2E79B +:10479000D1E9003213605A60F3E70000FFF7C4BFAD +:1047A000054BD9680875186802681A6053600122C1 +:1047B0000275D860FBF730BF6066002030B50C4B47 +:1047C000DD684B1C87B004460FD02B46094A68466B +:1047D00000F06CF92046FFF7E3FF009B13B1684639 +:1047E00000F06EF9A86907B030BDFFF7D9FFF9E70F +:1047F0006066002061470008044B1A68DB68906817 +:104800009B68984294BF002001207047606600209A +:10481000084B10B51C68D86822681A6053600122E2 +:104820002275DC60FFF78EFF01462046BDE8104090 +:10483000FBF7F2BE60660020044B1A68DB689268E2 +:104840009B689A4201D9FFF7E3BF7047606600207A +:1048500038B5074C074908480123002523706560D7 +:1048600000F01EFC0223237085F3118838BD00BFC1 +:10487000C8680020AC5700086066002008B572B612 +:10488000044B186500F0D4FA00F08CFB024B0322B5 +:104890001A70FEE760660020C868002000F046B984 +:1048A000EFF3118020B9EFF30583302282F31188F2 +:1048B0007047000010B530B9EFF30584C4F3080465 +:1048C00014B180F3118810BDFFF7B6FF84F311888F +:1048D000F9E700008B60022308618B82084670476D +:1048E0008368A3F1840243F8142C026943F8442C32 +:1048F000426943F8402C094A43F8242CC26843F823 +:10490000182C022203F80C2C002203F80B2C044A6A +:1049100043F8102CA3F12000704700BF31060008B7 +:104920006066002008B5FFF7DBFFBDE80840FFF731 +:1049300035BF0000024BDB6898610F20FFF730BFE6 +:1049400060660020302383F31188FFF7F3BF000077 +:1049500008B50146302383F311880820FFF72EFFA6 +:10496000002383F3118808BD064BDB6839B1426828 +:1049700018605A60136043600420FFF71FBF4FF0B8 +:10498000FF307047606600200368984206D01A68BE +:104990000260506099611846FFF700BF7047000041 +:1049A00010B503689C68A2420CD85C688A600B60F2 +:1049B0004C602160596099688A1A9A604FF0FF3301 +:1049C000836010BD1B68121BECE700000A2938BF8A +:1049D0000A2170B504460D460A26601900F05AFBFC +:1049E00000F046FB041BA54203D8751C2E46044666 +:1049F000F3E70A2E04D9BDE87040012000F090BB17 +:104A000070BD0000F8B5144B0D46D96103F11001DB +:104A100041600A2A1969826038BF0A220160486031 +:104A20001861A818144600F027FB0A2700F020FBA5 +:104A3000431BA342064606D37C1C281900F02AFB20 +:104A400027463546F2E70A2F04D9BDE8F840012091 +:104A500000F066BBF8BD00BF60660020F8B50646F2 +:104A60000D4600F005FB0F4A134653F8107F9F4296 +:104A700006D12A4601463046BDE8F840FFF7C2BFDE +:104A8000D169BB68441A2C1928BF2C46A34202D90D +:104A90002946FFF79BFF224631460348BDE8F84010 +:104AA000FFF77EBF606600207066002010B4C0E98A +:104AB000032300235DF8044B4361FFF7CFBF0000E1 +:104AC00010B5194C236998420DD0D0E900328168A5 +:104AD00013605A609A680A449A60002303604FF09A +:104AE000FF33A36110BD2346026843F8102F5360C3 +:104AF0000022026022699A4203D1BDE8104000F012 +:104B0000C3BA936881680B44936000F0B1FA2269DC +:104B1000E1699268441AA242E4D91144BDE8104008 +:104B2000091AFFF753BF00BF606600202DE9F04768 +:104B3000DFF8BC8008F110072C4ED8F8105000F0B8 +:104B400097FAD8F81C40AA68031B9A423ED814442E +:104B5000D5E900324FF00009C8F81C4013605A60D4 +:104B6000C5F80090D8F81030B34201D100F08CFAAB +:104B700089F31188D5E9033128469847302383F318 +:104B800011886B69002BD8D000F072FA6A69A0EB2B +:104B900004094A4582460DD2022000F0C1FA0022E3 +:104BA000D8F81030B34208D151462846BDE8F04746 +:104BB000FFF728BF121A2244F2E712EB090938BFA7 +:104BC0004A4629463846FFF7EBFEB5E7D8F81030DD +:104BD000B34208D01444211AC8F81C00A960BDE8EB +:104BE000F047FFF7F3BEBDE8F08700BF7066002016 +:104BF0006066002000207047FEE70000704700005C +:104C00004FF0FF3070470000BFF34F8F024A136927 +:104C1000DB03FCD4704700BF0020024008B5094BFD +:104C20001B7873B9FFF7F0FF074B5A69002ABFBF23 +:104C3000064A9A6002F188329A601A6822F4806209 +:104C40001A6008BDE068002000200240230167458B +:104C500008B50B4B1B7893B9FFF7D6FF094B5A6980 +:104C600042F000425A611A6842F480521A601A688F +:104C700022F480521A601A6842F480621A6008BDF9 +:104C8000E068002000200240FF289ABF00F5803035 +:104C9000C0020020704700004FF400607047000021 +:104CA0004FF4807070470000FF2808B50BD8FFF75D +:104CB000EBFF00F500630268013204D10430834247 +:104CC000F9D1012008BD0020FCE70000FF2810B545 +:104CD00004461FD8FFF798FFFFF7A0FF0E4BF32203 +:104CE0001A6102225A615A6942EAC0025A615A693B +:104CF00042F480325A61FFF787FF4FF40061FFF7FB +:104D0000C3FF00F04BF9FFF7A3FF2046BDE81040BA +:104D1000FFF7CABF002010BD002002402DE9F84374 +:104D200040EA020313F00703144606D0304B40F26A +:104D300031321A600020BDE8F88385182D4A95426B +:104D40000CD92B4A40F236311160F3E7031D1B6882 +:104D50004A68934208D1083C08300831072C14D91E +:104D600002680B689A42F1D0FFF758FFFFF74CFF3B +:104D7000214E08314FF001084FF00009012CA1F13C +:104D8000080706D8FFF764FF01E0002CECD10120F2 +:104D9000D1E7C6F81480054651F8083C45F8043BB5 +:104DA00051F8043C4360FFF72FFF336943F00103E0 +:104DB0003361C6F81490026851F8083C9A420CD04E +:104DC0000B4B40F25E321A600C4B18600C4B1C60AF +:104DD0000C4B1F60FFF73CFFACE72D6851F8043C1B +:104DE0009D4201F10801EBD1083C0830C6E700BF45 +:104DF000DC6800200000080800200240D068002085 +:104E0000D8680020D4680020084908B50B7828B17C +:104E10001BB9FFF703FF01230B7008BD002BFCD06B +:104E2000BDE808400870FFF713BF00BFE06800202E +:104E300008B54FF4C0314FF0005000F0B1F8BDE8B4 +:104E400008404FF400414FF0805000F0A9B8000036 +:104E5000084600F0F3BB000070B582B0FFF720FDFC +:104E60000E4E054600F004F93268904237BF0C4AF6 +:104E70000B49516814682EBFD1E9004101315160DE +:104E80000419034641F10001284601913360FFF700 +:104E900011FD0199204602B070BD00BFE4680020FA +:104EA000E868002070B582B0FFF7FAFC104E0546A6 +:104EB00000F0DEF83268904237BF0E4A0D49516863 +:104EC00014682EBFD1E9004101315160041941F14C +:104ED00000010346284601913360FFF7EBFC01997E +:104EE0004FF47A7200232046FBF782F902B070BDBE +:104EF000E4680020E86800200244D2B2904200D169 +:104F00007047431C800000F1804000F51450006899 +:104F100041F8040BD8B2F1E7124B10B5D3F890402A +:104F2000240409D4D3F89040C3F89040D3F89040BB +:104F300044F40044C3F890400B4C2368024443F40B +:104F400080732360D2B2904200D110BD431C800018 +:104F500000F1804000F5145051F8044B0460D8B2C1 +:104F6000F1E700BF001002400070004007B50122C9 +:104F700001A90020FFF7C0FF019803B05DF804FB12 +:104F800013B50446FFF7F2FFA04205D0012201A9A4 +:104F900000200194FFF7C0FF02B010BD7047000071 +:104FA0007047000070470000074B45F255521A60E9 +:104FB00002225A6040F6FF729A604CF6CC421A60A8 +:104FC000024B01221A70704700300040F468002044 +:104FD000034B1B781BB1034B4AF6AA221A60704799 +:104FE000F468002000300040054B1A6832B902F125 +:104FF000804202F50432D2F894201A60704700BF54 +:10500000F0680020024B4FF40002C3F89420704770 +:105010000010024008B5FFF7E7FF024B1868C0F325 +:10502000407008BDF068002070470000FEE70000F7 +:105030000A4B0B480B4A90420BD30B4BDA1C121A4B +:10504000C11E22F003028B4238BF00220021FCF770 +:105050002BBD53F8041B40F8041BECE71C59000857 +:1050600078690020786900207869002000F0C2B8D3 +:105070004FF08043586A70474FF0804300225863D6 +:105080001A610222DA6070474FF080430022DA6032 +:10509000704700004FF0804358637047FEE7000000 +:1050A00070B51B4B01630025044686B058608562CD +:1050B0000E46FEF7F1FF04F11003C4E904334FF08C +:1050C000FF33C4E90635C4E90044A560E562FFF793 +:1050D000CFFF2B460246C4E9082304F134010D4AF0 +:1050E000256580232046FFF7F5FB0123E0600A4A8F +:1050F0000375009272680192B268CDE90223074BF2 +:105100006846CDE90435FFF70DFC06B070BD00BF61 +:10511000C8680020B8570008BD5700089D50000817 +:10512000024AD36A1843D062704700BF606600200D +:105130004B6843608B688360CB68C3600B694361D5 +:105140004B6903628B6943620B6803607047000020 +:1051500008B5204BDA6A42F07F02DA62DA6A22F09E +:105160007F02DA62DA6ADA6C42F07F02DA64DA6EBF +:1051700042F07F02DA66184ADB6E11464FF090402B +:10518000FFF7D6FF02F11C0100F58060FFF7D0FFAA +:1051900002F1380100F58060FFF7CAFF02F1540107 +:1051A00000F58060FFF7C4FF02F1700100F5806038 +:1051B000FFF7BEFF02F18C0100F58060FFF7B8FF3A +:1051C00002F1A80100F58060FFF7B2FFBDE80840DA +:1051D00000F050B800100240C457000808B500F0B5 +:1051E000FBF9FFF735FBBDE80840FFF7FDBE000007 +:1051F000704700000F4B9A6D42F001029A659A6F5A +:1052000042F001029A670C4A9B6F936843F00103D6 +:1052100093604FF08043A7229A624FF0FF32DA6228 +:1052200000229A615A63DA605A6001225A611A6058 +:10523000704700BF00100240002004E04FF08042A1 +:1052400008B51169D3680B40D9B2C9439B071161F6 +:1052500007D5302383F31188FFF720FB002383F366 +:10526000118808BD08B5FFF76FF8BDE8084000F0E9 +:105270008BB900004E4B4FF0FF319A6A99629A6ADF +:1052800000229A62986AD86A60F07F00D862D86A71 +:1052900000F07F00D862D86A186B1963186B1A6324 +:1052A000186B986B9963986B9A63986BD86BD963FA +:1052B000D86BDA63D86B186C1964196C1A64196CA2 +:1052C000196E41F001011966D3F8801021F0010137 +:1052D000C3F88010D3F88010996D41F08051996522 +:1052E000996F21F080519967996F32494FF40040CE +:1052F0008860CA600A624A628A62CA620A634A6352 +:105300008A63CA630A644A648A64CA640A654A652D +:105310004A604FF48072C1F880204FF440720A60F6 +:105320004A6912F48062FBD1D3F8901011F4407FE7 +:105330001EBF4FF48031C3F89010C3F89020D3F80B +:10534000982042F00102C3F89820D3F898209207E1 +:10535000FBD51A6842F480321A601A689003FCD5B3 +:10536000D3F8902022F00322C3F89020124ADA608A +:105370001A6842F080721A601A689101FCD50F49D0 +:105380000F4800229A60C3F888100E49C3F89C2089 +:10539000016002684A401207FBD19A6842F003029A +:1053A0009A609A6802F00C020C2AFAD1704700BF8A +:1053B0000010024000700040132A610155010050A6 +:1053C0000020024004070400074A08B5536903F0AF +:1053D0000103536123B1054A13680BB15068984724 +:1053E000BDE80840FEF77CBE00040140F8680020DC +:1053F000074A08B5536903F00203536123B1054A14 +:1054000093680BB1D0689847BDE80840FEF768BEC6 +:1054100000040140F8680020074A08B5536903F00A +:105420000403536123B1054A13690BB150699847CE +:10543000BDE80840FEF754BE00040140F8680020B3 +:10544000074A08B5536903F00803536123B1054ABD +:1054500093690BB1D0699847BDE80840FEF740BE9C +:1054600000040140F8680020074A08B5536903F0BA +:105470001003536123B1054A136A0BB1506A984770 +:10548000BDE80840FEF72CBE00040140F86800208B +:10549000164B10B55C6904F478725A61A30604D502 +:1054A000134A936A0BB1D06A9847600604D5104A34 +:1054B000136B0BB1506B9847210604D50C4A936BC4 +:1054C0000BB1D06B9847E20504D5094A136C0BB1B8 +:1054D000506C9847A30504D5054A936C0BB1D06C6A +:1054E0009847BDE81040FEF7FBBD00BF0004014037 +:1054F000F8680020194B10B55C6904F47C425A61CD +:10550000620504D5164A136D0BB1506D98472305FB +:1055100004D5134A936D0BB1D06D9847E00404D5C0 +:105520000F4A136E0BB1506E9847A10404D50C4A74 +:10553000936E0BB1D06E9847620404D5084A136F7E +:105540000BB1506F9847230404D5054A936F0BB1F4 +:10555000D06F9847BDE81040FEF7C2BD000401407F +:10556000F868002008B50348FEF76AFEBDE8084069 +:10557000FEF7B6BDF063002008B5FFF75FFEBDE89B +:105580000840FEF7ADBD0000062108B50846FEF74D +:10559000EFFE06210720FEF7EBFE06210820FEF7AE +:1055A000E7FE06210920FEF7E3FE06210A20FEF7AA +:1055B000DFFE06211720FEF7DBFE06212820FEF77E +:1055C000D7FE07211C20FEF7D3FEBDE808400C21C2 +:1055D0002620FEF7CDBE000008B5FFF743FE00F021 +:1055E00009F8FFF76DF8FFF703FEBDE80840FFF785 +:1055F0003DBD00000023054A19460133102BC2E9C6 +:10560000001102F10802F8D1704700BFF8680020CD +:105610000B460146184600F003B8000000F00EB833 +:1056200010B5054C13462CB10A4601460220AFF3D3 +:10563000008010BD2046FCE700000000024B014640 +:105640001868FFF705BC00BF2823002010B50139FA +:105650000244904201D1002005E0037811F8014F87 +:10566000A34201D0181B10BD0130F2E72DE9F04133 +:10567000A3B1C91A17780144044603F1FF3C8C42D8 +:10568000204601D9002009E00578BD4204F101045B +:10569000F5D10CEB0405D618A54201D1BDE8F08187 +:1056A00015F8018D16F801EDF045F5D0E7E700009B +:1056B000034611F8012B03F8012B002AF9D170479A +:1056C0006F72672E6172647570696C6F742E486FAB +:1056D0006C7962726F47345F4750530053544D33B7 +:1056E0003247343F3F00000040A2E4F16468910675 +:1056F0000041A3E5F2656992070000004261642061 +:1057000043414E496661636520696E6465782E0089 +:10571000000100000001FF0000640040006800403C +:1057200000000000000000003D28000819230008C8 +:10573000492F000811230008C1230008A5250008EF +:105740008923000851230008552300082D23000851 +:10575000152300086525000839230008B13000082A +:1057600045230008392500080096000000000000CD +:105770000000000000000000000000000000000029 +:1057800000000000814600086D460008A946000898 +:1057900095460008A14600088D4600087946000895 +:1057A00065460008B546000863300000A8570008A9 +:1057B000B8660020C86800206D61696E0069646C7D +:1057C00065000000A000802A00000000AAAAAAAA82 +:1057D00050000024FFFF0000007700000090090047 +:1057E0000400005A00000000AAAAAA9A04000000BF +:1057F000FFBF00000000000000009900001110141D +:1058000000000000AAAAAAA600010010FFDF000005 +:105810000000000000000000000000000000000088 +:10582000AAAAAAAA00000000FFFF000000000000D2 +:10583000000000000000000000000000AAAAAAAAC0 +:1058400000000000FFFF000000000000000000005A +:105850000000000000000000AAAAAAAA00000000A0 +:10586000FFFF00000000000000000000000000003A +:1058700000000000AAAAAAAA00000000FFFF000082 +:10588000000000000000000098A9FF7F0100000058 +:105890001D04000000000000007007000000000070 +:1058A000FE2A0100D2040000FF000000F063002087 +:1058B00000000000DC5600082C230020000000003F +:1058C00000000000000000000000000000000000D8 +:1058D00000000000000000000000000000000000C8 +:1058E00000000000000000000000000000000000B8 +:1058F00000000000000000000000000000000000A8 +:105900000000000000000000000000000000000097 +:0C5910000000000000000000000000008B :00000001FF diff --git a/Tools/bootloaders/HolybroGPS_bl.bin b/Tools/bootloaders/HolybroGPS_bl.bin index cb050b6bfa9eba..1d0c994218074a 100755 Binary files a/Tools/bootloaders/HolybroGPS_bl.bin and b/Tools/bootloaders/HolybroGPS_bl.bin differ diff --git a/Tools/bootloaders/HolybroGPS_bl.elf b/Tools/bootloaders/HolybroGPS_bl.elf index f3c13816d49154..6a549f4e5e58c6 100755 Binary files a/Tools/bootloaders/HolybroGPS_bl.elf and b/Tools/bootloaders/HolybroGPS_bl.elf differ diff --git a/Tools/bootloaders/HolybroGPS_bl.hex b/Tools/bootloaders/HolybroGPS_bl.hex index f95a809d1fbb5c..faba48087fa096 100644 --- a/Tools/bootloaders/HolybroGPS_bl.hex +++ b/Tools/bootloaders/HolybroGPS_bl.hex @@ -1,25 +1,25 @@ :020000040800F2 -:1000000000070020F50400080D2C00088D2B0008C7 -:10001000E52B00088D2B0008B92B0008F704000819 -:10002000F7040008F7040008F7040008C53A0008C0 +:1000000000070020F5040008912F0008492F000880 +:10001000712F0008492F0008692F0008F704000815 +:10002000F7040008F7040008F7040008853F0008FB :10003000F7040008F7040008F7040008F7040008B4 :10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008A94D0008D54D000872 -:10006000014E00082D4E0008594E0008F704000804 +:10005000F7040008F704000831530008595300085A +:1000600081530008A9530008D1530008F704000881 :10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F7040008A527000893 -:10009000B5270008C9270008F7040008854E0008A6 +:10008000F7040008F7040008F7040008D92E000858 +:10009000E92E0008FD2E0008F7040008F9530008B7 :1000A000F7040008F7040008F7040008F704000844 -:1000B000F94B0008F7040008F7040008F7040008EB +:1000B000E1540008F7040008F7040008F7040008FA :1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008A93B0008F70400082B -:1000E000ED4E0008F7040008F7040008F7040008C4 +:1000D000F7040008F7040008CD540008F7040008EE +:1000E0005D540008F7040008F7040008F70400084E :1000F000F7040008F7040008F7040008F7040008F4 :10010000F7040008F7040008F7040008F7040008E3 :10011000F7040008F7040008F7040008F7040008D3 :10012000F7040008F7040008F7040008F7040008C3 -:10013000F7040008F7040008F7040008DD270008AA -:10014000ED27000801280008F7040008F70400085C +:10013000F7040008F7040008F7040008112F00086E +:10014000212F0008352F0008F7040008F7040008E5 :10015000F7040008F7040008F7040008F704000893 :10016000F7040008F7040008F7040008F704000883 :10017000F7040008F7040008F7040008F704000873 @@ -29,7 +29,7 @@ :1001B000F7040008F7040008F7040008F704000833 :1001C000F7040008F7040008F7040008F704000823 :1001D000F7040008F7040008F7040008F704000813 -:1001E00009190008000000000000000000000000E5 +:1001E000A51800080000000000000000000000004A :1001F00053B94AB9002908BF00281CBF4FF0FF318E :100200004FF0FF3000F074B9ADF1080C6DE904CE89 :1002100000F006F8DDF804E0DDE9022304B07047E1 @@ -78,1309 +78,1366 @@ :1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 :1004D0004646EAE7204694E74046D1E7D0467BE728 :1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B63A482D -:1005000080F30888394880F3098839484EF6085145 -:10051000CEF20001086040F20000CCF200004EF67E -:100520003471CEF200010860BFF34F8FBFF36F8FBD -:1005300040F20000C0F2F0004EF68851CEF2000109 -:100540000860BFF34F8FBFF36F8F4FF00000E1EEF5 -:10055000100A4EF63C71CEF200010860062080F3CE -:100560001488BFF36F8F04F089FA04F065FA04F081 -:10057000AFFA4FF055301F491B4A91423CBF41F83A -:10058000040BFAE71C49194A91423CBF41F8040B9D -:10059000FAE71A491A4A1B4B9A423EBF51F8040B1C -:1005A00042F8040BF8E700201749184A91423CBF73 -:1005B00041F8040BFAE704F043FA04F0D7FA144CBC -:1005C000144DAC4203DA54F8041B8847F9E700F0F5 -:1005D00041F8114C114DAC4203DA54F8041B884722 -:1005E000F9E704F02BBA00000007002000230020E8 -:1005F000000000080001002000070020F05500085E -:10060000002300208423002088230020C45C0020D5 -:10061000E0010008E4010008E4010008E40100082A -:100620002DE9F04F2DED108AC1F80CD0C3689D461E -:10063000BDEC108ABDE8F08F002383F311882846B3 -:10064000A047002003F0CCFEFEE703F045FE00DFEC -:10065000FEE70000F8B504F089F9074604F0D8F980 -:100660000546A0BB1F4B9F4231D001339F4231D082 -:100670001D4B27F0FF029A422FD1F8B200F032FD55 -:100680002E4642F2107400F037FF08B100242646CF -:1006900000F02EFD08B90646044635B1134B9F42C3 -:1006A00003D004F0ADF900242646002004F068F9D8 -:1006B0000EB100F063F801F0EDFA00F07BFF01F0FD -:1006C0008DF9204600F0A4F800F058F8F9E72E461E -:1006D0000024D8E704460126D5E7064640F6C414B0 -:1006E000D1E700BF010007B0000008B0263A09B00A -:1006F00008B501F045F9A0F120035842584108BD62 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600004F0F0FC04F082FD4FF055301F491B4AA7 +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE704F0CEFC34 +:1005B00004F0AAFD144C154DAC4203DA54F8041BA8 +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E704F0B6BC0007002074 +:1005E000002300200000000808ED00E000010020CA +:1005F00000070020805900080023002088230020E5 +:1006000088230020C8610020E0010008E401000800 +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002004F0F4F833 +:10064000FEE704F057F800DFFEE70000F8B501F020 +:100650003FF904F011FC074604F060FC0546B8BB06 +:10066000204B9F4234D001339F4234D01E4B27F0A1 +:10067000FF029A4232D1F8B200F020FF2E4642F239 +:10068000107400F021FF08B10024264601F002FD9D +:1006900020B1032000F07CF80024264635B1134B2E +:1006A0009F4203D004F032FC00242646002004F0D0 +:1006B000EDFB0EB100F082F801F0A0FA00F070FF3F +:1006C00001F064F9204600F0CDF800F077F8F9E782 +:1006D0002E460024D5E704460126D2E7064640F61A +:1006E000C414CEE7010007B0000008B0263A09B0F4 +:1006F00008B501F017F9A0F120035842584108BD90 :1007000007B541F21203022101A8ADF8043001F04F -:1007100055F903B05DF804FB10B5202383F311886D -:100720001248C3680BB103F0D3FE114A0F480023EF -:100730004FF47A7103F090FE002383F311880D4C7F +:1007100027F903B05DF804FB38B5302383F3118863 +:10072000174803680BB104F03DF9164A144800233A +:100730004FF47A7104F02CF9002383F31188124CE2 :10074000236813B12368013B2360636813B16368B6 -:10075000013B6360084B1B7833B9636823B90220FF -:1007600001F026FA3223636010BD00BF8823002009 -:1007700019070008A42400209C2300201E4B1F4AB8 -:1007800010B51C461968013134D004339342F9D1B5 -:1007900062681B4B9A422DD91A4B9B6803F1006388 -:1007A00003F580339A4225D204F0FEF804F010F9E4 -:1007B000002001F02DF9144B0220187001F0EEF921 -:1007C000124B1A6C00221A64196E1A66196E596C53 -:1007D0005A64596E5A665B6E72B64FF0E023202160 -:1007E000C3F8084DD4E9003281F311889D4683F3A4 -:1007F0000888104710BD00BF000001082000010854 -:10080000FFFF0008002300209C2300200038024046 -:100810002DE9F04F93B0AC4B00902022FF210AA8A5 -:100820009D6801F0E1F9A94A1378A3B9A84801210C -:10083000C3601170202383F31188C3680BB103F0E8 -:1008400047FEA44AA24800234FF47A7103F004FE45 -:10085000002383F31188009B9F4A03B113609F49D3 -:10086000009C00230B70536098469B461E469A4698 -:10087000012001F093F924B1974B1B68002B00F085 -:100880001C82002001F07CF80390039B002B01DA0E -:1008900000F0DEFE039B002BEDDB012001F074F97C -:1008A000039B213B162BE3D801A252F823F000BF93 -:1008B0000D09000835090008C90900087108000879 -:1008C00071080008710800085D0A00082F0C000874 -:1008D000490B0008AB0B0008D30B0008F90B00080C -:1008E000710800080B0C0008710800087D0C000856 -:1008F000AD09000871080008C10C000819090008BA -:10090000AD09000871080008AB0B00080220FFF7D2 -:10091000EFFE002840F0FB81009B0221B8F1000FA0 -:1009200008BF1C4605A841F21233ADF8143001F09F -:1009300045F89DE74FF47A7001F022F8071EEBDBD3 -:100940000220FFF7D5FE0028E6D0013F052F00F278 -:10095000E081DFE807F0030A0D1013360523059345 -:10096000042105A801F02AF817E057480421F9E707 -:100970005B480421F6E75B480421F3E74FF01C09CC -:10098000484601F047F809F104090590042105A83B -:1009900001F014F8B9F12C0FF2D1012000FA07F799 -:1009A00047EA0B0B5FFA8BFB4FF0000A01F068F986 -:1009B00026B10BF00B030B2B08BF0024FFF7A0FEA2 -:1009C00056E749480421CDE7002EA5D00BF00B03D4 -:1009D0000B2BA1D10220FFF78BFE074600289BD0EE -:1009E00001203E4E01F014F80220307001F0D6F8DC -:1009F0004FF000085FFA88F9484601F019F80446FC -:100A000090B1484601F024F808F101080028F1D11E -:100A1000B846044641F21213022105A8ADF814307D -:100A20003E4600F0CBFF23E701230220337001F0A4 -:100A3000ABF82546244B9B68AB4207D9284600F00B -:100A4000E9FF013040F068810435F3E7234B0025CE -:100A50001D70214BB8465D603E46A7E7002E3FF46F -:100A60005BAF0BF00B030B2B7FF456AF1B4B02203D -:100A7000187001F093F8322000F082FFB0F1000905 -:100A8000FFF64AAF19F003077FF446AF0E4A9268AB -:100A900009EB050393423FF63FAFB9F5807F3FF77F -:100AA0003BAF124B0193B94522DD4FF47A7000F051 -:100AB00067FF0390039A002AFFF62EAF019B039A6B -:100AC00003F8012B0137EDE700230020A0240020CC -:100AD0008823002019070008A42400209C2300205C -:100AE00004230020082300200C230020A023002042 -:100AF000C820FFF7FDFD074600283FF40DAF1F2D6E -:100B000011D8C5F120024A450AAB25F0030028BFE1 -:100B10004A4683490192184401F054F8019A8048EA -:100B2000FF2101F061F84FEAA9037D490193C9F360 -:100B30008702284601F060F8064600283FF46AAFB5 -:100B4000019B05EB830531E70220FFF7D1FD00286B -:100B50003FF4E2AE00F0A6FF00283FF4DDAE002730 -:100B6000B946704B9B68BB4218D91F2F11D80A9BFE -:100B700001330ED027F0030312AA134453F8203C8C -:100B800005934846042205A902F04EF80437814631 -:100B9000E7E7384600F03EFF0590F2E7CDF8149005 -:100BA000042105A800F00AFF00E70023642104A83F -:100BB000049300F0F9FE00287FF4AEAE0220FFF7A8 -:100BC00097FD00283FF4A8AE049800F053FF05906D -:100BD000E6E70023642104A8049300F0E5FE002862 -:100BE0007FF49AAE0220FFF783FD00283FF494AE15 -:100BF000049800F04FFFEAE70220FFF779FD002894 -:100C00003FF48AAE00F05EFFE1E70220FFF770FDDF -:100C100000283FF481AE05A9142000F059FF0421FB -:100C20000746049004A800F0C9FE3946B9E732200F -:100C300000F0A6FE071EFFF66FAEBB077FF46CAE9A -:100C4000384A926807EB0A0393423FF665AE0220EA -:100C5000FFF74EFD00283FF45FAE27F0030757442F -:100C6000BA453FF4A3AE504600F0D4FE04210590EF -:100C700005A800F0A3FE0AF1040AF1E74FF47A7028 -:100C8000FFF736FD00283FF447AE00F00BFF0028C9 -:100C900044D00A9B01330BD008220AA9002000F09F -:100CA000ABFF00283AD02022FF210AA800F09CFFC9 -:100CB000FFF726FD1C4803F099FB13B0BDE8F08F49 -:100CC000002E3FF429AE0BF00B030B2B7FF424AE68 -:100CD0000023642105A8059300F066FE074600285E -:100CE0007FF41AAE0220FFF703FD814600283FF48F -:100CF00013AEFFF705FD41F2883003F077FB05984E -:100D000000F0D4FF4E4600F0BBFF3C46B0E506467F -:100D10004CE64FF0000AFFE5B8467BE6374679E639 -:100D2000A023002000230020A0860100094A1368A8 -:100D300049F2690099B21B0C00FB01331360064BAA -:100D4000186844F2506182B2000C01FB0200186086 -:100D500080B27047182300201423002010B5002112 -:100D60001022044600F040FF034B03CB206061607B -:100D70001868A06010BD00BF107AFF1F2DE9F04376 -:100D8000224DBBB001F04AFFAB6840F2ED22C31A1E -:100D9000934232D906AFA8602B462822002138465C -:100DA00002F04CFC05F10E0000F016FF0026044690 -:100DB0005FFA80F905F10E08F3B2F100994501F1EF -:100DC000280107D908EB06030822384602F036FC52 -:100DD0000136F1E708230122CDE9023205340C4B3C -:100DE0000193A4B230230093CDE9047405A3D3E9A1 -:100DF0000023297B074802F039FA3BB0BDE8F083B5 -:100E0000AFF3008078F6339F93CACD8D90560020C3 -:100E10009D560020C434002070B50D4614461E4671 -:100E200002F0BAF950B9022E10D1012C0ED112A342 -:100E3000D3E90023C5E90023012007E0282C10D0C6 -:100E400005D8012C09D0052C0FD0002070BD302C06 -:100E5000FBD10BA3D3E90023ECE70BA3D3E90023D9 -:100E6000E8E70BA3D3E90023E4E70BA3D3E90023CE -:100E7000E0E700BFAFF30080401DA12026812A0BD0 -:100E800078F6339F93CACD8D9E6AC421818A46EE3F -:100E900026417272DF25D7B7F017304A39059E56C2 -:100EA00013B504462346084620220021019002F093 -:100EB000C5FB22790198032A234628BF032203F8A1 -:100EC000042F2021022202F0B9FB62790198072A3F -:100ED000234628BF072203F8052F2221032202F010 -:100EE000ADFBA2790198072A234628BF072203F801 -:100EF000062F2521032202F0A1FB019804F108032B -:100F00001022282102F09AFB382002B010BD000008 -:100F10002DE9F04FADF5017D21AD0EAE40F2751219 -:100F200080460F4622A80021296000F05DFE48227D -:100F30000021304600F058FE01F070FE564B4FF491 -:100F40007A72B0FBF2F0186093E80700012386E89C -:100F500007000DF15A003382FFF700FF40F604331B -:100F6000338407AB18464D4904F0AAF918223064BF -:100F70002946304686F83C20FFF792FF12AB044624 -:100F800001460822284602F059FB0822A1180DF15B -:100F90004903284602F052FB0DF14A03082204F1EE -:100FA0001001284602F04AFB13AB202204F118017D -:100FB000284602F043FB14AB402204F138012846D6 -:100FC00002F03CFB16AB082204F17801284602F03F -:100FD00035FB0DF15903082204F18001284602F087 -:100FE0002DFB04F1880A0DF15A0904F5847B4B4668 -:100FF0005146082228460AF1080A02F01FFBD34591 -:1010000009F10109F3D11BAB08225946284602F029 -:1010100015FB04F588744FF0000996F834304B4501 -:101020000AD9B36B21464B440822284602F006FB3E -:10103000083409F10109F0E74FF0000996F83C3057 -:101040004B4504EBC90108D9336C08224B442846B0 -:1010500002F0F4FA09F10109F0E700230393BB7EE3 -:101060000293073107F119030193C1F3CF01012363 -:10107000CDE904510093F97E05A3D3E9002340464E -:1010800002F0F4F80DF5017DBDE8F08FAFF30080BC -:101090009E6AC421818A46EEAC240020F0520008EA -:1010A000F8B50E4C0E4F0226A4F5805343F8487C49 -:1010B000237E3BB965692DB1284601F02DFC2846F9 -:1010C00003F090FF204601F027FCA4F58654012E82 -:1010D000A4F1100400D1F8BD0126E5E70856002070 -:1010E0003C540008014B1870704700BFB824002022 -:1010F000F0B5334B1C7B85B034B1324B0E221A81D4 -:101100000024204605B0F0BD2F4A1068516802AB9C -:1011100003C308232D492E480DEB030203F0B4FF4F -:10112000054630B9274B2B480A221A8101F072FB81 -:10113000E6E70169B1F5E02F06D9224B26480B22DC -:101140001A8101F067FBDCE7438B40F20B429342CC -:1011500007D01C490C2008811946204801F05AFB91 -:10116000CFE71F4A024402F11003994204D2154B03 -:101170001C4810221A81E4E710398E1A20461449BF -:1011800001F052FD3246074605F11801204601F0F4 -:101190004BFDAB689F4202D1EB6898420AD0094BE5 -:1011A0000D221A810090D5E902123B460E4801F04B -:1011B00031FBA5E70D4801F02DFB0124A1E700BF9D -:1011C00090560020AC2400209D530008DCFF060050 -:1011D000000001080C530008185300082A530008A7 -:1011E0000800FFF748530008655300088E530008B5 -:1011F0002DE9F04FADB006AF80460C4601F0CCFFB4 -:10120000054600285AD1237E022B1BD1E38A012BED -:1012100018D101F003FD0646FFF788FD03464FF4A1 -:10122000C870DFF8D092B3FBF0F206F5167602FB39 -:10123000103316FA83F3C9F80030E37E33B9A84BB4 -:1012400000221A709C37BD46BDE8F08FA38AEEB22B -:10125000013BB34205F101050BD93B1D1E44E900DA -:1012600000960023082201F0F801204602F0AAF8B7 -:10127000ECE707F11400FFF771FD324607F11401A6 -:10128000381D03F0F1FE0028D9D10F2E08D8944B59 -:101290001E70D9F80030A3F51673C9F80030D1E7F5 -:1012A000FB1CF8700146009307220346204602F01B -:1012B00089F8F978404601F067FFC3E7E38A282BF5 -:1012C00026D010D8012B1ED0052BBBD1BFF34F8FDA -:1012D0008449854BCA6802F4E0621343CB60BFF3D4 -:1012E0004F8F00BFFDE7302BACD1637E7F4D0133C4 -:1012F0006A7BDBB29342E94603D1E27E2B7B9A42C2 -:1013000065D0CD469EE721464046FFF701FE99E7AE -:10131000A38A013B9BB2C92B94D8744D2E7B26BB6C -:1013200005F10C030093082233463146204602F0B3 -:1013300049F8731CF2B2D9001E46A38A013B9A42B7 -:1013400005DA0E322A44009200230822EEE7002339 -:101350000022C5E900230023AB6085F8D730C5F82B -:10136000D8302B7B0BB9E37E2B73002507F11409D2 -:101370003B1D082229464846C7E90155FD6002F099 -:101380005DF93B7A05F1010AAB424FEACA0608D97A -:10139000FB6808222B443146484602F04FF9554677 -:1013A000EFE7C6F3CF06E17ECDE904960023039371 -:1013B000A37E0293193428230093019446A3D3E912 -:1013C0000023404601F052FFFFF7D8FC3AE74FF008 -:1013D000000807F11403A7F8148010220093414677 -:1013E0000123204601F0EEFFA68A023EB6B2F31CAE -:1013F0009B109B000733DB08A9EBC3039D460DF14F -:10140000180A1FFA88F34FEAC801B34201F110012C -:101410000AD20AEB0803009308220023204601F0B9 -:10142000D1FF08F10108ECE795F8D70000F000FBC8 -:10143000D5F8D83004461BB995F8D70000F008FB62 -:10144000D5F8D83033449C4204D295F8D700013007 -:1014500000F0FEFA4FEA960B4FF000081FFA88F1F1 -:101460008B45D5E9003209D90AEB880103EB8800E6 -:10147000012200F0C1FB08F10108EFE7F31842F187 -:101480000002C5E90032D5F8D83095F8D70006EB50 -:101490000308C5F8D88000F0CBFA804509D395F849 -:1014A000D730D5F8D8000133001B85F8D730C5F800 -:1014B000D800FF2E08D800232B7300F0F3FAFFF7B3 -:1014C00017FE08B1FFF75AF92B68094A9B0A013346 -:1014D00013810023AB6014E726417272DF25D7B772 -:1014E000BD34002000ED00E00400FA059056002015 -:1014F000AC240020C034002030B54FF00054244B01 -:1015000022689A4285B007D003F08CFA0446A8B945 -:101510000024204605B030BD1E4B627D1A701E4867 -:10152000237D03731D49C9220E3000F04BFB20467A -:10153000E022002100F058FB0124EAE7184A194D87 -:10154000136C43F000731364AA6D174B9A42DFD1FA -:101550002B6E013B7E2BDBD8144A07CA01AB83E814 -:1015600007001846032101F075FB6B6D83424FF0B5 -:101570000003CDD12A6D8A4201BFAB65054B2A6EAF -:101580001A7003BF0A4BEA6D1A601C46C1E700BF20 -:101590009AAD44C5B82400209056002016000020C3 -:1015A00000380240006600405041A0B0586600403C -:1015B0001023002037B51C4C1C4D21681C48022309 -:1015C00001226B7100F0DAFF1A48216850F8D03F11 -:1015D00001225B68984700230193174B174900933A -:1015E0001748184B4FF4805201F0A8FD164B19789C -:1015F00011B1134801F0C8FD01F010FB0446FFF7DC -:1016000095FB4FF4C873B0FBF3F202FB130304F530 -:10161000167010FA83F00D4B186003F0F9F908B159 -:101620000F232B8103B030BD10230020AC240020F9 -:10163000F0340020F0440020190E0008BC240020E3 -:10164000C4340020F1110008B8240020C034002068 -:101650002DE9F04F2DED028BDFF8A4B293B0DFF847 -:101660008092DFF8A0A2484601F064FE03460028FD -:101670003ED00024CDE90F440E94ADF84440027BE7 -:101680008DF8442099684068934D0FAA03C21B68E7 -:1016900043F000430E932746A0462B681B691E4665 -:1016A00001F0BEFA10EB0A0241F100032846CDF822 -:1016B00000800EA9B04704F2344440F668030028C5 -:1016C000C8BF47F0010705F586559C4205F1100596 -:1016D000E3D137B1484601F031FE804B83F80080FA -:1016E000C1E77E4A1378072B00F2E58001331370BF -:1016F0000BAF9FED738B00230A93ADF834300B933F -:101700007B600025744CDFF8D8912E4601238DF8BC -:101710001C3023688DED008B4FF0000AD3F8088051 -:101720008DF81DA053460DF11D0207A92046C047A4 -:101730009DF81C80B8F1000F24D0DBF8143083F43E -:101740000043CBF81430102251460EA800F04CFA9A -:10175000236808AA5E690AA90DF11E032046B04756 -:1017600097E803000FAB83E803009DF834308DF851 -:1017700044300A9B0E930EA9DDE90823484601F088 -:10178000A5FF464605F2344540F6680304F5865445 -:101790009D4204F11004B9D1002EB2D1504801F09D -:1017A000FBFC002840D14F4D01F038FA2B689842DD -:1017B0003AD301F033FA0446FFF7B8FA4FF4C8738E -:1017C00004F51674B0FBF3F202FB130314FA83F36F -:1017D0002B60454D8DF828602E7816B901238DF8C1 -:1017E0002830C6F11004E4B20EA8FFF7B7FA062CB1 -:1017F00028BF06240EAB224699190DF1290000F0EE -:10180000E1F90AAB0393182302930134374B019398 -:10181000E4B201230093324804942BA3D3E90023BC -:1018200001F0BCFC00232B7001F0F8F9304A314C78 -:101830001368C31AB3F57A7F30D3106001F0F0F962 -:1018400002460B46264801F083FD254801F0A4FC22 -:1018500020B3237B284D002B14BF032302236B717D -:1018600001F0DCF90EAE4FF47A733146B0FBF3F0C1 -:1018700028602846FFF714FB1823073002931F4BFC -:101880000193C0F3CF0040F25513CDE903600093FC -:1018900013480FA3D3E9002301F080FC237B2BB175 -:1018A000FFF76CFA237B002B7FF4D9AE13B0BDECAD -:1018B000028BBDE8F08F0A4801F040FD18E700BF39 -:1018C0000000000000000000401DA12026812A0B1E -:1018D000F1C6A7C1D068080FF0340020755700206A -:1018E000C4340020C0340020BD340020BC340020AB -:1018F0007057002090560020AC2400207457002020 -:101900000004024040420F0008B5064800F0ACFB5E -:10191000054800F0A9FBBDE80840044A044900203E -:1019200003F05ABBF0340020C0450020C857002007 -:10193000A110000870B50F4B1B780133DBB2012BEF -:101940000C4611D80C4D29684FF47A730E6AA2FB2D -:101950000332014622462846B047844204D1074B51 -:1019600000221A70012070BD4FF4FA7002F03EFDA3 -:101970000020F8E71C230020CC570020B857002097 -:1019800007B50023024601210DF107008DF807304D -:10199000FFF7D0FF20B19DF8070003B05DF804FB0E -:1019A0004FF0FF30F9E700000A4608B50421FFF7C1 -:1019B000C1FF80F00100C0B2404208BD30B4054C08 -:1019C0002368DD69044B0A46AC460146204630BC1C -:1019D000604700BFCC570020A086010070B502F020 -:1019E0005FFE094E094D3080002428683388834209 -:1019F00008D902F04FFE2B6804440133B4F5803F50 -:101A00002B60F2D370BD00BFBA570020785700207A -:101A100002F00ABF00F1006000F5803000687047F6 -:101A200000F10060920000F5803002F087BE0000F7 -:101A3000054B1A68054B1B889B1A834202D9104438 -:101A400002F028BE0020704778570020BA570020C7 -:101A500038B5074D04462868204402F023FE28B913 -:101A600028682044BDE8384002F034BE38BD00BFCD -:101A70007857002010F003030AD1B0F5047F05D297 -:101A800000F10050A0F51040D0F80038184670471B -:101A90000023FBE700F10050A0F51040D0F8100A39 -:101AA00070470000064991F8243033B10023086ADA -:101AB00081F824300822FFF7B3BF0120704700BF30 -:101AC0007C570020014B1868704700BF002004E0DD -:101AD00070B52A4B1B68C3F30B0204461B0C62B1A2 -:101AE00040F21340824230D040F2194082422ED060 -:101AF00040F2214082422CD10322214D0C2000FBD8 -:101B00000252556842F20102934224D0B3F5805F3D -:101B100023D041F20102934221D041F203029342C9 -:101B20001FD041F20702934214BF3F233123013CEF -:101B30000C44013D0A46A24215D215F9016F501C12 -:101B40009EB100F8016C0246F5E70122D5E70222BA -:101B5000D3E70C4DD6E73323E9E74123E7E75A23E0 -:101B6000E5E75923E3E7104605E02C25844215708C -:101B700001D9901C5370401A70BD00BF002004E0D2 -:101B8000D4530008A8530008022802BF024B4FF0AC -:101B900000429A61704700BF00040240022802BF61 -:101BA000024B4FF400429A61704700BF00040240AC -:101BB000022801BF024A536983F40043536170470E -:101BC0000004024010B50023934203D0CC5CC454FF -:101BD0000133F9E710BD000003460246D01A12F99E -:101BE000011B0029FAD1704702440346934202D0F8 -:101BF00003F8011BFAE770472DE9F8431F4D14461F -:101C000095F824200746884652BBDFF870909CB3B5 -:101C100095F824302BB92022FF2148462F62FFF788 -:101C2000E3FF95F82400C0F10802A24228BF224633 -:101C3000D6B24146920005EB8000FFF7C3FF95F84E -:101C40002430A41B1E44F6B2082E17449044E4B27C -:101C500085F82460DBD1FFF725FF0028D7D108E005 -:101C60002B6A03EB82038342CFD0FFF71BFF0028D0 -:101C7000CBD10020BDE8F8830120FBE77C57002092 -:101C8000024B1A78024B1A70704700BFB8570020F9 -:101C90001C230020034904484FF461430B6002F009 -:101CA0003FBA00BFA4570020CC570020074B10B507 -:101CB0000021044614221846FFF796FF04600146EF -:101CC000BDE81040024802F02BBA00BFA457002024 -:101CD000CC570020202383F3118862B670470000A0 -:101CE000002383F3118862B67047000010B40268C5 -:101CF00054681A4623465DF8044B18470120704784 -:101D000000207047002070477047000070470000B7 -:101D1000002070470E20704700F5805090F8C800F2 -:101D2000C0F340007047000000F5805090F9C900F2 -:101D3000704700002DE9F0410C68BDF8187014F0F0 -:101D400000541E466FD10B7B082B6CD8FFF7C2FFE7 -:101D50004569AB685B010CD4AB681B0108D4AC6867 -:101D600014F080545DD1FFF7BBFF2046BDE8F08141 -:101D700001240B6804F1180C002BB8BFDB004FEAFC -:101D80000C1CB4BF43F004035B0545F80C300B6832 -:101D90000FFA84FC13F0804F18BF05EB0C1E05EB07 -:101DA0000C1C1EBFDEF8803143F00203CEF88031F8 -:101DB0000B7BCCF8843105EB04158B68C5F88C31AE -:101DC0004B68C5F88831DCF8803143F00103CCF86A -:101DD000803100EB441541F268031D4403EB4413CA -:101DE0000344C5E9002608330D4601F10C0C55F8F3 -:101DF00004EB43F804EB6545F9D184342D881D804C -:101E000000EB441407F00303257925F00B052B4361 -:101E10002371FFF765FF06973346BDE8F04100F0F8 -:101E20001BBD0224A5E74FF0FF309FE713B500F577 -:101E300080540191E06D00F0A5FD1F280AD9019999 -:101E4000E06D202200F014FEA0F12003584258411A -:101E500002B010BD0020FBE708B500F58050FFF789 -:101E600039FFC06D00F062FDBDE80840FFF738BFE4 -:101E700000220260828142608260704710B50022B9 -:101E80000023C0E900230023044603810C30FFF740 -:101E9000EFFF204610BD0000F0B5054600F580506C -:101EA0000C4690F8C83013F0040FC3F3800108BF4C -:101EB000114661F3820304F1840680F8C83005EB13 -:101EC000461389B01B79D8072ED57AB319072DD4BC -:101ED0006846FFF7D3FF05EB441303F5835303F183 -:101EE000180703AA103318685968144603C4083346 -:101EF000BB422246F7D1186820609B88A380DDE9A9 -:101F00000E23CDE900230123ADF808302B68694684 -:101F10001B6C2846984705EB46152B791A075CBFC2 -:101F200043F008032B7101E0002AF4D109B0F0BDA1 -:101F30002DE9F047074688B007F5805468469A4671 -:101F40008846FFF7C7FE9146FFF798FFE06D00F067 -:101F5000FFFC1F2829D9E06D2022694600F00AFE07 -:101F6000202822D103AD444605AB2E4603CE9E4227 -:101F700020606160354604F10804F6D130682060C5 -:101F8000B388A380DDE90023C9E90023BDF8083048 -:101F9000AAF80030FFF7A4FE4A46534641463846A9 -:101FA00008B0BDE8F04700F045BCFFF799FE0020FF -:101FB00008B0BDE8F08700002DE9F84F0023C0E924 -:101FC0000133264B044640F8183B0F46FFF750FFFD -:101FD00004F12800FFF752FF04F1480804F5825588 -:101FE0004646083530462036FFF748FFAE42F9D165 -:101FF00004F580554FF480534FF00009C5E91339BB -:10200000C5F848800123EE6504F5875804F5845629 -:10201000C5F8549085F8583085F86030083608F1D6 -:1020200008084FF0000A4FF0000B46E908ABA6F194 -:102030001800FFF71DFF203646F8289C4645F4D1CE -:10204000012F85F8C97002D9054800F0E1FD054B64 -:1020500053F8273063612046BDE8F88F3C540008F0 -:10206000045400082054000810B5044B19780446A5 -:102070004A1C1A70FFF7A0FF204610BDC45700206D -:102080002DE9F047002950D0294B2A4FB7FBF1F535 -:1020900099428CBF0A231123581EB5FBF3FC03FBA6 -:1020A0001C53C4B22BB102280346F5D80020BDE86A -:1020B000F0870CF1FF36B6F5806FF7D2C4EBC40E93 -:1020C0000EF103034FEAE309C3F3C703A4EB0308CC -:1020D00009F1010A4FF47A755FFA88F009FB05559A -:1020E0005AFA88F8B5FBF8F5B5F5617FC1BF0EF176 -:1020F000FF33C3F3C703E01AC0B25C1C50FA84F488 -:102100000CFB04F4B7FBF4F4A142CFD1013BDBB2EA -:102110000F2BCBD80138C0B20728C7D800211071C7 -:1021200016809170D3700120C1E70846BFE700BF59 -:102130003F420F0040787D0170B505460E464FF4D2 -:102140007A746B695B6803F00103B34207D04FF404 -:102150007A7002F04BF9013CF3D1204670BD0120AA -:10216000FCE7000030B54269936913F0700F16D098 -:1021700000230B4C936103F1840200EB42121179AE -:102180004D0709D5890707D5416954F823508D605B -:10219000117941F0040111710133032BEBD130BDF2 -:1021A0002854000873B51D46436916469A68D2073D -:1021B000044609D59A6801219960C2F34002CDE92D -:1021C00000650021FFF768FE63699A68D1050BD5A9 -:1021D0009A684FF480719960C2F34022CDE900659E -:1021E00001212046FFF758FE63699A68D2030BD598 -:1021F0009A684FF480319960C2F34042CDE900659E -:1022000002212046FFF748FE204602B0BDE870409C -:10221000FFF7A8BF0C4B10B51C561B5C012B11D847 -:1022200000F0FEFC50EA0103024602D0421E61F1BA -:102230000001064B53F8240020B1BDE810400B46C6 -:10224000FFF7B0BF10BD00BF1C540008BC570020F2 -:10225000F8B50446466900296CD106F10C073868C8 -:1022600080076AD006EB01153868D5F8B00110F088 -:10227000040FD5F8B0011ABFC00840F00040400D6F -:10228000A061D5F8B0C11CF0020F1CBF40F0804027 -:10229000A061D5F8B40106EB011100F00F0084F83D -:1022A0002400D1F8B8012077D1F8B801000A60778E -:1022B000D1F8B801000CA077D1F8B801000EE07792 -:1022C000D1F8BC0184F82000D1F8BC01000A84F8E0 -:1022D0002100D1F8BC01000C84F82200D1F8BC1117 -:1022E000090E84F823103821396004F1340004F118 -:1022F000180104F1240551F8046B40F8046BA9425D -:10230000F9D109880180C4E90A23214600232386E4 -:1023100051F8283B20461B6C984704F58052204614 -:1023200092F8C83043F0040382F8C830BDE8F840A2 -:10233000FFF718BF06F1100791E7F8BD0D4B70B518 -:102340001D561B5C012B0C4612D800F069FC02469E -:102350000B4652EA030102D0013A63F10003064939 -:1023600051F8250020B12146BDE87040FFF770BF4D -:1023700070BD00BF1C540008BC570020F8B500F524 -:1023800083511E46FFF7A6FCDFF844C00831002445 -:1023900004F1840500EB45152B795F070ED4DB06AD -:1023A0000CD5D1E900739742B34107D243695CF879 -:1023B00024709F602B7943F004032B710134032CAC -:1023C00001F12001E4D1BDE8F840FFF789BC00BF6E -:1023D0002854000808B5FFF77DFCFFF7C3FEBDE8F1 -:1023E0000840FFF77DBC0000F8B5436905469868D2 -:1023F00000F0E050B0F1E05F0F461FD0E8B1FFF70A -:1024000069FC05F583541034002606F1840305EBBE -:1024100043131B791A0706D50136032E04F1200455 -:10242000F3D1012007E05B07F6D42146384600F0DF -:102430004DFA0028F0D1FFF753FCF8BD0120FCE76E -:1024400000F5805008B5FFF745FCC06D00F080FA3C -:10245000FFF746FC43090CBF0120002008BD000027 -:10246000F8B51D46002313700F4606461446FFF7C5 -:10247000E7FF80F00100387025B129463046FFF7AC -:10248000B3FF2070F8BD00002DE9B8410C46154699 -:102490001F46804600F0C4FB0B462178024609B96E -:1024A000287850B14046FFF769FFFFF793FF3B469E -:1024B0002A462146FFF7D4FF0120BDE8B88100007D -:1024C00038B500F58054FFF705FC2A4D94F8C93063 -:1024D000EB5CDBB1012B27D0FFF702FC94F8C8308E -:1024E000DB0746D4002944D0FFF7F4FB94F8C93049 -:1024F000EB5C33B3012B31D094F8C83043F00103C7 -:1025000084F8C830BDE83840FFF7EABB1A4B1A6CB4 -:1025100042F000721A641A6A42F000721A621A6A71 -:1025200022F000721A62D7E7134B1A6C42F08062F5 -:102530001A641A6A42F080621A621A6A22F0806291 -:10254000F0E70221132001F023FC0221142001F006 -:102550001FFC0221152001F01BFCCDE702213F20CA -:1025600001F016FC0221402001F012FC0221412062 -:10257000F1E738BD18540008003802402DE9F04753 -:1025800000F5805588B095F8C930022B044688467E -:10259000164600F20381824F57F823200AB947F804 -:1025A0002300D7F800A0C4F80C802674BAF1000FFD -:1025B00009D141F2D00002F017FD51468146FFF7E4 -:1025C000FBFCC7F8009095F8C930012B5DD00121C4 -:1025D0002046FFF775FFFFF77DFB6269136823F064 -:1025E000020313606269136843F0010313606369B7 -:1025F00000275F6101212046FFF772FBFFF79CFD7A -:10260000002800F08480E86D00F090F904F583590B -:10261000BA4609F10809202200216846FFF7E4FACA -:1026200002A8FFF725FCCDF818A06A4609EB0703BE -:102630000DF1180E9446BCE80300F445186059608B -:10264000624603F10803F5D1DCF80000186020377A -:102650009CF804201A71602FDDD195F8C8306FF313 -:102660008203002785F8C8306A4641462046ADF807 -:102670000070ADF802708DF80470FFF701FD63691A -:10268000C0B94FF400421A6011E0386803685B6B10 -:102690009847014600289AD13868FFF711FF38683B -:1026A000036832465B684146984700288FD108B0DE -:1026B000BDE8F08761221A609DF802309DF8032082 -:1026C0001B06120402F4702203F040731343BDF89A -:1026D0000020C2F3090213439DF804201205022EC4 -:1026E00002F4E0020CBF4FF0004100211343626985 -:1026F0000B43D361636913225A616269136823F043 -:102700000103136039462046FFF716FD08B96369D7 -:10271000B7E795F8C930002B39D16169D1F80022AB -:1027200042F00102C1F800226169D1F8002222F4CE -:102730007C5222F00E02C1F800226169D1F8002219 -:1027400042F46062C1F800226269C2F81432626920 -:10275000C2F8043262696FF07841C2F80C12626903 -:10276000C2F840326269C2F844326269C2F8B032DB -:102770006269C2F8B432636944F20102C3F81C22F0 -:102780006269D2F8003223F00103C2F8003295F8F2 -:10279000C83043F0020385F8C83088E7002086E798 -:1027A000BC57002008B50020FFF734FDBDE8084005 -:1027B00001F0BCB908B500210846FFF7BFFDBDE830 -:1027C000084001F0B3B9000008B501210020FFF76F -:1027D000B5FDBDE8084001F0A9B9000008B5012029 -:1027E000FFF718FDBDE8084001F0A0B908B50021C9 -:1027F0000120FFF7A3FDBDE8084001F097B90000F4 -:1028000008B501210846FFF799FDBDE8084001F031 -:102810008DB900000FB4002004B0704713B56C46AA -:1028200084E80600031D94E8030083E80500012006 -:1028300002B010BD73B58568019155B11B885B0767 -:1028400007D4D0E90036DB6B9847019AC1B2304615 -:10285000A847012002B070BDF0B5866889B0054672 -:102860000C465EB1BDF838305B070AD4D0E90037BA -:10287000DB6B98472246C1B23846B047012009B009 -:10288000F0BD00220023CDE900230023ADF808307D -:102890000A4603AB01F10806106851681C4603C4E0 -:1028A0000832B2422346F7D1106820609288A28095 -:1028B00000F0B8F90423ADF808302B68CDE9000129 -:1028C0001B6C694628469847D8E7000030B5036876 -:1028D0000968DD0FB5EBD17F23F0604421F0604241 -:1028E0004FEAD1700BD0002BB8BFA40C0029B8BFA1 -:1028F000920C944202D034BF0120002030BD94429B -:1029000005D1C1F38070C3F380738342F6D1944242 -:102910002CBF00200120F1E710B5037C044613B959 -:10292000006802F099FB204610BD00000023BFF3B1 -:102930005B8FC360BFF35B8FBFF35B8F8360BFF3BD -:102940005B8F7047BFF35B8F0068BFF35B8F70478F -:1029500070B505460C30FFF7F5FF05F10806044693 -:102960003046FFF7EFFFA04206D930466D68FFF70B -:10297000E9FF2544281A70BD3046FFF7E3FF201A0F -:10298000F9E7000070B50546406898B105F1080008 -:10299000FFF7D8FF05F10C0604463046FFF7D2FFDB -:1029A0008442304694BF6D680025FFF7CBFF013CA1 -:1029B0002C44201A70BD000038B50C460546FFF7C0 -:1029C000C7FFA04210D305F10800FFF7BBFF044486 -:1029D0006868B4FBF0F100FB1144BFF35B8F01208A -:1029E000AC60BFF35B8F38BD0020FCE72DE9F04100 -:1029F000144607460D46FFF7C5FF844228BF04462C -:102A0000D4B1B84658F80C6B4046FFF79BFF3044F2 -:102A1000286040467E68FFF795FF331A9C4203D832 -:102A20006C600120BDE8F0816B60A41B3B68AB606B -:102A30002044E8600220F5E72046F3E738B50C466D -:102A40000546FFF79FFFA04210D305F10C00FFF7EA -:102A500079FF04446868B4FBF0F100FB1144BFF354 -:102A60005B8F0120EC60BFF35B8F38BD0020FCE77B -:102A70002DE9FF41884669460746FFF7B7FF6C46D8 -:102A800006B204EBC6060025B44209D0626820688D -:102A900008EB0501FFF796F8636808341D44F3E777 -:102AA00029463846FFF7CAFF284604B0BDE8F08142 -:102AB000F8B505460C300F46FFF744FF05F1080650 -:102AC00004463046FFF73EFFA042304688BF6C68A0 -:102AD000FFF738FF201A386020B130462C68FFF726 -:102AE00031FF2044F8BD000073B5144606460D467C -:102AF000FFF72EFF844228BF04460190DCB101A9F4 -:102B00003046FFF7D5FF019B33B93268C5E9023380 -:102B1000C5E9002401200CE09C4238BF01942860E4 -:102B2000019868608442F5D93368AB60241AEC6080 -:102B3000022002B070BD2046FBE700002DE9FF41F6 -:102B40000F466946FFF7D0FF6C4600B204EBC005A4 -:102B50000026AC4209D0D4F8048054F8081BB819F8 -:102B60004246FFF72FF84644F3E7304604B0BDE88D -:102B7000F081000038B50546FFF7E0FF0446014646 -:102B80002846FFF719FF204638BD000000B59BB06E -:102B9000EFF3098168226846FFF714F8EFF3058325 -:102BA000044B9A6BDA6A9A6A9A6A9A6A9A6A9A6A79 -:102BB0009B6AFEE700ED00E000B59BB0EFF30981F2 -:102BC00068226846FEF7FEFFEFF30583044B9A6B1D -:102BD0009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF38 -:102BE00000ED00E000B59BB0EFF309816822684674 -:102BF000FEF7E8FFEFF30583034B5A6B9A6A9A6A74 -:102C00009A6A9A6A9B6AFEE700ED00E0FEE7000020 -:102C10000FB408B5029801F083FBFEE701F044BE53 -:102C200001F01CBE01F01ABE30B5094D0A449142B4 -:102C30000DD011F8013B5840082340F30004013B3C -:102C40002C4013F0FF0384EA5000F6D1EFE730BDCB -:102C50002083B8EDF7B54FF0FF33DFF854C0DFF84D -:102C600054E000EB81011A4688421CD050F8044B16 -:102C7000019401AF042417F8015B82EA056208257C -:102C8000DB18164605F1FF355241002EBCBF83EA22 -:102C90000C0382EA0E0215F0FF05F1D1013C14F09D -:102CA000FF04E8D1E0E7D843D14303B0F0BD00BF53 -:102CB0009336EAA9EBE1F0422DE9F041C56915B977 -:102CC000C161BDE8F0814B6823F06047C3F38A46D9 -:102CD0004FEAD37EC3F3807816EA230638BF3E4618 -:102CE000AC462B465A68BEEBD27F22F060440AD035 -:102CF000002A18DAA40CB44217D19D420FD10D60FE -:102D0000DEE71346EEE7A74207D102F08044C2F3A4 -:102D1000807242450BD054B1EFE708D2EDE7CCF812 -:102D200000100B60CDE7B44201D0B442E5D81A6878 -:102D30009C46002AE5D11960C3E700002DE9F04761 -:102D4000089D01F007044FEAD508224405F0070565 -:102D500000EBD1004FF47F49944201D1BDE8F087E8 -:102D600004F0070705F0070A57453E4638BF5646A8 -:102D7000C6F10806111B8E4228BF0E46E10808EB7B -:102D8000D50E415C13F80EC0B94029FA06F721FAB6 -:102D90000AF1FFB28CEA010147FA0AF739408CEADE -:102DA000010C03F80EC034443544D5E780EA012015 -:102DB000082341F2210201B24000002980B203F150 -:102DC000FF33B8BF504013F0FF03F4D17047000049 -:102DD00038B50C468D18A54200D138BD14F8011B3A -:102DE000FFF7E4FFF7E7000002684AB113680360E9 -:102DF000C388018901339BB29942C38038BF0381E4 -:102E00001046704770B588B0202204460D466846CB -:102E10000021FEF7E9FE20460495FFF7E5FF024694 -:102E200058B16B46054608AE1C4603CCB442286038 -:102E30006960234605F10805F6D1104608B070BD5B -:102E4000082817D909280CD00A280CD00B280CD038 -:102E50000C280CD00D280CD00E2814BF4020302098 -:102E600070470C20704710207047142070471820BE -:102E70007047202070470000082817D90C280CD96B -:102E800010280CD914280CD918280CD920280CD9B2 -:102E900030288CBF0F200E207047092070470A2071 -:102EA00070470B2070470C2070470D2070470000C2 -:102EB00010B54B6823B9CA8A63F30902CA8210BDF0 -:102EC000C4681A681C60C360438A013B43824A603D -:102ED000EFE700002DE9F84F1D46CB8A0F46C3F3FC -:102EE00009010629814692460B4630D00020AAB23D -:102EF00007F119049EB2052E1FFA80F80FD89045ED -:102F000003F1010306D3FB8A0A4462F30903FB823F -:102F100001201AE01AF80060E6540130EAE7904513 -:102F2000F1D2A1F1060B1C237C68BBFBF3F203FB7F -:102F300012BB1FFA8BF6002C45D14846FFF754FF11 -:102F4000044638B978606FF00200BDE8F88F4FF0A2 -:102F50000008E6E7002606607860ADB24FF0000B8F -:102F6000454510D90AEB0803221D13F8011B9155A2 -:102F7000B1B208F101081B291FFA88F82BD045458A -:102F800006F10106F1D8FB8AC3F30902154465F383 -:102F90000903BCE7013292B21C462368002BF9D129 -:102FA000AB1F0B441C21B3FBF1F301339BB29A42DC -:102FB000D3D2BBF1000FD0D14846FFF715FF20B99F -:102FC000C4F800B0BFE70122E7E7C0F800B05E46F2 -:102FD00020600446C1E74545D5D94846FFF704FFC0 -:102FE00008B92060AFE7C0F800B0002620600446B2 -:102FF000B6E700002DE9F04F2DED028B83B0CDE94F -:103000000013BDF83C5007469146002A00F092801C -:103010002DB10E9B002B00F08D80072D32D807F1CB -:103020000C00FFF7E1FE044638B96FF002042046B9 -:1030300003B0BDEC028BBDE8F08F14220021FEF737 -:10304000D3FD0E992A4604F10800FEF7BBFD681C6B -:10305000C0B2FFF711FFFFF7F3FE207499F80030BC -:10306000013814FA80F003F01F0363F03F0303728A -:10307000009B43F00041616038462146FFF71CFE8B -:103080000124D4E700F10C034FF0000808EE103AD9 -:103090004FF0800A4646444618EE100AFFF7A4FE99 -:1030A00083460028C1D014220021FEF79DFDC6BB37 -:1030B000019BABF8083002200E9B00F10802991921 -:1030C0005BFA82F20130C0B2082801D0AE422AD3A6 -:1030D000FFF7D2FEFFF7B4FE99F80020009B411ED7 -:1030E00002F01F0242EA4812AE4208BF4FF0400A07 -:1030F0005BFA81F14AEA020A43F0004281F808A033 -:103100008BF81000CBF8042059463846FFF7D4FD61 -:103110000134AE4224B288F001084FF0000ABBD15E -:1031200085E70020C8E711F801CB02F801CB013692 -:10313000B6B2C7E76FF0010479E70000F8B51546AD -:103140000E462822002104461F46FEF74DFD069B31 -:103150006360B5F5001F079BA76034BF6A094FF68F -:10316000FF72236204F10C0097B200239A4205D843 -:103170000023036027826382A382F8BD06600133C7 -:1031800030462036F2E7000003781BB94BB2002B23 -:10319000C8BF017070470000007870472DE9F74FF5 -:1031A000DDF83C90BDF830500D9E9DF83840BDF8DC -:1031B0004070804692469B46B9F1000F01D1002F26 -:1031C00051D11F2C4FD898F80000B0B9072F47D81D -:1031D00035F0030347D13A4649464FF6FF70FFF7F3 -:1031E000F7FD20F001002D02400445EA0464400C84 -:1031F00044EA40244FF6FF7321E040EA0520072F00 -:1032000040EA0464F6D900254FF6FF73C5F12000AB -:10321000A5F120022AFA05F10BFA00F001432BFA7E -:1032200002F211431846C9B2FFF7C0FD0835402D20 -:103230000346EBD13A464946FFF7CAFD0346CDE9BE -:103240000097324621464046FFF7D4FE33780133DB -:10325000DBB21F2B88BF0023337003B0BDE8F08FB3 -:103260006FF00300F9E76FF00100F6E72DE9F04F8A -:1032700085B09246DDF848800F9D9DF840209DF86E -:103280004490BDF84C7006469B46B8F1000F01D142 -:10329000002F48D11F2A46D83378002B46D00C0285 -:1032A00044EA02649DF8381044EAC93444EA01440F -:1032B0001C43072F44F0800432D900234FF6FF72DD -:1032C000C3F1200CA3F120002AFA03F10BFA0CFC45 -:1032D00041EA0C012BFA00F00143C9B210460393F6 -:1032E000FFF764FD039B0833402B0246E8D13A46C2 -:1032F0004146FFF76DFD0346CDE900872A4621468A -:103300003046FFF777FEB9F1010F06D12B78013374 -:10331000DBB21F2B88BF00232B7005B0BDE8F08FF8 -:103320004FF6FF73E8E76FF00100F6E76FF0030078 -:10333000F3E70000C06900B104307047C3691A6840 -:10334000C261C2681A60C360438A013B438270470E -:103350002DE9F041D0F81880194E14461D4641461B -:10336000002709B9BDE8F081D1E90223A21A65EB73 -:103370000303964277EB03031ED283698B420DD180 -:10338000FFF796FD83691B688361C3680B60438AFE -:10339000C1608169013B43828846E2E7FFF788FD0F -:1033A0000B68C8F80030C3680B60438AC160013BFA -:1033B0004382D8F80010D4E788460968D1E700BFF7 -:1033C00080841E002DE9F04F8BB00D46DDF8509043 -:1033D00014469B468046002800F01981B9F1000F81 -:1033E00000F01581531E3F2B00F21181012A03D1F9 -:1033F000BBF1000F40F00B810023CDE90833B8F892 -:103400001430B5EBC30F4FEAC30703D300200BB052 -:10341000BDE8F08F2B199F42D8F80C303ABF7F1BC4 -:10342000FFB227461BB9D8F81030002B7AD02F2DC9 -:103430004ED8C5F13006B7424FF000032CBFF6B2AC -:103440003E4600932946D8F8080008AB3246FFF7FD -:1034500075FCA7EB060A35445FFA8AFAB8F814300F -:1034600003F10053063BDB000493D8F80C300393C0 -:103470003021039B13B1BAF1000F2CD1D8F8100002 -:1034800040B1BAF1000F05D0009608AB5246691A58 -:10349000FFF754FC38B2002FB8D066070AD00AAB49 -:1034A00003EBD401624211F8083C02F00702134119 -:1034B00001F8083C082C3CD9102C40F2B580202C97 -:1034C00040F2B780BBF1000F00F09C80082334E08D -:1034D000BA460026C2E7049BE02B28BFE0230693F0 -:1034E0000B44AB42059314D95A1B0398009692459E -:1034F00034BF5246D2B2691A08AB04300792FFF7C4 -:103500001DFC079A1644AAEB020A1544F6B25FFAAC -:103510008AFA049B069A05999B1A0493039B1B68DD -:103520000393A6E70093D8F8080008AB3A4629466B -:10353000AEE7BBF1000F13D00123B4EBC30F6CD087 -:10354000082C12D89DF82030621E23FA02F2D5070B -:1035500006D54FF0FF3202FA04F423438DF82030F1 -:103560009DF8203089F8003051E7102C12D8BDF8B2 -:103570002030621E23FA02F2D10706D54FF0FF3247 -:1035800002FA04F42343ADF82030BDF82030A9F846 -:1035900000303CE7202C0FD80899631E21FA03F372 -:1035A000DA0705D54FF0FF3202FA04F40C43089411 -:1035B000089BC9F800302AE7402C2BD0DDE90865CC -:1035C000611EC4F12102A4F1210326FA01F105FADA -:1035D00002F225FA03F311431943CB0712D5012256 -:1035E000A4F12003C4F1200102FA03F322FA01F14D -:1035F000A240524243EA010363EB430332432B43AD -:10360000CDE90823DDE90823C9E90023FFE66FF0CF -:103610000100FCE66FF00800F9E6082CA0D9102C98 -:10362000B3D9202CEED8C3E7BBF1000FADD00223F5 -:1036300083E7BBF1000FBBD004237EE730B5012A3E -:10364000144638BF0124402C85B028BF40240025F3 -:10365000012ACDE9025518D81B788DF80830630788 -:103660000AD004AB03EBD405624215F8083C02F023 -:103670000702934005F8083C0091034622460021CA -:1036800002A8FFF75BFB05B030BD082AE4D9102A79 -:1036900003D81B88ADF80830E1E7202A8DBFD3E9B5 -:1036A00000231B680293CDE90223D8E710B5CB684D -:1036B0001BB98B600B618B8210BDC4681A681C60DB -:1036C000C360438A013B4382CA60F0E72DE9F04FB3 -:1036D000D1F8008093B018F0800FCDE90323C8F330 -:1036E000C01219BFC8F3C03BC8F306264FF0020B47 -:1036F0001646B8F1000F04460D4680F2D18118F04D -:10370000C043059340F0CC810B7B002B00F0C881B7 -:10371000BBF1020F03D00178B14240F0C48108F040 -:103720007F0106916AB3C8F3074A2B44069A93F8BF -:103730000390760646EA0B4646EA82465FEAD913CC -:1037400046EA0A06079300F0908000220023CDE9A4 -:103750000A23069B009367685B4652460AA92046E7 -:10376000B84700287ED0A7699FB9314604F10C0004 -:10377000FFF748FB0746E0B96FF0020013B0BDE861 -:10378000F08FC8F30F2A18F07F0F08BF0AF0030A62 -:10379000CBE73B699E420DD03F68002FF9D13146FF -:1037A00004F10C00FFF72EFB07460028E4D0A369C4 -:1037B0003B60A761DDE90A2300264FF6FF70C6F1E2 -:1037C000200E22FA06F103FA0EFEA6F1200C23FACF -:1037D0000CFC41EA0E0141EA0C01C9B2083609921B -:1037E0000893FFF7E3FA402EDDE90832E7D1B8820B -:1037F000FB7D09F01F06C3F384039B1BD7E902215D -:1038000098B2002BBCBF00F120031BB252EA0100AA -:10381000C8F304680FD00398821A049860EB010182 -:10382000A74890424FF000028A4104D3079A002A29 -:103830005BD0012B23DDFA7D4FEA890302F00302FE -:1038400003F07C031343FB7539462046FFF730FB3A -:10385000079BA3B9FB7DC3F38402013262F38603A5 -:10386000FB7504E06FF00B0088E7A76917B96FF0EC -:103870000C0083E73B699E42BAD03F68F6E719F037 -:10388000400F32D0039BBB60049BFB6014220021DD -:103890000DA8FEF7A9F9039B0A93049B0B932B1D1C -:1038A0000C932B7BADF83EA0013BDBB2ADF83C3076 -:1038B000069B8DF8433094F824308DF840B083F0A7 -:1038C00001038DF844308DF84160A3688DF8428083 -:1038D0000AA920469847FB7DC3F38403013303F014 -:1038E0001F039B02FB82002048E7FB7DC9F34012C7 -:1038F000B2EBD31F40F0DA80C3F38403B34240F04D -:10390000D88007992B7B4FEA9912002934D0D2072F -:1039100041D4032B40F2D080039BBB60049BFB602F -:103920002B7BAE1D033BDBB23246394604F10C0063 -:10393000FFF7D0FA00280DDA20463946FFF7B8FA2B -:10394000FB7DC3F38403013303F01F039B02FB825F -:10395000032013E7AB883B832A7B033AB88AD2B2B1 -:103960003146FFF735FAFB7DB882DA43C2F3C01265 -:1039700062F3C713FB75B6E76AB92E1D013BDBB2D4 -:103980003246394604F10C00FFF7A4FA0028D3DBD5 -:103990002A7B013AE2E7F98AC1F30901013B0529D3 -:1039A000DAB259D8281D002307F11A0C9A4208D917 -:1039B00010F801EB0CF801E0013101330629DBB20C -:1039C000F4D103990A9104990B91934207F11A01DA -:1039D0000C9138BF043379680D9134BF55FA83F3E5 -:1039E00000230E93FB8AADF83EA0C3F309031A44EB -:1039F000069B8DF8433094F82430ADF83C2083F0DA -:103A000001038DF8443000238DF840B08DF84160FB -:103A10008DF842807B602A7BB88A013A291DFFF726 -:103A2000D7F93B8BB882834203D1A3680AA9204609 -:103A3000984720460AA9FFF739FEFB7DB88AC3F3F1 -:103A40008403013303F01F039B02FB823B8B9842EC -:103A500014BF1120002091E67B68002BB1D0062016 -:103A600001E01C306346D3F800C0BCF1000FF8D170 -:103A7000091A081D05F1040C00EB030905989DF8CF -:103A8000143001EB000EBEF11B0F9AD89A4298D960 -:103A90001CF8013B09F8013B059B01330593EDE759 -:103AA0006FF009006AE66FF00A0067E66FF00D003C -:103AB00064E66FF00E0061E66FF00F005EE600BF97 -:103AC00080841E00EFF3098305494A6B22F001024E -:103AD0004A63683383F30988002383F311887047AE -:103AE00000EF00E0202080F3118862B60C4B0D4AF5 -:103AF000D96821F4E0610904090C0A43DA60D3F8BB -:103B0000FC20094942F08072C3F8FC200A6842F0A8 -:103B100001020A601022DA7783F82200704700BFA2 -:103B200000ED00E00003FA05001000E010B52023CE -:103B300083F311880E4B5B6813F4006314D0F1EE2D -:103B4000103AEFF30984683C4FF08073E361094B4E -:103B5000DB6B236684F3098800F094FB10B1064BFD -:103B6000A36110BD054BFBE783F31188F9E700BFA4 -:103B700000ED00E000EF00E04B0600084E060008F4 -:103B8000024AD36843F0C003D3607047004400404A -:103B9000044B5A6810439A6858600AB1181D1047C0 -:103BA000704700BFCC5700202DE9F0413C4ED6F8BD -:103BB0005C52EF682B68DA059CB20CD5202383F3A6 -:103BC00011884FF40070FFF7E3FF6FF480732B60F0 -:103BD000002383F31188202383F31188DFF8C0804A -:103BE00014F02F0339D183F31188380613D5210639 -:103BF00011D5202383F311882A4800F0EFF900281B -:103C00004CDA0820FFF7C4FF4FF67F733B40EB60B0 -:103C1000002383F311887A0615D5630613D5202374 -:103C200083F31188D6E913239A4209D1336C3BB14F -:103C300027F040073F0410203F0CFFF7A9FFEF607B -:103C4000002383F31188D6F86422D3680BB110697E -:103C50009847BDE8F041FFF769BF230712D014F081 -:103C6000080F0CBF00208020E10748BF40F0200073 -:103C7000A20748BF40F04000630748BF40F480708F -:103C8000FFF786FFA4066B6805D596F860124046DC -:103C9000194000F053FA2C68A4B2A1E76860B7E7B6 -:103CA000CC5700200458002010B5054C054A0021CF -:103CB000204600F013FA044BC4F85C3210BD00BF7C -:103CC000CC570020813B00080044004038B52A4C06 -:103CD000037C002918BF0C46012B0546C0F864423E -:103CE00010D1264B98420DD1254B1A6C42F400326C -:103CF0001A641A6E42F400321A660B2126201B6EDB -:103D000000F046F8D5F85C221E4923688A424FEA43 -:103D1000530003D001F580618A422AD11A49014437 -:103D2000B4F90400B1FBF3F30028BEBF23F0070091 -:103D300003F0070343EA4003A1889360E38843F05C -:103D400040031361238943F00103536141F4045399 -:103D500043F02C03D36001F4A05100231360B1F5AC -:103D6000806F136853680CBF7F23FF2385F8603290 -:103D700038BD0649D3E700BF80540008CC57002067 -:103D8000003802400010014080F0FA0240787D01C6 -:103D900000F1604303F561430901C9B283F80013E0 -:103DA000012200F01F039A4043099B0003F1604386 -:103DB00003F56143C3F880211A607047F8B51546D2 -:103DC00082680669AA420B46816938BF8568761AFF -:103DD000B54204460BD218462A46FDF7F3FEA36906 -:103DE0002B44A361A3685B1BA3602846F8BD0CD9D4 -:103DF00018463246FDF7E6FEAF1BE1683A4630440E -:103E0000FDF7E0FEE3683B44EBE718462A46FDF782 -:103E1000D9FEE368E5E7000083689342F7B51546ED -:103E2000044638BF8568D0E90460361AB5420BD223 -:103E30002A46FDF7C7FE63692B446361A3682846E1 -:103E40005B1BA36003B0F0BD0DD932460191FDF7B5 -:103E5000B9FE0199E068AF1B3A463144FDF7B2FE66 -:103E6000E3683B44E9E72A46FDF7ACFEE368E4E794 -:103E700010B50A440024C361029B8460C0E90000BD -:103E8000C0E90511C1600261036210BD08B5D0E947 -:103E90000532934201D1826882B982680132826020 -:103EA0005A1C42611970D0E904329A4224BFC36897 -:103EB0004361002100F0B6FA002008BD4FF0FF304A -:103EC000FBE7000070B5202304460E4683F31188FB -:103ED000A568A5B1A368A269013BA360531CA361B7 -:103EE00015782269934224BFE368A361E3690BB1AB -:103EF00020469847002383F31188284607E031467F -:103F0000204600F07FFA0028E2DA85F3118870BDC0 -:103F10002DE9F74F04460E4617469846D0F81C90F8 -:103F20004FF0200A8AF311884FF0000B154665B157 -:103F30002A4631462046FFF741FF034660B9414615 -:103F4000204600F05FFA0028F1D0002383F31188A7 -:103F5000781B03B0BDE8F08FB9F1000F03D00190DA -:103F60002046C847019B8BF31188ED1A1E448AF343 -:103F70001188DCE7C0E90511C160C3611144009BF1 -:103F80008260C0E90000016103627047F8B5044631 -:103F90000D461646202383F31188A768A7B1A368AE -:103FA000013BA36063695A1C62611D70D4E904324D -:103FB0009A4224BFE3686361E3690BB120469847E6 -:103FC000002080F3118807E03146204600F01AFAFD -:103FD0000028E2DA87F31188F8BD0000D0E9052354 -:103FE0009A4210B501D182687AB982680132826042 -:103FF0005A1C82611C7803699A4224BFC36883619A -:10400000002100F00FFA204610BD4FF0FF30FBE713 -:104010002DE9F74F04460E4617469846D0F81C90F7 -:104020004FF0200A8AF311884FF0000B154665B156 -:104030002A4631462046FFF7EFFE034660B9414667 -:10404000204600F0DFF90028F1D0002383F3118827 -:10405000781B03B0BDE8F08FB9F1000F03D00190D9 -:104060002046C847019B8BF31188ED1A1E448AF342 -:104070001188DCE7026843681143016003B1184707 -:10408000704700001430FFF743BF00004FF0FF33CC -:104090001430FFF73DBF00003830FFF7B9BF000014 -:1040A0004FF0FF333830FFF7B3BF00001430FFF795 -:1040B00009BF00004FF0FF311430FFF703BF0000CD -:1040C0003830FFF763BF00004FF0FF323830FFF7A2 -:1040D0005DBF000000207047FFF7E6BD37B515460D -:1040E0000E4A026000224260C0E902220122044618 -:1040F00002740B46009000F15C014FF480721430A2 -:10410000FFF7B6FE00942B464FF4807204F5AE71B3 -:1041100004F13800FFF72EFF03B030BD94540008BF -:1041200010B52023044683F31188FFF7CFFD022347 -:104130002374002383F3118810BD000038B5C369D0 -:1041400004460D461BB904210844FFF793FF294696 -:1041500004F11400FFF79AFE002806DA201D4FF440 -:104160008061BDE83840FFF785BF38BD024B0022B3 -:10417000C3E900339A607047345A00200023037467 -:104180008268054B1B6899689142FBD25A680360AC -:104190004260106058607047345A002008B52023F0 -:1041A00083F31188037C032B05D0042B0DD02BB98E -:1041B00083F3118808BD436900221A604FF0FF3372 -:1041C0004361FFF7DBFF0023F2E7D0E90032136021 -:1041D0005A60F3E7002303748268054B1B689968F3 -:1041E0009142FBD85A680360426010605860704783 -:1041F000345A0020054B19690874186802681A605F -:104200005360186101230374FCF70ABA345A002082 -:1042100030B54B1C0B4D87B0044610D02B690A4AB1 -:1042200001A800F019F92046FFF7E4FF049B13B141 -:1042300001A800F04DF92B69586907B030BDFFF7B0 -:10424000D9FFF8E7345A00209D41000838B50C4DDD -:1042500041612B6981689A689142044603D8BDE8A0 -:104260003840FFF78BBF1846FFF7B4FF01232C61DE -:10427000014623742046BDE83840FCF7D1B900BFA1 -:10428000345A0020044B1A681B6990689B68984256 -:1042900094BF002001207047345A002010B5084C0C -:1042A000236820691A6822605460012223611A740D -:1042B000FFF790FF01462069BDE81040FCF7B0B958 -:1042C000345A002008B5FFF7DDFF18B1BDE80840FB -:1042D000FFF7E4BF08BD0000FFF7E0BFFEE7000006 -:1042E00010B50C4CFFF742FF00F0A8F80A498022F5 -:1042F000204600F03DF8012344F8180C0374FFF742 -:10430000F1FB002383F3118862B60448BDE8104036 -:1043100000F04EB85C5A0020BC540008CC54000891 -:1043200008B572B6034B586200F092FA00F03AFBFF -:10433000FEE700BF345A002000F004B9EFF311800B -:1043400020B9EFF30583202282F311887047000023 -:1043500010B530B9EFF30584C4F3080414B180F349 -:10436000118810BDFFF7AEFF84F31188F9E7000054 -:1043700082600222028270478368A3F17C0243F8C4 -:104380000C2C026943F83C2C426943F8382C074A4C -:1043900043F81C2CC26843F8102C022203F8082CA6 -:1043A000002203F8072CA3F1180070473906000813 -:1043B00010B5202383F31188FFF7DEFF00210446A8 -:1043C000FFF744FF002383F31188204610BD00004F -:1043D000024B1B6958610F20FFF70CBF345A0020B5 -:1043E000202383F31188FFF7F3BF000008B50146CF -:1043F000202383F311880820FFF70AFF002383F3AB -:10440000118808BD49B1064B42681B6918605A60A3 -:10441000136043600420FFF7FBBE4FF0FF3070478E -:10442000345A00200368984206D01A68026050602F -:1044300059611846FFF7A2BE70470000054B03F113 -:104440001402C3E905224FF0FF310022C3E907122D -:10445000704700BF345A002070B51C4EC0E90323DA -:1044600005460C4600F020FB334653F8142F9A42C1 -:104470000DD13062C5E901242A600A2C2CBF001935 -:104480000A30C6E90555BDE8704000F0FBBA316A54 -:10449000431AE31838BF1C469368A34202D908198F -:1044A00000F0FEFA73699A6894420CD85A68AC60BE -:1044B0002B606A6015609A685D60121B9A604FF00D -:1044C000FF33F36170BD1B68A41AECE7345A002077 -:1044D00038B51B4C636998420DD0D0E900321360A7 -:1044E0005A6000228168C2609A680A449A604FF05C -:1044F000FF33E36138BD2246036842F8143F0021D0 -:1045000093425A60C16003D1BDE8384000F0C2BA9E -:104510009A688168256A0A449A6000F0C5FA63695E -:104520009A68411B8A42E5D9AB181D1A092D206AE9 -:1045300098BF01F10A02BDE83840104400F0B0BA5B -:10454000345A00202DE9F041184C002704F11406DC -:10455000656900F0A9FA236AAA68C11A8A4215D8C7 -:1045600013442362D5E9003213605A606369D5F8B9 -:104570000C80EF60B34201D100F08CFA87F3118810 -:104580002869C047202383F31188E1E76169B142BC -:1045900009D013441B1ABDE8F0410A2B2CBFC018E8 -:1045A0000A3000F07DBABDE8F08100BF345A002027 -:1045B0000C2303604FF0FF3070470000002070476D -:1045C000FEE70000704700004FF0FF30704700002A -:1045D000BFF34F8F024AD368DB03FCD4704700BFA0 -:1045E000003C024008B5094B1B7873B9FFF7F0FF98 -:1045F000074B1A69002ABFBF064A5A6002F1883287 -:104600005A601A6822F480621A6008BDF05B0020CC -:10461000003C02402301674508B50B4B1B7893B95A -:10462000FFF7D6FF094B1A6942F000421A611A6877 -:1046300042F480521A601A6822F480521A601A6892 -:1046400042F480621A6008BDF05B0020003C02402A -:104650000728F0B516D80C4C0C4923787BB90C4DC3 -:104660000E4608234FF0006255F8047B46F8042BF1 -:10467000013B13F0FF033A44F6D10123237051F8B4 -:104680002000F0BD0020FCE7145C0020F45B00205B -:10469000E4540008014B53F820007047E45400082C -:1046A00008207047072810B5044601D9002010BD26 -:1046B000FFF7CEFF064B53F824301844C21A0BB94B -:1046C0000120F4E712680132F0D1043BF6E700BFA5 -:1046D000E4540008072838B5044628D8FFF72EFE12 -:1046E000FFF776FFFFF77EFF124AF323D360E30064 -:1046F000DBB243F4007343F002031361136943F424 -:104700008033136105462046FFF762FFFFF7A0FFE5 -:10471000094B53F8241000F041F92846FFF77CFFBD -:10472000FFF716FE2046BDE83840FFF7BBBF00206C -:1047300038BD00BF003C0240E454000812F0010301 -:104740002DE9F04105460E4614464BD18118334AF7 -:10475000914261D8324B1B6813F001035CD0314F9A -:10476000FFF7ECFDFFF73EFFF323FB60FFF730FFA1 -:10477000314640F20128032C18D824F00104294EB8 -:104780000C446D1A40F20118A142336905EB010790 -:104790002AD123F001033361FFF73EFFFFF7D8FD75 -:1047A0000120BDE8F081043C0435E4E7AB07E4D127 -:1047B0003B6923F440733B613B6943EA08033B6177 -:1047C00051F8046B2E60BFF34F8FFFF701FF2B688A -:1047D0009E42E8D03B6923F001033B61FFF71CFFD9 -:1047E000FFF7B6FD0020DCE723F440733361336943 -:1047F00043EA080333610B883B80BFF34F8FFFF719 -:10480000E7FE3F8831F8023BBFB2BB42BCD0336900 -:1048100023F001033361E1E71846C2E7000008080E -:1048200000380240003C0240084908B50B7828B126 -:104830001BB9FFF7D7FE01230B7008BD002BFCD07E -:10484000BDE808400870FFF7E7BE00BFF05B00203E -:104850004FF480214FF0005000F0A2B870B582B044 -:10486000FFF76CFD0E4E054600F01EF932689042CF -:1048700037BF0C4A0B49516814682EBFD1E900417B -:10488000013151600419034641F1000128460191AC -:104890003360FFF75DFD0199204602B070BD00BF97 -:1048A000185C0020205C002070B582B0FFF746FD48 -:1048B000104E054600F0F8F83268904237BF0E4AB5 -:1048C0000D49516814682EBFD1E900410131516092 -:1048D000041941F100010346284601913360FFF7B6 -:1048E00037FD01994FF47A7200232046FBF780FCD4 -:1048F00002B070BD185C0020205C002010B502449E -:10490000064BD2B2904200D110BD441C00B253F805 -:10491000200041F8040BE0B2F4E700BF502800404B -:104920000F4B30B51C6F240407D41C6F44F4007483 -:104930001C671C6F44F400441C670A4C236843F452 -:10494000807323600244084BD2B2904200D130BD44 -:10495000441C00B251F8045B43F82050E0B2F4E785 -:1049600000380240007000405028004007B5012286 -:1049700001A90020FFF7C2FF019803B05DF804FB16 -:1049800013B50446FFF7F2FFA04205D0012201A9AA -:1049900000200194FFF7C4FF02B010BD7047000073 -:1049A0007047000070470000074B45F255521A60EF -:1049B00002225A6040F6FF729A604CF6CC421A60AE -:1049C000024B01221A707047003000402C5C00201E -:1049D000034B1B781BB1034B4AF6AA221A6070479F -:1049E0002C5C002000300040034B1A681AB9034ABF -:1049F000D2F874281A607047285C0020003002400A -:104A0000024B4FF08072C3F87428704700300240A8 -:104A100008B5FFF7E9FF024B1868C0F3407008BD06 -:104A2000285C002008B5FFF7DFFF024B1868C0F3D1 -:104A3000007008BD285C002070470000FEE7000001 -:104A40000A4B0B480B4A90420BD30B4BDA1C121A41 -:104A5000C11E22F003028B4238BF00220021FDF765 -:104A6000C3B853F8041B40F8041BECE77456000865 -:104A7000C45C0020C45C0020C45C002070470000BF -:104A800000F080B84FF08043002258631A61022280 -:104A9000DA6070474FF080430022DA607047000010 -:104AA0004FF08043586370474FF08043586A704717 -:104AB0004B6843608B688360CB68C3600B6943615C -:104AC0004B6903628B6943620B68036070470000A7 -:104AD00008B5234B23481A6942F0FF021A611A698C -:104AE00022F0FF021A611A691A6B42F0FF021A6380 -:104AF0001A6D42F0FF021A651B4A1B6D1146FFF743 -:104B0000D7FF02F11C0100F58060FFF7D1FF02F131 -:104B1000380100F58060FFF7CBFF02F1540100F58A -:104B20008060FFF7C5FF02F1700100F58060FFF7BC -:104B3000BFFF02F18C0100F58060FFF7B9FF02F1C1 -:104B4000A80100F58060FFF7B3FF02F1C40100F592 -:104B50008060FFF7ADFFBDE8084000F097B800BFE8 -:104B600000380240000002400455000808B500F07B -:104B700017FAFFF7B5FBBDE80840FFF735BF0000A7 -:104B800070470000104B1A6C42F001021A641A6E52 -:104B900042F001021A660D4A1B6E936843F001034E -:104BA00093604FF0804331229A624FF0FF32DA6215 -:104BB00000229A615A63DA605A6001225A61082120 -:104BC0001A601C20FFF7E4B800380240002004E01F -:104BD0004FF0804208B51169D3680B40D9B2C94380 -:104BE0009B07116107D5202383F31188FFF7A4FBEE -:104BF000002383F3118808BD08B5FFF7E9FFBDE87E -:104C00000840FEF793BF00001E4B1A6962F0FF02D6 -:104C10001A611A69D2B21A614FF0FF301A695A69E3 -:104C2000586100215A6959615A691A6A62F08052C2 -:104C30001A621A6A02F080521A621A6A5A6A586232 -:104C40005A6A59625A6A1A6C42F080521A641A6E91 -:104C500042F080521A661A6E0B4A106840F4807057 -:104C60001060186F00F44070B0F5007F1EBF4FF465 -:104C7000803018671967536823F40073536000F09D -:104C80006FB900BF00380240007000403B4B3C4A07 -:104C90001A643C4A4FF4404111601A6842F0010224 -:104CA0001A601A689007FCD59A6822F003029A608D -:104CB000324B9A6812F00C02FBD1196801F0F9012D -:104CC00019609A601A6842F480321A601A68910377 -:104CD000FCD55A6F42F001025A67284B5A6F92076F -:104CE000FCD5294A5A601A6842F080721A60254A37 -:104CF00053685804FCD5214B1A689101FCD5234A0E -:104D0000C3F884201A6842F080621A601A6812019F -:104D1000FCD51F4A9A600322C3F88C204FF0006232 -:104D2000C3F894201B4B1A681B4B9A421B4B21D192 -:104D30001B4A11681B4A91421CD140F203121A60AF -:104D4000164A136803F00F03032BFAD10B4B9A6832 -:104D500042F002029A609A6802F00C02082AFAD124 -:104D60005A6C42F480425A645A6E42F480425A6647 -:104D70005B6E704740F20372E1E700BF003802400B -:104D80000004001000700040081940021030002498 -:104D900000948838002004E011640020003C0240A8 -:104DA00000ED00E041C20F41084A08B5516913689F -:104DB0000B4003F00103536123B1054A13680BB1A3 -:104DC00050689847BDE80840FEF7B0BE003C01407F -:104DD000305C0020084A08B5516913680B4003F0A5 -:104DE0000203536123B1054A93680BB1D068984719 -:104DF000BDE80840FEF79ABE003C0140305C002050 -:104E0000084A08B5516913680B4003F00403536165 -:104E100023B1054A13690BB150699847BDE80840B2 -:104E2000FEF784BE003C0140305C0020084A08B513 -:104E3000516913680B4003F00803536123B1054A1D -:104E400093690BB1D0699847BDE80840FEF76EBE84 -:104E5000003C0140305C0020084A08B551691368E5 -:104E60000B4003F01003536123B1054A136A0BB1E1 -:104E7000506A9847BDE80840FEF758BE003C014024 -:104E8000305C0020174B10B55A691C68144004F4BC -:104E900078725A61A30604D5134A936A0BB1D06A9B -:104EA0009847600604D5104A136B0BB1506B9847B6 -:104EB000210604D50C4A936B0BB1D06B9847E205E1 -:104EC00004D5094A136C0BB1506C9847A30504D55F -:104ED000054A936C0BB1D06C9847BDE81040FEF7C3 -:104EE00025BE00BF003C0140305C00201A4B10B5CD -:104EF0005A691C68144004F47C425A61620504D566 -:104F0000164A136D0BB1506D9847230504D5134A0B -:104F1000936D0BB1D06D9847E00404D50F4A136E22 -:104F20000BB1506E9847A10404D50C4A936E0BB197 -:104F3000D06E9847620404D5084A136F0BB1506FC6 -:104F40009847230404D5054A936F0BB1D06F984757 -:104F5000BDE81040FEF7EABD003C0140305C002097 -:104F6000062108B50846FEF713FF06210720FEF7C5 -:104F70000FFF06210820FEF70BFF06210920FEF790 -:104F800007FF06210A20FEF703FF06211720FEF780 -:104F9000FFFEBDE8084006212820FEF7F9BE00000C -:104FA00008B5FFF731FE00F009F8FFF795F8FFF7B5 -:104FB000E7FDBDE80840FFF763BD00000023054A98 -:104FC00019460133102BC2E9001102F10802F8D191 -:104FD000704700BF305C00200B460146184600F0C9 -:104FE00025B8000000F038B8012838BF012010B5FE -:104FF0000446204600F028F830B900F007F808B958 -:1050000000F00CF88047F4E710BD0000024B186870 -:10501000BFF35B8F704700BFB05C002008B506206F -:1050200000F032F90120FFF7CBFA000010B5054C73 -:1050300013462CB10A4601460220AFF3008010BD92 -:105040002046FCE700000000024B0146186800F013 -:1050500089B800BF20230020024B0146186800F0E9 -:1050600035B800BF2023002010B50139024490421A -:1050700001D1002005E0037811F8014FA34201D0CF -:10508000181B10BD0130F2E72DE9F041A3B1C91A98 -:1050900017780144044603F1FF3C8C42204601D9B5 -:1050A000002009E00578BD4204F10104F5D10CEBC4 -:1050B0000405D618A54201D1BDE8F08115F8018D8F -:1050C00016F801EDF045F5D0E7E7000037B5002907 -:1050D00044D051F8043C0190002BA1F10404B8BF66 -:1050E000E41800F0F5F81E4A0198136833B96360BC -:1050F000146003B0BDE8304000F0F0B8A34208D916 -:10510000256861198B4201BF19685B6849192160E4 -:10511000EDE71A465B680BB1A342FAD9116855183E -:10512000A5420BD1246821445418A3421160E0D158 -:105130001C685B68536021441160DAE702D90C23D4 -:105140000360D6E7256861198B4204BF19685B6864 -:10515000636004BF491921605460CAE703B030BDE1 -:10516000B45C0020F8B5CD1C25F0030508350C2DE6 -:1051700038BF0C25002D064601DBA94203D90C23BC -:1051800033600020F8BD00F0A3F821490A681446F6 -:105190009CB9204F3B6823B92146304600F03CF8CB -:1051A00038602946304600F037F8431C23D10C23E1 -:1051B0003360304600F092F8E3E723685B1B17D4B6 -:1051C0000B2B03D923601C44256004E06368A242D2 -:1051D0000CBF0B605360304600F080F804F10B0008 -:1051E000231D20F00700C21ACCD01B1AA350C9E718 -:1051F00022466468CCE7C41C24F00304A042E3D038 -:10520000211A304600F008F80130DDD1CFE700BFA9 -:10521000B45C0020B85C002038B5064D002304467D -:1052200008462B60FFF7C4F9431C02D12B6803B179 -:10523000236038BDBC5C00201F2938B504460D46EC -:1052400004D9162303604FF0FF3038BD426C12B111 -:1052500052F821304BB9204600F030F82A4601467A -:105260002046BDE8384000F017B8012B0AD0591C81 -:1052700003D1162303600120E7E7002442F825400C -:10528000284698470020E0E7024B01461868FFF7E0 -:10529000D3BF00BF2023002038B5074D00230446AC -:1052A000084611462B60FFF78FF9431C02D12B688B -:1052B00003B1236038BD00BFBC5C0020FFF77EB99E -:1052C000034611F8012B03F8012B002AF9D170478E -:1052D000014800F009B800BFC05C0020014800F0A0 -:1052E00005B800BFC05C0020704700007047000098 -:1052F0006F72672E6172647570696C6F742E486F7F -:105300006C7962726F475053000000004E6F20614D -:105310007070207369670A00426164206677206CB0 -:10532000656E6774682025750A0042616420626FAB -:105330006172645F69642025752073686F756C64A1 -:105340002062652025750A0042616420667720642A -:10535000657363726970746F72206C656E677468D0 -:105360002025750A00426164206170702043524319 -:10537000203078253038783A307825303878203029 -:1053800078253038783A3078253038780A00476FF9 -:105390006F64206669726D776172650A0040A2E4ED -:1053A000F16468910600000053544D3332463F3F8C -:1053B0003F00000053544D3332463430780053548C -:1053C0004D3332463432780053544D333246343400 -:1053D0003658580000000000A85300083F000000A5 -:1053E00013040000B45300083F000000190400003B -:1053F000BE5300083F00000021040000C85300080D -:105400003F0000004261642043414E49666163658C -:1054100020696E6465782E00000100000001FF0025 -:105420000064004000680040800000000080000030 -:10543000000080000000000000000000ED1C0008DB -:105440007D25000889240008FD1C0008351D000882 -:10545000311F0008011D0008151D0008051D00086A -:10546000091D0008111D00080D1D0008591E000827 -:10547000191D00081D280008291D00082D1E000800 -:105480000096000000000000000000000000000086 -:105490000000000000000000A14000088D4000084E -:1054A000C9400008B5400008C1400008AD400008F0 -:1054B0009940000885400008D54000086D61696E7C -:1054C0000000000069646C6500000000C45400081E -:1054D000785A0020F05B002001000000DD42000847 -:1054E00000000000004000000040000000400000FC -:1054F0000040000000000100000002000000020067 -:1055000000000200A001812A00000000AAA9AAAAA6 -:1055100050000124EFFF0000007700000090090018 -:105520001000004A000000009AAAAAAA0000000089 -:10553000FBFF0000000000000000990000000000D8 -:1055400000000000AAAAAAAA00000000FFFF0000B5 -:10555000000000000000000000000000000000004B -:10556000AAAAAAAA00000000FFFF00000000000095 -:10557000000000000000000000000000AAAAAAAA83 -:1055800000000000FFFF000000000000000000001D -:105590000000000000000000AAAAAAAA0000000063 -:1055A000FFFF0000000000000000000000000000FD -:1055B00000000000AAAAAAAA00000000FFFF000045 -:1055C00000000000000000000000000000000000DB -:1055D0000A000000000000000300000000000000BE -:1055E000000000003CACFF7F010000000000000054 -:1055F0000B04000000000000000007000000000095 -:1056000040420F00FE2A0100D2040000FF0000000B -:105610002423002000000000000000000000000023 -:10562000000000000000000000000000000000007A -:10563000000000000000000000000000000000006A -:10564000000000000000000000000000000000005A -:10565000000000000000000000000000000000004A -:10566000000000000000000000000000000000003A -:045670000000000036 +:10075000013B63600D4D2B7833B963687BB9022090 +:1007600001F0DAF9322363602B78032B07D1636839 +:100770002BB9022001F0D0F94FF47A73636038BDD1 +:100780008823002019070008A8240020A0230020A7 +:10079000084B187003280CD8DFE800F008050208A1 +:1007A000022001F0AFB9022001F0A2B9024B0022F1 +:1007B0005A607047A0230020A824002010B501F043 +:1007C00069FC30B1204B03221A70204B00225A6082 +:1007D00010BD1F4B1F4A1C4619680131F8D0043365 +:1007E0009342F9D162681C4B9A42F1D91B4B9B682A +:1007F00003F1006303F580339A42E9D204F05AFB17 +:1008000004F06CFB002001F0DBF80220FFF7C0FFD2 +:10081000134B1A6C00221A64196E1A66196E596C01 +:100820005A64596E5A665B6E72B64FF0E0233021FF +:10083000C3F8084DD4E9003281F311889D4683F353 +:1008400008881047C4E700BFA0230020A824002088 +:100850000000010820000108FFFF0008002300201D +:10086000003802402DE9F04F93B0AC4B00902022AD +:10087000FF210AA89D6801F06BF9A94A1378A3B972 +:10088000A848012103601170302383F311880368A5 +:100890000BB104F087F8A44AA24800234FF47A7100 +:1008A00004F076F8002383F31188009B13B19F4B6B +:1008B000009A1A609E4A009C1378032B1EBF0023E7 +:1008C00013709A4A4FF0000A18BF5360D346564639 +:1008D000D146012001F016F924B1944B1B68002B7E +:1008E00000F01582002001F01DF80390039B002BFF +:1008F00001DA00F0A7FE039B002BEDDB012001F0E5 +:10090000F7F8039B213B162BE3D801A252F823F002 +:100910006D09000895090008290A0008D308000895 +:10092000D3080008D3080008B30A0008830C0008A5 +:100930009D0B0008FF0B0008270C00084D0C000859 +:10094000D30800085F0C0008D3080008D10C000889 +:100950000D0A0008D3080008150D000879090008E1 +:100960000D0A0008D3080008FF0B00080220FFF75B +:10097000BFFE002840F0F581009B0221BAF1000F74 +:1009800008BF1C4605A841F21233ADF8143000F040 +:10099000E7FF9EE74FF47A7000F0C4FF071EEBDB21 +:1009A0000220FFF7A5FE0028E6D0013F052F00F248 +:1009B000DA81DFE807F0030A0D10133605230593EB +:1009C000042105A800F0CCFF17E054480421F9E702 +:1009D00058480421F6E758480421F3E74FF01C0873 +:1009E000404600F0EFFF08F104080590042105A837 +:1009F00000F0B6FFB8F12C0FF2D1012000FA07F792 +:100A000047EA0B0B5FFA8BFB4FF0000901F0ECF8A3 +:100A100026B10BF00B030B2B08BF0024FFF770FE71 +:100A200057E746480421CDE7002EA5D00BF00B0375 +:100A30000B2BA1D10220FFF75BFE074600289BD0BD +:100A4000012000F0BDFF0220FFF7A2FE00261FFAE2 +:100A500086F8404600F0C4FF044690B100214046AD +:100A600000F0D6FF01360028F1D1BA46044641F223 +:100A70001213022105A8ADF814303E4600F070FFB5 +:100A800027E70120FFF784FE2546244B9B68AB42F5 +:100A900007D9284600F096FF013040F06781043501 +:100AA000F3E7234B00251D70204BBA465D603E46A0 +:100AB000ACE7002E3FF460AF0BF00B030B2B7FF481 +:100AC0005BAF0220FFF764FE322000F02BFFB0F195 +:100AD0000008FFF651AF18F003077FF44DAF0F4A3F +:100AE000926808EB050393423FF646AFB8F5807F66 +:100AF0003FF742AF124B0193B84523DD4FF47A70B4 +:100B000000F010FF0390039A002AFFF635AF019B17 +:100B1000039A03F8012B0137EDE700BF0023002003 +:100B2000A42400208823002019070008A8240020FE +:100B3000A023002004230020082300200C230020F1 +:100B4000A4230020C820FFF7D3FD074600283FF468 +:100B500013AF1F2D11D8C5F1200242450AAB25F075 +:100B6000030028BF424683490192184400F0DEFF8B +:100B7000019A8048FF2100F0EBFF4FEAA8037D496E +:100B80000193C8F38702284600F0EAFF06460028D2 +:100B90003FF46DAF019B05EB830537E70220FFF7BC +:100BA000A7FD00283FF4E8AE00F052FF00283FF414 +:100BB000E3AE0027B846704B9B68BB4218D91F2F85 +:100BC00011D80A9B01330ED027F0030312AA134455 +:100BD00053F8203C05934046042205A901F012FA7F +:100BE00004378046E7E7384600F0ECFE0590F2E770 +:100BF000CDF81480042105A800F0B2FE06E700231A +:100C0000642104A8049300F0A1FE00287FF4B4AE90 +:100C10000220FFF76DFD00283FF4AEAE049800F00F +:100C2000FFFE0590E6E70023642104A8049300F08A +:100C30008DFE00287FF4A0AE0220FFF759FD0028AA +:100C40003FF49AAE049800F0FBFEEAE70220FFF7BB +:100C50004FFD00283FF490AE00F00AFFE1E70220CC +:100C6000FFF746FD00283FF487AE05A9142000F0E9 +:100C700005FF04210746049004A800F071FE3946E0 +:100C8000B9E7322000F04EFE071EFFF675AEBB0737 +:100C90007FF472AE384A926807EB090393423FF63D +:100CA0006BAE0220FFF724FD00283FF465AE27F06D +:100CB00003074F44B9453FF4A9AE484600F082FE11 +:100CC0000421059005A800F04BFE09F10409F1E7A5 +:100CD0004FF47A70FFF70CFD00283FF44DAE00F0A2 +:100CE000B7FE002844D00A9B01330BD008220AA982 +:100CF000002000F035FF00283AD02022FF210AA86A +:100D000000F026FFFFF7FCFC1C4803F093FD13B036 +:100D1000BDE8F08F002E3FF42FAE0BF00B030B2B32 +:100D20007FF42AAE0023642105A8059300F00EFE8F +:100D3000074600287FF420AE0220FFF7D9FC80464A +:100D400000283FF419AEFFF7DBFC41F2883003F0D6 +:100D500071FD059800F05EFF464600F045FF3C46F9 +:100D6000B7E5064652E64FF0000905E6BA467EE6CC +:100D700037467CE6A423002000230020A086010043 +:100D8000094A136849F2690099B21B0C00FB013350 +:100D90001360064B186844F2506182B2000C01FBEC +:100DA0000200186080B2704718230020142300202E +:100DB00010B500211022044600F0CAFE034B03CBFD +:100DC000206061601868A06010BD00BF107AFF1F2E +:100DD0002DE9F041ADF54E7D0DF134086CAC40F2DB +:100DE000751207460D460EA80021C8F8001000F045 +:100DF000AFFE4FF4C4720021204600F0A9FE02F0BD +:100E0000CFF8254B4FF47A72B0FBF2F0186093E8FC +:100E10000700022384E807000DF5E9702382FFF73D +:100E2000C7FF40F604331D49238406A804F06AFC7A +:100E3000182384F832310DF2E3266B440DF1300CA7 +:100E40001A4603CA624530607160134606F108060F +:100E5000F6D141460122204600F0F6FE002303931E +:100E6000AB7E029305F11903019380B20123CDE912 +:100E700004800093E97E06A3D3E90023384602F0FC +:100E800057FC0DF54E7DBDE8F08100BFAFF300804B +:100E90009E6AC421818A46EEB024002014570008BF +:100EA0002DE9F0412C4C237ADAB080460D465BBB2D +:100EB00027A9284600F0D8FF0746002842D19DF810 +:100EC0009D60C82E3ED801464FF4A662204600F031 +:100ED0003FFE4FF48073C4F8F8314FF40073C4F848 +:100EE0000C334FF44073C4F8203432460DF19E01A8 +:100EF00004F1090000F01AFE26449DF89C30777238 +:100F000023720BB9EB7E23728122002106AC27A845 +:100F100000F01EFE0122214627A800F0E1FF002379 +:100F20000393AB7E029305F1190380B2019328234A +:100F3000CDE904400093E97E05A3D3E900234046B0 +:100F400002F0F6FB5AB0BDE8F08100BFAFF30080BD +:100F500026417272DF25D7B798560020F0B5254E8E +:100F60004FF48A7505FB0065F1B096F8D83085F826 +:100F7000DC300024D822214685F8E8403AA800F069 +:100F8000E7FD06F1090000F0DBFDD5F8E4308DF84F +:100F9000F000C2B206AF06F109010DF1F100CDE992 +:100FA0003A3400F0C3FD394601223AA800F0C4FFEC +:100FB00080B2CDE9047008230127CDE9023706F19C +:100FC000D803019330230093317A0B4807A3D3E968 +:100FD000002302F0ADFBA04206DD01F0E1FFC5F801 +:100FE000E000384671B0F0BD2046FBE778F6339F4D +:100FF00093CACD8D98560020C83400202DE9F04FBB +:10100000274FDFF8A880274E87B0384602F0BCFB98 +:10101000034600283DD00024CDE90344ADF8144038 +:10102000027B8DF8142099684068029403AA03C2D9 +:101030001B681D4D43F000430293A146A2462B6856 +:10104000D3F810B001F0AEFF10EB080241F100033D +:101050002846CDF800A002A9D84704F2344440F64F +:1010600068030028C8BF49F0010905F586559C4270 +:1010700005F11005E3D1B9F1000F05D0384602F0B3 +:1010800087FB86F800A0C0E73378072B04D801332C +:10109000337007B0BDE8F08F014802F079FBF8E744 +:1010A000C8340020CD5B0020F834002040420F00FF +:1010B00070B50D4614461E4602F096FA50B9022E3F +:1010C00010D1012C0ED112A3D3E90023C5E90023CE +:1010D000012007E0282C10D005D8012C09D0052CC0 +:1010E0000FD0002070BD302CFBD10BA3D3E900231F +:1010F000ECE70BA3D3E90023E8E70BA3D3E9002334 +:10110000E4E70BA3D3E90023E0E700BFAFF30080DF +:10111000401DA12026812A0B78F6339F93CACD8DDE +:101120009E6AC421818A46EE26417272DF25D7B7B6 +:10113000F017304A39059E5638B505460E4C002149 +:10114000013500F065FCA4F82C55B4F82C0500F02E +:1011500047FC78B1B4F82C0500F052FC014648B9C0 +:10116000B4F82C0500F054FCB4F82C350133A4F885 +:101170002C35EAE738BD00BF98560020F8B50E4C74 +:101180000E4F0226A4F5805343F8487C237E3BB9DA +:1011900065692DB1284600F0FBFF284604F0F2F9FE +:1011A000204600F0F5FFA4F58654012EA4F11004AA +:1011B00000D1F8BD0126E5E710560020DC570008F5 +:1011C0002DE9F04F8FB000AF05460C4602F00CFA47 +:1011D000002849D1237E022B1BD1E38A012B18D191 +:1011E00001F0DEFE0646FFF7CBFD03464FF4C87064 +:1011F000DFF8C482B3FBF0F206F5167602FB10337B +:1012000016FA83F3C8F80030E37E33B9A34B00220B +:101210001A703C37BD46BDE8F08F07F12401204627 +:1012200000F0E0FD0028F4D107F11400FFF7C0FD45 +:1012300097F8264007F11401224607F1270004F031 +:10124000EBF90028E2D10F2C08D8944B1C70D8F889 +:101250000030A3F51673C8F80030DAE797F82410C9 +:10126000284602F0B9F9D4E7E38A282B2BD010D80E +:10127000012B23D0052BCCD1BFF34F8F8849894B4D +:10128000CA6802F4E0621343CB60BFF34F8F00BF24 +:10129000FDE7302BBDD1844EE17E327A9142B8D148 +:1012A000607E3146002291F8DC50854200F0A58036 +:1012B0000132042A01F58A71F5D1AAE721462846B0 +:1012C000FFF786FDA5E721462846FFF7E9FDA0E7E1 +:1012D000B2F8EC507B6005F103094FEA99094FEA37 +:1012E0008902D11DC908A8EBC1039D46EB46002128 +:1012F000584600F02DFC04F1EE012A4631445846D0 +:1013000000F014FC7B6813B9012000F059FB96F83B +:10131000D20000F065FB044630B9307200F098FB53 +:10132000204600F04DFBB1E0D6F8D4203AB996F84B +:10133000D200B6F82C25824201D8FFF7FDFED6F880 +:10134000D4202A44944208D296F8D200B6F82C252C +:101350000130824201D8FFF7EFFE70685FFA89F230 +:10136000594600F0FDFB08B9C54679E0726896F869 +:10137000D2002A447260D6F8D42005EB0209C6F8E0 +:10138000D49000F02DFB814509D396F8D220D6F8F1 +:10139000D4000132001B86F8D220C6F8D400FF2DFD +:1013A0000FD80024347200F053FB204600F008FBF5 +:1013B00000F070FE3D4B188108B9FFF7FFF9C546F4 +:1013C00027E7BB6896F8D9000AFB0362FB68D2F8EE +:1013D000E41082F8E83001F58061C2F8E030C2F82C +:1013E000E410FFF7BBFDFFF709FE96F8D9200132A4 +:1013F00002F0030286F8D920B6E74FF48A7A0AFB96 +:1014000002F505F1EA013144204600F0C1FDF86023 +:1014100000287FF4FEAE3544012285F8E82001F073 +:10142000BFFDD5F8E020D6ED007ADFED216A801A05 +:10143000192838BF192040F6B832904228BF10460C +:10144000B8EE677A07EE900AF8EEE77A67EEA67ACA +:10145000DFED186AE7EE267AFCEEE77AC6ED007A51 +:1014600096F8D930BB60BA6873680AFB02F4321987 +:1014700092F8E81059B1D2F8E4108B42E8463FF4F4 +:1014800027AF002182F8E810C2F8E010C546736863 +:10149000064A9B0A01331381BBE600BFC13400201A +:1014A00000ED00E00400FA0598560020B02400206A +:1014B000CDCCCC3D6666663FC4340020014B18702D +:1014C000704700BFBC24002030B54FF000542B4BB8 +:1014D00022689A4285B007D003F02AFD044620BB5B +:1014E0000024204605B030BD254B627D25481A708A +:1014F000237D03724FF48073C0F8F8314FF400730A +:10150000C0F80C3300254FF44073C0F820341E4956 +:10151000C0F8E450C922093000F008FB2046E02260 +:10152000294600F015FB0124DBE7184A184D136C1F +:1015300043F000731364AA6D164B9A42D0D12B6E00 +:10154000013B7E2BCCD8144A07CA01AB83E80700C5 +:101550001846032100F06CFD6B6D83424FF00003D1 +:10156000BED12A6D8A4201BFAB65054B2A6E1A7047 +:1015700003BF0A4BEA6D1A601C46B2E79AAD44C538 +:10158000BC2400209856002016000020003802409D +:10159000006600405041A0B0586600401023002073 +:1015A00037B500F077FD1D4D1D4C288102232168C1 +:1015B0001C486B71012201F077FB1B48216850F831 +:1015C000D03F01225B68984700230193174B1849CD +:1015D00000931848184B4FF4805201F0D5FF174B79 +:1015E000197811B1134801F0F7FF01F0D9FC044656 +:1015F000FFF7C6FB4FF4C873B0FBF3F202FB130313 +:1016000004F5167010FA83F00D4B186003F086FC99 +:1016100008B10F232B8103B030BD00BFB0240020E0 +:1016200010230020F8340020F8440020B1100008F6 +:10163000C0240020C8340020C1110008BC240020B0 +:10164000C43400202DE9F04F2DED028BDFF85082DD +:1016500093B00BAF9FED838BFFF7D0FC00230A9371 +:10166000ADF834300B937B600025844CDFF810A27A +:101670002E4601238DF81C3023688DED008B4FF032 +:10168000000BD3F808908DF81DB05B460DF11D02DC +:1016900007A92046C8479DF81C90B9F1000F24D037 +:1016A000D8F8143083F40043C8F814301022594697 +:1016B0000EA800F04DFA236808AA5E690AA90DF188 +:1016C0001E032046B04797E803000FAB83E80300F2 +:1016D0009DF834308DF844300A9B0E930EA9DDE955 +:1016E0000823504602F032FA4E4605F2344540F6E1 +:1016F000680304F586549D4204F11004B9D1002E0C +:10170000B2D15F4801F070FF002840D15D4D01F07B +:1017100047FC2B6898423AD301F042FC0446FFF79D +:101720002FFB4FF4C873B0FBF3F202FB130304F575 +:10173000167010FA83F02860534D8DF828602E78CB +:1017400016B901238DF82830C6F11004E4B20EA8B2 +:10175000FFF72EFB062C28BF06240EAB2246991954 +:101760000DF1290000F0E2F90AAB0393182302936C +:101770000134464B0193E4B20123009340480494A2 +:101780003AA3D3E9002301F075FF00232B7001F089 +:1017900007FC3F4A3F4C1368C31AB3F57A7F2FD337 +:1017A000106001F0FFFB02460B46354801F0FAFFDE +:1017B000334801F019FF18B3237A374D002B14BFBB +:1017C000032302236B7101F0EBFB0EAE4FF47A732F +:1017D0000122B0FBF3F031462860284600F0DAFA27 +:1017E000182302932D4B019380B240F25513CDE99B +:1017F0000360009322481FA3D3E9002301F03AFFBE +:10180000237A93B101F0CCFB002506464FF48A778A +:1018100094F8D900284400F0030007FB004393F834 +:10182000E82072B10135042DF2D1C82003F002F88E +:10183000237A002B7FF40DAF13B0BDEC028BBDE813 +:10184000F08FD3F8E02042B12368FA2B38BFFA2397 +:10185000B21A0533B2EB430FE4D3FFF77FFB002846 +:10186000E0D1E2E70000000000000000401DA120E0 +:1018700026812A0BF1C6A7C1D068080FF8340020D2 +:10188000C8340020C4340020C1340020C0340020FB +:10189000C85B002098560020B0240020CC5B0020BC +:1018A0000004024008B5064800F074FF054800F047 +:1018B00071FFBDE80840044A0449002003F05CBE03 +:1018C000F8340020C8450020205C00207D1100086D +:1018D0007047000070B5104B1B780133DBB2012B51 +:1018E0000C4612D80D4B1D6829684FF47A730E6AA6 +:1018F000A2FB0332014622462846B047844204D167 +:10190000074B00221A70012070BD4FF4FA7002F0EC +:1019100091FF0020F8E700BF1C23002020230020B7 +:10192000105C002007B50023024601210DF10700DD +:101930008DF80730FFF7CEFF20B19DF8070003B008 +:101940005DF804FB4FF0FF30F9E700000A4608B5E8 +:101950000421FFF7BFFF80F00100C0B2404208BD84 +:1019600030B4074B0A461978064B53F821402368D8 +:10197000DD69054B0146AC46204630BC604700BFE0 +:10198000105C002020230020A086010070B503F029 +:1019900015F9094E094D30800024286833888342A8 +:1019A00008D903F005F92B6804440133B4F5803FEE +:1019B0002B60F2D370BD00BF125C0020D05B002012 +:1019C00003F0ACB900F1006000F5803000687047AA +:1019D00000F10060920000F5803003F035B900009E +:1019E000054B1A68054B1B889B1A834202D9104489 +:1019F00003F0DEB800207047D05B0020125C0020AE +:101A0000024B1B68184403F0DBB800BFD05B00201A +:101A1000024B1B68184403F0EBB800BFD05B0020FA +:101A200010F003030AD1B0F5047F05D200F1005095 +:101A3000A0F51040D0F80038184670470023FBE7A7 +:101A400000F10050A0F51040D0F8100A70470000D7 +:101A5000064991F8243033B10023086A81F8243014 +:101A60000822FFF7B5BF0120704700BFD45B0020FC +:101A7000014B1868704700BF002004E070B5194B97 +:101A80001D68194B0138C5F30B0408442D0C0422C2 +:101A90001E88A6420BD15C680A46013C824213466E +:101AA0000FD214F9016F4EB102F8016BF6E7013A5B +:101AB00003F10803ECD181420B4602D22C2203F839 +:101AC000012B0A4A05241688AE4204D1984284BFED +:101AD000967803F8016B013C02F10402F3D1581A25 +:101AE00070BD00BF002004E0705700085C5700087C +:101AF000022802BF024B4FF000429A61704700BFBC +:101B000000040240022802BF024B4FF400429A61D7 +:101B1000704700BF00040240022801BF024A536917 +:101B200083F40043536170470004024010B5002362 +:101B3000934203D0CC5CC4540133F9E710BD0000DC +:101B400003460246D01A12F9011B0029FAD1704748 +:101B500002440346934202D003F8011BFAE77047A0 +:101B60002DE9F8431F4D144695F824200746884672 +:101B700052BBDFF870909CB395F824302BB920222B +:101B8000FF2148462F62FFF7E3FF95F82400C0F1DC +:101B90000802A24228BF2246D6B24146920005EB77 +:101BA0008000FFF7C3FF95F82430A41B1E44F6B253 +:101BB000082E17449044E4B285F82460DBD1FFF787 +:101BC00047FF0028D7D108E02B6A03EB820383424A +:101BD000CFD0FFF73DFF0028CBD10020BDE8F88330 +:101BE0000120FBE7D45B0020024B1A78024B1A70ED +:101BF000704700BF105C00201C23002003494FF4F5 +:101C000061430B60024B186802F0DABCFC5B0020F9 +:101C100020230020094B10B5142204460021184649 +:101C2000FFF796FF064A074B127804600146BDE8AD +:101C3000104053F8220002F0C3BC00BFFC5B002040 +:101C4000105C0020202300202DE9F0470D460446BB +:101C500000219046284640F27912FFF779FF23468B +:101C600020220021284601F013FF231D02222021FB +:101C7000284601F00DFF631D03222221284601F0B2 +:101C800007FFA31D03222521284601F001FF04F1CF +:101C9000080310222821284601F0FAFE04F110035F +:101CA00008223821284601F0F3FE04F1110308222E +:101CB0004021284601F0ECFE04F1120308224821DD +:101CC000284601F0E5FE04F11403202250212846A5 +:101CD00001F0DEFE04F1180340227021284601F0D5 +:101CE000D7FE04F120030822B021284601F0D0FEDF +:101CF00004F121030822B821284601F0C9FE04F1AD +:101D00002207C0263B46314608222846083601F005 +:101D1000BFFEB6F5A07F07F10107F3D104F132034E +:101D200008223146284601F0B3FE002704F1330AA9 +:101D300094F832304FEAC7099F4209F5A47615D3CB +:101D4000B8F1000F08D1314604F5997307222846EF +:101D500001F09EFE09F24F16274694F832213B1BF4 +:101D600093420CD3F01DC008BDE8F0870AEB0703CF +:101D700008223146284601F08BFE0137D8E707F2EA +:101D8000331331460822284601F082FE0836013717 +:101D9000E3E7000013B5044608460021016023462E +:101DA000C0F803102022019001F072FE0198231D5B +:101DB0000222202101F06CFE0198631D03222221E2 +:101DC00001F066FE0198A31D0322252101F060FEAB +:101DD000019804F108031022282101F059FE072080 +:101DE00002B010BDF7B50023047F00910E46072214 +:101DF0001946054601F010FD731C009301220023D3 +:101E00000721284601F008FDC4B9B31C0093052240 +:101E100023460821284601F0FFFC0D243746B278FE +:101E2000BB1B934211D32B7FA88A0734E408BBB9AC +:101E3000844294BF0020012003B0F0BDAB8ADB00D8 +:101E4000083BDB08B3700824E8E7FB1C009321463D +:101E500000230822284601F0DFFC08340137DEE7C2 +:101E6000201A18BF0120E7E7F7B50023047F00918F +:101E70000E4608221946054601F0CEFC731CC4B973 +:101E80000822009311462346284601F0C5FC102481 +:101E9000012372785F1C013B934211D32B7FA88AE8 +:101EA0000734E408BBB9844294BF0020012003B08A +:101EB000F0BDAB8ADB00083BDB0873700824E7E762 +:101EC000F3190093214600230822284601F0A4FCC0 +:101ED00008343B46DDE7201A18BF0120E7E7000081 +:101EE000F8B50E4605461446002181223046FFF71C +:101EF0002FFE2B4608220021304601F0C9FD7CB997 +:101F00006B1C07220821304601F0C2FD0F2401237B +:101F10006A785F1C013B934204D3E01DC008F8BD02 +:101F20000824F4E7EB1921460822304601F0B0FD01 +:101F300008343B46ECE70000F8B50E46054614466B +:101F40000021CE223046FFF703FE2B462822002137 +:101F5000304601F09DFD7CB905F1080308222821D7 +:101F6000304601F095FD30242F462A7A7B1B9342A0 +:101F700004D3E01DC008F8BD2824F5E707F10903E4 +:101F800021460822304601F083FD08340137ECE792 +:101F9000F7B5047F00910E4601231022002105466B +:101FA00001F03AFCC4B9B31C009309222346102166 +:101FB000284601F031FC192437467288BB1B9A422F +:101FC00011D82B7FA88A0734E408BBB9844294BF98 +:101FD0000020012003B0F0BDAB8ADB00103BDB0822 +:101FE00073801024E8E73B1D00932146002308225C +:101FF000284601F011FC08340137DEE7201A18BF2B +:102000000120E7E730B5094D0A4491420DD011F89F +:10201000013B5840082340F30004013B2C4013F0DF +:10202000FF0384EA5000F6D1EFE730BD2083B8ED1E +:10203000F7B54FF0FF33DFF854C0DFF854E000EBA2 +:1020400081011A4688421CD050F8044B019401AF1C +:10205000042417F8015B82EA05620825DB1816469E +:1020600005F1FF355241002EBCBF83EA0C0382EA22 +:102070000E0215F0FF05F1D1013C14F0FF04E8D188 +:10208000E0E7D843D14303B0F0BD00BF9336EAA9DF +:10209000EBE1F042F7B5384A106851686B4603C36C +:1020A0006A4636493648082303F0C6FA0446002833 +:1020B00033D10A25334A106851686B4603C36A4618 +:1020C00031492F48082303F0B7FA0446002849D0C5 +:1020D0000369B3F5E02F45D8B0F8661040F20B4223 +:1020E00091423FD1294A024402F15C018B4239D32B +:1020F0005C3B234900209E1AFFF784FF32460746C7 +:1021000004F164010020FFF77DFFA3689F4229D1FD +:10211000E368984208BF002524E00369B3F5E02F87 +:1021200027D8418B40F20B42914220D1174A0244FA +:1021300002F110018B4218D3103B114900209D1A67 +:10214000FFF760FF2A46064604F118010020FFF75A +:1021500059FFA3689E4202D1E368984201D00D2541 +:10216000A8E70025284603B0F0BD1025A2E70C25FE +:10217000A0E70B259EE700BF90570008DCFF060094 +:10218000000001089957000890FF06000800FFF7BB +:1021900010B5037C044613B9006803F035FA2046F5 +:1021A00010BD00000023BFF35B8FC360BFF35B8FE4 +:1021B000BFF35B8F8360BFF35B8F7047BFF35B8FB1 +:1021C0000068BFF35B8F704770B505460C30FFF7B2 +:1021D000F5FF05F1080604463046FFF7EFFFA04281 +:1021E00006D930466D68FFF7E9FF2544281A70BD0F +:1021F0003046FFF7E3FF201AF9E7000070B5054607 +:10220000406898B105F10800FFF7D8FF05F10C060A +:1022100004463046FFF7D2FF8442304694BF6D68D3 +:102220000025FFF7CBFF013C2C44201A70BD0000B5 +:1022300038B50C460546FFF7C7FFA04210D305F19D +:102240000800FFF7BBFF04446868B4FBF0F100FB33 +:102250001144BFF35B8F0120AC60BFF35B8F38BDCF +:102260000020FCE72DE9F041144607460D46FFF734 +:10227000C5FF844228BF0446D4B1B84658F80C6B59 +:102280004046FFF79BFF3044286040467E68FFF7DA +:1022900095FF331A9C4203D86C600120BDE8F081A1 +:1022A0006B60A41B3B68AB602044E8600220F5E74C +:1022B0002046F3E738B50C460546FFF79FFFA042DE +:1022C00010D305F10C00FFF779FF04446868B4FBF4 +:1022D000F0F100FB1144BFF35B8F0120EC60BFF312 +:1022E0005B8F38BD0020FCE72DE9FF418846694639 +:1022F0000746FFF7B7FF6C4606B204EBC60600259B +:10230000B44209D06268206808EB0501FFF70EFCB3 +:10231000636808341D44F3E729463846FFF7CAFFCF +:10232000284604B0BDE8F081F8B505460C300F46EC +:10233000FFF744FF05F1080604463046FFF73EFF6D +:10234000A042304688BF6C68FFF738FF201A38601B +:1023500020B130462C68FFF731FF2044F8BD000063 +:1023600073B5144606460D46FFF72EFF844228BF7C +:1023700004460190DCB101A93046FFF7D5FF019B6F +:1023800033B93268C5E90233C5E9002401200CE005 +:102390009C4238BF01942860019868608442F5D956 +:1023A0003368AB60241AEC60022002B070BD204696 +:1023B000FBE700002DE9FF410F466946FFF7D0FF1C +:1023C0006C4600B204EBC0050026AC4209D0D4F83C +:1023D000048054F8081BB8194246FFF7A7FB46448F +:1023E000F3E7304604B0BDE8F081000038B505469B +:1023F000FFF7E0FF044601462846FFF719FF204695 +:1024000038BD0000302383F3118862B670470000A6 +:10241000002383F3118862B67047000010B402688D +:1024200054681A4623465DF8044B1847012070474C +:102430000020704700207047704700000020704760 +:102440000E20704700F5805090F8C800C0F340009F +:102450007047000000F5805090F9C90070470000F7 +:10246000F7B50C68BDF8207014F000541E466FD10B +:102470000B7B082B6CD8FFF7C5FF4569AB685B0188 +:102480000CD4AB681B0108D4AC6814F080545DD147 +:10249000FFF7BEFF204603B0F0BD01240B6804F136 +:1024A000180C002BB8BFDB004FEA0C1CB4BF43F084 +:1024B00004035B0545F80C300B680FFA84FC13F03D +:1024C000804F18BF05EB0C1E05EB0C1C1EBFDEF881 +:1024D000803143F00203CEF880310B7BCCF884319D +:1024E00005EB04158B68C5F88C314B68C5F888314D +:1024F000DCF8803143F00103CCF8803100EB441567 +:1025000041F268031D4403EB44130344C5E900266C +:1025100008330D4601F10C0C55F804EB43F804EBBD +:102520006545F9D184342D881D8000EB441407F0F3 +:102530000303257925F00B052B432371FFF768FF73 +:102540000097334600F04EFD0120A4E70224A5E7E2 +:102550004FF0FF309FE7000013B500F58054019164 +:10256000E06DFFF74BFE1F280AD90199E06D20228C +:10257000FFF7BAFEA0F120035842584102B010BD47 +:102580000020FBE708B500F58050FFF73BFFC06D6A +:10259000FFF708FEBDE80840FFF73ABF00220260DF +:1025A000828142608260704710B500220023C0E93A +:1025B00000230023044603810C30FFF7EFFF204681 +:1025C00010BD0000F0B5054600F580500C4690F8AF +:1025D000C83013F0040FC3F3800108BF114661F344 +:1025E000820304F1840680F8C83005EB461389B0F5 +:1025F0001B79D8072ED57AB319072DD46846FFF773 +:10260000D3FF05EB441303F5835303F1180703AA23 +:10261000103318685968144603C40833BB42224675 +:10262000F7D1186820609B88A380DDE90E23CDE9EF +:1026300000230123ADF808302B686946DB6B284680 +:10264000984705EB46152B791A075CBF43F0080342 +:102650002B7101E0002AF4D109B0F0BD2DE9F0475B +:10266000074688B007F5805468469A468846FFF7C3 +:10267000C9FE9146FFF798FFE06DFFF7A5FD1F2803 +:1026800029D9E06D20226946FFF7B0FE202822D12B +:1026900003AD444605AB2E4603CE9E4220606160EA +:1026A000354604F10804F6D130682060B388A38071 +:1026B000DDE90023C9E90023BDF80830AAF800309D +:1026C000FFF7A6FE4A4653464146384608B0BDE8E5 +:1026D000F04700F075BCFFF79BFE002008B0BDE896 +:1026E000F08700002DE9F84F0023C0E90133264BA5 +:1026F000044640F8183B0F46FFF750FF04F128004E +:10270000FFF752FF04F1480804F5825546460835A4 +:1027100030462036FFF748FFAE42F9D104F5805528 +:102720004FF480534FF00009C5E91339C5F84880CC +:102730000123EE6504F5875804F58456C5F85490D6 +:1027400085F8583085F86030083608F108084FF0F1 +:10275000000A4FF0000B46E908ABA6F11800FFF79E +:102760001DFF203646F8289C4645F4D1012F85F8F8 +:10277000C97002D9054800F00DFC054B53F827300D +:1027800063612046BDE8F88FDC570008A4570008B5 +:10279000C057000810B5044B197804464A1C1A703B +:1027A000FFF7A0FF204610BD1C5C00202DE9F0477C +:1027B000002950D0294B2A4FB7FBF1F599428CBF25 +:1027C0000A231123581EB5FBF3FC03FB1C53C4B2B0 +:1027D0002BB102280346F5D80020BDE8F0870CF1A4 +:1027E000FF36B6F5806FF7D2C4EBC40E0EF10303CB +:1027F0004FEAE309C3F3C703A4EB030809F1010A95 +:102800004FF47A755FFA88F009FB05555AFA88F893 +:10281000B5FBF8F5B5F5617FC1BF0EF1FF33C3F32A +:10282000C703E01AC0B25C1C50FA84F40CFB04F439 +:10283000B7FBF4F4A142CFD1013BDBB20F2BCBD8D5 +:102840000138C0B20728C7D80021107116809170D6 +:10285000D3700120C1E70846BFE700BF3F420F0029 +:1028600040787D0170B505460E464FF47A746B6969 +:102870005B6803F00103B34207D04FF47A7001F0B4 +:10288000D9FF013CF3D1204670BD0120FCE70000D8 +:1028900030B54269936913F0700F16D000230B4CCA +:1028A000936103F1840200EB421211794D0709D5BF +:1028B000890707D5416954F823508D60117941F09B +:1028C000040111710133032BEBD130BDC85700084F +:1028D00073B51D46436916469A68D207044609D562 +:1028E0009A6801219960C2F34002CDE90065002198 +:1028F000FFF768FE63699A68D1050BD59A684FF4B3 +:1029000080719960C2F34022CDE900650121204623 +:10291000FFF758FE63699A68D2030BD59A684FF4A3 +:1029200080319960C2F34042CDE900650221204622 +:10293000FFF748FE204602B0BDE87040FFF7A8BF91 +:102940000C4B10B51C561B5C012B11D800F02AFB58 +:1029500050EA0103024602D0421E61F10001064B1B +:1029600053F8240020B1BDE810400B46FFF7B0BF7C +:1029700010BD00BFBC570008145C0020F8B5044629 +:10298000466900296CD106F10C07386880076AD0C7 +:1029900006EB01153868D5F8B00110F0040FD5F832 +:1029A000B0011ABFC00840F00040400DA061D5F84A +:1029B000B0C11CF0020F1CBF40F08040A061D5F8F0 +:1029C000B40106EB011100F00F0084F82400D1F8E7 +:1029D000B8012077D1F8B801000A6077D1F8B801C2 +:1029E000000CA077D1F8B801000EE077D1F8BC0157 +:1029F00084F82000D1F8BC01000A84F82100D1F845 +:102A0000BC01000C84F82200D1F8BC11090E84F836 +:102A100023103821396004F1340004F1180104F165 +:102A2000240551F8046B40F8046BA942F9D10988D8 +:102A30000180C4E90A2321460023238651F8283B5C +:102A40002046DB6B984704F58052204692F8C83048 +:102A500043F0040382F8C830BDE8F840FFF718BF20 +:102A600006F1100791E7F8BD0D4B70B51D561B5CC4 +:102A7000012B0C4612D800F095FA02460B4652EA9A +:102A8000030102D0013A63F10003064951F8250021 +:102A900020B12146BDE87040FFF770BF70BD00BF98 +:102AA000BC570008145C0020F8B500F583511E46A1 +:102AB000FFF7A8FCDFF844C00831002404F18405C6 +:102AC00000EB45152B795F070ED4DB060CD5D1E959 +:102AD00000739742B34107D243695CF824709F604A +:102AE0002B7943F004032B710134032C01F12001F5 +:102AF000E4D1BDE8F840FFF78BBC00BFC857000821 +:102B000008B5FFF77FFCFFF7C3FEBDE80840FFF7FD +:102B10007FBC0000F8B543690546986800F0E050B6 +:102B2000B0F1E05F0F461FD0E8B1FFF76BFC05F591 +:102B300083541034002606F1840305EB43131B79FC +:102B40001A0706D50136032E04F12004F3D1012023 +:102B500007E05B07F6D42146384600F07DFA0028EE +:102B6000F0D1FFF755FCF8BD0120FCE700F58050DF +:102B700008B5FFF747FCC06DFFF726FBFFF748FCE1 +:102B800043090CBF0120002008BD0000F8B51D4618 +:102B9000002313700F4606461446FFF7E7FF80F048 +:102BA0000100387025B129463046FFF7B3FF207089 +:102BB000F8BD00002DE9B8410C4615461F46804679 +:102BC00000F0F0F90B462178024609B9287850B197 +:102BD0004046FFF769FFFFF793FF3B462A46214631 +:102BE000FFF7D4FF0120BDE8B881000038B500F53B +:102BF0008054FFF707FC2A4D94F8C930EB5CDBB139 +:102C0000012B27D0FFF704FC94F8C830DB0746D42B +:102C1000002944D0FFF7F6FB94F8C930EB5C33B3DE +:102C2000012B31D094F8C83043F0010384F8C83048 +:102C3000BDE83840FFF7ECBB1A4B1A6C42F000724B +:102C40001A641A6A42F000721A621A6A22F000725A +:102C50001A62D7E7134B1A6C42F080621A641A6A40 +:102C600042F080621A621A6A22F08062F0E7032161 +:102C7000132001F0D9FA0321142001F0D5FA032121 +:102C8000152001F0D1FACDE703213F2001F0CCFA65 +:102C90000321402001F0C8FA03214120F1E738BDAB +:102CA000B8570008003802402DE9F04700F580557C +:102CB00088B095F8C930022B0446884616467FD85E +:102CC000844F57F823200AB947F82300D7F800A00B +:102CD000C4F80C802674BAF1000F63D095F8C9309F +:102CE000012B6FD001212046FFF780FFFFF78AFB01 +:102CF0006269136823F0020313606269136843F08A +:102D000001031360636900275F6101212046FFF71B +:102D10007FFBFFF7A7FD002800F09580E86DFFF727 +:102D200041FA04F58359BA4609F108092022002125 +:102D30006846FEF70DFF02A8FFF730FCCDF818A09B +:102D40006A4609EB07030DF1180E9446BCE8030030 +:102D5000F44518605960624603F10803F5D1DCF8C8 +:102D60000000186020379CF804201A71602FDDD114 +:102D700095F8C8306FF38203002785F8C8306A469B +:102D800041462046ADF80070ADF802708DF8047031 +:102D9000FFF70CFD636948BB4FF400421A6008B0AE +:102DA000BDE8F08741F2D00002F0EEFB814610B1A1 +:102DB0005146FFF797FCC7F80090B9F1000F8DD18D +:102DC0000020ECE7386803681B6B98470146002831 +:102DD00088D13868FFF70AFF3868036832465B68B5 +:102DE0004146984700287FF47DAFE9E761221A60E9 +:102DF0009DF802309DF803201B06120402F4702295 +:102E000003F040731343BDF80020C2F309021343DB +:102E10009DF804201205022E02F4E0020CBF4FF0D0 +:102E200000410021134362690B43D361636913229C +:102E30005A616269136823F0010313603946204622 +:102E4000FFF710FD08B96369A6E795F8C930002BB4 +:102E500039D16169D1F8002242F00102C1F80022A3 +:102E60006169D1F8002222F47C5222F00E02C1F8EE +:102E700000226169D1F8002242F46062C1F80022A8 +:102E80006269C2F814326269C2F8043262696FF092 +:102E90007841C2F80C126269C2F840326269C2F825 +:102EA00044326269C2F8B0326269C2F8B43263690E +:102EB00044F20102C3F81C226269D2F8003223F006 +:102EC0000103C2F8003295F8C83043F0020385F8D8 +:102ED000C83064E7145C002008B50020FFF730FD1F +:102EE000BDE8084001F082B808B500210846FFF7A8 +:102EF000BBFDBDE8084001F079B8000008B501212C +:102F00000020FFF7B1FDBDE8084001F06FB80000F8 +:102F100008B50120FFF714FDBDE8084001F066B8D0 +:102F200008B500210120FFF79FFDBDE8084001F032 +:102F30005DB8000008B501210846FFF795FDBDE822 +:102F4000084001F053B8000000B59BB0EFF30981D1 +:102F500068226846FEF7EAFDEFF30583014B9B6BA1 +:102F6000FEE700BF00ED00E008B5FFF7EDFF000051 +:102F700000B59BB0EFF3098168226846FEF7D6FDE5 +:102F8000EFF30583014B5B6BFEE700BF00ED00E054 +:102F9000FEE700000FB408B5029801F0E1FBFEE780 +:102FA00001F008BF01F0E0BE13B56C4684E80600EE +:102FB000031D94E8030083E80500012002B010BD62 +:102FC00073B58568019155B11B885B0707D4D0E9BB +:102FD00000369B6B9847019AC1B23046A847012042 +:102FE00002B070BDF0B5866889B005460C465EB18A +:102FF000BDF838305B070AD4D0E900379B6B98479F +:103000002246C1B23846B047012009B0F0BD0022C7 +:103010000023CDE900230023ADF808300A4603ABB6 +:1030200001F10806106851681C4603C40832B24218 +:103030002346F7D1106820609288A280FFF7B2FF84 +:103040000423ADF808302B68CDE90001DB6B69463D +:1030500028469847D8E7000030B503680968DD0FB7 +:10306000B5EBD17F23F0604421F060424FEAD1708C +:103070000BD0002BB8BFA40C0029B8BF920C94420F +:1030800002D034BF0120002030BD944205D1C1F3ED +:103090008070C3F380738342F6D194422CBF00202A +:1030A0000120F1E72DE9F041456A15B94162BDE81B +:1030B000F0814B6823F06047C3F38A464FEAD37E22 +:1030C000C3F3807816EA230638BF3E46AC462B464B +:1030D0005A68BEEBD27F22F060440AD0002A18DA88 +:1030E000A40CB44217D19D420FD10D60DEE7134608 +:1030F000EEE7A74207D102F08044C2F38072424556 +:103100000BD054B1EFE708D2EDE7CCF800100B601C +:10311000CDE7B44201D0B442E5D81A689C46002AF3 +:10312000E5D11960C3E700002DE9F047089D01F0E3 +:1031300007044FEAD508224405F0070500EBD1004B +:103140004FF47F49944201D1BDE8F08704F00707AE +:1031500005F0070A57453E4638BF5646C6F10806F1 +:10316000111B8E4228BF0E46E10808EBD50E415CCC +:1031700013F80EC0B94029FA06F721FA0AF1FFB296 +:103180008CEA010147FA0AF739408CEA010C03F88E +:103190000EC034443544D5E780EA0120082341F2CB +:1031A000210201B24000002980B203F1FF33B8BF11 +:1031B000504013F0FF03F4D17047000038B50C46BF +:1031C0008D18A54200D138BD14F8011BFFF7E4FFAC +:1031D000F7E7000042684AB1136843604389818978 +:1031E00001339BB29942438138BF838110467047B7 +:1031F00070B588B0202204460D4668460021FEF7CF +:10320000A7FC20460495FFF7E5FF024658B16B4640 +:10321000054608AE1C4603CCB442286069602346CC +:1032200005F10805F6D1104608B070BD082817D979 +:1032300009280CD00A280CD00B280CD00C280CD054 +:103240000D280CD00E2814BF4020302070470C20D1 +:1032500070471020704714207047182070472020B6 +:1032600070470000082817D90C280CD910280CD951 +:1032700014280CD918280CD920280CD930288CBF38 +:103280000F200E207047092070470A2070470B203E +:1032900070470C2070470D20704700002DE9F8435F +:1032A000078C072F04461ED9D0E9029800254FF657 +:1032B000FF73C5F12006A5F1200029FA05F108FAEF +:1032C00006F628FA00F031430143C9B21846FFF769 +:1032D00063FF0835402D0346EBD1E1693A46BDE86E +:1032E000F843FFF76BBF4FF6FF70BDE8F8830000AF +:1032F00010B54B6823B9CA8A63F30902CA8210BDAC +:1033000004691A681C600361C38A013BC3824A6076 +:10331000EFE700002DE9F84F1D46CB8A0F46C3F3B7 +:1033200009010529814692460B4630D00020AAB2F9 +:1033300007F11A049EB2042E1FFA80F80FD89045A8 +:1033400003F1010306D3FB8A0A4462F30903FB82FB +:1033500001201AE01AF80060E6540130EAE79045CF +:10336000F1D2A1F1050B1C237C68BBFBF3F203FB3C +:1033700012BB1FFA8BF6002C45D14846FFF72AFFF7 +:10338000044638B978606FF00200BDE8F88F4FF05E +:103390000008E6E7002606607860ADB24FF0000B4B +:1033A000454510D90AEB0803221D13F8011B91555E +:1033B000B1B208F101081B291FFA88F82BD0454546 +:1033C00006F10106F1D8FB8AC3F30902154465F33F +:1033D0000903BCE7013292B21C462368002BF9D1E5 +:1033E0006B1F0B441C21B3FBF1F301339BB29A42D8 +:1033F000D3D2BBF1000FD0D14846FFF7EBFE20B986 +:10340000C4F800B0BFE70122E7E7C0F800B05E46AD +:1034100020600446C1E74545D5D94846FFF7DAFEA6 +:1034200008B92060AFE7C0F800B00026206004466D +:10343000B6E700002DE9F04F2DED028B1C4683B05E +:103440005B69019207468846002B00F09A80238C26 +:103450002BB1E269002A00F09480072B35D807F1E0 +:103460000C00FFF7B7FE054638B96FF00205284695 +:1034700003B0BDEC028BBDE8F08F14220021FEF7F3 +:1034800067FB228CE16905F10800FEF74FFB208CF9 +:10349000013080B2FFF7E6FEFFF7C8FE013880B2C8 +:1034A0002084013028746369228C1B782A4403F03D +:1034B0001F0363F03F0348F0004113723846696010 +:1034C0002946FFF7EFFD0125D1E700F10C034FF08E +:1034D000000908EE103A4FF0800A4E464D4618EEAD +:1034E000100AFFF777FE83460028BED01422002181 +:1034F000FEF72EFB002E3AD1019BABF808300222DA +:103500000BF1080E1FFA82FC0CF10100BCF1060F52 +:10351000218C80B201D88E422BD3FFF7A3FEFFF798 +:1035200085FE62691278013802F01F028E4208BFE0 +:103530004FF0400A42EA49121BFA80F14AEA020AB5 +:10354000013048F0004281F808A08BF81000CBF859 +:10355000042059463846FFF7A5FD238C0135B342B8 +:103560002DB289F001094FF0000AB8D17FE700229F +:10357000C6E7E169895D0EF802100136B6B2013284 +:10358000C0E76FF0010572E7F8B515460E46302228 +:10359000002104461F46FEF7DBFA069B6360B5F583 +:1035A000001F079BA76034BF6A094FF6FF72A36232 +:1035B00097B2E66104F1100000239A4206D8002376 +:1035C0000360A782E3822383E360F8BD06600133D2 +:1035D00030462036F1E7000003781BB94BB2002BD0 +:1035E000C8BF01707047000000787047F8B50C46FE +:1035F000C969074611B9238C002B37D1257E1F2DB1 +:1036000034D8387828BB228C072A2CD8268A36F062 +:1036100003032BD14FF6FF70FFF7D0FD20F0010020 +:103620003102400441EA0561400C41EA40254FF671 +:10363000FF72234629463846FFF7FCFE002807DDC7 +:10364000626913780133DBB21F2B88BF002313702C +:10365000F8BD218A2D0645EA012505432046FFF7DE +:103660001DFE0246E5E76FF00300F1E76FF0010091 +:10367000EEE7000070B58AB0044616460021282205 +:1036800068461D46FEF764FABDF83830ADF81030D4 +:103690000F9B05939DF840308DF81830119B0793D0 +:1036A0006946BDF84830ADF820302046CDE90265C6 +:1036B000FFF79CFF0AB070BD2DE9F041D3690546C4 +:1036C0000C4616460BB9138C5BBB377E1F2F28D8D0 +:1036D00095F80080B8F1000F26D03046FFF7DEFDE8 +:1036E0003378210241EAC33141EA0801338A41EAD1 +:1036F000076141EA03410246334641F08001284612 +:10370000FFF798FE00280ADD3378012B07D1726994 +:1037100013780133DBB21F2B88BF00231370BDE881 +:10372000F0816FF00100FAE76FF00300F7E70000A7 +:10373000F0B58BB004460D46174600212822684696 +:103740001E46FEF705FA9DF84C305A1E534253416F +:103750008DF800309DF84030ADF81030119B059386 +:103760009DF848308DF81830149B07936A46BDF8D1 +:103770005430ADF8203029462046CDE90276FFF7D7 +:103780009BFF0BB0F0BD0000406A00B104307047F1 +:10379000436A1A68426202691A600361C38A013B84 +:1037A000C38270472DE9F041D0F82080194E1446AD +:1037B0001D464146002709B9BDE8F081D1E9022341 +:1037C000A21A65EB0303964277EB03031ED2036A4A +:1037D0008B420DD1FFF78CFD036A1B6803620369FE +:1037E0000B60C38A0161016A013BC3828846E2E73C +:1037F000FFF77EFD0B68C8F8003003690B60C38AD1 +:103800000161013BC382D8F80010D4E788460968FB +:10381000D1E700BF80841E002DE9F04F8BB00D462C +:10382000DDF8509014469B468046002800F0198130 +:10383000B9F1000F00F01581531E3F2B00F21181EA +:10384000012A03D1BBF1000F40F00B810023CDE929 +:103850000833B8F81430B5EBC30F4FEAC30703D3EE +:1038600000200BB0BDE8F08F2B199F42D8F80C3028 +:103870003ABF7F1BFFB227461BB9D8F81030002B88 +:103880007AD0272D4ED8C5F12806B7424FF0000355 +:103890002CBFF6B23E4600932946D8F8080008AB84 +:1038A0003246FFF741FCA7EB060A35445FFA8AFA75 +:1038B000B8F8143003F10053053BDB000493D8F84B +:1038C0000C3003932821039B13B1BAF1000F2CD1C4 +:1038D000D8F8100040B1BAF1000F05D0009608AB3F +:1038E0005246691AFFF720FC38B2002FB8D066079D +:1038F0000AD00AAB03EBD401624211F8083C02F093 +:103900000702134101F8083C082C3CD9102C40F266 +:10391000B580202C40F2B780BBF1000F00F09C80F6 +:10392000082334E0BA460026C2E7049BE02B28BFF8 +:10393000E02306930B44AB42059314D95A1B03981A +:103940000096924534BF5246D2B2691A08AB043091 +:103950000792FFF7E9FB079A1644AAEB020A1544FF +:10396000F6B25FFA8AFA049B069A05999B1A0493A9 +:10397000039B1B680393A6E70093D8F8080008ABE5 +:103980003A462946AEE7BBF1000F13D00123B4EB52 +:10399000C30F6CD0082C12D89DF82030621E23FA79 +:1039A00002F2D50706D54FF0FF3202FA04F42343A2 +:1039B0008DF820309DF8203089F8003051E7102C28 +:1039C00012D8BDF82030621E23FA02F2D10706D5C4 +:1039D0004FF0FF3202FA04F42343ADF82030BDF873 +:1039E0002030A9F800303CE7202C0FD80899631E3E +:1039F00021FA03F3DA0705D54FF0FF3202FA04F497 +:103A00000C430894089BC9F800302AE7402C2BD0BF +:103A1000DDE90865611EC4F12102A4F1210326FA43 +:103A200001F105FA02F225FA03F311431943CB071A +:103A300012D50122A4F12003C4F1200102FA03F3FC +:103A400022FA01F1A240524243EA010363EB43032D +:103A500032432B43CDE90823DDE90823C9E90023DC +:103A6000FFE66FF00100FCE66FF00800F9E6082CB5 +:103A7000A0D9102CB3D9202CEED8C3E7BBF1000F8E +:103A8000ADD0022383E7BBF1000FBBD004237EE758 +:103A900030B5012A144638BF0124402C85B028BF18 +:103AA00040240025012ACDE9025518D81B788DF84D +:103AB000083063070AD004AB03EBD405624215F863 +:103AC000083C02F00702934005F8083C00910346C9 +:103AD0002246002102A8FFF727FB05B030BD082AC7 +:103AE000E4D9102A03D81B88ADF80830E1E7202A72 +:103AF0008DBFD3E900231B680293CDE90223D8E7E9 +:103B000010B5CB681BB98B600B618B8210BD04694B +:103B10001A681C600361C38A013BC382CA60F0E774 +:103B200003064CBFC0F3C0300220704708B5024600 +:103B3000FFF7F6FF022806D15306C2F30F2001D18A +:103B400000F0030008BDC2F30740FBE72DE9F04F8A +:103B500093B0CDE903230A6804461046FFF7E0FF5F +:103B6000022814BFC2F306260026002A0D4682460C +:103B700080F2F28112F0C04940F0EE81097B002909 +:103B800000F0EA81022803D02378B34240F0E781B5 +:103B9000C2F304630693104602F07F030593FFF718 +:103BA000C5FF059B29444FEA834848EA0A4848EA8A +:103BB0004668CE7800230022CDE90823F309834626 +:103BC00048EA0008029367D0059B009302466768A5 +:103BD000534608A92046B847002800F0C381276A49 +:103BE0004FB9414604F10C00FFF702FB074690B9BC +:103BF0006FF0020054E03B6998450DD03F68002FFC +:103C0000F9D1414604F10C00FFF7F2FA074600280B +:103C1000EED0236A3B60276297F817C006F01F08B2 +:103C2000CCF3840CACEB08001FFA80FE0028B8BF70 +:103C30000EF12000A8EB0C031FFA83FED7E9022146 +:103C4000B8BF00B2002B0793BEBF0EF120031BB21A +:103C5000079352EA010338D0039BDFF824E39A1A52 +:103C6000049B4FF0000C63EB010196457CEB0103D4 +:103C70002BD36B7B97F81AE0734519D1029B002B6D +:103C800078D0012821DC7868F8B9DFF8F0C29445D3 +:103C900070EB010316D337E0276A27B96FF00C00E9 +:103CA00013B0BDE8F08F3B699845B5D03F68F4E7A5 +:103CB000B24890427CEB010301D30020F0E7029B65 +:103CC000002BFAD0079B0F2B17DCFA7DB30002F014 +:103CD000030203F07C031343FB7539462046FFF7CC +:103CE00007FB6B7BBB76029B3BB9FB7DC3F3840276 +:103CF000013262F38603FB75D0E76A7BBB7E9A4292 +:103D0000DBD1029B002B35D0B309022B32D0039BB1 +:103D1000BB60049BFB60142200210DA8FDF718FF77 +:103D2000039B0A93049B0B932B1D0C932B7BADF8E9 +:103D30003EB0013BDBB2ADF83C30069B8DF8423023 +:103D4000059B8DF8433094F82C308DF840A083F01B +:103D500001038DF844308DF84180A3680AA92046FC +:103D60009847FB7DC3F38403013303F01F039B02D9 +:103D7000FB82A2E7FB7DC6F34012B2EBD31F40F0FB +:103D8000F480C3F38403434540F0F280029A2B7B16 +:103D9000B609002A4DD0F2075DD4032B40F2EB8028 +:103DA000039BBB60049BFB602B7BAE1D033BDBB224 +:103DB0003246394604F10C00FFF7ACFA00280CDA61 +:103DC00039462046FFF794FAFB7DC3F384030133A1 +:103DD00003F01F039B02FB820AE7DDE90884AB883E +:103DE0003B834FF6FF73C9F12000A9F1200228FAA6 +:103DF00009F104FA00F0014324FA02F211431846D3 +:103E0000C9B2FFF7C9F909F10809B9F1400F034632 +:103E1000E9D1B8822A7B033AD2B23146FFF7CEF914 +:103E2000FB7DB882DA43C2F3C01262F3C713FB759D +:103E300043E786B92E1D013BDBB23246394604F119 +:103E40000C00FFF767FA0028BADB2A7BB88A013A30 +:103E5000D2B23146E2E7F98AC1F30901013B0429F4 +:103E6000DAB25BD8281D002307F11B069A4208D955 +:103E700010F801CB06F801C0013101330529DBB28E +:103E8000F4D103990A9104990B91934207F11B0114 +:103E90000C9138BF043379680D9134BF55FA83F320 +:103EA00000230E93FB8AADF83EB0C3F309031A4416 +:103EB000069B8DF84230059B8DF8433094F82C30EA +:103EC000ADF83C2083F001038DF8443000238DF8D9 +:103ED00040A08DF841807B602A7BB88A013A291D79 +:103EE000FFF76CF93B8BB882834203D1A3680AA920 +:103EF0002046984720460AA9FFF702FEFB7DBA8AB2 +:103F0000C3F38403013303F01F039B02FB823B8B4B +:103F10009A420CBF00206FF01000C1E67B68002BB6 +:103F2000AFD0052001E01C3033461E68002EFAD1C8 +:103F3000091A081D2E1D184401EB090CBCF11B0FBA +:103F40005FFA89F39DD89A429BD916F8013B00F895 +:103F5000013B09F10109EFE76FF00900A0E66FF0FE +:103F60000A009DE66FF00B009AE66FF00D0097E6F1 +:103F70006FF00E0094E66FF00F0091E640420F00E4 +:103F800080841E00EFF3098305494A6B22F0010289 +:103F90004A63683383F30988002383F311887047E9 +:103FA00000EF00E0302080F3118862B60C4B0D4A20 +:103FB000D96821F4E0610904090C0A43DA60D3F8F6 +:103FC000FC20094942F08072C3F8FC200A6842F0E4 +:103FD00001020A602022DA7783F82200704700BFCE +:103FE00000ED00E00003FA05001000E010B53023FA +:103FF00083F311880E4B5B6813F4006314D0F1EE69 +:10400000103AEFF30984683C4FF08073E361094B89 +:10401000DB6B236684F3098800F060FB10B1064B6C +:10402000A36110BD054BFBE783F31188F9E700BFDF +:1040300000ED00E000EF00E043060008460600083F +:10404000026843681143016003B1184770470000DC +:10405000024AD36843F0C003D36070470044004075 +:1040600010B5054C054A0021204600F087FA044AA5 +:10407000044BC4E9972310BD245C00205140000884 +:104080000044004040787D01234A037C002918BF8A +:104090000A46012B30B5C0F868220CD11F4B98425C +:1040A00009D11F4B196C41F400311964196E41F4A8 +:1040B000003119661B6EB2F904501468D0F86032F2 +:1040C000D0F85C12002D03EB5403B3FBF4F3BEBF36 +:1040D00023F0070503F0070343EA450394888B6048 +:1040E000D38843F040030B61138943F001034B6114 +:1040F00044F4045343F02C03CB6004F4A054002395 +:104100000B60B4F5806F0B684B680CBF7F23FF23F7 +:1041100080F8643230BD00BF1C580008245C0020C9 +:10412000003802402DE9F041D0F85C62F76833684E +:10413000DA0504469DB20DD5302383F311884FF480 +:1041400080610430FFF77CFF6FF4807333600023DD +:1041500083F31188302383F3118804F1040815F0E8 +:104160002F033AD183F31188380615D5290613D5C4 +:10417000302383F3118804F1380000F07BF9002824 +:104180004EDA0821201DFFF75BFF4FF67F733B409F +:10419000F360002383F311887A0616D56B0614D5D5 +:1041A000302383F31188D4E913239A420AD1236C74 +:1041B00043B127F040073F041021201D3F0CFFF7BB +:1041C0003FFFF760002383F31188D4F86822D36897 +:1041D00043B3BDE8F041106918472B0714D015F020 +:1041E000080F0CBF00214FF48071E80748BF41F071 +:1041F0002001AA0748BF41F040016B0748BF41F0CA +:1042000080014046FFF71CFFAD06736805D594F8A2 +:1042100064122046194000F0E1F93568ADB29EE71E +:104220007060B6E7BDE8F08100F1604303F56143DB +:104230000901C9B283F80013012200F01F039A405C +:1042400043099B0003F1604303F56143C3F88021F8 +:104250001A607047F8B5154682680669AA420B468F +:10426000816938BF8568761AB54204460BD2184674 +:104270002A46FDF75BFCA3692B44A361A3685B1B83 +:10428000A3602846F8BD0CD918463246FDF74EFC0F +:10429000AF1BE1683A463044FDF748FCE3683B4415 +:1042A000EBE718462A46FDF741FCE368E5E7000026 +:1042B00083689342F7B51546044638BF8568D0E950 +:1042C0000460361AB5420BD22A46FDF72FFC63690B +:1042D0002B446361A36828465B1BA36003B0F0BD59 +:1042E0000DD932460191FDF721FC0199E068AF1B21 +:1042F0003A463144FDF71AFCE3683B44E9E72A46B5 +:10430000FDF714FCE368E4E710B50A440024C36138 +:10431000029B8460C0E90000C0E90511C160026130 +:10432000036210BD08B5D0E90532934201D182681D +:1043300082B98268013282605A1C42611970D0E9E8 +:1043400004329A4224BFC3684361002100F08EFA10 +:10435000002008BD4FF0FF30FBE7000070B53023B0 +:1043600004460E4683F31188A568A5B1A368A26927 +:10437000013BA360531CA36115782269934224BFBB +:10438000E368A361E3690BB120469847002383F3F8 +:104390001188284607E03146204600F057FA0028E9 +:1043A000E2DA85F3118870BD2DE9F74F04460E4619 +:1043B00017469846D0F81C904FF0300A8AF31188BF +:1043C0004FF0000B154665B12A4631462046FFF7EF +:1043D00041FF034660B94146204600F037FA002805 +:1043E000F1D0002383F31188781B03B0BDE8F08F70 +:1043F000B9F1000F03D001902046C847019B8BF311 +:104400001188ED1A1E448AF31188DCE7C0E9051112 +:10441000C160C3611144009B8260C0E9000001617A +:1044200003627047F8B504460D461646302383F301 +:104430001188A768A7B1A368013BA36063695A1CF0 +:1044400062611D70D4E904329A4224BFE36863615B +:10445000E3690BB120469847002080F3118807E0FC +:104460003146204600F0F2F90028E2DA87F311889D +:10447000F8BD0000D0E905239A4210B501D1826849 +:104480007AB98268013282605A1C82611C780369A1 +:104490009A4224BFC3688361002100F0E7F92046F7 +:1044A00010BD4FF0FF30FBE72DE9F74F04460E46F5 +:1044B00017469846D0F81C904FF0300A8AF31188BE +:1044C0004FF0000B154665B12A4631462046FFF7EE +:1044D000EFFE034660B94146204600F0B7F90028D8 +:1044E000F1D0002383F31188781B03B0BDE8F08F6F +:1044F000B9F1000F03D001902046C847019B8BF310 +:104500001188ED1A1E448AF31188DCE702684368BB +:104510001143016003B11847704700001430FFF7E2 +:1045200043BF00004FF0FF331430FFF73DBF0000E2 +:104530003830FFF7B9BF00004FF0FF333830FFF7D6 +:10454000B3BF00001430FFF709BF00004FF0FF3188 +:104550001430FFF703BF00003830FFF763BF0000DF +:104560004FF0FF323830FFF75DBF0000012914BF64 +:104570006FF0130000207047FFF772BD37B5154686 +:104580000E4A026000224260C0E902220122044673 +:1045900002740B46009000F15C014FF480721430FD +:1045A000FFF7B2FE00942B464FF4807204F5AE7113 +:1045B00004F13800FFF72AFF03B030BD305800087F +:1045C00010B53023044683F31188FFF75DFD022305 +:1045D0002374002080F3118810BD000038B5C36932 +:1045E00004460D461BB904210844FFF78FFF2946F6 +:1045F00004F11400FFF796FE002806DA201D4FF4A0 +:104600000061BDE83840FFF781BF38BD0023037566 +:10461000826803691B6899689142FBD25A680360FB +:104620004260106058607047002303758268036918 +:104630001B6899689142FBD85A6803604260106019 +:104640005860704708B50846302383F311880B7D06 +:10465000032B05D0042B0DD02BB983F3118808BD93 +:104660008B6900221A604FF0FF338361FFF7CEFFA2 +:104670000023F2E7D1E9003213605A60F3E700004B +:10468000FFF7C4BF054BD9680875186802681A603F +:10469000536001220275D860FBF7BEBF905E002018 +:1046A00030B50C4BDD684B1C87B004460FD02B4651 +:1046B000094A684600F06CF92046FFF7E3FF009BCB +:1046C00013B1684600F06EF9A86907B030BDFFF776 +:1046D000D9FFF9E7905E002045460008044B1A68B0 +:1046E000DB6890689B68984294BF00200120704767 +:1046F000905E0020084B10B51C68D86822681A60CC +:10470000536001222275DC60FFF78EFF01462046D0 +:10471000BDE81040FBF780BF905E0020044B1A6894 +:10472000DB6892689B689A4201D9FFF7E3BF704744 +:10473000905E002038B5074C074908480123002542 +:104740002370656000F03AFC0223237085F3118822 +:1047500038BD00BFF86000205C580008905E002063 +:1047600008B572B6044B186500F0ECFA00F0A0FB37 +:10477000024B03221A70FEE7905E0020F8600020D2 +:1047800000F046B9EFF3118020B9EFF30583302232 +:1047900082F311887047000010B530B9EFF305843B +:1047A000C4F3080414B180F3118810BDFFF7B6FFFD +:1047B00084F31188F9E700008B60022308618B8283 +:1047C000084670478368A3F1840243F8142C0269F9 +:1047D00043F8442C426943F8402C094A43F8242CFE +:1047E000C26843F8182C022203F80C2C002203F8AC +:1047F0000B2C044A43F8102CA3F12000704700BF93 +:1048000031060008905E002008B5FFF7DBFFBDE829 +:104810000840FFF735BF0000024BDB6898610F20AE +:10482000FFF730BF905E0020302383F31188FFF73D +:10483000F3BF000008B50146302383F31188082038 +:10484000FFF72EFF002383F3118808BD064BDB68BA +:1048500039B1426818605A60136043600420FFF762 +:104860001FBF4FF0FF307047905E002003689842F2 +:1048700006D01A680260506099611846FFF700BFC1 +:104880007047000010B503689C68A2420CD85C68B1 +:104890008A600B604C602160596099688A1A9A603E +:1048A0004FF0FF33836010BD1B68121BECE7000064 +:1048B0000A2938BF0A2170B504460D460A26601938 +:1048C00000F076FB00F062FB041BA54203D8751CC8 +:1048D0002E460446F3E70A2E04D9BDE870400120B5 +:1048E00000F0ACBB70BD0000F8B5144B0D46D961AB +:1048F00003F1100141600A2A1969826038BF0A2257 +:10490000016048601861A818144600F043FB0A27AC +:1049100000F03CFB431BA342064606D37C1C28192F +:1049200000F046FB27463546F2E70A2F04D9BDE8DA +:10493000F840012000F082BBF8BD00BF905E00206F +:10494000F8B506460D4600F021FB0F4A134653F812 +:10495000107F9F4206D12A4601463046BDE8F84006 +:10496000FFF7C2BFD169BB68441A2C1928BF2C4677 +:10497000A34202D92946FFF79BFF2246314603484E +:10498000BDE8F840FFF77EBF905E0020A05E0020EB +:1049900010B4C0E9032300235DF8044B4361FFF723 +:1049A000CFBF000010B5194C236998420DD0D0E953 +:1049B0000032816813605A609A680A449A60002342 +:1049C00003604FF0FF33A36110BD2346026843F834 +:1049D000102F53600022026022699A4203D1BDE881 +:1049E000104000F0DFBA936881680B44936000F0D8 +:1049F000CDFA2269E1699268441AA242E4D91144CD +:104A0000BDE81040091AFFF753BF00BF905E0020B9 +:104A10002DE9F047DFF8BC8008F110072C4ED8F8DC +:104A2000105000F0B3FAD8F81C40AA68031B9A4251 +:104A30003ED81444D5E900324FF00009C8F81C40B4 +:104A400013605A60C5F80090D8F81030B34201D115 +:104A500000F0A8FA89F31188D5E903312846984770 +:104A6000302383F311886B69002BD8D000F08EFAC5 +:104A70006A69A0EB04094A4582460DD2022000F083 +:104A8000DDFA0022D8F81030B34208D1514628464A +:104A9000BDE8F047FFF728BF121A2244F2E712EBF5 +:104AA000090938BF4A4629463846FFF7EBFEB5E705 +:104AB000D8F81030B34208D01444211AC8F81C00AA +:104AC000A960BDE8F047FFF7F3BEBDE8F08700BF7F +:104AD000A05E0020905E002000207047FEE70000EE +:104AE000704700004FF0FF3070470000BFF34F8F5A +:104AF000024AD368DB03FCD4704700BF003C02408D +:104B000008B5094B1B7873B9FFF7F0FF074B1A691B +:104B1000002ABFBF064A5A6002F188325A601A68FA +:104B200022F480621A6008BD00610020003C02404F +:104B30002301674508B50B4B1B7893B9FFF7D6FFE8 +:104B4000094B1A6942F000421A611A6842F4805215 +:104B50001A601A6822F480521A601A6842F480625D +:104B60001A6008BD00610020003C02400728F0B533 +:104B700016D80C4C0C4923787BB90C4D0E460823F3 +:104B80004FF0006255F8047B46F8042B013B13F00C +:104B9000FF033A44F6D10123237051F82000F0BD01 +:104BA0000020FCE724610020046100206858000810 +:104BB000014B53F8200070476858000808207047E0 +:104BC000072810B5044601D9002010BDFFF7CEFF1D +:104BD000064B53F824301844C21A0BB90120F4E7ED +:104BE00012680132F0D1043BF6E700BF68580008B4 +:104BF000072810B5044621D8FFF778FFFFF780FF9C +:104C00000F4AF323D360C300DBB243F4007343F0D5 +:104C100002031361136943F480331361FFF766FFE6 +:104C2000FFF7A4FF074B53F8241000F03DF9FFF7FE +:104C300081FF2046BDE81040FFF7C2BF002010BD35 +:104C4000003C024068580008F8B512F00103144611 +:104C500042D185182E4A954257D82E4B1B6813F027 +:104C6000010352D02C4DFFF74BFFF323EB60FFF70E +:104C70003DFF40F20127032C15D824F001046618EB +:104C8000254C401A40F20117B142236900EB01059F +:104C900024D123F001032361FFF74CFF0120F8BD6D +:104CA000043C0430E7E78307E7D12B6923F4407322 +:104CB0002B612B693B432B6151F8046B0660BFF3FA +:104CC0004F8FFFF713FF03689E42E9D02B6923F053 +:104CD00001032B61FFF72EFF0020E0E723F4407370 +:104CE000236123693B4323610B882B80BFF34F8FE4 +:104CF000FFF7FCFE2D8831F8023BADB2AB42C3D0CA +:104D0000236923F001032361E4E71846C7E700BFE6 +:104D10000000080800380240003C0240084908B57D +:104D20000B7828B11BB9FFF7EBFE01230B7008BD10 +:104D3000002BFCD0BDE808400870FFF7FBBE00BFA9 +:104D4000006100204FF480214FF0005000F0AEB819 +:104D50000846114600F03ABC012000F037BC0000C4 +:104D6000084600F051BC000070B582B0FFF70AFDA4 +:104D70000E4E054600F00AF93268904237BF0C4AE1 +:104D80000B49516814682EBFD1E9004101315160CF +:104D90000419034641F10001284601913360FFF7F1 +:104DA000FBFC0199204602B070BD00BF28610020C5 +:104DB0003061002070B582B0FFF7E4FC104E05466C +:104DC00000F0E4F83268904237BF0E4A0D4951684E +:104DD00014682EBFD1E9004101315160041941F13D +:104DE00000010346284601913360FFF7D5FC019985 +:104DF0004FF47A7200232046FBF7FAF902B070BD37 +:104E0000286100203061002010B50244064BD2B268 +:104E1000904200D110BD441C00B253F8200041F86C +:104E2000040BE0B2F4E700BF502800400F4B30B550 +:104E30001C6F240407D41C6F44F400741C671C6F9F +:104E400044F400441C670A4C236843F480732360D5 +:104E50000244084BD2B2904200D130BD441C00B293 +:104E600051F8045B43F82050E0B2F4E70038024008 +:104E7000007000405028004007B5012201A9002021 +:104E8000FFF7C2FF019803B05DF804FB13B50446B9 +:104E9000FFF7F2FFA04205D0012201A900200194F2 +:104EA000FFF7C4FF02B010BD70470000704700005C +:104EB00070470000074B45F255521A6002225A60B3 +:104EC00040F6FF729A604CF6CC421A60024B012207 +:104ED0001A707047003000403C610020034B1B7883 +:104EE0001BB1034B4AF6AA221A6070473C610020AE +:104EF00000300040034B1A681AB9034AD2F87428EC +:104F00001A6070473861002000300240024B4FF0B9 +:104F10008072C3F8742870470030024008B5FFF76C +:104F2000E9FF024B1868C0F3407008BD38610020EB +:104F300008B5FFF7DFFF024B1868C0F3007008BD2B +:104F40003861002070470000FEE700000A4B0B4864 +:104F50000B4A90420BD30B4BDA1C121AC11E22F0E3 +:104F600003028B4238BF00220021FCF7F1BD53F849 +:104F7000041B40F8041BECE7085A0008C861002035 +:104F8000C8610020C861002000F0CAB84FF080431B +:104F9000586A70474FF08043002258631A6102221A +:104FA000DA6070474FF080430022DA6070470000FB +:104FB0004FF0804358637047FEE7000070B51B4B0D +:104FC00001630025044686B0586085620E46FEF7F0 +:104FD000E9FF04F11003C4E904334FF0FF33C4E9DF +:104FE0000635C4E90044A560E562FFF7CFFF2B4614 +:104FF0000246C4E9082304F134010D4A25658023E3 +:105000002046FFF7D9FB0123E0600A4A03750092AE +:1050100072680192B268CDE90223074B6846CDE978 +:105020000435FFF7F1FB06B070BD00BFF86000204B +:10503000885800088D580008B94F0008024AD36A02 +:105040001843D062704700BF905E00204B684360F9 +:105050008B688360CB68C3600B6943614B690362F3 +:105060008B6943620B6803607047000008B5234BEF +:1050700023481A6942F0FF021A611A6922F0FF02FE +:105080001A611A691A6B42F0FF021A631A6D42F034 +:10509000FF021A651B4A1B6D1146FFF7D7FF02F18D +:1050A0001C0100F58060FFF7D1FF02F1380100F527 +:1050B0008060FFF7CBFF02F1540100F58060FFF73D +:1050C000C5FF02F1700100F58060FFF7BFFF02F13C +:1050D0008C0100F58060FFF7B9FF02F1A80100F52F +:1050E0008060FFF7B3FF02F1C40100F58060FFF7B5 +:1050F000ADFFBDE8084000F08DB800BF00380240A9 +:10510000000002409458000808B500F019FAFFF7B3 +:1051100011FBBDE80840FFF7EDBE0000704700003E +:105120000F4B1A6C42F001021A641A6E42F001022F +:105130001A660C4A1B6E936843F0010393604FF0AC +:10514000804331229A624FF0FF32DA6200229A6184 +:105150005A63DA605A6001225A611A60704700BFD0 +:1051600000380240002004E04FF0804208B5116989 +:10517000D3680B40D9B2C9439B07116107D53023CF +:1051800083F31188FFF7FCFA002383F3118808BD2D +:105190001E4B1A6962F0FF021A611A69D2B21A61D3 +:1051A0004FF0FF301A695A69586100215A695961F4 +:1051B0005A691A6A62F080521A621A6A02F08052C0 +:1051C0001A621A6A5A6A58625A6A59625A6A1A6C98 +:1051D00042F080521A641A6E42F080521A661A6EB9 +:1051E0000B4A106840F480701060186F00F4407033 +:1051F000B0F5007F1EBF4FF4803018671967536801 +:1052000023F40073536000F073B900BF003802400C +:10521000007000403B4B3C4A1A643C4A4FF440410A +:1052200011601A6842F001021A601A689007FCD5F2 +:105230009A6822F003029A60324B9A6812F00C02CC +:10524000FBD1196801F0F90119609A601A6842F4FB +:1052500080321A601A689103FCD55A6F42F001023D +:105260005A67284B5A6F9207FCD5294A5A601A6828 +:1052700042F080721A60254A53685804FCD5214BCD +:105280001A689101FCD5234AC3F884201A6842F0B9 +:1052900080621A601A681201FCD51F4A9A600322C4 +:1052A000C3F88C204FF00062C3F894201B4B1A689F +:1052B0001B4B9A421B4B21D11B4A11681B4A91423E +:1052C0001CD140F203121A60164A136803F00F0350 +:1052D000032BFAD10B4B9A6842F002029A609A684B +:1052E00002F00C02082AFAD15A6C42F480425A6445 +:1052F0005A6E42F480425A665B6E704740F2037207 +:10530000E1E700BF003802400004001000700040D8 +:10531000081940021030002400948838002004E06E +:1053200011640020003C024000ED00E041C20F414A +:10533000074A08B5536903F00103536123B1054AD5 +:1053400013680BB150689847BDE80840FEF74EBEA1 +:10535000003C014040610020074A08B5536903F052 +:105360000203536123B1054A93680BB1D068984793 +:10537000BDE80840FEF73ABE003C01404061002015 +:10538000074A08B5536903F00403536123B1054A82 +:1053900013690BB150699847BDE80840FEF726BE77 +:1053A000003C014040610020074A08B5536903F002 +:1053B0000803536123B1054A93690BB1D06998473B +:1053C000BDE80840FEF712BE003C014040610020ED +:1053D000074A08B5536903F01003536123B1054A26 +:1053E000136A0BB1506A9847BDE80840FEF7FEBD4E +:1053F000003C014040610020164B10B55C6904F48C +:1054000078725A61A30604D5134A936A0BB1D06A25 +:105410009847600604D5104A136B0BB1506B984740 +:10542000210604D50C4A936B0BB1D06B9847E2056B +:1054300004D5094A136C0BB1506C9847A30504D5E9 +:10544000054A936C0BB1D06C9847BDE81040FEF74D +:10545000CDBD00BF003C014040610020194B10B59C +:105460005C6904F47C425A61620504D5164A136DE6 +:105470000BB1506D9847230504D5134A936D0BB1BA +:10548000D06D9847E00404D50F4A136E0BB1506EEF +:105490009847A10404D50C4A936E0BB1D06E98477F +:1054A000620404D5084A136F0BB1506F9847230468 +:1054B00004D5054A936F0BB1D06F9847BDE81040F3 +:1054C000FEF794BD003C01404061002008B5034850 +:1054D000FEF728FEBDE80840FEF788BD245C0020EA +:1054E00008B5FFF741FEBDE80840FEF77FBD0000AC +:1054F000062108B50846FEF797FE06210720FEF7AD +:1055000093FE06210820FEF78FFE06210920FEF7F4 +:105510008BFE06210A20FEF787FE06211720FEF7E4 +:1055200083FE06212820FEF77FFE07211C20FEF7C0 +:105530007BFEBDE808400C212620FEF775BE00006A +:1055400008B5FFF725FE00F009F8FFF715F8FFF79B +:10555000E5FDBDE80840FFF717BD00000023054A40 +:1055600019460133102BC2E9001102F10802F8D1EB +:10557000704700BF406100200B460146184600F00E +:105580002DB8000000F040B8012838BF012010B548 +:105590000446204600F030F830B900F007F808B9AA +:1055A00000F00CF88047F4E710BD0000024B1868CB +:1055B000BFF35B8F704700BFC061002008B50620B5 +:1055C00000F084F80120FFF789FA0000024B0A4638 +:1055D00001461868FFF7BCBB2423002010B5054C1A +:1055E00013462CB10A4601460220AFF3008010BDDD +:1055F0002046FCE700000000024B01461868FFF758 +:10560000ABBB00BF24230020024B01461868FFF704 +:10561000A7BB00BF2423002010B5013902449042EB +:1056200001D1002005E0037811F8014FA34201D019 +:10563000181B10BD0130F2E72DE9F041A3B1C91AE2 +:1056400017780144044603F1FF3C8C42204601D9FF +:10565000002009E00578BD4204F10104F5D10CEB0E +:105660000405D618A54201D1BDE8F08115F8018DD9 +:1056700016F801EDF045F5D0E7E700001F2938B531 +:1056800004460D4604D9162303604FF0FF3038BDA1 +:10569000426C12B152F821304BB9204600F030F87C +:1056A0002A4601462046BDE8384000F017B8012BD5 +:1056B0000AD0591C03D1162303600120E7E7002418 +:1056C00042F82540284698470020E0E7024B014673 +:1056D0001868FFF7D3BF00BF2423002038B5074D5B +:1056E00000230446084611462B60FFF7FBF9431CD4 +:1056F00002D12B6803B1236038BD00BFC461002014 +:10570000FFF7EAB9034611F8012B03F8012B002A31 +:10571000F9D170476F72672E6172647570696C6F32 +:10572000742E486F6C7962726F475053000000000E +:1057300053544D3332463F3F3F0053544D3332466E +:105740003430780053544D33324634327800535459 +:105750004D333246343436585800000001203300AF +:105760000010410001105A000310590007103100C9 +:105770000000000030570008130400003A570008EA +:105780001904000044570008210400004E57000887 +:1057900040A2E4F1646891060041A3E5F2656992D4 +:1057A000070000004261642043414E496661636521 +:1057B00020696E6465782E00000100000001FF0082 +:1057C000006400400068004080000000008000008D +:1057D0000000800000000000000000001D24000800 +:1057E000A92C0008B52B00082D240008612400080E +:1057F0005D260008312400084124000835240008F3 +:105800003D240008392400088525000845240008A7 +:10581000A92F00085524000859250008009600000B +:105820000000000000000000000000000000000078 +:1058300000000000394500082545000861450008C2 +:105840004D45000859450008454500083145000808 +:105850001D4500086D4500086330000058580008D9 +:10586000E85E0020F86000200040000000400000DA +:1058700000400000004000000000010000000200A5 +:1058800000000200000002006D61696E0069646C36 +:1058900065000000A001812A00000000AAA9AAAAB0 +:1058A00050000124EFFF0000007700000090090085 +:1058B0001000004A000000009AAAAAAA00000000F6 +:1058C000FBFF000000000000000099000000000045 +:1058D00000000000AAAAAAAA00000000FFFF000022 +:1058E00000000000000000000000000000000000B8 +:1058F000AAAAAAAA00000000FFFF00000000000002 +:10590000000000000000000000000000AAAAAAAAEF +:1059100000000000FFFF0000000000000000000089 +:105920000000000000000000AAAAAAAA00000000CF +:10593000FFFF000000000000000000000000000069 +:1059400000000000AAAAAAAA00000000FFFF0000B1 +:105950000000000000000000000000000000000047 +:105960000A0000000000000003000000000000002A +:1059700000000000ACA8FF7F010000000000000054 +:105980000B04000000000000000007000000000001 +:1059900040420F00FE2A0100D2040000FF00000078 +:1059A000245C0020282300200000000000000000EC +:1059B00000000000000000000000000000000000E7 +:1059C00000000000000000000000000000000000D7 +:1059D00000000000000000000000000000000000C7 +:1059E00000000000000000000000000000000000B7 +:1059F00000000000000000000000000000000000A7 +:085A000000000000000000009E :00000001FF diff --git a/Tools/bootloaders/JFB110_bl.bin b/Tools/bootloaders/JFB110_bl.bin new file mode 100755 index 00000000000000..06d3969c94474a Binary files /dev/null and b/Tools/bootloaders/JFB110_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-ADSB_bl.bin b/Tools/bootloaders/MatekL431-ADSB_bl.bin new file mode 100755 index 00000000000000..017ff999e0d358 Binary files /dev/null and b/Tools/bootloaders/MatekL431-ADSB_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-ADSB_bl.hex b/Tools/bootloaders/MatekL431-ADSB_bl.hex new file mode 100644 index 00000000000000..5718b9a9ff16fd --- /dev/null +++ b/Tools/bootloaders/MatekL431-ADSB_bl.hex @@ -0,0 +1,1160 @@ +:020000040800F2 +:1000000000090020B5040008C52500087D2500086A +:10001000A52500087D2500089D250008B7040008D7 +:10002000B7040008B7040008B7040008B935000891 +:10003000B7040008B7040008B7040008B7040008B4 +:10004000B7040008B7040008B7040008B7040008A4 +:10005000B7040008B7040008554300087D430008B2 +:10006000A5430008CD430008F5430008B704000885 +:10007000B7040008B7040008B7040008B704000874 +:10008000B7040008B7040008B704000831250008C9 +:100090005D2500086D250008B70400081D44000810 +:1000A000B7040008B7040008B7040008B704000844 +:1000B000F1440008B7040008B7040008B7040008BA +:1000C000B7040008B7040008B7040008B704000824 +:1000D000B7040008B7040008B7040008B704000814 +:1000E00081440008B7040008B7040008B7040008FA +:1000F000B7040008B7040008B7040008B7040008F4 +:10010000B7040008B7040008B7040008B7040008E3 +:10011000B7040008B7040008B7040008B7040008D3 +:10012000B7040008B7040008B7040008B7040008C3 +:10013000B7040008B7040008B7040008B7040008B3 +:10014000B7040008B7040008B7040008B7040008A3 +:10015000B7040008B7040008B7040008B704000893 +:10016000B7040008B7040008B7040008B704000883 +:10017000B7040008B7040008B7040008B704000873 +:10018000B7040008B7040008B7040008B704000863 +:10019000B7040008B7040008B7040008B704000853 +:1001A000091200080000000000000000000000002C +:1001B00053B94AB9002908BF00281CBF4FF0FF31CE +:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA +:1001D00000F006F8DDF804E0DDE9022304B0704722 +:1001E0002DE9F047089D04468E46002B4DD18A42EA +:1001F000944669D9B2FA82F252B101FA02F3C2F11D +:10020000200120FA01F10CFA02FC41EA030E9440AD +:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE +:1002200016E341EA034306FB07F199420AD91CEBA6 +:10023000030306F1FF3080F01F81994240F21C81D8 +:10024000023E63445B1AA4B2B3FBF8F008FB103320 +:1002500044EA034400FB07F7A7420AD91CEB040455 +:1002600000F1FF3380F00A81A74240F20781644425 +:10027000023840EA0640E41B00261DB1D4400023AA +:10028000C5E900433146BDE8F0878B4209D9002D0E +:1002900000F0EF800026C5E9000130463146BDE898 +:1002A000F087B3FA83F6002E4AD18B4202D3824202 +:1002B00000F2F980841A61EB030301209E46002DB1 +:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 +:1002D000002A40F09280A1EB0C014FEA1C471FFA64 +:1002E0008CFE0126200CB1FBF7F307FB131140EA4B +:1002F00001410EFB03F0884208D91CEB010103F118 +:10030000FF3802D2884200F2CB804346091AA4B2D9 +:10031000B1FBF7F007FB101144EA01440EFB00FEAD +:10032000A64508D91CEB040400F1FF3102D2A64512 +:1003300000F2BB800846A4EB0E0440EA03409CE7B1 +:10034000C6F12007B34022FA07FC4CEA030C20FA5E +:1003500007F401FA06F31C43F9404FEA1C4900FA7E +:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB +:1003700040EA014108FB0EF0884202FA06F20BD96E +:100380001CEB010108F1FF3A80F08880884240F2BE +:100390008580A8F102086144091AA4B2B1FBF9F002 +:1003A00009FB101144EA014100FB0EFE8E4508D9FD +:1003B0001CEB010100F1FF346CD28E456AD9023882 +:1003C000614440EA0840A0FB0294A1EB0E01A14267 +:1003D000C846A64656D353D05DB1B3EB080261EBD5 +:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF +:1003F000007100263146BDE8F087C2F12003D840E5 +:100400000CFA02FC21FA03F3914001434FEA1C4726 +:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 +:10042000064300FB0EF69E4204FA02F408D91CEBC8 +:10043000030300F1FF382FD29E422DD902386344C6 +:100440009B1B89B2B3FBF7F607FB163341EA034166 +:1004500006FB0EF38B4208D91CEB010106F1FF38B5 +:1004600016D28B4214D9023E6144C91A46EA0046AC +:1004700038E72E46284605E70646E3E61846F8E63E +:100480004B45A9D2B9EB020864EB0C0E0138A3E787 +:100490004646EAE7204694E74046D1E7D0467BE768 +:1004A000023B614432E7304609E76444023842E7E0 +:1004B000704700BF02E000F000F8FEE772B6374870 +:1004C00080F30888364880F3098836483649086042 +:1004D00040F20000CCF200004EF63471CEF2000182 +:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 +:1004F000F0004EF68851CEF200010860BFF34F8F36 +:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 +:10051000CEF200010860062080F31488BFF36F8FCD +:1005200003F034FD03F0B6FD4FF055301F491B4A70 +:1005300091423CBF41F8040BFAE71D49184A914229 +:100540003CBF41F8040BFAE71A491B4A1B4B9A427D +:100550003EBF51F8040B42F8040BF8E7002018499D +:10056000184A91423CBF41F8040BFAE703F012FD30 +:1005700003F0E2FD144C154DAC4203DA54F8041BB1 +:100580008847F9E700F042F8114C124DAC4203DA0B +:1005900054F8041B8847F9E703F0FABC000900206F +:1005A000001100200000000808ED00E0000100201C +:1005B00000090020D8470008001100207C1100200D +:1005C00080110020003B0020A0010008A4010008C9 +:1005D000A4010008A40100082DE9F04F2DED108AB8 +:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 +:1005F000002383F311882846A047002003F072F9F6 +:10060000FEE703F0D5F800DFFEE70000F8B500F0E4 +:100610000DFE03F05DFC074603F0AEFC0546D0BBC3 +:10062000294B9F4237D001339F4237D0274B27F0C9 +:10063000FF029A4235D1F8B200F03EFC2E4642F25B +:10064000107400F03FFC08B10024264601F0A8F821 +:1006500058B3032000F03EF80024264635B11C4B69 +:100660009F4203D003F080FC00242646002003F0C4 +:1006700039FC0EB100F044F800F056FC00F0D8FD53 +:1006800001F0A8FF0546B4B900F096FC4FF47A706B +:1006900003F02EF9F7E72E460024D2E704460126A0 +:1006A000CFE706464FF47A74CBE7002CD6D04FF450 +:1006B0007A740126D2E701F08DFF431BA342E3D9F0 +:1006C00000F01EF8DCE700BF010007B0000008B032 +:1006D000263A09B0084B187003280CD8DFE800F060 +:1006E00008050208022000F001BE022000F0F4BD5F +:1006F000024B00225A6070478011002084110020B4 +:1007000010B501F04DF830B1234B03221A70234B82 +:1007100000225A6010BD224B224A1C461968013142 +:10072000F8D004339342F9D16268A242F2D31E4B4F +:100730009B6803F1006303F520439A42EAD203F079 +:10074000E5FB03F0F7FB002000F08CFD0220FFF733 +:10075000C1FF164B9A6D00229A65996F9A67996F3F +:10076000D96DDA65D96FDA67D96F196E1A66D3F861 +:100770008010C3F88020D3F8803072B64FF0E023A9 +:100780003021C3F8084DD4E9003281F311889D4629 +:1007900083F308881047BDE78011002084110020F2 +:1007A00000A0000820A00008001100200010024056 +:1007B000094A136849F2690099B21B0C00FB013326 +:1007C0001360064B186844F2506182B2000C01FBC2 +:1007D0000200186080B27047141100201011002030 +:1007E00010B500211022044600F09AFD034B03CB04 +:1007F000206061601868A06010BD00BF9075FF1F89 +:100800002DE9F041ADF5507D0DF13C086EAC40F2A4 +:10081000751207460D4610A80021C8F8001000F018 +:100820007FFD4FF4C4720021204600F079FD01F0F5 +:10083000D1FE254B4FF47A72B0FBF2F0186093E8CA +:100840000700022384E807000DF5ED702382FFF70F +:10085000C7FF42F204631D49238407A803F054FF35 +:100860001C2384F832310DF2EB226B440DF1340C71 +:100870001E4603CE664510605160334602F1080201 +:10088000F6D13068106041460122204600F094FD08 +:1008900000230393AB7E029305F11903019380B209 +:1008A0000123CDE904800093E97E05A3D3E9002369 +:1008B000384602F057FA0DF5507DBDE8F08100BFD3 +:1008C0009E6AC421818A46EE8C11002018470008D8 +:1008D0002DE9F0412C4C237ADAB080460D465BBB03 +:1008E00027A9284600F078FE0746002842D19DF847 +:1008F0009D60C82E3ED801464FF4A662204600F007 +:100900000FFD4FF48073C4F8F8314FF40073C4F84E +:100910000C334FF44073C4F8203432460DF19E017D +:1009200004F1090000F0EAFC26449DF89C3077723F +:1009300023720BB9EB7E23728122002106AC27A81B +:1009400000F0EEFC0122214627A800F081FE0023E2 +:100950000393AB7E029305F1190380B20193282320 +:10096000CDE904400093E97E05A3D3E90023404686 +:1009700002F0F8F95AB0BDE8F08100BFAFF3008093 +:1009800026417272DF25D7B7A8320020F0B5254E78 +:100990004FF48A7505FB0065F1B096F8D83085F8FC +:1009A000DC300024D822214685F8E8403AA800F03F +:1009B000B7FC06F1090000F0ABFCD5F8E4308DF887 +:1009C000F000C2B206AF06F109010DF1F100CDE968 +:1009D0003A3400F093FC394601223AA800F064FE54 +:1009E00080B2CDE9047008230127CDE9023706F172 +:1009F000D803019330230093317A0B4807A3D3E93E +:100A0000002302F0AFF9A04206DD01F0E3FDC5F8D6 +:100A1000E000384671B0F0BD2046FBE778F6339F22 +:100A200093CACD8DA8320020A42100202DE9F041E9 +:100A30001D4D1E4E1E4F86B0284602F0BFF90346DC +:100A400058B30024CDE90344ADF81440027B8DF87F +:100A5000142099684068029403AA03C21B68DFF857 +:100A6000548043F00043029301F0B6FD821941F136 +:100A70000003009402A9384601F078F8A04205DD91 +:100A8000284602F09FF988F80040D5E798F8003032 +:100A9000072B05D8013388F8003006B0BDE8F08197 +:100AA000014802F08FF9F8E7A421002040420F002E +:100AB000D8210020DD37002070B50D4614461E46B3 +:100AC00002F0ACF850B9022E10D1012C0ED112A3B5 +:100AD000D3E90023C5E90023012007E0282C10D02A +:100AE00005D8012C09D0052C0FD0002070BD302C6A +:100AF000FBD10BA3D3E90023ECE70BA3D3E900233D +:100B0000E8E70BA3D3E90023E4E70BA3D3E9002331 +:100B1000E0E700BFAFF30080401DA12026812A0B33 +:100B200078F6339F93CACD8D9E6AC421818A46EEA2 +:100B300026417272DF25D7B7F017304A39059E5625 +:100B400038B505460E4C0021013500F0ADFBA4F888 +:100B50002C55B4F82C0500F08FFB78B1B4F82C05B7 +:100B600000F09AFB014648B9B4F82C0500F09CFB54 +:100B7000B4F82C350133A4F82C35EAE738BD00BFB2 +:100B8000A832002010B50A4B0A4A1A6003F58053B8 +:100B900093F860203AB9DC6D2CB1204600F07EFE5F +:100BA000204603F0F1FCBDE81040034800F076BE9B +:100BB000D821002074470008203200202DE9F04F92 +:100BC0008FB000AF05460C4602F028F8002849D146 +:100BD000237E022B1BD1E38A012B18D101F0FAFCF2 +:100BE0000646FFF7E5FD03464FF4C870DFF8C48200 +:100BF000B3FBF0F206F5167602FB103316FA83F318 +:100C0000C8F80030E37E33B9A34B00221A703C379A +:100C1000BD46BDE8F08F07F12401204600F09AFCA4 +:100C20000028F4D107F11400FFF7DAFD97F8264009 +:100C300007F11401224607F1270003F0EFFC00281A +:100C4000E2D10F2C08D8944B1C70D8F80030A3F5D3 +:100C50001673C8F80030DAE797F82410284601F038 +:100C6000D5FFD4E7E38A282B2BD010D8012B23D033 +:100C7000052BCCD1BFF34F8F8849894BCA6802F44A +:100C8000E0621343CB60BFF34F8F00BFFDE7302B13 +:100C9000BDD1844EE17E327A9142B8D1607E314638 +:100CA000002291F8DC50854200F0A5800132042A30 +:100CB00001F58A71F5D1AAE721462846FFF7A0FD84 +:100CC000A5E721462846FFF703FEA0E7B2F8EC505F +:100CD0007B6005F103094FEA99094FEA8902D11DAA +:100CE000C908A8EBC1039D46EB460021584600F019 +:100CF00017FB04F1EE012A463144584600F0FEFA93 +:100D00007B6813B9012000F0ADFA96F8D20000F02C +:100D1000B3FA044630B9307200F0CEFA204600F043 +:100D2000A1FAB1E0D6F8D4203AB996F8D200B6F8D4 +:100D30002C25824201D8FFF703FFD6F8D4202A449D +:100D4000944208D296F8D200B6F82C25013082429F +:100D500001D8FFF7F5FE70685FFA89F2594600F096 +:100D6000E7FA08B9C54679E0726896F8D2002A44D5 +:100D70007260D6F8D42005EB0209C6F8D49000F0D2 +:100D80007BFA814509D396F8D220D6F8D4000132F7 +:100D9000001B86F8D220C6F8D400FF2D0FD80024FF +:100DA000347200F089FA204600F05CFA00F0F8FC9A +:100DB0003D4B188108B9FFF7A3FCC54627E7BB6880 +:100DC00096F8D9000AFB0362FB68D2F8E41082F8B7 +:100DD000E83001F58061C2F8E030C2F8E410FFF7B6 +:100DE000D5FDFFF723FE96F8D920013202F0030269 +:100DF00086F8D920B6E74FF48A7A0AFB02F505F1A6 +:100E0000EA013144204600F07BFCF86000287FF4C2 +:100E1000FEAE3544012285F8E82001F0DBFBD5F871 +:100E2000E020D6ED007ADFED216A801A192838BF5C +:100E3000192040F6B832904228BF1046B8EE677AC3 +:100E400007EE900AF8EEE77A67EEA67ADFED186A09 +:100E5000E7EE267AFCEEE77AC6ED007A96F8D9300E +:100E6000BB60BA6873680AFB02F4321992F8E810A2 +:100E700059B1D2F8E4108B42E8463FF427AF002185 +:100E800082F8E810C2F8E010C5467368064A9B0A6B +:100E900001331381BBE600BF9D21002000ED00E07F +:100EA0000400FA05A83200208C110020CDCCCC3DE6 +:100EB0006666663FA0210020014B1870704700BF96 +:100EC0009811002038B54FF00054134B22689A4215 +:100ED00020D1124B627D12481A70237D03724FF4A9 +:100EE0008073C0F8F8314FF40073C0F80C3300255C +:100EF0004FF44073C0F820340A49C0F8E450C922C6 +:100F0000093000F0FBF9E0222946204600F008FAFB +:100F1000012038BD0020FCE79AAD44C5981100209F +:100F2000A83200201600002037B500F039FC194D1A +:100F3000194928810223012218486B7101F0E8F950 +:100F400000230193164B174900931748174B4FF492 +:100F5000805201F033FE164B197811B1124801F09E +:100F600055FE01F037FB0446FFF722FC4FF4C8732F +:100F7000B0FBF3F202FB130304F5167010FA83F0D2 +:100F80000C4B186002F0F8FF08B10F232B8103B05F +:100F900030BD00BF8C11002040420F00D82100203E +:100FA000B90A00089C110020A4210020BD0B0008F4 +:100FB00098110020A02100202DE9F04F2DED028B8B +:100FC0000FF23829D9E90089834C93B00BAE9FED1D +:100FD0007E8BFFF72BFD814FDFF828A200230A93B9 +:100FE000ADF834300B9373604FF0000B5B468DED22 +:100FF000008B01250DF11D0207A938468DF81C5004 +:101000008DF81DB001F034F99DF81C30002B40F034 +:10101000A580204601F002FE0646002845D1704F0B +:1010200001F0D8FA3B6898423FD301F0D3FA8246E8 +:10103000FFF7BEFB4FF4C873B0FBF3F202FB1303E0 +:101040000AF5167010FA83F03860664F97F800B012 +:10105000CBF1100ABBF1000F14BF33462B465FFAE9 +:101060008AFA0EA88DF82830FFF7BAFBBAF1060FFE +:1010700028BF4FF0060A0EAB03EB0B0152460DF1F1 +:10108000290000F03BF90AAB0393182302930AF1FD +:101090000102554BD2B2CDE90053049220464CA335 +:1010A000D3E9002301F000FE3E7001F093FA4F4AAD +:1010B0004F4D1368C31AB3F57A7F2ED3106001F039 +:1010C0008BFA02460B46204601F086FE204601F0D0 +:1010D000A5FD10B32B7A474E002B14BF0323022328 +:1010E000737101F077FA0EAF4FF47A730122B0FBFF +:1010F000F3F039463060304600F004FA18230293CA +:101100003D4B019380B240F25513CDE9037000933B +:1011100042464B46204601F0C7FD2B7A93B101F0C1 +:1011200059FA002607464FF48A7A95F8D9003044D8 +:1011300000F003000AFB005393F8E82092B3013655 +:10114000042EF2D1C82002F0D3FB2B7A002B7FF4BF +:101150003DAF13B0BDEC028BBDE8F08FDAF8143070 +:1011600083F00803CAF81430594610220EA800F084 +:10117000D7F80DF11E0308AA0AA9384600F0F4FDBD +:1011800096E803000FAB83E803009DF834308DF838 +:1011900044300A9B0E930EA9DDE90823204601F096 +:1011A000EFFF21E7D3F8E02042B12B68FA2B38BFDC +:1011B000FA23BA1A0533B2EB430FC0D3FFF7E6FBAD +:1011C0000028BCD1BEE700BF000000000000000006 +:1011D000401DA12026812A0BA4210020D821002017 +:1011E000A02100209D2100209C210020D837002034 +:1011F000A83200208C110020DC370020F1C6A7C1E6 +:10120000D068080F0004004808B5054800F046FE05 +:10121000BDE80840034A0449002003F0AFB900BF0D +:10122000D821002018380020850B000870470000E6 +:1012300070B502F0E9FC094E094D308000242868A1 +:101240003388834208D902F0DBFC2B680444013365 +:10125000B4F5204F2B60F2D370BD00BF0C380020D6 +:10126000E037002002F082BD00F10060920000F53E +:10127000204002F005BD0000054B1A68054B1B8895 +:101280009B1A834202D9104402F0BABC0020704776 +:10129000E03700200C380020024B1B68184402F095 +:1012A000B5BC00BFE0370020024B1B68184402F0B9 +:1012B000BFBC00BFE0370020064991F8243033B1AD +:1012C0000023086A81F824300822FFF7CDBF0120EF +:1012D000704700BFE4370020022802BF024B4FF4E2 +:1012E00000229A61704700BF00040048022802BF34 +:1012F000014B08229A6170470004004810B5002392 +:10130000934203D0CC5CC4540133F9E710BD000014 +:1013100003460246D01A12F9011B0029FAD1704780 +:1013200002440346934202D003F8011BFAE77047D8 +:101330002DE9F8431F4D144695F8242007468846AA +:1013400052BBDFF870909CB395F824302BB9202263 +:10135000FF2148462F62FFF7E3FF95F82400C0F114 +:101360000802A24228BF2246D6B24146920005EBAF +:101370008000FFF7C3FF95F82430A41B1E44F6B28B +:10138000082E17449044E4B285F82460DBD1FFF7BF +:1013900093FF0028D7D108E02B6A03EB8203834236 +:1013A000CFD0FFF789FF0028CBD10020BDE8F8831C +:1013B0000120FBE7E43700202DE9F0470D46044605 +:1013C00000219046284640F27912FFF7A9FF2346F4 +:1013D00020220021284601F075FE231D0222202133 +:1013E000284601F06FFE631D03222221284601F0EA +:1013F00069FEA31D03222521284601F063FE04F1A6 +:10140000080310222821284601F05CFE04F1100395 +:1014100008223821284601F055FE04F11103082264 +:101420004021284601F04EFE04F112030822482113 +:10143000284601F047FE04F11403202250212846DB +:1014400001F040FE04F1180340227021284601F00B +:1014500039FE04F120030822B021284601F032FEB3 +:1014600004F121030822B821284601F02BFE04F1E3 +:101470002207C0263B46314608222846083601F09E +:1014800021FEB6F5A07F07F10107F3D104F1320385 +:1014900008223146284601F015FE002704F1330AE0 +:1014A00094F832304FEAC7099F4209F5A47615D364 +:1014B000B8F1000F08D1314604F599730722284688 +:1014C00001F000FE09F24F16274694F832213B1B2B +:1014D00093420CD3F01DC008BDE8F0870AEB070368 +:1014E00008223146284601F0EDFD0137D8E707F222 +:1014F000331331460822284601F0E4FD083601374F +:10150000E3E7000013B504460846002101602346C6 +:10151000C0F803102022019001F0D4FD0198231D92 +:101520000222202101F0CEFD0198631D0322222119 +:1015300001F0C8FD0198A31D0322252101F0C2FD81 +:10154000019804F108031022282101F0BBFD0720B7 +:1015500002B010BDF7B50023047F00910E460722AC +:101560001946054601F072FC731C0093012200230A +:101570000721284601F06AFCC4B9B31C0093052278 +:1015800023460821284601F061FC0D243746B27835 +:10159000BB1B934211D32B7FA88A0734E408BBB945 +:1015A000844294BF0020012003B0F0BDAB8ADB0071 +:1015B000083BDB08B3700824E8E7FB1C00932146D6 +:1015C00000230822284601F041FC08340137DEE7F9 +:1015D000201A18BF0120E7E7F7B50023047F009128 +:1015E0000E4608221946054601F030FC731CC4B9AA +:1015F0000822009311462346284601F027FC1024B8 +:10160000012372785F1C013B934211D32B7FA88A80 +:101610000734E408BBB9844294BF0020012003B022 +:10162000F0BDAB8ADB00083BDB0873700824E7E7FA +:10163000F3190093214600230822284601F006FCF6 +:1016400008343B46DDE7201A18BF0120E7E7000019 +:10165000F8B50E4605461446002181223046FFF7B4 +:101660005FFE2B4608220021304601F02BFD7CB99D +:101670006B1C07220821304601F024FD0F240123B2 +:101680006A785F1C013B934204D3E01DC008F8BD9B +:101690000824F4E7EB1921460822304601F012FD38 +:1016A00008343B46ECE70000F8B50E460546144604 +:1016B0000021CE223046FFF733FE2B4628220021A0 +:1016C000304601F0FFFC7CB905F10803082228210F +:1016D000304601F0F7FC30242F462A7A7B1B9342D8 +:1016E00004D3E01DC008F8BD2824F5E707F109037D +:1016F00021460822304601F0E5FC08340137ECE7CA +:10170000F7B5047F00910E46012310220021054603 +:1017100001F09CFBC4B9B31C00930922234610219D +:10172000284601F093FB192437467288BB1B9A4266 +:1017300011D82B7FA88A0734E408BBB9844294BF30 +:101740000020012003B0F0BDAB8ADB00103BDB08BA +:1017500073801024E8E73B1D0093214600230822F4 +:10176000284601F073FB08340137DEE7201A18BF62 +:101770000120E7E730B5094D0A4491420DD011F838 +:10178000013B5840082340F30004013B2C4013F078 +:10179000FF0384EA5000F6D1EFE730BD2083B8EDB7 +:1017A000F7B5384A106851686B4603C36A46364934 +:1017B0003648082302F042FF0446002833D10A25A8 +:1017C000334A106851686B4603C36A4631492F4853 +:1017D000082302F033FF0446002849D00369B3F51B +:1017E000583F45D8B0F8661040F2264291423FD1AA +:1017F000294A024402F15C018B4239D35C3B234904 +:1018000000209E1AFFF7B6FF3246074604F1640136 +:101810000020FFF7AFFFA3689F4229D1E3689842F9 +:1018200008BF002524E00369B3F5583F27D8418B52 +:1018300040F22642914220D1174A024402F110019F +:101840008B4218D3103B114900209D1AFFF792FFDD +:101850002A46064604F118010020FFF78BFFA36813 +:101860009E4202D1E368984201D00D25A8E70025E9 +:10187000284603B0F0BD1025A2E70C25A0E70B25F4 +:101880009EE700BF38470008DC5F030000A00008A7 +:1018900041470008905F03000860FFF710B5037C24 +:1018A000044613B9006802F0B1FE204610BD0000E6 +:1018B0000023BFF35B8FC360BFF35B8FBFF35B8F0E +:1018C0008360BFF35B8F7047BFF35B8F0068BFF32C +:1018D0005B8F704770B505460C30FFF7F5FF05F1DB +:1018E000080604463046FFF7EFFFA04206D930460F +:1018F0006D68FFF7E9FF2544281A70BD3046FFF7F1 +:10190000E3FF201AF9E7000070B50546406898B17A +:1019100005F10800FFF7D8FF05F10C060446304634 +:10192000FFF7D2FF8442304694BF6D680025FFF771 +:10193000CBFF013C2C44201A70BD000038B50C468A +:101940000546FFF7C7FFA04210D305F10800FFF7D7 +:10195000BBFF04446868B4FBF0F100FB1144BFF323 +:101960005B8F0120AC60BFF35B8F38BD0020FCE7CC +:101970002DE9F041144607460D46FFF7C5FF8442A6 +:1019800028BF0446D4B1B84658F80C6B4046FFF760 +:101990009BFF3044286040467E68FFF795FF331A6E +:1019A0009C4203D86C600120BDE8F0816B60A41BF1 +:1019B0003B68AB602044E8600220F5E72046F3E78F +:1019C00038B50C460546FFF79FFFA04210D305F13E +:1019D0000C00FFF779FF04446868B4FBF0F100FBEA +:1019E0001144BFF35B8F0120EC60BFF35B8F38BD08 +:1019F0000020FCE72DE9FF41884669460746FFF7CE +:101A0000B7FF6C4606B204EBC6060025B44209D007 +:101A10006268206808EB0501FFF770FC6368083412 +:101A20001D44F3E729463846FFF7CAFF284604B0AD +:101A3000BDE8F081F8B505460C300F46FFF744FFCE +:101A400005F1080604463046FFF73EFFA042304647 +:101A500088BF6C68FFF738FF201A386020B1304625 +:101A60002C68FFF731FF2044F8BD000073B5144621 +:101A700006460D46FFF72EFF844228BF044601901C +:101A8000DCB101A93046FFF7D5FF019B33B93268BD +:101A9000C5E90233C5E9002401200CE09C4238BFAF +:101AA00001942860019868608442F5D93368AB607E +:101AB000241AEC60022002B070BD2046FBE7000053 +:101AC0002DE9FF410F466946FFF7D0FF6C4600B293 +:101AD00004EBC0050026AC4209D0D4F8048054F8C9 +:101AE000081BB8194246FFF709FC4644F3E73046A5 +:101AF00004B0BDE8F081000038B50546FFF7E0FF0F +:101B0000044601462846FFF719FF204638BD00006D +:101B1000302383F3118862B670470000002383F3FB +:101B2000118862B67047000010B4026854681A4603 +:101B300023465DF8044B184701207047002070478A +:101B40000020704770470000002070470E2070474B +:101B500000F5805090F8C800C0F3400070470000C6 +:101B600000F5805090F9C90070470000F7B50C6887 +:101B7000BDF8207014F000541E466FD10B7B082B6B +:101B80006CD8FFF7C5FF4569AB685B010CD4AB6847 +:101B90001B0108D4AC6814F080545DD1FFF7BEFF80 +:101BA000204603B0F0BD01240B6804F1180C002B93 +:101BB000B8BFDB004FEA0C1CB4BF43F004035B0565 +:101BC00045F80C300B680FFA84FC13F0804F18BFF7 +:101BD00005EB0C1E05EB0C1C1EBFDEF8803143F03C +:101BE0000203CEF880310B7BCCF8843105EB041571 +:101BF0008B68C5F88C314B68C5F88831DCF88031CA +:101C000043F00103CCF8803100EB441541F2680346 +:101C10001D4403EB44130344C5E9002608330D4675 +:101C200001F10C0C55F804EB43F804EB6545F9D1D0 +:101C300084342D881D8000EB441407F003032579BC +:101C400025F00B052B432371FFF768FF0097334600 +:101C500000F0E2FC0120A4E70224A5E74FF0FF30EA +:101C60009FE7000013B500F580540191E06DFFF788 +:101C70004BFE1F280AD90199E06D2022FFF7BAFE1A +:101C8000A0F120035842584102B010BD0020FBE7EC +:101C900008B500F58050FFF73BFFC06DFFF708FE69 +:101CA000BDE80840FFF73ABF00220260828142602F +:101CB0008260704710B500220023C0E90023002392 +:101CC000044603810C30FFF7EFFF204610BD0000F3 +:101CD000F0B5054600F580500C4690F8C83013F07A +:101CE000040FC3F3800108BF114661F3820304F1BE +:101CF000840680F8C83005EB461389B01B79D807F5 +:101D00002ED57AB319072DD46846FFF7D3FF05EB1C +:101D1000441303F5835303F1180703AA103318681B +:101D20005968144603C40833BB422246F7D11868E9 +:101D300020609B88A380DDE90E23CDE900230123E9 +:101D4000ADF808302B686946DB6B2846984705EBF1 +:101D500046152B791A075CBF43F008032B7101E08D +:101D6000002AF4D109B0F0BD2DE9F047074688B04C +:101D700007F5805468469A468846FFF7C9FE9146A3 +:101D8000FFF798FFE06DFFF7A5FD1F2829D9E06D4B +:101D900020226946FFF7B0FE202822D103AD444639 +:101DA00005AB2E4603CE9E4220606160354604F1AD +:101DB0000804F6D130682060B388A380DDE90023F1 +:101DC000C9E90023BDF80830AAF80030FFF7A6FEE5 +:101DD0004A4653464146384608B0BDE8F04700F051 +:101DE00009BCFFF79BFE002008B0BDE8F0870000AB +:101DF0002DE9F84F0023C0E90133254B044640F894 +:101E0000183B0F46FFF750FF04F12800FFF752FF81 +:101E100004F1480804F58255464608353046203618 +:101E2000FFF748FFAE42F9D104F580554FF48053D7 +:101E30004FF00009C5E91339C5F848800123EE6564 +:101E400004F5875804F58456C5F8549085F8583041 +:101E500085F86030083608F108084FF0000A4FF0A6 +:101E6000000B46E908ABA6F11800FFF71DFF20366E +:101E700046F8289C4645F4D185F8C97017B1054845 +:101E800000F0A2FB044B63612046BDE8F88F00BF61 +:101E9000744700084C4700080064004010B5044B2C +:101EA000197804464A1C1A70FFF7A2FF204610BD9D +:101EB000143800202DE9F047002950D0294B2A4F33 +:101EC000B7FBF1F599428CBF0A231123581EB5FBCD +:101ED000F3FC03FB1C53C4B22BB102280346F5D814 +:101EE0000020BDE8F0870CF1FF36B6F5806FF7D221 +:101EF000C4EBC40E0EF103034FEAE309C3F3C703B7 +:101F0000A4EB030809F1010A4FF47A755FFA88F02F +:101F100009FB05555AFA88F8B5FBF8F5B5F5617F68 +:101F2000C1BF0EF1FF33C3F3C703E01AC0B25C1C9C +:101F300050FA84F40CFB04F4B7FBF4F4A142CFD1C3 +:101F4000013BDBB20F2BCBD80138C0B20728C7D872 +:101F50000021107116809170D3700120C1E70846EE +:101F6000BFE700BF3F420F0000B4C40470B5054690 +:101F70000E464FF47A746B695B6803F00103B34259 +:101F800007D04FF47A7001F0B3FC013CF3D1204646 +:101F900070BD0120FCE7000030B54269936913F081 +:101FA000700F16D000230B4C936103F1840200EBF9 +:101FB000421211794D0709D5890707D5416954F8AF +:101FC00023508D60117941F0040111710133032B0D +:101FD000EBD130BD6047000873B51D464369164616 +:101FE0009A68D207044609D59A6801219960C2F31C +:101FF0004002CDE900650021FFF76AFE63699A6837 +:10200000D1050BD59A684FF480719960C2F34022D4 +:10201000CDE9006501212046FFF75AFE63699A6801 +:10202000D2030BD59A684FF480319960C2F34042D5 +:10203000CDE9006502212046FFF74AFE204602B0A6 +:10204000BDE87040FFF7A8BFF8B50446466900290F +:102050006CD106F10C07386880076AD006EB0115D1 +:102060003868D5F8B00110F0040FD5F8B0011ABFE8 +:10207000C00840F00040400DA061D5F8B0C11CF090 +:10208000020F1CBF40F08040A061D5F8B40106EB00 +:10209000011100F00F0084F82400D1F8B801207776 +:1020A000D1F8B801000A6077D1F8B801000CA07728 +:1020B000D1F8B801000EE077D1F8BC0184F8200017 +:1020C000D1F8BC01000A84F82100D1F8BC01000C51 +:1020D00084F82200D1F8BC11090E84F823103821AD +:1020E000396004F1340004F1180104F1240551F8B9 +:1020F000046B40F8046BA942F9D109880180C4E956 +:102100000A2321460023238651F8283B2046DB6B17 +:10211000984704F58052204692F8C83043F00403F3 +:1021200082F8C830BDE8F840FFF736BF06F1100767 +:1021300091E7F8BD10B5044600F04EFA02460B4692 +:1021400052EA030102D0013A63F10003044908682E +:1021500020B12146BDE81040FFF776BF10BD00BF9B +:1021600010380020F8B500F583511E46FFF7D0FC6B +:10217000DFF844C00831002404F1840500EB451564 +:102180002B795F070ED4DB060CD5D1E9007397429B +:10219000B34107D243695CF824709F602B7943F008 +:1021A00004032B710134032C01F12001E4D1BDE8BB +:1021B000F840FFF7B3BC00BF6047000808B5FFF761 +:1021C000A7FCFFF7E9FEBDE80840FFF7A7BC000049 +:1021D000F8B543690546986800F0E050B0F1E05F5B +:1021E0000F461FD0E8B1FFF793FC05F58354103478 +:1021F000002606F1840305EB43131B791A0706D565 +:102200000136032E04F12004F3D1012007E05B071F +:10221000F6D42146384600F039FA0028F0D1FFF70D +:102220007DFCF8BD0120FCE700F5805008B5FFF704 +:102230006FFCC06DFFF74EFBFFF770FC43090CBF4E +:102240000120002008BD0000F8B51D4600231370D2 +:102250000F4606461446FFF7E7FF80F0010038708E +:1022600025B129463046FFF7B3FF2070F8BD0000C6 +:102270002DE9B8410C4615461F46804600F0ACF9E2 +:102280000B462178024609B9287850B14046FFF73D +:1022900069FFFFF793FF3B462A462146FFF7D4FF2D +:1022A0000120BDE8B881000010B5FFF731FC174BE5 +:1022B0009A6D42F000729A659A6B42F000729A63CE +:1022C0009A6B00F5805422F000729A63FFF726FCA7 +:1022D00094F8C830DB0718D4B9B103211320FFF7F5 +:1022E00017FC01F0DBF90321142001F0D7F90321D9 +:1022F000152001F0D3F994F8C83043F0010384F8B5 +:10230000C830BDE81040FFF709BC10BD0010024006 +:102310002DE9F04700F5805588B095F8C930012BBC +:102320000446884616467FD8804F57F823200AB9BE +:1023300047F82300D7F800A0C4F80C802674BAF13F +:10234000000F63D095F8C930012B6FD001212046D2 +:10235000FFF7AAFFFFF7DCFB6269136823F00203B3 +:1023600013606269136843F0010313606369002717 +:102370005F6101212046FFF7D1FBFFF7F7FD002841 +:1023800000F09580E86DFFF793FA04F58359BA469B +:1023900009F10809202200216846FEF7C1FF02A8C2 +:1023A000FFF782FCCDF818A06A4609EB07030DF190 +:1023B000180E9446BCE80300F44518605960624664 +:1023C00003F10803F5D1DCF80000186020379CF811 +:1023D00004201A71602FDDD195F8C8306FF38203A5 +:1023E000002785F8C8306A4641462046ADF800709F +:1023F000ADF802708DF80470FFF75CFD636948BBAF +:102400004FF400421A6008B0BDE8F08741F2D000F6 +:1024100002F0BCF8814610B15146FFF7E9FCC7F85D +:102420000090B9F1000F8DD10020ECE73868036807 +:102430001B6B98470146002888D13868FFF734FFA6 +:102440003868036832465B684146984700287FF445 +:102450007DAFE9E761221A609DF802309DF8032004 +:102460001B06120402F4702203F040731343BDF8FC +:102470000020C2F3090213439DF804201205022E26 +:1024800002F4E0020CBF4FF00041002113436269E7 +:102490000B43D361636913225A616269136823F0A5 +:1024A0000103136039462046FFF760FD08B96369F0 +:1024B000A6E795F8C93093BB6169D1F8002242F0D4 +:1024C0000102C1F800226169D1F8002222F47C5295 +:1024D00022F00E02C1F800226169D1F8002242F414 +:1024E0006062C1F800226269C2F814326269C2F8FF +:1024F0000432626941F6FF71C2F80C126269C2F8D7 +:1025000040326269C2F8443263690122C3F81C2276 +:102510006269D2F8003223F00103C2F8003295F864 +:10252000C83043F0020385F8C8306CE7103800204B +:1025300008B500F051F850EA0103024602D0421EED +:1025400061F10001044B186810B10B46FFF744FD20 +:10255000BDE8084001F064B81038002008B500203C +:10256000FFF7E8FDBDE8084001F05AB808B50120C2 +:10257000FFF7E0FDBDE8084001F052B800B59BB0A0 +:10258000EFF3098168226846FEF7B8FEEFF3058392 +:10259000014B9B6BFEE700BF00ED00E008B5FFF7C5 +:1025A000EDFF000000B59BB0EFF30981682268469B +:1025B000FEF7A4FEEFF30583014B5B6BFEE700BF64 +:1025C00000ED00E0FEE700000FB408B5029801F04E +:1025D00025F9FEE701F016BC01F0EEBB13B56C4621 +:1025E00084E80600031D94E8030083E80500012049 +:1025F00002B010BD73B58568019155B11B885B07AA +:1026000007D4D0E900369B6B9847019AC1B2304697 +:10261000A847012002B070BDF0B5866889B00546B4 +:102620000C465EB1BDF838305B070AD4D0E90037FC +:102630009B6B98472246C1B23846B047012009B08B +:10264000F0BD00220023CDE900230023ADF80830BF +:102650000A4603AB01F10806106851681C4603C422 +:102660000832B2422346F7D1106820609288A280D7 +:10267000FFF7B2FF0423ADF808302B68CDE9000165 +:10268000DB6B694628469847D8E7000030B50368F9 +:102690000968DD0FB5EBD17F23F0604421F0604283 +:1026A0004FEAD1700BD0002BB8BFA40C0029B8BFE3 +:1026B000920C944202D034BF0120002030BD9442DD +:1026C00005D1C1F38070C3F380738342F6D1944285 +:1026D0002CBF00200120F1E72DE9F041456A15B932 +:1026E0004162BDE8F0814B6823F06047C3F38A463E +:1026F0004FEAD37EC3F3807816EA230638BF3E46FE +:10270000AC462B465A68BEEBD27F22F060440AD01A +:10271000002A18DAA40CB44217D19D420FD10D60E3 +:10272000DEE71346EEE7A74207D102F08044C2F38A +:10273000807242450BD054B1EFE708D2EDE7CCF8F8 +:1027400000100B60CDE7B44201D0B442E5D81A685E +:102750009C46002AE5D11960C3E700002DE9F04747 +:10276000089D01F007044FEAD508224405F007054B +:1027700000EBD1004FF47F49944201D1BDE8F087CE +:1027800004F0070705F0070A57453E4638BF56468E +:10279000C6F10806111B8E4228BF0E46E10808EB61 +:1027A000D50E415C13F80EC0B94029FA06F721FA9C +:1027B0000AF1FFB28CEA010147FA0AF739408CEAC4 +:1027C000010C03F80EC034443544D5E780EA0120FB +:1027D000082341F2210201B24000002980B203F136 +:1027E000FF33B8BF504013F0FF03F4D1704700002F +:1027F00038B50C468D18A54200D138BD14F8011B20 +:10280000FFF7E4FFF7E7000042684AB1136843604E +:102810004389818901339BB29942438138BF8381C7 +:102820001046704770B588B0202204460D466846B1 +:102830000021FEF775FD20460495FFF7E5FF0246EF +:1028400058B16B46054608AE1C4603CCB44228601E +:102850006960234605F10805F6D1104608B070BD41 +:10286000082817D909280CD00A280CD00B280CD01E +:102870000C280CD00D280CD00E2814BF402030207E +:1028800070470C20704710207047142070471820A4 +:102890007047202070470000082817D90C280CD951 +:1028A00010280CD914280CD918280CD920280CD998 +:1028B00030288CBF0F200E207047092070470A2057 +:1028C00070470B2070470C2070470D2070470000A8 +:1028D0002DE9F843078C072F04461ED9D0E902984A +:1028E00000254FF6FF73C5F12006A5F1200029FA57 +:1028F00005F108FA06F628FA00F031430143C9B29F +:102900001846FFF763FF0835402D0346EBD1E16918 +:102910003A46BDE8F843FFF76BBF4FF6FF70BDE8DE +:10292000F883000010B54B6823B9CA8A63F3090223 +:10293000CA8210BD04691A681C600361C38A013B26 +:10294000C3824A60EFE700002DE9F84F1D46CB8AAD +:102950000F46C3F309010529814692460B4630D044 +:102960000020AAB207F11A049EB2042E1FFA80F8C2 +:102970000FD8904503F1010306D3FB8A0A4462F3A2 +:102980000903FB8201201AE01AF80060E6540130C6 +:10299000EAE79045F1D2A1F1050B1C237C68BBFB53 +:1029A000F3F203FB12BB1FFA8BF6002C45D148460D +:1029B000FFF72AFF044638B978606FF00200BDE8DF +:1029C000F88F4FF00008E6E7002606607860ADB2A9 +:1029D0004FF0000B454510D90AEB0803221D13F8F0 +:1029E000011B9155B1B208F101081B291FFA88F8A3 +:1029F0002BD0454506F10106F1D8FB8AC3F3090245 +:102A0000154465F30903BCE7013292B21C46236802 +:102A1000002BF9D16B1F0B441C21B3FBF1F30133E5 +:102A20009BB29A42D3D2BBF1000FD0D14846FFF7F8 +:102A3000EBFE20B9C4F800B0BFE70122E7E7C0F819 +:102A400000B05E4620600446C1E74545D5D94846FA +:102A5000FFF7DAFE08B92060AFE7C0F800B0002643 +:102A600020600446B6E700002DE9F04F2DED028B03 +:102A70001C4683B05B69019207468846002B00F034 +:102A80009A80238C2BB1E269002A00F09480072BF6 +:102A900035D807F10C00FFF7B7FE054638B96FF0DF +:102AA0000205284603B0BDEC028BBDE8F08F14226E +:102AB0000021FEF735FC228CE16905F10800FEF7E4 +:102AC0001DFC208C013080B2FFF7E6FEFFF7C8FE48 +:102AD000013880B22084013028746369228C1B780D +:102AE0002A4403F01F0363F03F0348F000411372D0 +:102AF000384669602946FFF7EFFD0125D1E700F16F +:102B00000C034FF0000908EE103A4FF0800A4E46D1 +:102B10004D4618EE100AFFF777FE83460028BED018 +:102B200014220021FEF7FCFB002E3AD1019BABF8EA +:102B3000083002220BF1080E1FFA82FC0CF1010092 +:102B4000BCF1060F218C80B201D88E422BD3FFF747 +:102B5000A3FEFFF785FE62691278013802F01F02BA +:102B60008E4208BF4FF0400A42EA49121BFA80F138 +:102B70004AEA020A013048F0004281F808A08BF8C6 +:102B80001000CBF8042059463846FFF7A5FD238CEA +:102B90000135B3422DB289F001094FF0000AB8D1D6 +:102BA0007FE70022C6E7E169895D0EF80210013671 +:102BB000B6B20132C0E76FF0010572E7F8B515460D +:102BC0000E463022002104461F46FEF7A9FB069B55 +:102BD0006360B5F5001F079BA76034BF6A094FF615 +:102BE000FF72A36297B2E66104F1100000239A42DB +:102BF00006D800230360A782E3822383E360F8BD45 +:102C00000660013330462036F1E7000003781BB937 +:102C10004BB2002BC8BF01707047000000787047AE +:102C2000F8B50C46C969074611B9238C002B37D17A +:102C3000257E1F2D34D8387828BB228C072A2CD823 +:102C4000268A36F003032BD14FF6FF70FFF7D0FD35 +:102C500020F001003102400441EA0561400C41EAE4 +:102C600040254FF6FF72234629463846FFF7FCFE03 +:102C7000002807DD626913780133DBB21F2B88BFA0 +:102C800000231370F8BD218A2D0645EA012505436E +:102C90002046FFF71DFE0246E5E76FF00300F1E76F +:102CA0006FF00100EEE7000070B58AB004461646EA +:102CB0000021282268461D46FEF732FBBDF8383059 +:102CC000ADF810300F9B05939DF840308DF818300B +:102CD000119B07936946BDF84830ADF82030204677 +:102CE000CDE90265FFF79CFF0AB070BD2DE9F04108 +:102CF000D36905460C4616460BB9138C5BBB377E71 +:102D00001F2F28D895F80080B8F1000F26D0304644 +:102D1000FFF7DEFD3378210241EAC33141EA0801C1 +:102D2000338A41EA076141EA03410246334641F0F2 +:102D300080012846FFF798FE00280ADD3378012B32 +:102D400007D1726913780133DBB21F2B88BF0023D0 +:102D50001370BDE8F0816FF00100FAE76FF0030037 +:102D6000F7E70000F0B58BB004460D46174600218A +:102D7000282268461E46FEF7D3FA9DF84C305A1EAC +:102D8000534253418DF800309DF84030ADF810307B +:102D9000119B05939DF848308DF81830149B0793CC +:102DA0006A46BDF85430ADF8203029462046CDE9BA +:102DB0000276FFF79BFF0BB0F0BD0000406A00B148 +:102DC00004307047436A1A68426202691A600361FC +:102DD000C38A013BC38270472DE9F041D0F82080BF +:102DE000194E14461D464146002709B9BDE8F08139 +:102DF000D1E90223A21A65EB0303964277EB0303A2 +:102E00001ED2036A8B420DD1FFF78CFD036A1B684B +:102E1000036203690B60C38A0161016A013BC382DB +:102E20008846E2E7FFF77EFD0B68C8F800300369CB +:102E30000B60C38A0161013BC382D8F80010D4E75C +:102E400088460968D1E700BF80841E002DE9F04F55 +:102E50008BB00D46DDF8509014469B468046002806 +:102E600000F01981B9F1000F00F01581531E3F2BBE +:102E700000F21181012A03D1BBF1000F40F00B8158 +:102E80000023CDE90833B8F81430B5EBC30F4FEA8F +:102E9000C30703D300200BB0BDE8F08F2B199F426E +:102EA000D8F80C303ABF7F1BFFB227461BB9D8F8C1 +:102EB0001030002B7AD0272D4ED8C5F12806B74206 +:102EC0004FF000032CBFF6B23E4600932946D8F8D7 +:102ED000080008AB3246FFF741FCA7EB060A354471 +:102EE0005FFA8AFAB8F8143003F10053053BDB00AF +:102EF0000493D8F80C3003932821039B13B1BAF143 +:102F0000000F2CD1D8F8100040B1BAF1000F05D055 +:102F1000009608AB5246691AFFF720FC38B2002F22 +:102F2000B8D066070AD00AAB03EBD401624211F8AD +:102F3000083C02F00702134101F8083C082C3CD978 +:102F4000102C40F2B580202C40F2B780BBF1000F6E +:102F500000F09C80082334E0BA460026C2E7049BB8 +:102F6000E02B28BFE02306930B44AB42059314D912 +:102F70005A1B03980096924534BF5246D2B2691A42 +:102F800008AB04300792FFF7E9FB079A1644AAEB57 +:102F9000020A1544F6B25FFA8AFA049B069A05996A +:102FA0009B1A0493039B1B680393A6E70093D8F82E +:102FB000080008AB3A462946AEE7BBF1000F13D034 +:102FC0000123B4EBC30F6CD0082C12D89DF820302D +:102FD000621E23FA02F2D50706D54FF0FF3202FA3D +:102FE00004F423438DF820309DF8203089F8003018 +:102FF00051E7102C12D8BDF82030621E23FA02F2DD +:10300000D10706D54FF0FF3202FA04F42343ADF89E +:103010002030BDF82030A9F800303CE7202C0FD834 +:103020000899631E21FA03F3DA0705D54FF0FF3242 +:1030300002FA04F40C430894089BC9F800302AE70C +:10304000402C2BD0DDE90865611EC4F12102A4F1FA +:10305000210326FA01F105FA02F225FA03F31143DE +:103060001943CB0712D50122A4F12003C4F120019A +:1030700002FA03F322FA01F1A240524243EA0103A9 +:1030800063EB430332432B43CDE90823DDE90823F7 +:10309000C9E90023FFE66FF00100FCE66FF00800CD +:1030A000F9E6082CA0D9102CB3D9202CEED8C3E710 +:1030B000BBF1000FADD0022383E7BBF1000FBBD003 +:1030C00004237EE730B5012A144638BF0124402C82 +:1030D00085B028BF40240025012ACDE9025518D823 +:1030E0001B788DF8083063070AD004AB03EBD405D6 +:1030F000624215F8083C02F00702934005F8083CCC +:10310000009103462246002102A8FFF727FB05B0E5 +:1031100030BD082AE4D9102A03D81B88ADF808303E +:10312000E1E7202A8DBFD3E900231B680293CDE994 +:103130000223D8E710B5CB681BB98B600B618B827B +:1031400010BD04691A681C600361C38A013BC38215 +:10315000CA60F0E703064CBFC0F3C03002207047DE +:1031600008B50246FFF7F6FF022806D15306C2F360 +:103170000F2001D100F0030008BDC2F30740FBE7B8 +:103180002DE9F04F93B0CDE903230A6804461046B9 +:10319000FFF7E0FF022814BFC2F306260026002A2C +:1031A0000D46824680F2F28112F0C04940F0EE8175 +:1031B000097B002900F0EA81022803D02378B3427A +:1031C00040F0E781C2F304630693104602F07F03E8 +:1031D0000593FFF7C5FF059B29444FEA834848EA5A +:1031E0000A4848EA4668CE7800230022CDE9082341 +:1031F000F309834648EA0008029367D0059B0093D1 +:1032000002466768534608A92046B847002800F0E0 +:10321000C381276A4FB9414604F10C00FFF702FB56 +:10322000074690B96FF0020054E03B6998450DD015 +:103230003F68002FF9D1414604F10C00FFF7F2FA84 +:1032400007460028EED0236A3B60276297F817C034 +:1032500006F01F08CCF3840CACEB08001FFA80FECC +:103260000028B8BF0EF12000A8EB0C031FFA83FE64 +:10327000D7E90221B8BF00B2002B0793BEBF0EF101 +:1032800020031BB2079352EA010338D0039BDFF8F7 +:1032900024E39A1A049B4FF0000C63EB010196455E +:1032A0007CEB01032BD36B7B97F81AE0734519D1A4 +:1032B000029B002B78D0012821DC7868F8B9DFF870 +:1032C000F0C2944570EB010316D337E0276A27B9A3 +:1032D0006FF00C0013B0BDE8F08F3B699845B5D096 +:1032E0003F68F4E7B24890427CEB010301D3002031 +:1032F000F0E7029B002BFAD0079B0F2B17DCFA7D1F +:10330000B30002F0030203F07C031343FB7539465C +:103310002046FFF707FB6B7BBB76029B3BB9FB7D2F +:10332000C3F38402013262F38603FB75D0E76A7B44 +:10333000BB7E9A42DBD1029B002B35D0B309022B16 +:1033400032D0039BBB60049BFB60142200210DA8BC +:10335000FDF7E6FF039B0A93049B0B932B1D0C9335 +:103360002B7BADF83EB0013BDBB2ADF83C30069BA9 +:103370008DF84230059B8DF8433094F82C308DF851 +:1033800040A083F001038DF844308DF84180A3689C +:103390000AA920469847FB7DC3F38403013303F059 +:1033A0001F039B02FB82A2E7FB7DC6F34012B2EB38 +:1033B000D31F40F0F480C3F38403434540F0F28010 +:1033C000029A2B7BB609002A4DD0F2075DD4032B5D +:1033D00040F2EB80039BBB60049BFB602B7BAE1D2C +:1033E000033BDBB23246394604F10C00FFF7ACFA7E +:1033F00000280CDA39462046FFF794FAFB7DC3F328 +:103400008403013303F01F039B02FB820AE7DDE91B +:103410000884AB883B834FF6FF73C9F12000A9F104 +:10342000200228FA09F104FA00F0014324FA02F21A +:1034300011431846C9B2FFF7C9F909F10809B9F1F2 +:10344000400F0346E9D1B8822A7B033AD2B2314613 +:10345000FFF7CEF9FB7DB882DA43C2F3C01262F304 +:10346000C713FB7543E786B92E1D013BDBB232461D +:10347000394604F10C00FFF767FA0028BADB2A7B13 +:10348000B88A013AD2B23146E2E7F98AC1F30901BA +:10349000013B0429DAB25BD8281D002307F11B0683 +:1034A0009A4208D910F801CB06F801C00131013366 +:1034B0000529DBB2F4D103990A9104990B91934247 +:1034C00007F11B010C9138BF043379680D9134BFAB +:1034D00055FA83F300230E93FB8AADF83EB0C3F395 +:1034E00009031A44069B8DF84230059B8DF8433042 +:1034F00094F82C30ADF83C2083F001038DF8443073 +:1035000000238DF840A08DF841807B602A7BB88A2B +:10351000013A291DFFF76CF93B8BB882834203D136 +:10352000A3680AA92046984720460AA9FFF702FE89 +:10353000FB7DBA8AC3F38403013303F01F039B02AC +:10354000FB823B8B9A420CBF00206FF01000C1E65B +:103550007B68002BAFD0052001E01C3033461E688D +:10356000002EFAD1091A081D2E1D184401EB090C72 +:10357000BCF11B0F5FFA89F39DD89A429BD916F8CC +:10358000013B00F8013B09F10109EFE76FF0090089 +:10359000A0E66FF00A009DE66FF00B009AE66FF070 +:1035A0000D0097E66FF00E0094E66FF00F0091E6C5 +:1035B00040420F0080841E00EFF3098305494A6BE7 +:1035C00022F001024A63683383F30988002383F3FE +:1035D0001188704700EF00E0302080F3118862B658 +:1035E0000C4B0D4AD96821F4E0610904090C0A4327 +:1035F000DA60D3F8FC20094942F08072C3F8FC205D +:103600000A6842F001020A602022DA7783F8220079 +:10361000704700BF00ED00E00003FA05001000E075 +:1036200010B5302383F311880E4B5B6813F40063ED +:1036300014D0F1EE103AEFF30984683C4FF0807338 +:10364000E361094BDB6B236684F3098800F0A4F87F +:1036500010B1064BA36110BD054BFBE783F3118846 +:10366000F9E700BF00ED00E000EF00E0030600080E +:10367000060600084FF0E023002258684FF0FF31A3 +:10368000930003F1604303F5614301329042C3F8B4 +:103690008010C3F88011F3D27047000000F160433E +:1036A00003F561430901C9B283F80013012200F058 +:1036B0001F039A4043099B0003F1604303F56143F4 +:1036C000C3F880211A60704700230375826803697C +:1036D0001B6899689142FBD25A680360426010608F +:1036E0005860704700230375826803691B689968F6 +:1036F0009142FBD85A68036042601060586070477E +:1037000008B50846302383F311880B7D032B05D0C1 +:10371000042B0DD02BB983F3118808BD8B690022CF +:103720001A604FF0FF338361FFF7CEFF0023F2E70B +:10373000D1E9003213605A60F3E70000FFF7C4BF1D +:10374000054BD9680875186802681A605360012231 +:103750000275D860FCF740BF2038002030B50C4B14 +:10376000DD684B1C87B004460FD02B46094A6846DB +:1037700000F050F92046FFF7E3FF009B13B16846C5 +:1037800000F052F9A86907B030BDFFF7D9FFF9E79B +:103790002038002001370008044B1A68DB68906865 +:1037A0009B68984294BF0020012070472038002079 +:1037B000084B10B51C68D86822681A605360012253 +:1037C0002275DC60FFF78EFF01462046BDE8104001 +:1037D000FCF702BF20380020044B1A68DB689268AF +:1037E0009B689A4201D9FFF7E3BF70472038002059 +:1037F00038B5074C07490848012300252370656048 +:1038000000F000FC0223237085F3118838BD00BF4F +:10381000483A0020B84700082038002008B572B6A2 +:10382000044B186500F0B6FA00F06EFB024B032261 +:103830001A70FEE720380020483A002000F02AB92C +:10384000EFF3118020B9EFF30583302282F3118862 +:103850007047000010B530B9EFF30584C4F30804D5 +:1038600014B180F3118810BDFFF7B6FF84F31188FF +:10387000F9E700008B60022308618B8208467047DD +:103880008368A3F1840243F8142C026943F8442CA2 +:10389000426943F8402C094A43F8242CC26843F893 +:1038A000182C022203F80C2C002203F80B2C044ADB +:1038B00043F8102CA3F12000704700BFF105000869 +:1038C0002038002008B5FFF7DBFFBDE80840FFF710 +:1038D00035BF0000024BDB6898610F20FFF730BF57 +:1038E00020380020302383F31188FFF7F3BF000056 +:1038F00008B50146302383F311880820FFF72EFF17 +:10390000002383F3118808BD10B503689C68A242A8 +:103910000CD85C688A600B604C60216059609968C3 +:103920008A1A9A604FF0FF33836010BD1B68121B28 +:10393000ECE700000A2938BF0A2170B504460D469D +:103940000A26601900F058FB00F044FB041BA54256 +:1039500003D8751C2E460446F3E70A2E04D9BDE8A9 +:103960007040012000F08EBB70BD0000F8B5144B14 +:103970000D46D96103F1100141600A2A196982607C +:1039800038BF0A22016048601861A818144600F088 +:1039900025FB0A2700F01EFB431BA342064606D365 +:1039A0007C1C281900F028FB27463546F2E70A2F31 +:1039B00004D9BDE8F840012000F064BBF8BD00BFA9 +:1039C00020380020F8B506460D4600F003FB0F4AEC +:1039D000134653F8107F9F4206D12A4601463046CF +:1039E000BDE8F840FFF7C2BFD169BB68441A2C1983 +:1039F00028BF2C46A34202D92946FFF79BFF224647 +:103A000031460348BDE8F840FFF77EBF203800206C +:103A10003038002010B4C0E9032300235DF8044BC4 +:103A20004361FFF7CFBF000010B5194C23699842DE +:103A30000DD0D0E90032816813605A609A680A4458 +:103A40009A60002303604FF0FF33A36110BD23464B +:103A5000026843F8102F53600022026022699A42E4 +:103A600003D1BDE8104000F0C1BA936881680B44EF +:103A7000936000F0AFFA2269E1699268441AA242A9 +:103A8000E4D91144BDE81040091AFFF753BF00BF45 +:103A9000203800202DE9F047DFF8BC8008F110073E +:103AA0002C4ED8F8105000F095FAD8F81C40AA68AF +:103AB000031B9A423ED81444D5E900324FF0000966 +:103AC000C8F81C4013605A60C5F80090D8F8103050 +:103AD000B34201D100F08AFA89F31188D5E90331A4 +:103AE00028469847302383F311886B69002BD8D080 +:103AF00000F070FA6A69A0EB04094A4582460DD2CB +:103B0000022000F0BFFA0022D8F81030B34208D1EA +:103B100051462846BDE8F047FFF728BF121A224455 +:103B2000F2E712EB090938BF4A4629463846FFF743 +:103B3000EBFEB5E7D8F81030B34208D01444211A90 +:103B4000C8F81C00A960BDE8F047FFF7F3BEBDE868 +:103B5000F08700BF30380020203800200020704758 +:103B6000FEE70000704700004FF0FF307047000094 +:103B7000BFF34F8F024A1369DB03FCD4704700BFC9 +:103B80000020024008B5094B1B7873B9FFF7F0FF1E +:103B9000074B5A69002ABFBF064A9A6002F1883271 +:103BA0009A601A6822F480621A6008BD603A0020A8 +:103BB000002002402301674508B50B4B1B7893B9E1 +:103BC000FFF7D6FF094B5A6942F000425A611A6862 +:103BD00042F480521A601A6822F480521A601A68FD +:103BE00042F480621A6008BD603A00200020024062 +:103BF0007F289ABF00F58030C00200207047000087 +:103C00004FF4006070470000802070477F2808B59F +:103C10000BD8FFF7EDFF00F500630268013204D115 +:103C200004308342F9D1012008BD0020FCE70000E8 +:103C30007F2810B504461FD8FFF79AFFFFF7A2FFB1 +:103C40000E4BF3221A6102225A615A6942EAC002FB +:103C50005A615A6942F480325A61FFF789FF4FF482 +:103C60000061FFF7C5FF00F04BF9FFF7A5FF204605 +:103C7000BDE81040FFF7CABF002010BD0020024081 +:103C80002DE9F84340EA020313F00703144606D077 +:103C9000304B40F231321A600020BDE8F8838518BD +:103CA0002D4A95420CD92B4A40F236311160F3E788 +:103CB000031D1B684A68934208D1083C083008314C +:103CC000072C14D902680B689A42F1D0FFF75AFF0B +:103CD000FFF74EFF214E08314FF001084FF0000969 +:103CE000012CA1F1080706D8FFF766FF01E0002CC0 +:103CF000ECD10120D1E7C6F81480054651F8083C04 +:103D000045F8043B51F8043C4360FFF731FF336949 +:103D100043F001033361C6F81490026851F8083C7F +:103D20009A420CD00B4B40F25E321A600C4B18607A +:103D30000C4B1C600C4B1F60FFF73EFFACE72D687F +:103D400051F8043C9D4201F10801EBD1083C0830D8 +:103D5000C6E700BF5C3A00200000040800200240D3 +:103D6000503A0020583A0020543A0020084908B53B +:103D70000B7828B11BB9FFF705FF01230B7008BDB5 +:103D8000002BFCD0BDE808400870FFF715BF00BF4E +:103D9000603A00204FF480314FF0005000F0B2B88C +:103DA0000846114600F014BC012000F011BC0000D0 +:103DB000084600F02BBC000070B582B0FFF740FD54 +:103DC0000E4E054600F006F93268904237BF0C4AA5 +:103DD0000B49516814682EBFD1E90041013151608F +:103DE0000419034641F10001284601913360FFF7B1 +:103DF00031FD0199204602B070BD00BF643A002039 +:103E0000683A002070B582B0FFF71AFD104E0546E3 +:103E100000F0E0F83268904237BF0E4A0D49516811 +:103E200014682EBFD1E9004101315160041941F1FC +:103E300000010346284601913360FFF70BFD01990D +:103E40004FF47A7200232046FCF7B2F902B070BD3D +:103E5000643A0020683A002010B50244064BD2B202 +:103E6000904200D110BD441C00B253F8200041F82C +:103E7000040BE0B2F4E700BF50280040114B30B50E +:103E8000D3F89040240409D4D3F89040C3F890406C +:103E9000D3F8904044F40044C3F890400A4C23689F +:103EA00043F4807323600244084BD2B2904200D1A5 +:103EB00030BD441C00B251F8045B43F82050E0B21E +:103EC000F4E700BF0010024000700040502800409E +:103ED00007B5012201A90020FFF7BEFF019803B03A +:103EE0005DF804FB13B50446FFF7F2FFA04205D0CE +:103EF000012201A900200194FFF7C0FF02B010BD0C +:103F0000704700007047000070470000074B45F203 +:103F100055521A6002225A6040F6FF729A604CF6BF +:103F2000CC421A60024B01221A70704700300040E8 +:103F3000743A0020034B1B781BB1034B4AF6AA22AC +:103F40001A607047743A002000300040054B1A6830 +:103F500032B902F1804202F50432D2F894201A609C +:103F6000704700BF703A0020024B4FF40002C3F8C4 +:103F7000942070470010024008B5FFF7E7FF024B9E +:103F80001868C0F3407008BD703A00207047000008 +:103F9000FEE700000A4B0B480B4A90420BD30B4B39 +:103FA000DA1C121AC11E22F003028B4238BF002213 +:103FB0000021FDF7B5B953F8041B40F8041BECE7EA +:103FC00054480008003B0020003B0020003B00203C +:103FD00000F0BEB84FF08043586A70474FF08043FE +:103FE000002258631A610222DA6070474FF0804362 +:103FF0000022DA60704700004FF08043586370473A +:10400000FEE7000070B51B4B01630025044686B037 +:10401000586085620E46FFF7DFFA04F11003C4E929 +:1040200004334FF0FF33C4E90635C4E90044A5600A +:10403000E562FFF7CFFF2B460246C4E9082304F1EF +:1040400034010D4A256580232046FFF713FC012328 +:10405000E0600A4A0375009272680192B268CDE985 +:104060000223074B6846CDE90435FFF72BFC06B069 +:1040700070BD00BF483A0020C4470008C947000887 +:1040800001400008024AD36A1843D062704700BF5B +:1040900020380020244B2548DA6A42F0070210B489 +:1040A000DA62DA6A224C22F00702DA62DA6ADA6C41 +:1040B00042F00702DA64DA6E42F00702DA664FF085 +:1040C0009042DB6E4FF0AA31002353609160D060C4 +:1040D0004FF6FF7050611362536214601024C2F8EF +:1040E0000434C2F80814C2F80C444FF6F774C2F84E +:1040F00014449924C2F82034C2F824440D4CC2F868 +:104100000044C2F80438C2F80818C2F80C38C2F8E3 +:104110001408C2F82038C2F82438C2F800385DF814 +:10412000044B00F055B800BF00100240000100240D +:104130000001002850000A0008B500F005FAFFF75A +:1041400057FBBDE80840FFF701BF000070470000C3 +:104150000F4B9A6D42F001029A659A6F42F001028C +:104160009A670C4A9B6F936843F0010393604FF08A +:1041700080434F229A624FF0FF32DA6200229A6146 +:104180005A63DA605A6001225A611A60704700BFB0 +:1041900000100240002004E04FF0804208B5116991 +:1041A000D3680B40D9B2C9439B07116107D53023AF +:1041B00083F31188FFF742FB002383F3118808BDC6 +:1041C00008B5FFF757FABDE8084000F099B90000BC +:1041D0005A4B4FF0FF319A6A99629A6A00229A62AA +:1041E000986AD86A60F00700D862D86A00F00700C1 +:1041F000D862D86A186B1963186B1A63186B986BBE +:104200009963986B9A63986BD86BD963D86BDA63B0 +:10421000D86B186C1964196C1A641A6C484A4FF4FC +:10422000E06111601A6E474942F001021A66D3F844 +:10423000802022F00102C3F88020D3F880209A6DFC +:1042400042F080529A659A6F22F080529A679A6F74 +:104250004FF440720A604A6912F48062FBD14A60EE +:104260001A6822F0F00242F060021A601A6842F006 +:1042700001021A601A689107FCD500229A609A68B8 +:1042800012F00C02FBD1D3F8901011F4407F1EBF46 +:104290004FF48031C3F89010C3F8902061221A6067 +:1042A0001A689207FCD500229A609A6812F00C0FE7 +:1042B000FBD169221A60D3F8942022F4706242F490 +:1042C000C062C3F894201A6842F480321A601A68F7 +:1042D0009003FCD5D3F8902022F00322C3F890205D +:1042E000194ADA601A6842F080721A601A689101FD +:1042F000FCD5164A1A611A6842F080621A601A6880 +:104300001201FCD500229A600D49114AC3F8882099 +:104310000A6822F0070242F004020A600A6802F00A +:104320000702042AFAD19A6842F003029A609A6856 +:1043300002F00C020C2AFAD1704700BF00100240B4 +:10434000002002400070004003140001000C100027 +:1043500055550134074A08B5536903F00103536109 +:1043600023B1054A13680BB150689847BDE808406F +:10437000FFF756B900040140783A0020074A08B513 +:10438000536903F00203536123B1054A93680BB1EB +:10439000D0689847BDE80840FFF742B900040140E3 +:1043A000783A0020074A08B5536903F004035361C3 +:1043B00023B1054A13690BB150699847BDE808401D +:1043C000FFF72EB900040140783A0020074A08B5EB +:1043D000536903F00803536123B1054A93690BB194 +:1043E000D0699847BDE80840FFF71AB900040140BA +:1043F000783A0020074A08B5536903F01003536167 +:1044000023B1054A136A0BB1506A9847BDE80840CA +:10441000FFF706B900040140783A0020164B10B5AA +:104420005C6904F478725A61A30604D5134A936A4E +:104430000BB1D06A9847600604D5104A136B0BB1D4 +:10444000506B9847210604D50C4A936B0BB1D06B87 +:104450009847E20504D5094A136C0BB1506C984794 +:10446000A30504D5054A936C0BB1D06C9847BDE801 +:104470001040FFF7D5B800BF00040140783A002093 +:10448000194B10B55C6904F47C425A61620504D58D +:10449000164A136D0BB1506D9847230504D5134A86 +:1044A000936D0BB1D06D9847E00404D50F4A136E9D +:1044B0000BB1506E9847A10404D50C4A936E0BB112 +:1044C000D06E9847620404D5084A136F0BB1506F41 +:1044D0009847230404D5054A936F0BB1D06F9847D2 +:1044E000BDE81040FFF79CB800040140783A002076 +:1044F00008B5FFF751FEBDE80840FFF791B800008E +:10450000062108B50846FFF7C9F806210720FFF77E +:10451000C5F806210820FFF7C1F806210920FFF79A +:10452000BDF806210A20FFF7B9F806211720FFF78A +:10453000B5F806212820FFF7B1F8BDE808400721AB +:104540001C20FFF7ABB8000008B5FFF739FE00F0FC +:1045500007F8FFF7FBFDBDE80840FFF739BD000095 +:104560000023054A19460133102BC2E9001102F15C +:104570000802F8D1704700BF783A00200B46014688 +:10458000184600F02DB8000000F040B8012838BFF0 +:10459000012010B50446204600F030F830B900F094 +:1045A00007F808B900F00CF88047F4E710BD0000E8 +:1045B000024B1868BFF35B8F704700BFF83A0020CA +:1045C00008B5062000F084F80120FFF7C9FA0000C2 +:1045D000024B0A4601461868FFF7E2BB181100209B +:1045E00010B5054C13462CB10A4601460220AFF324 +:1045F000008010BD2046FCE700000000024B014691 +:104600001868FFF7D1BB00BF18110020024B01460C +:104610001868FFF7CDBB00BF1811002010B5013995 +:104620000244904201D1002005E0037811F8014FC7 +:10463000A34201D0181B10BD0130F2E72DE9F04173 +:10464000A3B1C91A17780144044603F1FF3C8C4218 +:10465000204601D9002009E00578BD4204F101049B +:10466000F5D10CEB0405D618A54201D1BDE8F081C7 +:1046700015F8018D16F801EDF045F5D0E7E70000DB +:104680001F2938B504460D4604D9162303604FF0A0 +:10469000FF3038BD426C12B152F821304BB9204680 +:1046A00000F030F82A4601462046BDE8384000F0C8 +:1046B00017B8012B0AD0591C03D11623036001201F +:1046C000E7E7002442F82540284698470020E0E725 +:1046D000024B01461868FFF7D3BF00BF1811002036 +:1046E00038B5074D00230446084611462B60FFF7F6 +:1046F0003BFA431C02D12B6803B1236038BD00BFD5 +:10470000FC3A0020FFF72ABA034611F8012B03F800 +:10471000012B002AF9D170476F72672E61726475A0 +:1047200070696C6F742E4D6174656B4C3433312D30 +:10473000414453420000000040A2E4F16468910645 +:104740000041A3E5F2656992070000004261642020 +:1047500043414E496661636520696E6465782E0049 +:1047600080000000008000000000800000000000C9 +:1047700000000000291B0008112300087122000816 +:10478000391B00086D1B0008691D00083D1B00084F +:104790004D1B0008411B0008491B0008451B000871 +:1047A000911C0008511B0008DD250008611B000852 +:1047B000651C000863300000B4470008783800200A +:1047C000483A00206D61696E0069646C6500000004 +:1047D00010BAFF7F01000000260400000000000066 +:1047E0000060030000000000FE2A0100D204000067 +:1047F0001C1100200000000000000000000000006C +:1048000000000000000000000000000000000000A8 +:104810000000000000000000000000000000000098 +:104820000000000000000000000000000000000088 +:104830000000000000000000000000000000000078 +:104840000000000000000000000000000000000068 +:044850000000000064 +:00000001FF diff --git a/Tools/bootloaders/MatekL431-Airspeed_bl.bin b/Tools/bootloaders/MatekL431-Airspeed_bl.bin index 2e150c5ae1ff73..4b3dbcd326bfa3 100755 Binary files a/Tools/bootloaders/MatekL431-Airspeed_bl.bin and b/Tools/bootloaders/MatekL431-Airspeed_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Airspeed_bl.hex b/Tools/bootloaders/MatekL431-Airspeed_bl.hex index 46fc143ca830e5..641e598c7d3506 100644 --- a/Tools/bootloaders/MatekL431-Airspeed_bl.hex +++ b/Tools/bootloaders/MatekL431-Airspeed_bl.hex @@ -1,19 +1,19 @@ :020000040800F2 -:1000000000090020B5040008E5290008652900085A -:10001000BD2900086529000891290008B7040008D7 -:10002000B7040008B7040008B7040008393800080E +:1000000000090020B5040008C52500087D2500086A +:10001000A52500087D2500089D250008B7040008D7 +:10002000B7040008B7040008B7040008B935000891 :10003000B7040008B7040008B7040008B7040008B4 :10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B7040008714B0008994B00086A -:10006000C14B0008E94B0008114C0008B704000818 +:10005000B7040008B7040008554300087D430008B2 +:10006000A5430008CD430008F5430008B704000885 :10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B7040008A125000859 -:10009000CD250008DD250008B7040008394C00080C +:10008000B7040008B7040008B704000831250008C9 +:100090005D2500086D250008B70400081D44000810 :1000A000B7040008B7040008B7040008B704000844 -:1000B000494D0008B7040008B7040008B704000859 +:1000B000F1440008B7040008B7040008B7040008BA :1000C000B7040008B7040008B7040008B704000824 -:1000D000B70400080D4D0008214D0008354D0008FB -:1000E0009D4C0008B7040008B7040008B7040008D6 +:1000D000B7040008B7040008B7040008B704000814 +:1000E00081440008B7040008B7040008B7040008FA :1000F000B7040008B7040008B7040008B7040008F4 :10010000B7040008B7040008B7040008B7040008E3 :10011000B7040008B7040008B7040008B7040008D3 @@ -25,7 +25,7 @@ :10017000B7040008B7040008B7040008B704000873 :10018000B7040008B7040008B7040008B704000863 :10019000B7040008B7040008B7040008B704000853 -:1001A000051800080000000000000000000000002A +:1001A000091200080000000000000000000000002C :1001B00053B94AB9002908BF00281CBF4FF0FF31CE :1001C0004FF0FF3000F074B9ADF1080C6DE904CECA :1001D00000F006F8DDF804E0DDE9022304B0704722 @@ -74,1262 +74,1087 @@ :100480004B45A9D2B9EB020864EB0C0E0138A3E787 :100490004646EAE7204694E74046D1E7D0467BE768 :1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B63A486D -:1004C00080F30888394880F3098839484EF6085186 -:1004D000CEF20001086040F20000CCF200004EF6BF -:1004E0003471CEF200010860BFF34F8FBFF36F8FFE -:1004F00040F20000C0F2F0004EF68851CEF200014A -:100500000860BFF34F8FBFF36F8F4FF00000E1EE35 -:10051000100A4EF63C71CEF200010860062080F30E -:100520001488BFF36F8F04F09DF904F079F904F09B -:10053000B3F94FF055301F491B4A91423CBF41F877 -:10054000040BFAE71C49194A91423CBF41F8040BDD -:10055000FAE71A491A4A1B4B9A423EBF51F8040B5C -:1005600042F8040BF8E700201749184A91423CBFB3 -:1005700041F8040BFAE704F057F904F0E5F9144CDC -:10058000144DAC4203DA54F8041B8847F9E700F035 -:1005900041F8114C114DAC4203DA54F8041B884762 -:1005A000F9E704F03FB90000000900200011002025 -:1005B000000000080001002000090020C0520008CF -:1005C000001100208C110020901100203C390020E7 -:1005D000A0010008A4010008A4010008A40100086B -:1005E0002DE9F04F2DED108AC1F80CD0C3689D465F -:1005F000BDEC108ABDE8F08F002383F311882846F4 -:10060000A047002003F004FEFEE703F07DFD00DFBD -:10061000FEE70000F8B504F0A5F8074604F0F6F888 -:100620000546A0BB1F4B9F4231D001339F4231D0C2 -:100630001D4B27F0FF029A422FD1F8B200F030FD97 -:100640002E4642F2107400F035FF08B10024264611 -:1006500000F02CFD08B90646044635B1134B9F4205 -:1006600003D004F0CBF800242646002004F084F8E0 -:100670000EB100F063F801F051FA00F03FFF01F015 -:100680003DF9204600F0A8F800F058F8F9E72E46AA -:100690000024D8E704460126D5E706464FF47A74CD -:1006A000D1E700BF010007B0000008B0263A09B04A -:1006B00008B501F0EFF8A0F120035842584108BDF9 -:1006C00007B541F21203022101A8ADF8043001F090 -:1006D000FFF803B05DF804FB10B5202383F3118805 -:1006E0001248C3680BB103F00BFE114A0F480023F8 -:1006F0004FF47A7103F0C8FD002383F311880D4C89 -:10070000236813B12368013B2360636813B16368F6 -:10071000013B6360084B1B7833B9636823B902203F -:1007200001F08AF93223636010BD00BF90110020F0 -:10073000D9060008AC120020A4110020214B224A47 -:1007400010B51C46196801313BD004339342F9D1EE -:100750006268A24235D31D4B9B6803F1006303F529 -:1007600020439A422DD204F01BF804F02DF800200B -:1007700001F0DEF8164B0220187001F055F9154B08 -:100780009A6D00229A65996F9A67996FD96DDA65AB -:10079000D96FDA67D96F196E1A66D3F88010C3F86B -:1007A0008020D3F8803072B64FF0E0232021C3F8C8 -:1007B000084DD4E9003281F311889D4683F30888FF -:1007C000104710BD00A0000820A000080011002064 -:1007D000A4110020001002402DE9F04F93B0AC4B63 -:1007E00000902022FF210AA89D6801F041F9A94A42 -:1007F0001378A3B9A8480121C3601170202383F3A3 -:100800001188C3680BB103F07BFDA44AA248002302 -:100810004FF47A7103F038FD002383F31188009BB5 -:100820009F4A03B113609F49009C00230B705360E3 -:1008300098469B461E469A46012001F0F5F824B1E1 -:10084000974B1B68002B00F01C82002001F022F85F -:100850000390039B002B01DA00F094FE039B002B16 -:10086000EDDB012001F0D6F8039B213B162BE3D8EA -:1008700001A252F823F000BFD5080008FD080008C7 -:1008800091090008390800083908000839080008EB -:10089000250A0008F70B0008110B0008730B00086D -:1008A0009B0B0008C10B000839080008D30B000897 -:1008B00039080008450C00087509000839080008C7 -:1008C000890C0008E10800087509000839080008CB -:1008D000730B00080220FFF7EBFE002840F0FB81BD -:1008E000009B0221B8F1000F08BF1C4605A841F289 -:1008F0001233ADF8143000F0EBFF9DE74FF47A703F -:1009000000F0C8FF071EEBDB0220FFF7D1FE002836 -:10091000E6D0013F052F00F2E081DFE807F0030A8F -:100920000D10133605230593042105A800F0D0FF10 -:1009300017E057480421F9E75B480421F6E75B48D4 -:100940000421F3E74FF01C09484600F0F3FF09F1DA -:1009500004090590042105A800F0BAFFB9F12C0F95 -:10096000F2D1012000FA07F747EA0B0B5FFA8BFB85 -:100970004FF0000A01F0C8F826B10BF00B030B2B67 -:1009800008BF0024FFF79CFE56E749480421CDE745 -:10099000002EA5D00BF00B030B2BA1D10220FFF7EB -:1009A00087FE074600289BD001203E4E00F0C0FF86 -:1009B0000220307001F038F84FF000085FFA88F933 -:1009C000484600F0C5FF044690B1484600F0D0FF0D -:1009D00008F101080028F1D1B846044641F212138B -:1009E000022105A8ADF814303E4600F071FF23E760 -:1009F00001230220337001F00DF82546244B9B683B -:100A0000AB4207D9284600F095FF013040F06881DD -:100A10000435F3E7234B00251D70214BB8465D607C -:100A20003E46A7E7002E3FF45BAF0BF00B030B2B0A -:100A30007FF456AF1B4B0220187000F0F5FF3220F8 -:100A400000F028FFB0F10009FFF64AAF19F00307E4 -:100A50007FF446AF0E4A926809EB050393423FF6D6 -:100A60003FAFB9F5807F3FF73BAF124B0193B945DC -:100A700022DD4FF47A7000F00DFF0390039A002AF4 -:100A8000FFF62EAF019B039A03F8012B0137EDE728 -:100A900000110020A812002090110020D9060008A3 -:100AA000AC120020A4110020041100200811002025 -:100AB0000C110020A8110020C820FFF7F9FD0746FF -:100AC00000283FF40DAF1F2D11D8C5F120024A4573 -:100AD0000AAB25F0030028BF4A4683490192184417 -:100AE00000F0B4FF019A8048FF2100F0C1FF4FEAF7 -:100AF000A9037D490193C9F38702284600F0C0FF8E -:100B0000064600283FF46AAF019B05EB830531E7F9 -:100B10000220FFF7CDFD00283FF4E2AE00F044FFD5 -:100B200000283FF4DDAE0027B946704B9B68BB42FE -:100B300018D91F2F11D80A9B01330ED027F00303B9 -:100B400012AA134453F8203C05934846042205A9F1 -:100B500001F056FF04378146E7E7384600F0EAFE29 -:100B60000590F2E7CDF81490042105A800F0B0FE3E -:100B700000E70023642104A8049300F09FFE0028EE -:100B80007FF4AEAE0220FFF793FD00283FF4A8AE3D -:100B9000049800F0FFFE0590E6E70023642104A816 -:100BA000049300F08BFE00287FF49AAE0220FFF73A -:100BB0007FFD00283FF494AE049800F0EDFEEAE7D4 -:100BC0000220FFF775FD00283FF48AAE00F0FCFE1E -:100BD000E1E70220FFF76CFD00283FF481AE05A994 -:100BE000142000F0F7FE04210746049004A800F04A -:100BF0006FFE3946B9E7322000F04CFE071EFFF6C3 -:100C00006FAEBB077FF46CAE384A926807EB0A03FD -:100C100093423FF665AE0220FFF74AFD00283FF4FD -:100C20005FAE27F003075744BA453FF4A3AE5046E2 -:100C300000F080FE0421059005A800F049FE0AF1AD -:100C4000040AF1E74FF47A70FFF732FD00283FF411 -:100C500047AE00F0A9FE002844D00A9B01330BD018 -:100C600008220AA9002000F00BFF00283AD0202219 -:100C7000FF210AA800F0FCFEFFF722FD1C4803F04C -:100C8000CDFA13B0BDE8F08F002E3FF429AE0BF083 -:100C90000B030B2B7FF424AE0023642105A80593DE -:100CA00000F00CFE074600287FF41AAE0220FFF782 -:100CB000FFFC814600283FF413AEFFF701FD41F22F -:100CC000883003F0ABFA059800F042FF4E4600F082 -:100CD0001BFF3C46B0E506464CE64FF0000AFFE538 -:100CE000B8467BE6374679E6A811002000110020BF -:100CF000A0860100094A136849F2690099B21B0CE9 -:100D000000FB01331360064B186844F2506182B255 -:100D1000000C01FB0200186080B270471411002023 -:100D20001011002010B500211022044600F0A0FE92 -:100D3000034B03CB206061601868A06010BD00BF4A -:100D40009075FF1F2DE9F043224DBBB001F052FE1C -:100D5000AB6840F2ED22C31A934232D906AFA860C5 -:100D60002B4628220021384602F022FB05F10E0016 -:100D700000F076FE002604465FFA80F905F10E08C1 -:100D8000F3B2F100994501F1280107D908EB0603F8 -:100D90000822384602F00CFB0136F1E70823012255 -:100DA000CDE9023205340C4B0193A4B230230093F9 -:100DB000CDE9047405A3D3E90023297B074802F099 -:100DC0000FF93BB0BDE8F083AFF3008078F6339FB6 -:100DD00093CACD8DC8330020D5330020CC2200200B -:100DE00070B50D4614461E4602F090F850B9022E1A -:100DF00010D1012C0ED112A3D3E90023C5E90023A1 -:100E0000012007E0282C10D005D8012C09D0052C92 -:100E10000FD0002070BD302CFBD10BA3D3E90023F1 -:100E2000ECE70BA3D3E90023E8E70BA3D3E9002306 -:100E3000E4E70BA3D3E90023E0E700BFAFF30080B2 -:100E4000401DA12026812A0B78F6339F93CACD8DB1 -:100E50009E6AC421818A46EE26417272DF25D7B789 -:100E6000F017304A39059E5613B504462346084606 -:100E700020220021019002F09BFA22790198032A96 -:100E8000234628BF032203F8042F2021022202F068 -:100E90008FFA62790198072A234628BF072203F8B0 -:100EA000052F2221032202F083FAA2790198072A52 -:100EB000234628BF072203F8062F2521032202F02C -:100EC00077FA019804F108031022282102F070FA41 -:100ED000382002B010BD00002DE9F04FADF5037DC4 -:100EE00023AD10AE40F2751280460F4624A80021B3 -:100EF000296000F0BDFD48220021304600F0B8FD19 -:100F000001F078FD564B4FF47A72B0FBF2F01860A6 -:100F100093E80700012386E807000DF162003382A1 -:100F2000FFF700FF42F20463338407AB18464D49D4 -:100F300004F0D2F84FF0200930642946304686F894 -:100F40003C90FFF791FF14AB044601460822284667 -:100F500002F02EFA0822A1180DF15103284602F0E2 -:100F600027FA0DF15203082204F11001284602F07D -:100F70001FFA4A4615AB04F11801284602F018FA88 -:100F800016AB402204F13801284602F011FA18ABE2 -:100F9000082204F17801284602F00AFA0DF16103F3 -:100FA000082204F18001284602F002FA04F1880ABE -:100FB0000DF1620904F5847B4B4651460822284610 -:100FC0000AF1080A02F0F4F9D34509F10109F3D155 -:100FD0001DAB08225946284602F0EAF904F5887448 -:100FE0004FF0000996F834304B450AD9B36B2146CF -:100FF0004B440822284602F0DBF9083409F10109C4 -:10100000F0E74FF0000996F83C304B4504EBC9017E -:1010100008D9336C08224B44284602F0C9F909F17B -:101020000109F0E7CB1DC3F3CF03CDE9045300233F -:101030000393BB7E029307F11903019301230093ED -:10104000F97E05A3D3E90023404601F0C9FF0DF561 -:10105000037DBDE8F08F00BF9E6AC421818A46EE01 -:10106000B41200200851000810B50A4B0A4A1A6051 -:1010700003F5805393F860203AB9DC6D2CB120461B -:1010800001F036FB204603F0B9FEBDE810400348EE -:1010900001F02EBBF8220020085200084033002047 -:1010A000014B1870704700BFC0120020F0B5334BE1 -:1010B0001C7B85B034B1324B0E221A8100242046AD -:1010C00005B0F0BD2F4A1068516802AB03C3082376 -:1010D0002D492E480DEB030203F0E2FE054630B920 -:1010E000274B2B480A221A8101F080FAE6E70169B2 -:1010F000B1F5583F06D9224B26480B221A8101F040 -:1011000075FADCE7438B40F22642934207D01C4934 -:101110000C2008811946204801F068FACFE71F4AE1 -:10112000024402F11003994204D2154B1C481022CC -:101130001A81E4E710398E1A2046144901F060FC48 -:101140003246074605F11801204601F059FCAB680C -:101150009F4202D1EB6898420AD0094B0D221A81B6 -:101160000090D5E902123B460E4801F03FFAA5E790 -:101170000D4801F03BFA0124A1E700BFC83300206D -:10118000B4120020BD510008DC5F030000A000087D -:101190002C510008385100084A5100080860FFF738 -:1011A0006851000885510008AE5100082DE9F04F44 -:1011B000ADB006AF80460C4601F0A8FE05460028FB -:1011C0005AD1237E022B1BD1E38A012B18D101F0C7 -:1011D00011FC0646FFF78EFD03464FF4C870DFF89A -:1011E000D092B3FBF0F206F5167602FB103316FA36 -:1011F00083F3C9F80030E37E33B9A84B00221A709C -:101200009C37BD46BDE8F08FA38AEEB2013BB342E6 -:1012100005F101050BD93B1D1E44E9000096002392 -:10122000082201F0F801204601F086FFECE707F103 -:101230001400FFF777FD324607F11401381D03F063 -:101240001FFE0028D9D10F2E08D8944B1E70D9F854 -:101250000030A3F51673C9F80030D1E7FB1CF87015 -:101260000146009307220346204601F065FFF97806 -:10127000404601F043FEC3E7E38A282B26D010D86E -:10128000012B1ED0052BBBD1BFF34F8F8449854B5B -:10129000CA6802F4E0621343CB60BFF34F8F00BF14 -:1012A000FDE7302BACD1637E7F4D01336A7BDBB22F -:1012B0009342E94603D1E27E2B7B9A4265D0CD462C -:1012C0009EE721464046FFF707FE99E7A38A013BC8 -:1012D0009BB2C92B94D8744D2E7B26BB05F10C0311 -:1012E0000093082233463146204601F025FF731C47 -:1012F000F2B2D9001E46A38A013B9A4205DA0E32A9 -:101300002A44009200230822EEE700230022C5E9C8 -:1013100000230023AB6085F8D730C5F8D8302B7B8D -:101320000BB9E37E2B73002507F114093B1D08223E -:1013300029464846C7E90155FD6002F039F83B7A75 -:1013400005F1010AAB424FEACA0608D9FB68082238 -:101350002B443146484602F02BF85546EFE7C6F3DA -:10136000CF06E17ECDE9049600230393A37E02938A -:10137000193428230093019446A3D3E9002340465F -:1013800001F02EFEFFF7DEFC3AE74FF0000807F110 -:101390001403A7F81480102200934146012320462D -:1013A00001F0CAFEA68A023EB6B2F31C9B109B0057 -:1013B0000733DB08A9EBC3039D460DF1180A1FFA9A -:1013C00088F34FEAC801B34201F110010AD20AEBD7 -:1013D0000803009308220023204601F0ADFE08F127 -:1013E0000108ECE795F8D70000F0B2FAD5F8D8304C -:1013F00004461BB995F8D70000F0BAFAD5F8D830F2 -:1014000033449C4204D295F8D700013000F0B0FA82 -:101410004FEA960B4FF000081FFA88F18B45D5E98B -:10142000003209D90AEB880103EB8800012200F0A1 -:1014300027FB08F10108EFE7F31842F10002C5E9C4 -:101440000032D5F8D83095F8D70006EB0308C5F878 -:10145000D88000F07DFA804509D395F8D730D5F8CB -:10146000D8000133001B85F8D730C5F8D800FF2E0F -:1014700008D800232B7300F097FAFFF717FE08B186 -:10148000FFF75CF92B68094A9B0A0133138100239B -:10149000AB6014E726417272DF25D7B7C522002062 -:1014A00000ED00E00400FA05C8330020B41200206B -:1014B000C822002010B54FF000540C4B22689A420D -:1014C00011D10B4B627D1A700A48237D03730A49C0 -:1014D000C9220E3000F0BAFAE0220021204600F0C6 -:1014E000C7FA012010BD0020FCE700BF9AAD44C53B -:1014F000C0120020C83300201600002037B5184D58 -:1015000018491948022301226B7100F03DFF0023A6 -:101510000193164B164900931648174B4FF480520F -:1015200001F0C6FC154B197811B1124801F0E6FC28 -:1015300001F060FA0446FFF7DDFB4FF4C873B0FB1F -:10154000F3F202FB130304F5167010FA83F00C4B50 -:10155000186003F05BF908B10F232B8103B030BD95 -:10156000B412002040420F00F8220020E10D0008D4 -:10157000C4120020CC220020AD110008C0120020AF -:10158000C82200202DE9F04F2DED028B0FF26429C7 -:10159000D9E900898D4C93B08D4E8E4F204601F0D5 -:1015A00083FD034660B30025CDE90F550E95ADF8D8 -:1015B0004450027B8DF8442099684068DFF83CA2D3 -:1015C0000FAA03C21B6843F000430E9301F014FA04 -:1015D000821941F1000300950EA9384600F002FB84 -:1015E000A84205DD204601F063FD8AF80050D5E7EA -:1015F0009AF80030072B00F2B68001338AF80030E9 -:101600000BAE9FED6E8B0023724FDFF8F4A10A93AF -:10161000ADF834300B9373604FF0000B5B468DEDEB -:10162000008B01250DF11D0207A938468DF81C50CD -:101630008DF81DB000F058FE9DF81C30002B40F0D6 -:101640009680204601F062FC0646002845D1624F94 -:1016500001F0D0F93B6898423FD301F0CBF98246C4 -:10166000FFF748FB4FF4C8730AF5167AB0FBF3F2A4 -:1016700002FB13031AFA83F33B60584F97F800B04C -:10168000CBF1100ABBF1000F14BF33462B465FFAB3 -:101690008AFA0EA88DF82830FFF744FBBAF1060F3E -:1016A00028BF4FF0060A0EAB03EB0B0152460DF1BB -:1016B000290000F0CBF90AAB0393182302930AF137 -:1016C0000102474BD2B2CDE90053049220463DA31C -:1016D000D3E9002301F01CFC3E7001F08BF9414A74 -:1016E000414D1368C31AB3F57A7F2FD3106001F010 -:1016F00083F902460B46204601F0E4FC204601F047 -:1017000005FC18B32B7B394E002B14BF0323022397 -:10171000737101F06FF90EAF4FF47A733946B0FB75 -:10172000F3F030603046FFF79FFB18230730029339 -:101730002F4B0193C0F3CF0040F25513CDE9037056 -:10174000009342464B46204601F0E2FB2B7B2BB137 -:10175000FFF7F8FA2B7B002B7FF41EAF13B0BDEC24 -:10176000028BBDE8F08F204601F0A2FC48E7DAF8D2 -:10177000143083F00803CAF81430594610220EA81A -:1017800000F076F90DF11E0308AA0AA9384600F008 -:1017900027FB96E803000FAB83E803009DF8343085 -:1017A0008DF844300A9B0E930EA9DDE908232046EC -:1017B00001F046FE30E700BFAFF3008000000000FC -:1017C00000000000401DA12026812A0BCC22002011 -:1017D00040420F00F8220020C8220020C52200202D -:1017E000C4220020A8340020C8330020B4120020F6 -:1017F000AC340020F1C6A7C1D068080FAD3400207A -:101800000004004808B5054800F084FBBDE8084026 -:10181000034A0449002003F0EBBA00BFF82200207D -:1018200000350020691000082DE9F84F4FF47A7355 -:10183000DFF85880DFF8589006460D4602FB03F7A4 -:10184000002498F900305A1C5FFA84FA01D0A342B0 -:1018500010D159F8240003682A46D3F820B0314645 -:101860003B46D847854205D1074B012083F800A0AD -:10187000BDE8F88F0134032CE3D14FF4FA7002F085 -:10188000CDFC0020F4E700BFF43400201811002044 -:10189000D451000807B50023024601210DF10700CD -:1018A0008DF80730FFF7C0FF20B19DF8070003B0A7 -:1018B0005DF804FB4FF0FF30F9E700000A4608B579 -:1018C0000421FFF7B1FF80F00100C0B2404208BD23 -:1018D00030B4074B0A461978064B53F82140236869 -:1018E000DD69054B0146AC46204630BC604700BF71 -:1018F000F4340020D4510008A086010070B502F035 -:10190000CBFD094E094D308000242868338883427E -:1019100008D902F0BDFD2B6804440133B4F5204F13 -:101920002B60F2D370BD00BFF6340020B03400202D -:1019300002F072BE00F1006000F5204000687047C0 -:1019400000F10060920000F5204002F0E9BD0000C7 -:10195000054B1A68054B1B889B1A834202D9104419 -:1019600002F096BD00207047B0340020F63400200D -:1019700038B5074D04462868204402F08FFD28B989 -:1019800028682044BDE8384002F09ABD38BD00BF49 -:10199000B03400200020704700F10050A0F5104046 -:1019A000D0F8900570470000064991F8243033B113 -:1019B0000023086A81F824300822FFF7C1BF012004 -:1019C000704700BFB4340020014B1868704700BF57 -:1019D000002004E070B50E4B5C6893F90860421E6D -:1019E0000A44013C0B46934207D214F9015F581C8C -:1019F0002DB100F8015C0346F5E7184605E02C24FC -:101A000082421C7001D9981C5E70401A70BD00BFE4 -:101A10001C110020022802BF024B4FF400229A61E1 -:101A2000704700BF00040048022802BF014B082293 -:101A30009A61704700040048022801BF024A5369B6 -:101A400083F00803536170470004004810B5002379 -:101A5000934203D0CC5CC4540133F9E710BD0000BD -:101A600003460246D01A12F9011B0029FAD1704729 -:101A700002440346934202D003F8011BFAE7704781 -:101A80002DE9F8431F4D144695F824200746884653 -:101A900052BBDFF870909CB395F824302BB920220C -:101AA000FF2148462F62FFF7E3FF95F82400C0F1BD -:101AB0000802A24228BF2246D6B24146920005EB58 -:101AC0008000FFF7C3FF95F82430A41B1E44F6B234 -:101AD000082E17449044E4B285F82460DBD1FFF768 -:101AE00063FF0028D7D108E02B6A03EB820383420F -:101AF000CFD0FFF759FF0028CBD10020BDE8F883F5 -:101B00000120FBE7B4340020024B1A78024B1A7014 -:101B1000704700BFF43400201811002008B50849B0 -:101B200008484FF461430B6002F012FA044906487A -:101B300002F00EFABDE808400149044802F008BA74 -:101B4000DC3400200435002070350020DC35002016 -:101B5000094B10B51822044600211846FFF788FFEC -:101B6000064A074B127804600146BDE8104053F85E -:101B7000220002F0EDB900BFDC340020F434002074 -:101B8000D4510008202383F3118862B67047000007 -:101B9000002383F3118862B67047000010B4026816 -:101BA00054681A4623465DF8044B184701207047D5 -:101BB0000020704700207047704700007047000009 -:101BC000002070470E20704700F5805090F8C80044 -:101BD000C0F340007047000000F5805090F9C90044 -:101BE000704700002DE9F0410C68BDF8187014F042 -:101BF00000541E466FD10B7B082B6CD8FFF7C2FF39 -:101C00004569AB685B010CD4AB681B0108D4AC68B8 -:101C100014F080545DD1FFF7BBFF2046BDE8F08192 -:101C200001240B6804F1180C002BB8BFDB004FEA4D -:101C30000C1CB4BF43F004035B0545F80C300B6883 -:101C40000FFA84FC13F0804F18BF05EB0C1E05EB58 -:101C50000C1C1EBFDEF8803143F00203CEF8803149 -:101C60000B7BCCF8843105EB04158B68C5F88C31FF -:101C70004B68C5F88831DCF8803143F00103CCF8BB -:101C8000803100EB441541F268031D4403EB44131B -:101C90000344C5E9002608330D4601F10C0C55F844 -:101CA00004EB43F804EB6545F9D184342D881D809D -:101CB00000EB441407F00303257925F00B052B43B3 -:101CC0002371FFF765FF06973346BDE8F04100F04A -:101CD000AFBC0224A5E74FF0FF309FE713B500F536 -:101CE00080540191E06D00F039FD1F280AD9019957 -:101CF000E06D202200F0A8FDA0F1200358425841D9 -:101D000002B010BD0020FBE708B500F58050FFF7DA -:101D100039FFC06D00F0F6FCBDE80840FFF738BFA2 -:101D200000220260828142608260704710B500220A -:101D30000023C0E900230023044603810C30FFF791 -:101D4000EFFF204610BD0000F0B5054600F58050BD -:101D50000C4690F8C83013F0040FC3F3800108BF9D -:101D6000114661F3820304F1840680F8C83005EB64 -:101D7000461389B01B79D8072ED57AB319072DD40D -:101D80006846FFF7D3FF05EB441303F5835303F1D4 -:101D9000180703AA103318685968144603C4083397 -:101DA000BB422246F7D1186820609B88A380DDE9FA -:101DB0000E23CDE900230123ADF808302B686946D6 -:101DC0001B6C2846984705EB46152B791A075CBF14 -:101DD00043F008032B7101E0002AF4D109B0F0BDF3 -:101DE0002DE9F047074688B007F5805468469A46C3 -:101DF0008846FFF7C7FE9146FFF798FFE06D00F0B9 -:101E000093FC1F2829D9E06D2022694600F09EFD31 -:101E1000202822D103AD444605AB2E4603CE9E4278 -:101E200020606160354604F10804F6D13068206016 -:101E3000B388A380DDE90023C9E90023BDF8083099 -:101E4000AAF80030FFF7A4FE4A46534641463846FA -:101E500008B0BDE8F04700F0D9BBFFF799FE0020BD -:101E600008B0BDE8F08700002DE9F84F0023C0E975 -:101E70000133254B044640F8183B0F46FFF750FF4F -:101E800004F12800FFF752FF04F1480804F58255D9 -:101E90004646083530462036FFF748FFAE42F9D1B6 -:101EA00004F580554FF480534FF00009C5E913390C -:101EB000C5F848800123EE6504F5875804F584567B -:101EC000C5F8549085F8583085F86030083608F128 -:101ED00008084FF0000A4FF0000B46E908ABA6F1E6 -:101EE0001800FFF71DFF203646F8289C4645F4D120 -:101EF00085F8C97017B1054800F076FD044B6361A1 -:101F00002046BDE8F88F00BF08520008E0510008E5 -:101F10000064004010B5044B197804464A1C1A703E -:101F2000FFF7A2FF204610BDFC3400202DE9F0474A -:101F3000002950D0294B2A4FB7FBF1F599428CBFAD -:101F40000A231123581EB5FBF3FC03FB1C53C4B238 -:101F50002BB102280346F5D80020BDE8F0870CF12C -:101F6000FF36B6F5806FF7D2C4EBC40E0EF1030353 -:101F70004FEAE309C3F3C703A4EB030809F1010A1D -:101F80004FF47A755FFA88F009FB05555AFA88F81C -:101F9000B5FBF8F5B5F5617FC1BF0EF1FF33C3F3B3 -:101FA000C703E01AC0B25C1C50FA84F40CFB04F4C2 -:101FB000B7FBF4F4A142CFD1013BDBB20F2BCBD85E -:101FC0000138C0B20728C7D800211071168091705F -:101FD000D3700120C1E70846BFE700BF3F420F00B2 -:101FE00000B4C40470B505460E464FF47A746B69AC -:101FF0005B6803F00103B34207D04FF47A7002F03C -:102000000DF9013CF3D1204670BD0120FCE7000032 -:1020100030B54269936913F0700F16D000230B4C52 -:10202000936103F1840200EB421211794D0709D547 -:10203000890707D5416954F823508D60117941F023 -:10204000040111710133032BEBD130BDF4510008B1 -:1020500073B51D46436916469A68D207044609D5EA -:102060009A6801219960C2F34002CDE90065002120 -:10207000FFF76AFE63699A68D1050BD59A684FF439 -:1020800080719960C2F34022CDE9006501212046AC -:10209000FFF75AFE63699A68D2030BD59A684FF42A -:1020A00080319960C2F34042CDE9006502212046AB -:1020B000FFF74AFE204602B0BDE87040FFF7A8BF18 -:1020C000F8B50446466900296CD106F10C0738685A -:1020D00080076AD006EB01153868D5F8B00110F01A -:1020E000040FD5F8B0011ABFC00840F00040400D01 -:1020F000A061D5F8B0C11CF0020F1CBF40F08040B9 -:10210000A061D5F8B40106EB011100F00F0084F8CE -:102110002400D1F8B8012077D1F8B801000A60771F -:10212000D1F8B801000CA077D1F8B801000EE07723 -:10213000D1F8BC0184F82000D1F8BC01000A84F871 -:102140002100D1F8BC01000C84F82200D1F8BC11A8 -:10215000090E84F823103821396004F1340004F1A9 -:10216000180104F1240551F8046B40F8046BA942EE -:10217000F9D109880180C4E90A2321460023238676 -:1021800051F8283B20461B6C984704F580522046A6 -:1021900092F8C83043F0040382F8C830BDE8F84034 -:1021A000FFF736BF06F1100791E7F8BD10B50446FA -:1021B00000F022FC02460B4652EA030102D0013A2B -:1021C00063F100030449086820B12146BDE81040CE -:1021D000FFF776BF10BD00BFF8340020F8B500F55A -:1021E00083511E46FFF7CEFCDFF844C008310024BF -:1021F00004F1840500EB45152B795F070ED4DB064F -:102200000CD5D1E900739742B34107D243695CF81A -:1022100024709F602B7943F004032B710134032C4D -:1022200001F12001E4D1BDE8F840FFF7B1BC00BFE7 -:10223000F451000808B5FFF7A5FCFFF7E9FEBDE87B -:102240000840FFF7A5BC0000F8B54369054698684B -:1022500000F0E050B0F1E05F0F461FD0E8B1FFF7AB -:1022600091FC05F583541034002606F1840305EB38 -:1022700043131B791A0706D50136032E04F12004F7 -:10228000F3D1012007E05B07F6D42146384600F081 -:1022900009FA0028F0D1FFF77BFCF8BD0120FCE72C -:1022A00000F5805008B5FFF76DFCC06D00F03CFAFA -:1022B000FFF76EFC43090CBF0120002008BD0000A1 -:1022C000F8B51D46002313700F4606461446FFF767 -:1022D000E7FF80F00100387025B129463046FFF74E -:1022E000B3FF2070F8BD00002DE9B8410C4615463B -:1022F0001F46804600F080FB0B462178024609B954 -:10230000287850B14046FFF769FFFFF793FF3B463F -:102310002A462146FFF7D4FF0120BDE8B88100001E -:1023200010B5FFF72FFC174B9A6D42F000729A65BB -:102330009A6B42F000729A639A6B00F5805422F017 -:1023400000729A63FFF724FC94F8C830DB0718D4B6 -:10235000B9B102211320FFF715FC01F047FC02215F -:10236000142001F043FC0221152001F03FFC94F8F9 -:10237000C83043F0010384F8C830BDE81040FFF7CF -:1023800007BC10BD001002402DE9F04700F5805554 -:1023900088B095F8C930012B04468846164600F2ED -:1023A000FB807E4F57F823200AB947F82300D7F85F -:1023B00000A0C4F80C802674BAF1000F09D141F2D4 -:1023C000D00002F01DFD51468146FFF74DFDC7F8D4 -:1023D000009095F8C930012B5DD001212046FFF710 -:1023E0009FFFFFF7CFFB6269136823F002031360BE -:1023F0006269136843F001031360636900275F613A -:1024000001212046FFF7C4FBFFF7ECFD002800F098 -:102410008480E86D00F076F904F58359BA4609F135 -:102420000809202200216846FFF722FB02A8FFF7D7 -:1024300077FCCDF818A06A4609EB07030DF1180EDA -:102440009446BCE80300F44518605960624603F105 -:102450000803F5D1DCF80000186020379CF8042050 -:102460001A71602FDDD195F8C8306FF38203002711 -:1024700085F8C8306A4641462046ADF80070ADF890 -:1024800002708DF80470FFF751FD6369C0B94FF415 -:1024900000421A6011E0386803685B6B9847014698 -:1024A00000289AD13868FFF73BFF38680368324646 -:1024B0005B684146984700288FD108B0BDE8F08797 -:1024C00061221A609DF802309DF803201B06120459 -:1024D00002F4702203F040731343BDF80020C2F3EE -:1024E000090213439DF804201205022E02F4E002B3 -:1024F0000CBF4FF000410021134362690B43D361CD -:10250000636913225A616269136823F0010313603F -:1025100039462046FFF766FD08B96369B7E795F8C5 -:10252000C93093BB6169D1F8002242F00102C1F8C1 -:1025300000226169D1F8002222F47C5222F00E02BE -:10254000C1F800226169D1F8002242F46062C1F84A -:1025500000226269C2F814326269C2F80432626908 -:1025600041F6FF71C2F80C126269C2F8403262692A -:10257000C2F8443263690122C3F81C226269D2F8AE -:10258000003223F00103C2F8003295F8C83043F05E -:10259000020385F8C83090E700208EE7F834002069 -:1025A00008B500F029FA50EA0103024602D0421EA3 -:1025B00061F10001044B186810B10B46FFF748FDAC -:1025C000BDE8084001F06CB9F834002008B50020DF -:1025D000FFF7ECFDBDE8084001F062B908B5012045 -:1025E000FFF7E4FDBDE8084001F05AB90FB4002040 -:1025F00004B0704713B56C4684E80600031D94E8E8 -:10260000030083E80500012002B010BD73B58568A2 -:10261000019155B11B885B0707D4D0E90036DB6B0D -:102620009847019AC1B23046A847012002B070BD58 -:10263000F0B5866889B005460C465EB1BDF8383005 -:102640005B070AD4D0E90037DB6B98472246C1B25A -:102650003846B047012009B0F0BD00220023CDE983 -:1026600000230023ADF808300A4603AB01F1080649 -:10267000106851681C4603C40832B2422346F7D1A1 -:10268000106820609288A28000F0B8F90423ADF8A9 -:1026900008302B68CDE900011B6C69462846984735 -:1026A000D8E7000030B503680968DD0FB5EBD17FCE -:1026B00023F0604421F060424FEAD1700BD0002B30 -:1026C000B8BFA40C0029B8BF920C944202D034BF0A -:1026D0000120002030BD944205D1C1F38070C3F3C6 -:1026E00080738342F6D194422CBF00200120F1E791 -:1026F00010B5037C044613B9006802F0B9FB20460C -:1027000010BD00000023BFF35B8FC360BFF35B8F7E -:10271000BFF35B8F8360BFF35B8F7047BFF35B8F4B -:102720000068BFF35B8F704770B505460C30FFF74C -:10273000F5FF05F1080604463046FFF7EFFFA0421B -:1027400006D930466D68FFF7E9FF2544281A70BDA9 -:102750003046FFF7E3FF201AF9E7000070B50546A1 -:10276000406898B105F10800FFF7D8FF05F10C06A5 -:1027700004463046FFF7D2FF8442304694BF6D686E -:102780000025FFF7CBFF013C2C44201A70BD000050 -:1027900038B50C460546FFF7C7FFA04210D305F138 -:1027A0000800FFF7BBFF04446868B4FBF0F100FBCE -:1027B0001144BFF35B8F0120AC60BFF35B8F38BD6A -:1027C0000020FCE72DE9F041144607460D46FFF7CF -:1027D000C5FF844228BF0446D4B1B84658F80C6BF4 -:1027E0004046FFF79BFF3044286040467E68FFF775 -:1027F00095FF331A9C4203D86C600120BDE8F0813C -:102800006B60A41B3B68AB602044E8600220F5E7E6 -:102810002046F3E738B50C460546FFF79FFFA04278 -:1028200010D305F10C00FFF779FF04446868B4FB8E -:10283000F0F100FB1144BFF35B8F0120EC60BFF3AC -:102840005B8F38BD0020FCE72DE9FF4188466946D3 -:102850000746FFF7B7FF6C4606B204EBC606002535 -:10286000B44209D06268206808EB0501FFF7EEF872 -:10287000636808341D44F3E729463846FFF7CAFF6A -:10288000284604B0BDE8F081F8B505460C300F4687 -:10289000FFF744FF05F1080604463046FFF73EFF08 -:1028A000A042304688BF6C68FFF738FF201A3860B6 -:1028B00020B130462C68FFF731FF2044F8BD0000FE -:1028C00073B5144606460D46FFF72EFF844228BF17 -:1028D00004460190DCB101A93046FFF7D5FF019B0A -:1028E00033B93268C5E90233C5E9002401200CE0A0 -:1028F0009C4238BF01942860019868608442F5D9F1 -:102900003368AB60241AEC60022002B070BD204630 -:10291000FBE700002DE9FF410F466946FFF7D0FFB6 -:102920006C4600B204EBC0050026AC4209D0D4F8D6 -:10293000048054F8081BB8194246FFF787F846444C -:10294000F3E7304604B0BDE8F081000038B5054635 -:10295000FFF7E0FF044601462846FFF719FF20462F -:1029600038BD000000B59BB0EFF3098168226846CE -:10297000FFF76CF8EFF30583044B9A6BDA6A9A6AF7 -:102980009A6A9A6A9A6A9A6A9B6AFEE700ED00E080 -:1029900000B59BB0EFF3098168226846FFF756F84F -:1029A000EFF30583044B9A6B9A6A9A6A9A6A9A6A59 -:1029B0009A6A9B6AFEE700BF00ED00E000B59BB09D -:1029C000EFF3098168226846FFF740F8EFF30583CB -:1029D000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE7EA -:1029E00000ED00E0FEE700000FB408B5029801F02A -:1029F000AFFBFEE701F050BE01F028BE01F026BE9D -:102A000030B5094D0A4491420DD011F8013B5840B0 -:102A1000082340F30004013B2C4013F0FF0384EA39 -:102A20005000F6D1EFE730BD2083B8ED2DE9F0413D -:102A3000C56915B9C161BDE8F0814B6823F06047F5 -:102A4000C3F38A464FEAD37EC3F3807816EA23069F -:102A500038BF3E46AC462B465A68BEEBD27F22F0CA -:102A600060440AD0002A18DAA40CB44217D19D425F -:102A70000FD10D60DEE71346EEE7A74207D102F063 -:102A80008044C2F3807242450BD054B1EFE708D2C4 -:102A9000EDE7CCF800100B60CDE7B44201D0B442B2 -:102AA000E5D81A689C46002AE5D11960C3E7000002 -:102AB0002DE9F047089D01F007044FEAD5082244AC -:102AC00005F0070500EBD1004FF47F49944201D196 -:102AD000BDE8F08704F0070705F0070A57453E46B2 -:102AE00038BF5646C6F10806111B8E4228BF0E4657 -:102AF000E10808EBD50E415C13F80EC0B94029FA85 -:102B000006F721FA0AF1FFB28CEA010147FA0AF747 -:102B100039408CEA010C03F80EC034443544D5E743 -:102B200080EA0120082341F2210201B2400000297D -:102B300080B203F1FF33B8BF504013F0FF03F4D16C -:102B40007047000038B50C468D18A54200D138BD3D -:102B500014F8011BFFF7E4FFF7E7000002684AB131 -:102B600013680360C388018901339BB29942C38013 -:102B700038BF03811046704770B588B020220446E4 -:102B80000D4668460021FEF773FF20460495FFF7C7 -:102B9000E5FF024658B16B46054608AE1C4603CC1D -:102BA000B44228606960234605F10805F6D1104655 -:102BB00008B070BD082817D909280CD00A280CD0F5 -:102BC0000B280CD00C280CD00D280CD00E2814BFCC -:102BD0004020302070470C20704710207047142090 -:102BE000704718207047202070470000082817D928 -:102BF0000C280CD910280CD914280CD918280CD959 -:102C000020280CD930288CBF0F200E2070470920B7 -:102C100070470A2070470B2070470C2070470D202A -:102C20007047000010B54B6823B9CA8A63F30902E4 -:102C3000CA8210BDC4681A681C60C360438A013B25 -:102C400043824A60EFE700002DE9F84F1D46CB8A2A -:102C50000F46C3F309010629814692460B4630D040 -:102C60000020AAB207F119049EB2052E1FFA80F8BF -:102C70000FD8904503F1010306D3FB8A0A4462F39F -:102C80000903FB8201201AE01AF80060E6540130C3 -:102C9000EAE79045F1D2A1F1060B1C237C68BBFB4F -:102CA000F3F203FB12BB1FFA8BF6002C45D148460A -:102CB000FFF754FF044638B978606FF00200BDE8B2 -:102CC000F88F4FF00008E6E7002606607860ADB2A6 -:102CD0004FF0000B454510D90AEB0803221D13F8ED -:102CE000011B9155B1B208F101081B291FFA88F8A0 -:102CF0002BD0454506F10106F1D8FB8AC3F3090242 -:102D0000154465F30903BCE7013292B21C462368FF -:102D1000002BF9D1AB1F0B441C21B3FBF1F30133A2 -:102D20009BB29A42D3D2BBF1000FD0D14846FFF7F5 -:102D300015FF20B9C4F800B0BFE70122E7E7C0F8EB -:102D400000B05E4620600446C1E74545D5D94846F7 -:102D5000FFF704FF08B92060AFE7C0F800B0002615 -:102D600020600446B6E700002DE9F04F2DED028B00 -:102D700083B0CDE90013BDF83C5007469146002AC8 -:102D800000F092802DB10E9B002B00F08D80072D5E -:102D900032D807F10C00FFF7E1FE044638B96FF0B6 -:102DA0000204204603B0BDEC028BBDE8F08F142274 -:102DB0000021FEF75DFE0E992A4604F10800FEF799 -:102DC00045FE681CC0B2FFF711FFFFF7F3FE207449 -:102DD00099F80030013814FA80F003F01F0363F013 -:102DE0003F030372009B43F0004161603846214677 -:102DF000FFF71CFE0124D4E700F10C034FF000089C -:102E000008EE103A4FF0800A4646444618EE100A83 -:102E1000FFF7A4FE83460028C1D014220021FEF74C -:102E200027FEC6BB019BABF8083002200E9B00F1C9 -:102E3000080299195BFA82F20130C0B2082801D069 -:102E4000AE422AD3FFF7D2FEFFF7B4FE99F8002076 -:102E5000009B411E02F01F0242EA4812AE4208BF28 -:102E60004FF0400A5BFA81F14AEA020A43F000425D -:102E700081F808A08BF81000CBF80420594638469A -:102E8000FFF7D4FD0134AE4224B288F001084FF0C0 -:102E9000000ABBD185E70020C8E711F801CB02F892 -:102EA00001CB0136B6B2C7E76FF0010479E7000045 -:102EB000F8B515460E462822002104461F46FEF7A7 -:102EC000D7FD069B6360B5F5001F079BA76034BF65 -:102ED0006A094FF6FF72236204F10C0097B20023D7 -:102EE0009A4205D80023036027826382A382F8BD3B -:102EF0000660013330462036F2E7000003781BB944 -:102F00004BB2002BC8BF01707047000000787047BB -:102F10002DE9F74FDDF83C90BDF830500D9E9DF83F -:102F20003840BDF84070804692469B46B9F1000F8C -:102F300001D1002F51D11F2C4FD898F80000B0B903 -:102F4000072F47D835F0030347D13A4649464FF695 -:102F5000FF70FFF7F7FD20F001002D02400445EA65 -:102F60000464400C44EA40244FF6FF7321E040EA39 -:102F70000520072F40EA0464F6D900254FF6FF73B9 -:102F8000C5F12000A5F120022AFA05F10BFA00F0A4 -:102F900001432BFA02F211431846C9B2FFF7C0FDF4 -:102FA0000835402D0346EBD13A464946FFF7CAFDA6 -:102FB0000346CDE90097324621464046FFF7D4FE4E -:102FC00033780133DBB21F2B88BF0023337003B08B -:102FD000BDE8F08F6FF00300F9E76FF00100F6E74E -:102FE0002DE9F04F85B09246DDF848800F9D9DF8A1 -:102FF00040209DF84490BDF84C7006469B46B8F1C1 -:10300000000F01D1002F48D11F2A46D83378002B5A -:1030100046D00C0244EA02649DF8381044EAC934F0 -:1030200044EA01441C43072F44F0800432D90023B2 -:103030004FF6FF72C3F1200CA3F120002AFA03F12E -:103040000BFA0CFC41EA0C012BFA00F00143C9B267 -:1030500010460393FFF764FD039B0833402B0246A1 -:10306000E8D13A464146FFF76DFD0346CDE90087BA -:103070002A4621463046FFF777FEB9F1010F06D107 -:103080002B780133DBB21F2B88BF00232B7005B0D8 -:10309000BDE8F08F4FF6FF73E8E76FF00100F6E749 -:1030A0006FF00300F3E70000C06900B1043070471F -:1030B000C3691A68C261C2681A60C360438A013B6F -:1030C000438270472DE9F041D0F81880194E14461C -:1030D0001D464146002709B9BDE8F081D1E9022328 -:1030E000A21A65EB0303964277EB03031ED28369B2 -:1030F0008B420DD1FFF796FD83691B688361C3681E -:103100000B60438AC1608169013B43828846E2E7E4 -:10311000FFF788FD0B68C8F80030C3680B60438A6E -:10312000C160013B4382D8F80010D4E788460968A3 -:10313000D1E700BF80841E002DE9F04F8BB00D4613 -:10314000DDF8509014469B468046002800F0198117 -:10315000B9F1000F00F01581531E3F2B00F21181D1 -:10316000012A03D1BBF1000F40F00B810023CDE910 -:103170000833B8F81430B5EBC30F4FEAC30703D3D5 -:1031800000200BB0BDE8F08F2B199F42D8F80C300F -:103190003ABF7F1BFFB227461BB9D8F81030002B6F -:1031A0007AD02F2D4ED8C5F13006B7424FF000032C -:1031B0002CBFF6B23E4600932946D8F8080008AB6B -:1031C0003246FFF775FCA7EB060A35445FFA8AFA28 -:1031D000B8F8143003F10053063BDB000493D8F831 -:1031E0000C3003933021039B13B1BAF1000F2CD1A3 -:1031F000D8F8100040B1BAF1000F05D0009608AB26 -:103200005246691AFFF754FC38B2002FB8D066074F -:103210000AD00AAB03EBD401624211F8083C02F079 -:103220000702134101F8083C082C3CD9102C40F24D -:10323000B580202C40F2B780BBF1000F00F09C80DD -:10324000082334E0BA460026C2E7049BE02B28BFDF -:10325000E02306930B44AB42059314D95A1B039801 -:103260000096924534BF5246D2B2691A08AB043078 -:103270000792FFF71DFC079A1644AAEB020A1544B1 -:10328000F6B25FFA8AFA049B069A05999B1A049390 -:10329000039B1B680393A6E70093D8F8080008ABCC -:1032A0003A462946AEE7BBF1000F13D00123B4EB39 -:1032B000C30F6CD0082C12D89DF82030621E23FA60 -:1032C00002F2D50706D54FF0FF3202FA04F4234389 -:1032D0008DF820309DF8203089F8003051E7102C0F -:1032E00012D8BDF82030621E23FA02F2D10706D5AB -:1032F0004FF0FF3202FA04F42343ADF82030BDF85A -:103300002030A9F800303CE7202C0FD80899631E24 -:1033100021FA03F3DA0705D54FF0FF3202FA04F47D -:103320000C430894089BC9F800302AE7402C2BD0A6 -:10333000DDE90865611EC4F12102A4F1210326FA2A -:1033400001F105FA02F225FA03F311431943CB0701 -:1033500012D50122A4F12003C4F1200102FA03F3E3 -:1033600022FA01F1A240524243EA010363EB430314 -:1033700032432B43CDE90823DDE90823C9E90023C3 -:10338000FFE66FF00100FCE66FF00800F9E6082C9C -:10339000A0D9102CB3D9202CEED8C3E7BBF1000F75 -:1033A000ADD0022383E7BBF1000FBBD004237EE73F -:1033B00030B5012A144638BF0124402C85B028BFFF -:1033C00040240025012ACDE9025518D81B788DF834 -:1033D000083063070AD004AB03EBD405624215F84A -:1033E000083C02F00702934005F8083C00910346B0 -:1033F0002246002102A8FFF75BFB05B030BD082A7A -:10340000E4D9102A03D81B88ADF80830E1E7202A58 -:103410008DBFD3E900231B680293CDE90223D8E7CF -:1034200010B5CB681BB98B600B618B8210BDC46873 -:103430001A681C60C360438A013B4382CA60F0E79C -:103440002DE9F04FD1F8008093B018F0800FCDE94E -:103450000323C8F3C01219BFC8F3C03BC8F3062644 -:103460004FF0020B1646B8F1000F04460D4680F2ED -:10347000D18118F0C043059340F0CC810B7B002B29 -:1034800000F0C881BBF1020F03D00178B14240F0D7 -:10349000C48108F07F0106916AB3C8F3074A2B4440 -:1034A000069A93F80390760646EA0B4646EA824669 -:1034B0005FEAD91346EA0A06079300F090800022DB -:1034C0000023CDE90A23069B009367685B465246BA -:1034D0000AA92046B84700287ED0A7699FB931467F -:1034E00004F10C00FFF748FB0746E0B96FF002005B -:1034F00013B0BDE8F08FC8F30F2A18F07F0F08BF94 -:103500000AF0030ACBE73B699E420DD03F68002FCB -:10351000F9D1314604F10C00FFF72EFB07460028D5 -:10352000E4D0A3693B60A761DDE90A2300264FF6DA -:10353000FF70C6F1200E22FA06F103FA0EFEA6F184 -:10354000200C23FA0CFC41EA0E0141EA0C01C9B23D -:10355000083609920893FFF7E3FA402EDDE90832B6 -:10356000E7D1B882FB7D09F01F06C3F384039B1BE0 -:10357000D7E9022198B2002BBCBF00F120031BB297 -:1035800052EA0100C8F304680FD00398821A049825 -:1035900060EB0101A74890424FF000028A4104D33A -:1035A000079A002A5BD0012B23DDFA7D4FEA8903BD -:1035B00002F0030203F07C031343FB7539462046F7 -:1035C000FFF730FB079BA3B9FB7DC3F384020132F5 -:1035D00062F38603FB7504E06FF00B0088E7A769D0 -:1035E00017B96FF00C0083E73B699E42BAD03F6881 -:1035F000F6E719F0400F32D0039BBB60049BFB60E1 -:10360000142200210DA8FEF733FA039B0A93049BB2 -:103610000B932B1D0C932B7BADF83EA0013BDBB233 -:10362000ADF83C30069B8DF8433094F824308DF88B -:1036300040B083F001038DF844308DF84160A368F9 -:103640008DF842800AA920469847FB7DC3F3840386 -:10365000013303F01F039B02FB82002048E7FB7D40 -:10366000C9F34012B2EBD31F40F0DA80C3F38403F6 -:10367000B34240F0D88007992B7B4FEA991200297A -:1036800034D0D20741D4032B40F2D080039BBB60DF -:10369000049BFB602B7BAE1D033BDBB232463946FD -:1036A00004F10C00FFF7D0FA00280DDA2046394665 -:1036B000FFF7B8FAFB7DC3F38403013303F01F0364 -:1036C0009B02FB82032013E7AB883B832A7B033AF0 -:1036D000B88AD2B23146FFF735FAFB7DB882DA43B9 -:1036E000C2F3C01262F3C713FB75B6E76AB92E1DA9 -:1036F000013BDBB23246394604F10C00FFF7A4FA75 -:103700000028D3DB2A7B013AE2E7F98AC1F30901F9 -:10371000013B0529DAB259D8281D002307F11A0CFC -:103720009A4208D910F801EB0CF801E0013101339D -:103730000629DBB2F4D103990A9104990B919342C3 -:1037400007F11A010C9138BF043379680D9134BF29 -:1037500055FA83F300230E93FB8AADF83EA0C3F322 -:1037600009031A44069B8DF8433094F82430ADF8D1 -:103770003C2083F001038DF8443000238DF840B0E5 -:103780008DF841608DF842807B602A7BB88A013ACF -:10379000291DFFF7D7F93B8BB882834203D1A36879 -:1037A0000AA92046984720460AA9FFF739FEFB7D63 -:1037B000B88AC3F38403013303F01F039B02FB8227 -:1037C0003B8B984214BF1120002091E67B68002BB0 -:1037D000B1D0062001E01C306346D3F800C0BCF134 -:1037E000000FF8D1091A081D05F1040C00EB0309BC -:1037F00005989DF8143001EB000EBEF11B0F9AD80E -:103800009A4298D91CF8013B09F8013B059B01330A -:103810000593EDE76FF009006AE66FF00A0067E6CE -:103820006FF00D0064E66FF00E0061E66FF00F00C0 -:103830005EE600BF80841E00EFF3098305494A6BF2 -:1038400022F001024A63683383F30988002383F37B -:103850001188704700EF00E0202080F3118862B6E5 -:103860000C4B0D4AD96821F4E0610904090C0A43A4 -:10387000DA60D3F8FC20094942F08072C3F8FC20DA -:103880000A6842F001020A601022DA7783F8220007 -:10389000704700BF00ED00E00003FA05001000E0F3 -:1038A00010B5202383F311880E4B5B6813F400637B -:1038B00014D0F1EE103AEFF30984683C4FF08073B6 -:1038C000E361094BDB6B236684F3098800F0F2FBAC -:1038D00010B1064BA36110BD054BFBE783F31188C4 -:1038E000F9E700BF00ED00E000EF00E00B06000884 -:1038F0000E060008026843681143016003B11847CF -:1039000070470000024A136843F0C0031360704719 -:1039100000380140024A136843F0C0031360704747 -:1039200000440040024A136843F0C003136070472C -:103930000048004037B5244C244D204600F0FCFAE6 -:10394000009404F1140022490023202200F0BEF963 -:1039500020490094202204F138001F4B00F038FA6F -:103960001E4BC4E917351E4C204600F0E5FA0094C2 -:1039700004F114001B490023202200F0A7F91A4982 -:103980000094202204F13800184B00F021FA184B63 -:10399000C4E91735174C204600F0CEFA04F11400A4 -:1039A000154900940023202200F090F9134B14498C -:1039B0000094202204F1380000F00AFA114BC4E907 -:1039C000173503B030BD00BF0435002000B4C40477 -:1039D00048360020A836002005390008003801408C -:1039E0007035002068360020C836002015390008E0 -:1039F00000440040DC3500208836002025390008CE -:103A0000E83600200048004030B5037C304C0029E7 -:103A100018BF0C46012B0FD12E4B984239D12E4B9B -:103A20001A6E42F480421A66D3F8802042F4804233 -:103A3000C3F88020D3F880302268036EC16D84669D -:103A400003EB5203B3FBF2F36268150442BF23F0A9 -:103A5000070503F0070343EA4503CB60A36843F07F -:103A600040034B60E36843F001038B6042F49673BC -:103A700043F001030B604FF0FF330B62510505D596 -:103A800012F010221FD0B2F1805F1ED080F8643097 -:103A900030BD124B98420BD0114B9842CCD10E4BFB -:103AA0009A6D42F480229A659A6F42F4802207E070 -:103AB000094B9A6D42F400329A659A6F42F40032D3 -:103AC0009A679B6FB8E77F23E0E73F23DEE700BFFD -:103AD0004C520008043500200010024070350020D0 -:103AE000DC3500202DE9F047C66D3768F469346293 -:103AF0002107054618D014F0080118BF8021E207FD -:103B000048BF41F02001A30748BF41F040016007D2 -:103B100048BF41F48071202383F31188281DFFF7EB -:103B2000E9FE002383F31188E2050AD5202383F3FD -:103B300011884FF40071281DFFF7DCFE002383F38A -:103B400011884FF020094FF0000A14F0200838D1F6 -:103B50003B0616D54FF0200905F1380A200610D58E -:103B600089F31188504600F067F9002836DA0821F9 -:103B7000281DFFF7BFFE27F080033360002383F387 -:103B80001188790614D5620612D5202383F3118893 -:103B9000D5E913239A4208D12B6C33B11021281D8B -:103BA00027F04007FFF7A6FE3760002383F3118854 -:103BB000E30619D5AA6E1369B3B1BDE8F0475069A1 -:103BC000184789F31188B38C95F86410284619407A -:103BD00000F0CCF98AF31188F469B6E780B2308539 -:103BE00088F31188F469B9E7BDE8F08700F1604314 -:103BF00003F561430901C9B283F80013012200F003 -:103C00001F039A4043099B0003F1604303F561439E -:103C1000C3F880211A607047F8B5154682680669B6 -:103C2000AA420B46816938BF8568761AB5420446B8 -:103C30000BD218462A46FDF709FFA3692B44A3615E -:103C4000A3685B1BA3602846F8BD0CD91846324612 -:103C5000FDF7FCFEAF1BE1683A463044FDF7F6FE87 -:103C6000E3683B44EBE718462A46FDF7EFFEE368BE -:103C7000E5E7000083689342F7B51546044638BF70 -:103C80008568D0E90460361AB5420BD22A46FDF7A2 -:103C9000DDFE63692B446361A36828465B1BA36058 -:103CA00003B0F0BD0DD932460191FDF7CFFE019969 -:103CB000E068AF1B3A463144FDF7C8FEE3683B4479 -:103CC000E9E72A46FDF7C2FEE368E4E710B50A44D7 -:103CD0000024C361029B8460C0E90000C0E90511B3 -:103CE000C1600261036210BD08B5D0E9053293429C -:103CF00001D1826882B98268013282605A1C4261B5 -:103D00001970D0E904329A4224BFC368436100218C -:103D100000F0A0FA002008BD4FF0FF30FBE70000E4 -:103D200070B5202304460E4683F31188A568A5B11B -:103D3000A368A269013BA360531CA36115782269A3 -:103D4000934224BFE368A361E3690BB1204698471F -:103D5000002383F31188284607E03146204600F00F -:103D600069FA0028E2DA85F3118870BD2DE9F74F72 -:103D700004460E4617469846D0F81C904FF0200A8D -:103D80008AF311884FF0000B154665B12A4631467B -:103D90002046FFF741FF034660B94146204600F048 -:103DA00049FA0028F1D0002383F31188781B03B06F -:103DB000BDE8F08FB9F1000F03D001902046C8474D -:103DC000019B8BF31188ED1A1E448AF31188DCE7FE -:103DD000C0E90511C160C3611144009B8260C0E964 -:103DE0000000016103627047F8B504460D461646AF -:103DF000202383F31188A768A7B1A368013BA360C0 -:103E000063695A1C62611D70D4E904329A4224BF6E -:103E1000E3686361E3690BB120469847002080F3B3 -:103E2000118807E03146204600F004FA0028E2DA63 -:103E300087F31188F8BD0000D0E905239A4210B538 -:103E400001D182687AB98268013282605A1C82612B -:103E50001C7803699A4224BFC3688361002100F083 -:103E6000F9F9204610BD4FF0FF30FBE72DE9F74F81 -:103E700004460E4617469846D0F81C904FF0200A8C -:103E80008AF311884FF0000B154665B12A4631467A -:103E90002046FFF7EFFE034660B94146204600F09A -:103EA000C9F90028F1D0002383F31188781B03B0EF -:103EB000BDE8F08FB9F1000F03D001902046C8474C -:103EC000019B8BF31188ED1A1E448AF31188DCE7FD -:103ED000026843681143016003B11847704700004E -:103EE0001430FFF743BF00004FF0FF331430FFF7EB -:103EF0003DBF00003830FFF7B9BF00004FF0FF337F -:103F00003830FFF7B3BF00001430FFF709BF0000DF -:103F10004FF0FF311430FFF703BF00003830FFF7D8 -:103F200063BF00004FF0FF323830FFF75DBF000085 -:103F300000207047FFF7FEBC044B03600023C0E97C -:103F40000233436001230374704700BF64520008CA -:103F500010B52023044683F31188FFF755FD022393 -:103F60002374002383F3118810BD000038B5C369A2 -:103F700004460D461BB904210844FFF7A9FF294652 -:103F800004F11400FFF7B0FE002806DA201D4FF4FC -:103F90008061BDE83840FFF79BBF38BD024B00226F -:103FA000C3E900339A607047083700200023037488 -:103FB0008268054B1B6899689142FBD25A6803607E -:103FC00042601060586070470837002008B5202311 -:103FD00083F31188037C032B05D0042B0DD02BB960 -:103FE00083F3118808BD436900221A604FF0FF3344 -:103FF0004361FFF7DBFF0023F2E7D0E900321360F3 -:104000005A60F3E7002303748268054B1B689968C4 -:104010009142FBD85A680360426010605860704754 -:1040200008370020054B19690874186802681A607F -:104030005360186101230374FCF7D2BA08370020DB -:1040400030B54B1C0B4D87B0044610D02B690A4A83 -:1040500001A800F019F92046FFF7E4FF049B13B113 -:1040600001A800F04DF92B69586907B030BDFFF782 -:10407000D9FFF8E708370020CD3F000838B50C4DD0 -:1040800041612B6981689A689142044603D8BDE872 -:104090003840FFF78BBF1846FFF7B4FF01232C61B0 -:1040A000014623742046BDE83840FCF799BA00BFAA -:1040B00008370020044B1A681B6990689B68984277 -:1040C00094BF0020012070470837002010B5084C2D -:1040D000236820691A6822605460012223611A74DF -:1040E000FFF790FF01462069BDE81040FCF778BA61 -:1040F0000837002008B5FFF7DDFF18B1BDE808401C -:10410000FFF7E4BF08BD0000FFF7E0BFFEE70000D7 -:1041100010B50C4CFFF742FF00F0A8F80A498022C6 -:10412000204600F03DF8012344F8180C0374FFF713 -:1041300093FB002383F3118862B60448BDE8104066 -:1041400000F04EB8303700208C5200089C52000816 -:1041500008B572B6034B586200F072FA00F01EFB0D -:10416000FEE700BF0837002000F004B9EFF311802C -:1041700020B9EFF30583202282F3118870470000F5 -:1041800010B530B9EFF30584C4F3080414B180F31B -:10419000118810BDFFF7AEFF84F31188F9E7000026 -:1041A00082600222028270478368A3F17C0243F896 -:1041B0000C2C026943F83C2C426943F8382C074A1E -:1041C00043F81C2CC26843F8102C022203F8082C78 -:1041D000002203F8072CA3F118007047F905000826 -:1041E00010B5202383F31188FFF7DEFF002104467A -:1041F000FFF744FF002383F31188204610BD000021 -:10420000024B1B6958610F20FFF70CBF08370020D5 -:10421000202383F31188FFF7F3BF000008B50146A0 -:10422000202383F311880820FFF70AFF002383F37C -:10423000118808BD49B1064B42681B6918605A6075 -:10424000136043600420FFF7FBBE4FF0FF30704760 -:10425000083700200368984206D01A680260506050 -:1042600059611846FFF7A2BE70470000054B03F1E5 -:104270001402C3E905224FF0FF310022C3E90712FF -:10428000704700BF0837002070B51C4EC0E90323FB -:1042900005460C4600F0FCFA334653F8142F9A42B8 -:1042A0000DD13062C5E901242A600A2C2CBF001907 -:1042B0000A30C6E90555BDE8704000F0D7BA316A4A -:1042C000431AE31838BF1C469368A34202D9081961 -:1042D00000F0DAFA73699A6894420CD85A68AC60B4 -:1042E0002B606A6015609A685D60121B9A604FF0DF -:1042F000FF33F36170BD1B68A41AECE70837002098 -:1043000038B51B4C636998420DD0D0E90032136078 -:104310005A6000228168C2609A680A449A604FF02D -:10432000FF33E36138BD2246036842F8143F0021A1 -:1043300093425A60C16003D1BDE8384000F09EBA94 -:104340009A688168256A0A449A6000F0A1FA636954 -:104350009A68411B8A42E5D9AB181D1A092D206ABB -:1043600098BF01F10A02BDE83840104400F08CBA51 -:10437000083700202DE9F041184C002704F11406FD -:10438000656900F085FA236AAA68C11A8A4215D8BD -:1043900013442362D5E9003213605A606369D5F88B -:1043A0000C80EF60B34201D100F068FA87F3118806 -:1043B0002869C047202383F31188E1E76169B1428E -:1043C00009D013441B1ABDE8F0410A2B2CBFC018BA -:1043D0000A3000F059BABDE8F08100BF083700206C -:1043E0000C2303604FF0FF3070470000002070473F -:1043F000FEE70000704700004FF0FF3070470000FC -:10440000BFF34F8F024A1369DB03FCD4704700BF30 -:104410000020024008B5094B1B7873B9FFF7F0FF85 -:10442000074B5A69002ABFBF064A9A6002F18832D8 -:104430009A601A6822F480621A6008BD90380020E1 -:10444000002002402301674508B50B4B1B7893B948 -:10445000FFF7D6FF094B5A6942F000425A611A68C9 -:1044600042F480521A601A6822F480521A601A6864 -:1044700042F480621A6008BD90380020002002409B -:104480007F289ABF00F58030C002002070470000EE -:104490004FF4006070470000802070477F2808B507 -:1044A0000BD8FFF7EDFF00F500630268013204D17D -:1044B00004308342F9D1012008BD0020FCE7000050 -:1044C0007F2838B5044626D8FFF750FEFFF798FF3F -:1044D000FFF7A0FF114BF3221A6102225A615A69B9 -:1044E00042EAC4025A615A6942F480325A6105466E -:1044F0002046FFF785FF4FF40061FFF7C1FF00F092 -:1045000049F92846FFF7A0FFFFF73AFE2046BDE82D -:104510003840FFF7C3BF002038BD00BF0020024075 -:1045200040EA020313F007032DE9F04705460C4665 -:10453000164606D0324B40F2FB221A600020BDE83E -:10454000F08781182F4A91420CD92D4A4FF44071BF -:104550001160F3E72B1D1B686268934208D1083E87 -:1045600008350834072E19D92A6823689A42F1D0F1 -:10457000FFF7FCFDFFF74EFFFFF742FF04F10801D4 -:10458000214C4FF001084FF00009012EA1F108075E -:1045900008D8FFF759FFFFF7F3FD01E0002EE7D140 -:1045A0000120CCE7C4F81480AA4651F8083C4AF828 -:1045B000043B51F8043C6B60FFF722FFC4F81490F1 -:1045C0002A6851F8083C9A420ED00D4B40F2263230 -:1045D0001A600E4B1D600E4B1E600E4B1F60FFF7E6 -:1045E00033FFFFF7CDFDA9E7DAF800A051F8043C4E -:1045F0009A4501F10801E8D1083E0835C5E700BF3A -:104600008C38002000000408002002408038002080 -:104610008838002084380020084908B50B7828B174 -:104620001BB9FFF7F7FE01230B7008BD002BFCD070 -:10463000BDE808400870FFF707BF00BF90380020B2 -:104640004FF480314FF0005000F0A6B870B582B042 -:10465000FFF78CFD0E4E054600F01AF932689042C5 -:1046600037BF0C4A0B49516814682EBFD1E900418D -:10467000013151600419034641F1000128460191BE -:104680003360FFF77DFD0199204602B070BD00BF89 -:10469000943800209838002070B582B0FFF766FD8E -:1046A000104E054600F0F4F83268904237BF0E4ACB -:1046B0000D49516814682EBFD1E9004101315160A4 -:1046C000041941F100010346284601913360FFF7C8 -:1046D00057FD01994FF47A7200232046FBF768FDDD -:1046E00002B070BD943800209838002010B5024404 -:1046F000064BD2B2904200D110BD441C00B253F818 -:10470000200041F8040BE0B2F4E700BF502800405D -:10471000114B30B5D3F89040240409D4D3F890401D -:10472000C3F89040D3F8904044F40044C3F890405C -:104730000A4C236843F4807323600244084BD2B2CE -:10474000904200D130BD441C00B251F8045B43F8E4 -:104750002050E0B2F4E700BF0010024000700040BB -:104760005028004007B5012201A90020FFF7BEFF35 -:10477000019803B05DF804FB13B50446FFF7F2FFA0 -:10478000A04205D0012201A900200194FFF7C0FF3B -:1047900002B010BD70470000704700007047000075 -:1047A000074B45F255521A6002225A6040F6FF72DA -:1047B0009A604CF6CC421A60024B01221A70704784 -:1047C00000300040A4380020034B1B781BB1034B82 -:1047D0004AF6AA221A607047A43800200030004030 -:1047E000054B1A6832B902F1804202F50432D2F860 -:1047F00094201A60704700BFA0380020024B4FF48D -:104800000002C3F8942070470010024008B5FFF77B -:10481000E7FF024B1868C0F3407008BDA0380020C5 -:1048200070470000FEE700000A4B0B480B4A90421D -:104830000BD30B4BDA1C121AC11E22F003028B425F -:1048400038BF00220021FDF713B953F8041B40F8CC -:10485000041BECE74C5300083C3900203C39002095 -:104860003C3900207047000000F07AB84FF08043D8 -:10487000002258631A610222DA6070474FF08043C9 -:104880000022DA60704700004FF0804358637047A1 -:104890004FF08043586A7047264B2748DA6A42F047 -:1048A000070210B4DA62DA6A22F00702DA62DA6A20 -:1048B000DA6C42F00702DA64DA6E42F00702DA6676 -:1048C0004FF09042DB6E4FF0AA31002353604FF45B -:1048D000EE449160D0604FF6FF7050611462174C47 -:1048E00053621460164CC2F80434C2F80814C2F8BB -:1048F0000C444FF6F774C2F814444FF0EE44C2F87B -:10490000204447F29974C2F824440E4CC2F8004483 -:10491000C2F80438C2F80818C2F80C38C2F81408F3 -:10492000C2F82038C2F82438C2F800385DF8044BC9 -:1049300000F09CB80010024050010024A0010028A3 -:104940001050500050A0AA0008B500F035FAFFF74B -:10495000DFFBBDE80840FFF743BF000070470000E1 -:104960000F4B9A6D42F001029A659A6F42F0010274 -:104970009A670C4A9B6F936843F0010393604FF072 -:1049800080434F229A624FF0FF32DA6200229A612E -:104990005A63DA605A6001225A611A60704700BF98 -:1049A00000100240002004E04FF0804208B5116979 -:1049B000D3680B40D9B2C9439B07116107D52023A7 -:1049C00083F31188FFF7D0FB002383F3118808BD20 -:1049D00008B5244B4FF0FF319A6A99629A6A002217 -:1049E0009A62986AD86A60F00700D862D86A00F0C4 -:1049F0000700D862D86A186B1963186B1A63186BB2 -:104A0000986B60F080509863986B00F080509863CA -:104A1000986BD86BD963D86BDA63D86B186C196450 -:104A2000196C1A64196C996D41F080519965996FF0 -:104A300041F080519967996FD3F8901011F4407F3D -:104A40001EBF4FF48031C3F89010C3F89020D3F804 -:104A50009020C3F8902000F07FF9034B00225A60A9 -:104A600008BD00BF0010024000700040394B3A4AB8 -:104A70009A6501221A601A689007FCD500229A6094 -:104A80009A6812F00C0FFBD1344A4FF40071116098 -:104A900051694905FCD41A6842F480321A601A68D8 -:104AA0009203FCD52D490A6842F480720A602C4AB0 -:104AB0004FF4E06111601A6842F060021A601A68EF -:104AC00042F008021A601A689007FCD59A6812F042 -:104AD0000C0FFBD1D3F8942042F4C062C3F89420A9 -:104AE000204ADA601A6842F080721A601A689101EE -:104AF000FCD51D4A1A611A6842F080621A601A6871 -:104B00001201FCD500229A601549184AC3F8882082 -:104B10000A6822F0070242F004020A600A6802F002 -:104B20000702042AFAD19A6842F003029A609A684E -:104B300002F00C020C2AFAD11A6E42F001021A6637 -:104B4000D3F8802042F00102C3F88020D3F88030EF -:104B5000704700BF001002400004001000700040C9 -:104B60000020024003140001000C100055550134D0 -:104B7000074A08B5536903F00103536123B1054A9D -:104B800013680BB150689847BDE80840FEF788BE2F -:104B900000040140A8380020074A08B5536903F013 -:104BA0000203536123B1054A93680BB1D06898475B -:104BB000BDE80840FEF774BE00040140A83800209C -:104BC000074A08B5536903F00403536123B1054A4A -:104BD00013690BB150699847BDE80840FEF760BE05 -:104BE00000040140A8380020074A08B5536903F0C3 -:104BF0000803536123B1054A93690BB1D069984703 -:104C0000BDE80840FEF74CBE00040140A838002073 -:104C1000074A08B5536903F01003536123B1054AED -:104C2000136A0BB1506A9847BDE80840FEF738BEDA -:104C300000040140A8380020164B10B55C6904F44C -:104C400078725A61A30604D5134A936A0BB1D06AED -:104C50009847600604D5104A136B0BB1506B984708 -:104C6000210604D50C4A936B0BB1D06B9847E20533 -:104C700004D5094A136C0BB1506C9847A30504D5B1 -:104C8000054A936C0BB1D06C9847BDE81040FEF715 -:104C900007BE00BF00040140A8380020194B10B522 -:104CA0005C6904F47C425A61620504D5164A136DAE -:104CB0000BB1506D9847230504D5134A936D0BB182 -:104CC000D06D9847E00404D50F4A136E0BB1506EB7 -:104CD0009847A10404D50C4A936E0BB1D06E984747 -:104CE000620404D5084A136F0BB1506F9847230430 -:104CF00004D5054A936F0BB1D06F9847BDE81040BB -:104D0000FEF7CEBD00040140A838002008B50348D6 -:104D1000FEF7E8FEBDE80840FEF7C2BD04350020FE -:104D200008B50348FEF7DEFEBDE80840FEF7B8BD53 -:104D30007035002008B50348FEF7D4FEBDE80840F2 -:104D4000FEF7AEBDDC35002008B5FFF72DFEBDE84F -:104D50000840FEF7A5BD0000062108B50846FEF78D -:104D600045FF06210720FEF741FF06210820FEF738 -:104D70003DFF06210920FEF739FF06210A20FEF734 -:104D800035FF06211720FEF731FF06212820FEF708 -:104D90002DFF07211C20FEF729FF0C212520FEF7FF -:104DA00025FF0C212620FEF721FFBDE808400C213D -:104DB0002720FEF71BBF000008B5FFF709FE00F033 -:104DC00009F8FFF7B7F8FFF7C9FDBDE80840FFF79E -:104DD0004BBD00000023054A19460133102BC2E9E0 -:104DE000001102F10802F8D1704700BFA838002076 -:104DF0000B460146184600F025B8000000F038B810 -:104E0000012838BF012010B50446204600F028F8DC -:104E100030B900F007F808B900F00CF88047F4E763 -:104E200010BD0000024B1868BFF35B8F704700BFD6 -:104E30002839002008B5062000F032F90120FFF7DC -:104E4000D7FA000010B5054C13462CB10A460146AE -:104E50000220AFF3008010BD2046FCE700000000F8 -:104E6000024B0146186800F089B800BF28110020E5 -:104E7000024B0146186800F035B800BF2811002029 -:104E800010B501390244904201D1002005E00378B9 -:104E900011F8014FA34201D0181B10BD0130F2E7F9 -:104EA0002DE9F041A3B1C91A17780144044603F172 -:104EB000FF3C8C42204601D9002009E00578BD4224 -:104EC00004F10104F5D10CEB0405D618A54201D17B -:104ED000BDE8F08115F8018D16F801EDF045F5D02B -:104EE000E7E7000037B5002944D051F8043C0190B1 -:104EF000002BA1F10404B8BFE41800F0F5F81E4A35 -:104F00000198136833B96360146003B0BDE83040A2 -:104F100000F0F0B8A34208D9256861198B4201BF9F -:104F200019685B6849192160EDE71A465B680BB1A7 -:104F3000A342FAD911685518A5420BD1246821441F -:104F40005418A3421160E0D11C685B68536021448F -:104F50001160DAE702D90C230360D6E725686119EE -:104F60008B4204BF19685B68636004BF4919216004 -:104F70005460CAE703B030BD2C390020F8B5CD1C11 -:104F800025F0030508350C2D38BF0C25002D0646ED -:104F900001DBA94203D90C2333600020F8BD00F0E7 -:104FA000A3F821490A6814469CB9204F3B6823B9ED -:104FB0002146304600F03CF838602946304600F083 -:104FC00037F8431C23D10C233360304600F092F8AD -:104FD000E3E723685B1B17D40B2B03D923601C4426 -:104FE000256004E06368A2420CBF0B60536030464A -:104FF00000F080F804F10B00231D20F00700C21A16 -:10500000CCD01B1AA350C9E722466468CCE7C41C65 -:1050100024F00304A042E3D0211A304600F008F83F -:105020000130DDD1CFE700BF2C390020303900201E -:1050300038B5064D0023044608462B60FFF7D0F92B -:10504000431C02D12B6803B1236038BD34390020E2 -:105050001F2938B504460D4604D9162303604FF0C6 -:10506000FF3038BD426C12B152F821304BB92046A6 -:1050700000F030F82A4601462046BDE8384000F0EE -:1050800017B8012B0AD0591C03D116230360012045 -:10509000E7E7002442F82540284698470020E0E74B -:1050A000024B01461868FFF7D3BF00BF281100204C -:1050B00038B5074D00230446084611462B60FFF71C -:1050C0009BF9431C02D12B6803B1236038BD00BF9C -:1050D00034390020FFF78AB9034611F8012B03F891 -:1050E000012B002AF9D17047014800F009B800BF30 -:1050F00038390020014800F005B800BF38390020D9 -:1051000070470000704700006F72672E617264750F -:1051100070696C6F742E4D6174656B4C3433312D36 -:105120004169727370656564000000004E6F206114 -:105130007070207369670A00426164206677206C92 -:10514000656E6774682025750A0042616420626F8D -:105150006172645F69642025752073686F756C6483 -:105160002062652025750A0042616420667720640C -:10517000657363726970746F72206C656E677468B2 -:105180002025750A004261642061707020435243FB -:10519000203078253038783A30782530387820300B -:1051A00078253038783A3078253038780A00476FDB -:1051B0006F64206669726D776172650A0040A2E4CF -:1051C000F16468910600000053544D33324C343F73 -:1051D0003F0000000435002070350020DC35002041 -:1051E0004261642043414E496661636520696E6493 -:1051F00065782E0080000000008000000000800024 -:1052000000000000000000009D1B0008892300082A -:10521000E9220008AD1B0008E51B0008E11D00089D -:10522000B11B0008C51B0008B51B0008B91B00080E -:10523000C11B0008BD1B0008091D0008C91B000890 -:10524000F5250008D91B0008DD1C000800960000A9 -:10525000000000000000000000000000000000004E -:105260000000000000000000FD3E0008E93E0008CC -:10527000253F0008113F00081D3F0008093F0008B6 -:10528000F53E0008E13E0008313F00086D61696E9F -:105290000000000069646C65000000009452000882 -:1052A0004837002080380020010000000D41000830 -:1052B000000000002CAFFF7F010000000000000094 -:1052C0002604000000000000006003000000000051 -:1052D000FE2A0100D2040000FF00000000000000D0 -:1052E000C85100083F0000002C1100200000000001 -:1052F00000000000000000000000000000000000AE -:10530000000000000000000000000000000000009D -:10531000000000000000000000000000000000008D -:10532000000000000000000000000000000000007D -:10533000000000000000000000000000000000006D -:0C53400000000000000000000000000061 +:1004B000704700BF02E000F000F8FEE772B6374870 +:1004C00080F30888364880F3098836483649086042 +:1004D00040F20000CCF200004EF63471CEF2000182 +:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 +:1004F000F0004EF68851CEF200010860BFF34F8F36 +:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 +:10051000CEF200010860062080F31488BFF36F8FCD +:1005200003F034FD03F0B6FD4FF055301F491B4A70 +:1005300091423CBF41F8040BFAE71D49184A914229 +:100540003CBF41F8040BFAE71A491B4A1B4B9A427D +:100550003EBF51F8040B42F8040BF8E7002018499D +:10056000184A91423CBF41F8040BFAE703F012FD30 +:1005700003F0E2FD144C154DAC4203DA54F8041BB1 +:100580008847F9E700F042F8114C124DAC4203DA0B +:1005900054F8041B8847F9E703F0FABC000900206F +:1005A000001100200000000808ED00E0000100201C +:1005B00000090020E0470008001100207C11002005 +:1005C00080110020003B0020A0010008A4010008C9 +:1005D000A4010008A40100082DE9F04F2DED108AB8 +:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 +:1005F000002383F311882846A047002003F072F9F6 +:10060000FEE703F0D5F800DFFEE70000F8B500F0E4 +:100610000DFE03F05DFC074603F0AEFC0546D0BBC3 +:10062000294B9F4237D001339F4237D0274B27F0C9 +:10063000FF029A4235D1F8B200F03EFC2E4642F25B +:10064000107400F03FFC08B10024264601F0A8F821 +:1006500058B3032000F03EF80024264635B11C4B69 +:100660009F4203D003F080FC00242646002003F0C4 +:1006700039FC0EB100F044F800F056FC00F0D8FD53 +:1006800001F0A8FF0546B4B900F096FC4FF47A706B +:1006900003F02EF9F7E72E460024D2E704460126A0 +:1006A000CFE706464FF47A74CBE7002CD6D04FF450 +:1006B0007A740126D2E701F08DFF431BA342E3D9F0 +:1006C00000F01EF8DCE700BF010007B0000008B032 +:1006D000263A09B0084B187003280CD8DFE800F060 +:1006E00008050208022000F001BE022000F0F4BD5F +:1006F000024B00225A6070478011002084110020B4 +:1007000010B501F04DF830B1234B03221A70234B82 +:1007100000225A6010BD224B224A1C461968013142 +:10072000F8D004339342F9D16268A242F2D31E4B4F +:100730009B6803F1006303F520439A42EAD203F079 +:10074000E5FB03F0F7FB002000F08CFD0220FFF733 +:10075000C1FF164B9A6D00229A65996F9A67996F3F +:10076000D96DDA65D96FDA67D96F196E1A66D3F861 +:100770008010C3F88020D3F8803072B64FF0E023A9 +:100780003021C3F8084DD4E9003281F311889D4629 +:1007900083F308881047BDE78011002084110020F2 +:1007A00000A0000820A00008001100200010024056 +:1007B000094A136849F2690099B21B0C00FB013326 +:1007C0001360064B186844F2506182B2000C01FBC2 +:1007D0000200186080B27047141100201011002030 +:1007E00010B500211022044600F09AFD034B03CB04 +:1007F000206061601868A06010BD00BF9075FF1F89 +:100800002DE9F041ADF5507D0DF13C086EAC40F2A4 +:10081000751207460D4610A80021C8F8001000F018 +:100820007FFD4FF4C4720021204600F079FD01F0F5 +:10083000D1FE254B4FF47A72B0FBF2F0186093E8CA +:100840000700022384E807000DF5ED702382FFF70F +:10085000C7FF42F204631D49238406A803F054FF36 +:10086000202384F832310DF2EB2606AB0DF1380C63 +:100870001A4603CA624530607160134606F10806E5 +:10088000F6D141460122204600F096FD0023039355 +:10089000AB7E029305F11903019380B20123CDE9E8 +:1008A00004800093E97E06A3D3E90023384602F0D2 +:1008B00059FA0DF5507DBDE8F08100BFAFF300801F +:1008C0009E6AC421818A46EE8C11002018470008D8 +:1008D0002DE9F0412C4C237ADAB080460D465BBB03 +:1008E00027A9284600F078FE0746002842D19DF847 +:1008F0009D60C82E3ED801464FF4A662204600F007 +:100900000FFD4FF48073C4F8F8314FF40073C4F84E +:100910000C334FF44073C4F8203432460DF19E017D +:1009200004F1090000F0EAFC26449DF89C3077723F +:1009300023720BB9EB7E23728122002106AC27A81B +:1009400000F0EEFC0122214627A800F081FE0023E2 +:100950000393AB7E029305F1190380B20193282320 +:10096000CDE904400093E97E05A3D3E90023404686 +:1009700002F0F8F95AB0BDE8F08100BFAFF3008093 +:1009800026417272DF25D7B7A8320020F0B5254E78 +:100990004FF48A7505FB0065F1B096F8D83085F8FC +:1009A000DC300024D822214685F8E8403AA800F03F +:1009B000B7FC06F1090000F0ABFCD5F8E4308DF887 +:1009C000F000C2B206AF06F109010DF1F100CDE968 +:1009D0003A3400F093FC394601223AA800F064FE54 +:1009E00080B2CDE9047008230127CDE9023706F172 +:1009F000D803019330230093317A0B4807A3D3E93E +:100A0000002302F0AFF9A04206DD01F0E3FDC5F8D6 +:100A1000E000384671B0F0BD2046FBE778F6339F22 +:100A200093CACD8DA8320020A42100202DE9F041E9 +:100A30001D4D1E4E1E4F86B0284602F0BFF90346DC +:100A400058B30024CDE90344ADF81440027B8DF87F +:100A5000142099684068029403AA03C21B68DFF857 +:100A6000548043F00043029301F0B6FD821941F136 +:100A70000003009402A9384601F078F8A04205DD91 +:100A8000284602F09FF988F80040D5E798F8003032 +:100A9000072B05D8013388F8003006B0BDE8F08197 +:100AA000014802F08FF9F8E7A421002040420F002E +:100AB000D8210020DD37002070B50D4614461E46B3 +:100AC00002F0ACF850B9022E10D1012C0ED112A3B5 +:100AD000D3E90023C5E90023012007E0282C10D02A +:100AE00005D8012C09D0052C0FD0002070BD302C6A +:100AF000FBD10BA3D3E90023ECE70BA3D3E900233D +:100B0000E8E70BA3D3E90023E4E70BA3D3E9002331 +:100B1000E0E700BFAFF30080401DA12026812A0B33 +:100B200078F6339F93CACD8D9E6AC421818A46EEA2 +:100B300026417272DF25D7B7F017304A39059E5625 +:100B400038B505460E4C0021013500F0ADFBA4F888 +:100B50002C55B4F82C0500F08FFB78B1B4F82C05B7 +:100B600000F09AFB014648B9B4F82C0500F09CFB54 +:100B7000B4F82C350133A4F82C35EAE738BD00BFB2 +:100B8000A832002010B50A4B0A4A1A6003F58053B8 +:100B900093F860203AB9DC6D2CB1204600F07EFE5F +:100BA000204603F0F1FCBDE81040034800F076BE9B +:100BB000D821002078470008203200202DE9F04F8E +:100BC0008FB000AF05460C4602F028F8002849D146 +:100BD000237E022B1BD1E38A012B18D101F0FAFCF2 +:100BE0000646FFF7E5FD03464FF4C870DFF8C48200 +:100BF000B3FBF0F206F5167602FB103316FA83F318 +:100C0000C8F80030E37E33B9A34B00221A703C379A +:100C1000BD46BDE8F08F07F12401204600F09AFCA4 +:100C20000028F4D107F11400FFF7DAFD97F8264009 +:100C300007F11401224607F1270003F0EFFC00281A +:100C4000E2D10F2C08D8944B1C70D8F80030A3F5D3 +:100C50001673C8F80030DAE797F82410284601F038 +:100C6000D5FFD4E7E38A282B2BD010D8012B23D033 +:100C7000052BCCD1BFF34F8F8849894BCA6802F44A +:100C8000E0621343CB60BFF34F8F00BFFDE7302B13 +:100C9000BDD1844EE17E327A9142B8D1607E314638 +:100CA000002291F8DC50854200F0A5800132042A30 +:100CB00001F58A71F5D1AAE721462846FFF7A0FD84 +:100CC000A5E721462846FFF703FEA0E7B2F8EC505F +:100CD0007B6005F103094FEA99094FEA8902D11DAA +:100CE000C908A8EBC1039D46EB460021584600F019 +:100CF00017FB04F1EE012A463144584600F0FEFA93 +:100D00007B6813B9012000F0ADFA96F8D20000F02C +:100D1000B3FA044630B9307200F0CEFA204600F043 +:100D2000A1FAB1E0D6F8D4203AB996F8D200B6F8D4 +:100D30002C25824201D8FFF703FFD6F8D4202A449D +:100D4000944208D296F8D200B6F82C25013082429F +:100D500001D8FFF7F5FE70685FFA89F2594600F096 +:100D6000E7FA08B9C54679E0726896F8D2002A44D5 +:100D70007260D6F8D42005EB0209C6F8D49000F0D2 +:100D80007BFA814509D396F8D220D6F8D4000132F7 +:100D9000001B86F8D220C6F8D400FF2D0FD80024FF +:100DA000347200F089FA204600F05CFA00F0F8FC9A +:100DB0003D4B188108B9FFF7A3FCC54627E7BB6880 +:100DC00096F8D9000AFB0362FB68D2F8E41082F8B7 +:100DD000E83001F58061C2F8E030C2F8E410FFF7B6 +:100DE000D5FDFFF723FE96F8D920013202F0030269 +:100DF00086F8D920B6E74FF48A7A0AFB02F505F1A6 +:100E0000EA013144204600F07BFCF86000287FF4C2 +:100E1000FEAE3544012285F8E82001F0DBFBD5F871 +:100E2000E020D6ED007ADFED216A801A192838BF5C +:100E3000192040F6B832904228BF1046B8EE677AC3 +:100E400007EE900AF8EEE77A67EEA67ADFED186A09 +:100E5000E7EE267AFCEEE77AC6ED007A96F8D9300E +:100E6000BB60BA6873680AFB02F4321992F8E810A2 +:100E700059B1D2F8E4108B42E8463FF427AF002185 +:100E800082F8E810C2F8E010C5467368064A9B0A6B +:100E900001331381BBE600BF9D21002000ED00E07F +:100EA0000400FA05A83200208C110020CDCCCC3DE6 +:100EB0006666663FA0210020014B1870704700BF96 +:100EC0009811002038B54FF00054134B22689A4215 +:100ED00020D1124B627D12481A70237D03724FF4A9 +:100EE0008073C0F8F8314FF40073C0F80C3300255C +:100EF0004FF44073C0F820340A49C0F8E450C922C6 +:100F0000093000F0FBF9E0222946204600F008FAFB +:100F1000012038BD0020FCE79AAD44C5981100209F +:100F2000A83200201600002037B500F039FC194D1A +:100F3000194928810223012218486B7101F0E8F950 +:100F400000230193164B174900931748174B4FF492 +:100F5000805201F033FE164B197811B1124801F09E +:100F600055FE01F037FB0446FFF722FC4FF4C8732F +:100F7000B0FBF3F202FB130304F5167010FA83F0D2 +:100F80000C4B186002F0F8FF08B10F232B8103B05F +:100F900030BD00BF8C11002040420F00D82100203E +:100FA000B90A00089C110020A4210020BD0B0008F4 +:100FB00098110020A02100202DE9F04F2DED028B8B +:100FC0000FF23829D9E90089834C93B00BAE9FED1D +:100FD0007E8BFFF72BFD814FDFF828A200230A93B9 +:100FE000ADF834300B9373604FF0000B5B468DED22 +:100FF000008B01250DF11D0207A938468DF81C5004 +:101000008DF81DB001F034F99DF81C30002B40F034 +:10101000A580204601F002FE0646002845D1704F0B +:1010200001F0D8FA3B6898423FD301F0D3FA8246E8 +:10103000FFF7BEFB4FF4C873B0FBF3F202FB1303E0 +:101040000AF5167010FA83F03860664F97F800B012 +:10105000CBF1100ABBF1000F14BF33462B465FFAE9 +:101060008AFA0EA88DF82830FFF7BAFBBAF1060FFE +:1010700028BF4FF0060A0EAB03EB0B0152460DF1F1 +:10108000290000F03BF90AAB0393182302930AF1FD +:101090000102554BD2B2CDE90053049220464CA335 +:1010A000D3E9002301F000FE3E7001F093FA4F4AAD +:1010B0004F4D1368C31AB3F57A7F2ED3106001F039 +:1010C0008BFA02460B46204601F086FE204601F0D0 +:1010D000A5FD10B32B7A474E002B14BF0323022328 +:1010E000737101F077FA0EAF4FF47A730122B0FBFF +:1010F000F3F039463060304600F004FA18230293CA +:101100003D4B019380B240F25513CDE9037000933B +:1011100042464B46204601F0C7FD2B7A93B101F0C1 +:1011200059FA002607464FF48A7A95F8D9003044D8 +:1011300000F003000AFB005393F8E82092B3013655 +:10114000042EF2D1C82002F0D3FB2B7A002B7FF4BF +:101150003DAF13B0BDEC028BBDE8F08FDAF8143070 +:1011600083F00803CAF81430594610220EA800F084 +:10117000D7F80DF11E0308AA0AA9384600F0F4FDBD +:1011800096E803000FAB83E803009DF834308DF838 +:1011900044300A9B0E930EA9DDE90823204601F096 +:1011A000EFFF21E7D3F8E02042B12B68FA2B38BFDC +:1011B000FA23BA1A0533B2EB430FC0D3FFF7E6FBAD +:1011C0000028BCD1BEE700BF000000000000000006 +:1011D000401DA12026812A0BA4210020D821002017 +:1011E000A02100209D2100209C210020D837002034 +:1011F000A83200208C110020DC370020F1C6A7C1E6 +:10120000D068080F0004004808B5054800F046FE05 +:10121000BDE80840034A0449002003F0AFB900BF0D +:10122000D821002018380020850B000870470000E6 +:1012300070B502F0E9FC094E094D308000242868A1 +:101240003388834208D902F0DBFC2B680444013365 +:10125000B4F5204F2B60F2D370BD00BF0C380020D6 +:10126000E037002002F082BD00F10060920000F53E +:10127000204002F005BD0000054B1A68054B1B8895 +:101280009B1A834202D9104402F0BABC0020704776 +:10129000E03700200C380020024B1B68184402F095 +:1012A000B5BC00BFE0370020024B1B68184402F0B9 +:1012B000BFBC00BFE0370020064991F8243033B1AD +:1012C0000023086A81F824300822FFF7CDBF0120EF +:1012D000704700BFE4370020022802BF024B4FF4E2 +:1012E00000229A61704700BF00040048022802BF34 +:1012F000014B08229A6170470004004810B5002392 +:10130000934203D0CC5CC4540133F9E710BD000014 +:1013100003460246D01A12F9011B0029FAD1704780 +:1013200002440346934202D003F8011BFAE77047D8 +:101330002DE9F8431F4D144695F8242007468846AA +:1013400052BBDFF870909CB395F824302BB9202263 +:10135000FF2148462F62FFF7E3FF95F82400C0F114 +:101360000802A24228BF2246D6B24146920005EBAF +:101370008000FFF7C3FF95F82430A41B1E44F6B28B +:10138000082E17449044E4B285F82460DBD1FFF7BF +:1013900093FF0028D7D108E02B6A03EB8203834236 +:1013A000CFD0FFF789FF0028CBD10020BDE8F8831C +:1013B0000120FBE7E43700202DE9F0470D46044605 +:1013C00000219046284640F27912FFF7A9FF2346F4 +:1013D00020220021284601F075FE231D0222202133 +:1013E000284601F06FFE631D03222221284601F0EA +:1013F00069FEA31D03222521284601F063FE04F1A6 +:10140000080310222821284601F05CFE04F1100395 +:1014100008223821284601F055FE04F11103082264 +:101420004021284601F04EFE04F112030822482113 +:10143000284601F047FE04F11403202250212846DB +:1014400001F040FE04F1180340227021284601F00B +:1014500039FE04F120030822B021284601F032FEB3 +:1014600004F121030822B821284601F02BFE04F1E3 +:101470002207C0263B46314608222846083601F09E +:1014800021FEB6F5A07F07F10107F3D104F1320385 +:1014900008223146284601F015FE002704F1330AE0 +:1014A00094F832304FEAC7099F4209F5A47615D364 +:1014B000B8F1000F08D1314604F599730722284688 +:1014C00001F000FE09F24F16274694F832213B1B2B +:1014D00093420CD3F01DC008BDE8F0870AEB070368 +:1014E00008223146284601F0EDFD0137D8E707F222 +:1014F000331331460822284601F0E4FD083601374F +:10150000E3E7000013B504460846002101602346C6 +:10151000C0F803102022019001F0D4FD0198231D92 +:101520000222202101F0CEFD0198631D0322222119 +:1015300001F0C8FD0198A31D0322252101F0C2FD81 +:10154000019804F108031022282101F0BBFD0720B7 +:1015500002B010BDF7B50023047F00910E460722AC +:101560001946054601F072FC731C0093012200230A +:101570000721284601F06AFCC4B9B31C0093052278 +:1015800023460821284601F061FC0D243746B27835 +:10159000BB1B934211D32B7FA88A0734E408BBB945 +:1015A000844294BF0020012003B0F0BDAB8ADB0071 +:1015B000083BDB08B3700824E8E7FB1C00932146D6 +:1015C00000230822284601F041FC08340137DEE7F9 +:1015D000201A18BF0120E7E7F7B50023047F009128 +:1015E0000E4608221946054601F030FC731CC4B9AA +:1015F0000822009311462346284601F027FC1024B8 +:10160000012372785F1C013B934211D32B7FA88A80 +:101610000734E408BBB9844294BF0020012003B022 +:10162000F0BDAB8ADB00083BDB0873700824E7E7FA +:10163000F3190093214600230822284601F006FCF6 +:1016400008343B46DDE7201A18BF0120E7E7000019 +:10165000F8B50E4605461446002181223046FFF7B4 +:101660005FFE2B4608220021304601F02BFD7CB99D +:101670006B1C07220821304601F024FD0F240123B2 +:101680006A785F1C013B934204D3E01DC008F8BD9B +:101690000824F4E7EB1921460822304601F012FD38 +:1016A00008343B46ECE70000F8B50E460546144604 +:1016B0000021CE223046FFF733FE2B4628220021A0 +:1016C000304601F0FFFC7CB905F10803082228210F +:1016D000304601F0F7FC30242F462A7A7B1B9342D8 +:1016E00004D3E01DC008F8BD2824F5E707F109037D +:1016F00021460822304601F0E5FC08340137ECE7CA +:10170000F7B5047F00910E46012310220021054603 +:1017100001F09CFBC4B9B31C00930922234610219D +:10172000284601F093FB192437467288BB1B9A4266 +:1017300011D82B7FA88A0734E408BBB9844294BF30 +:101740000020012003B0F0BDAB8ADB00103BDB08BA +:1017500073801024E8E73B1D0093214600230822F4 +:10176000284601F073FB08340137DEE7201A18BF62 +:101770000120E7E730B5094D0A4491420DD011F838 +:10178000013B5840082340F30004013B2C4013F078 +:10179000FF0384EA5000F6D1EFE730BD2083B8EDB7 +:1017A000F7B5384A106851686B4603C36A46364934 +:1017B0003648082302F042FF0446002833D10A25A8 +:1017C000334A106851686B4603C36A4631492F4853 +:1017D000082302F033FF0446002849D00369B3F51B +:1017E000583F45D8B0F8661040F2264291423FD1AA +:1017F000294A024402F15C018B4239D35C3B234904 +:1018000000209E1AFFF7B6FF3246074604F1640136 +:101810000020FFF7AFFFA3689F4229D1E3689842F9 +:1018200008BF002524E00369B3F5583F27D8418B52 +:1018300040F22642914220D1174A024402F110019F +:101840008B4218D3103B114900209D1AFFF792FFDD +:101850002A46064604F118010020FFF78BFFA36813 +:101860009E4202D1E368984201D00D25A8E70025E9 +:10187000284603B0F0BD1025A2E70C25A0E70B25F4 +:101880009EE700BF3C470008DC5F030000A00008A3 +:1018900045470008905F03000860FFF710B5037C20 +:1018A000044613B9006802F0B1FE204610BD0000E6 +:1018B0000023BFF35B8FC360BFF35B8FBFF35B8F0E +:1018C0008360BFF35B8F7047BFF35B8F0068BFF32C +:1018D0005B8F704770B505460C30FFF7F5FF05F1DB +:1018E000080604463046FFF7EFFFA04206D930460F +:1018F0006D68FFF7E9FF2544281A70BD3046FFF7F1 +:10190000E3FF201AF9E7000070B50546406898B17A +:1019100005F10800FFF7D8FF05F10C060446304634 +:10192000FFF7D2FF8442304694BF6D680025FFF771 +:10193000CBFF013C2C44201A70BD000038B50C468A +:101940000546FFF7C7FFA04210D305F10800FFF7D7 +:10195000BBFF04446868B4FBF0F100FB1144BFF323 +:101960005B8F0120AC60BFF35B8F38BD0020FCE7CC +:101970002DE9F041144607460D46FFF7C5FF8442A6 +:1019800028BF0446D4B1B84658F80C6B4046FFF760 +:101990009BFF3044286040467E68FFF795FF331A6E +:1019A0009C4203D86C600120BDE8F0816B60A41BF1 +:1019B0003B68AB602044E8600220F5E72046F3E78F +:1019C00038B50C460546FFF79FFFA04210D305F13E +:1019D0000C00FFF779FF04446868B4FBF0F100FBEA +:1019E0001144BFF35B8F0120EC60BFF35B8F38BD08 +:1019F0000020FCE72DE9FF41884669460746FFF7CE +:101A0000B7FF6C4606B204EBC6060025B44209D007 +:101A10006268206808EB0501FFF770FC6368083412 +:101A20001D44F3E729463846FFF7CAFF284604B0AD +:101A3000BDE8F081F8B505460C300F46FFF744FFCE +:101A400005F1080604463046FFF73EFFA042304647 +:101A500088BF6C68FFF738FF201A386020B1304625 +:101A60002C68FFF731FF2044F8BD000073B5144621 +:101A700006460D46FFF72EFF844228BF044601901C +:101A8000DCB101A93046FFF7D5FF019B33B93268BD +:101A9000C5E90233C5E9002401200CE09C4238BFAF +:101AA00001942860019868608442F5D93368AB607E +:101AB000241AEC60022002B070BD2046FBE7000053 +:101AC0002DE9FF410F466946FFF7D0FF6C4600B293 +:101AD00004EBC0050026AC4209D0D4F8048054F8C9 +:101AE000081BB8194246FFF709FC4644F3E73046A5 +:101AF00004B0BDE8F081000038B50546FFF7E0FF0F +:101B0000044601462846FFF719FF204638BD00006D +:101B1000302383F3118862B670470000002383F3FB +:101B2000118862B67047000010B4026854681A4603 +:101B300023465DF8044B184701207047002070478A +:101B40000020704770470000002070470E2070474B +:101B500000F5805090F8C800C0F3400070470000C6 +:101B600000F5805090F9C90070470000F7B50C6887 +:101B7000BDF8207014F000541E466FD10B7B082B6B +:101B80006CD8FFF7C5FF4569AB685B010CD4AB6847 +:101B90001B0108D4AC6814F080545DD1FFF7BEFF80 +:101BA000204603B0F0BD01240B6804F1180C002B93 +:101BB000B8BFDB004FEA0C1CB4BF43F004035B0565 +:101BC00045F80C300B680FFA84FC13F0804F18BFF7 +:101BD00005EB0C1E05EB0C1C1EBFDEF8803143F03C +:101BE0000203CEF880310B7BCCF8843105EB041571 +:101BF0008B68C5F88C314B68C5F88831DCF88031CA +:101C000043F00103CCF8803100EB441541F2680346 +:101C10001D4403EB44130344C5E9002608330D4675 +:101C200001F10C0C55F804EB43F804EB6545F9D1D0 +:101C300084342D881D8000EB441407F003032579BC +:101C400025F00B052B432371FFF768FF0097334600 +:101C500000F0E2FC0120A4E70224A5E74FF0FF30EA +:101C60009FE7000013B500F580540191E06DFFF788 +:101C70004BFE1F280AD90199E06D2022FFF7BAFE1A +:101C8000A0F120035842584102B010BD0020FBE7EC +:101C900008B500F58050FFF73BFFC06DFFF708FE69 +:101CA000BDE80840FFF73ABF00220260828142602F +:101CB0008260704710B500220023C0E90023002392 +:101CC000044603810C30FFF7EFFF204610BD0000F3 +:101CD000F0B5054600F580500C4690F8C83013F07A +:101CE000040FC3F3800108BF114661F3820304F1BE +:101CF000840680F8C83005EB461389B01B79D807F5 +:101D00002ED57AB319072DD46846FFF7D3FF05EB1C +:101D1000441303F5835303F1180703AA103318681B +:101D20005968144603C40833BB422246F7D11868E9 +:101D300020609B88A380DDE90E23CDE900230123E9 +:101D4000ADF808302B686946DB6B2846984705EBF1 +:101D500046152B791A075CBF43F008032B7101E08D +:101D6000002AF4D109B0F0BD2DE9F047074688B04C +:101D700007F5805468469A468846FFF7C9FE9146A3 +:101D8000FFF798FFE06DFFF7A5FD1F2829D9E06D4B +:101D900020226946FFF7B0FE202822D103AD444639 +:101DA00005AB2E4603CE9E4220606160354604F1AD +:101DB0000804F6D130682060B388A380DDE90023F1 +:101DC000C9E90023BDF80830AAF80030FFF7A6FEE5 +:101DD0004A4653464146384608B0BDE8F04700F051 +:101DE00009BCFFF79BFE002008B0BDE8F0870000AB +:101DF0002DE9F84F0023C0E90133254B044640F894 +:101E0000183B0F46FFF750FF04F12800FFF752FF81 +:101E100004F1480804F58255464608353046203618 +:101E2000FFF748FFAE42F9D104F580554FF48053D7 +:101E30004FF00009C5E91339C5F848800123EE6564 +:101E400004F5875804F58456C5F8549085F8583041 +:101E500085F86030083608F108084FF0000A4FF0A6 +:101E6000000B46E908ABA6F11800FFF71DFF20366E +:101E700046F8289C4645F4D185F8C97017B1054845 +:101E800000F0A2FB044B63612046BDE8F88F00BF61 +:101E900078470008504700080064004010B5044B24 +:101EA000197804464A1C1A70FFF7A2FF204610BD9D +:101EB000143800202DE9F047002950D0294B2A4F33 +:101EC000B7FBF1F599428CBF0A231123581EB5FBCD +:101ED000F3FC03FB1C53C4B22BB102280346F5D814 +:101EE0000020BDE8F0870CF1FF36B6F5806FF7D221 +:101EF000C4EBC40E0EF103034FEAE309C3F3C703B7 +:101F0000A4EB030809F1010A4FF47A755FFA88F02F +:101F100009FB05555AFA88F8B5FBF8F5B5F5617F68 +:101F2000C1BF0EF1FF33C3F3C703E01AC0B25C1C9C +:101F300050FA84F40CFB04F4B7FBF4F4A142CFD1C3 +:101F4000013BDBB20F2BCBD80138C0B20728C7D872 +:101F50000021107116809170D3700120C1E70846EE +:101F6000BFE700BF3F420F0000B4C40470B5054690 +:101F70000E464FF47A746B695B6803F00103B34259 +:101F800007D04FF47A7001F0B3FC013CF3D1204646 +:101F900070BD0120FCE7000030B54269936913F081 +:101FA000700F16D000230B4C936103F1840200EBF9 +:101FB000421211794D0709D5890707D5416954F8AF +:101FC00023508D60117941F0040111710133032B0D +:101FD000EBD130BD6447000873B51D464369164612 +:101FE0009A68D207044609D59A6801219960C2F31C +:101FF0004002CDE900650021FFF76AFE63699A6837 +:10200000D1050BD59A684FF480719960C2F34022D4 +:10201000CDE9006501212046FFF75AFE63699A6801 +:10202000D2030BD59A684FF480319960C2F34042D5 +:10203000CDE9006502212046FFF74AFE204602B0A6 +:10204000BDE87040FFF7A8BFF8B50446466900290F +:102050006CD106F10C07386880076AD006EB0115D1 +:102060003868D5F8B00110F0040FD5F8B0011ABFE8 +:10207000C00840F00040400DA061D5F8B0C11CF090 +:10208000020F1CBF40F08040A061D5F8B40106EB00 +:10209000011100F00F0084F82400D1F8B801207776 +:1020A000D1F8B801000A6077D1F8B801000CA07728 +:1020B000D1F8B801000EE077D1F8BC0184F8200017 +:1020C000D1F8BC01000A84F82100D1F8BC01000C51 +:1020D00084F82200D1F8BC11090E84F823103821AD +:1020E000396004F1340004F1180104F1240551F8B9 +:1020F000046B40F8046BA942F9D109880180C4E956 +:102100000A2321460023238651F8283B2046DB6B17 +:10211000984704F58052204692F8C83043F00403F3 +:1021200082F8C830BDE8F840FFF736BF06F1100767 +:1021300091E7F8BD10B5044600F04EFA02460B4692 +:1021400052EA030102D0013A63F10003044908682E +:1021500020B12146BDE81040FFF776BF10BD00BF9B +:1021600010380020F8B500F583511E46FFF7D0FC6B +:10217000DFF844C00831002404F1840500EB451564 +:102180002B795F070ED4DB060CD5D1E9007397429B +:10219000B34107D243695CF824709F602B7943F008 +:1021A00004032B710134032C01F12001E4D1BDE8BB +:1021B000F840FFF7B3BC00BF6447000808B5FFF75D +:1021C000A7FCFFF7E9FEBDE80840FFF7A7BC000049 +:1021D000F8B543690546986800F0E050B0F1E05F5B +:1021E0000F461FD0E8B1FFF793FC05F58354103478 +:1021F000002606F1840305EB43131B791A0706D565 +:102200000136032E04F12004F3D1012007E05B071F +:10221000F6D42146384600F039FA0028F0D1FFF70D +:102220007DFCF8BD0120FCE700F5805008B5FFF704 +:102230006FFCC06DFFF74EFBFFF770FC43090CBF4E +:102240000120002008BD0000F8B51D4600231370D2 +:102250000F4606461446FFF7E7FF80F0010038708E +:1022600025B129463046FFF7B3FF2070F8BD0000C6 +:102270002DE9B8410C4615461F46804600F0ACF9E2 +:102280000B462178024609B9287850B14046FFF73D +:1022900069FFFFF793FF3B462A462146FFF7D4FF2D +:1022A0000120BDE8B881000010B5FFF731FC174BE5 +:1022B0009A6D42F000729A659A6B42F000729A63CE +:1022C0009A6B00F5805422F000729A63FFF726FCA7 +:1022D00094F8C830DB0718D4B9B103211320FFF7F5 +:1022E00017FC01F0DBF90321142001F0D7F90321D9 +:1022F000152001F0D3F994F8C83043F0010384F8B5 +:10230000C830BDE81040FFF709BC10BD0010024006 +:102310002DE9F04700F5805588B095F8C930012BBC +:102320000446884616467FD8804F57F823200AB9BE +:1023300047F82300D7F800A0C4F80C802674BAF13F +:10234000000F63D095F8C930012B6FD001212046D2 +:10235000FFF7AAFFFFF7DCFB6269136823F00203B3 +:1023600013606269136843F0010313606369002717 +:102370005F6101212046FFF7D1FBFFF7F7FD002841 +:1023800000F09580E86DFFF793FA04F58359BA469B +:1023900009F10809202200216846FEF7C1FF02A8C2 +:1023A000FFF782FCCDF818A06A4609EB07030DF190 +:1023B000180E9446BCE80300F44518605960624664 +:1023C00003F10803F5D1DCF80000186020379CF811 +:1023D00004201A71602FDDD195F8C8306FF38203A5 +:1023E000002785F8C8306A4641462046ADF800709F +:1023F000ADF802708DF80470FFF75CFD636948BBAF +:102400004FF400421A6008B0BDE8F08741F2D000F6 +:1024100002F0BCF8814610B15146FFF7E9FCC7F85D +:102420000090B9F1000F8DD10020ECE73868036807 +:102430001B6B98470146002888D13868FFF734FFA6 +:102440003868036832465B684146984700287FF445 +:102450007DAFE9E761221A609DF802309DF8032004 +:102460001B06120402F4702203F040731343BDF8FC +:102470000020C2F3090213439DF804201205022E26 +:1024800002F4E0020CBF4FF00041002113436269E7 +:102490000B43D361636913225A616269136823F0A5 +:1024A0000103136039462046FFF760FD08B96369F0 +:1024B000A6E795F8C93093BB6169D1F8002242F0D4 +:1024C0000102C1F800226169D1F8002222F47C5295 +:1024D00022F00E02C1F800226169D1F8002242F414 +:1024E0006062C1F800226269C2F814326269C2F8FF +:1024F0000432626941F6FF71C2F80C126269C2F8D7 +:1025000040326269C2F8443263690122C3F81C2276 +:102510006269D2F8003223F00103C2F8003295F864 +:10252000C83043F0020385F8C8306CE7103800204B +:1025300008B500F051F850EA0103024602D0421EED +:1025400061F10001044B186810B10B46FFF744FD20 +:10255000BDE8084001F064B81038002008B500203C +:10256000FFF7E8FDBDE8084001F05AB808B50120C2 +:10257000FFF7E0FDBDE8084001F052B800B59BB0A0 +:10258000EFF3098168226846FEF7B8FEEFF3058392 +:10259000014B9B6BFEE700BF00ED00E008B5FFF7C5 +:1025A000EDFF000000B59BB0EFF30981682268469B +:1025B000FEF7A4FEEFF30583014B5B6BFEE700BF64 +:1025C00000ED00E0FEE700000FB408B5029801F04E +:1025D00025F9FEE701F016BC01F0EEBB13B56C4621 +:1025E00084E80600031D94E8030083E80500012049 +:1025F00002B010BD73B58568019155B11B885B07AA +:1026000007D4D0E900369B6B9847019AC1B2304697 +:10261000A847012002B070BDF0B5866889B00546B4 +:102620000C465EB1BDF838305B070AD4D0E90037FC +:102630009B6B98472246C1B23846B047012009B08B +:10264000F0BD00220023CDE900230023ADF80830BF +:102650000A4603AB01F10806106851681C4603C422 +:102660000832B2422346F7D1106820609288A280D7 +:10267000FFF7B2FF0423ADF808302B68CDE9000165 +:10268000DB6B694628469847D8E7000030B50368F9 +:102690000968DD0FB5EBD17F23F0604421F0604283 +:1026A0004FEAD1700BD0002BB8BFA40C0029B8BFE3 +:1026B000920C944202D034BF0120002030BD9442DD +:1026C00005D1C1F38070C3F380738342F6D1944285 +:1026D0002CBF00200120F1E72DE9F041456A15B932 +:1026E0004162BDE8F0814B6823F06047C3F38A463E +:1026F0004FEAD37EC3F3807816EA230638BF3E46FE +:10270000AC462B465A68BEEBD27F22F060440AD01A +:10271000002A18DAA40CB44217D19D420FD10D60E3 +:10272000DEE71346EEE7A74207D102F08044C2F38A +:10273000807242450BD054B1EFE708D2EDE7CCF8F8 +:1027400000100B60CDE7B44201D0B442E5D81A685E +:102750009C46002AE5D11960C3E700002DE9F04747 +:10276000089D01F007044FEAD508224405F007054B +:1027700000EBD1004FF47F49944201D1BDE8F087CE +:1027800004F0070705F0070A57453E4638BF56468E +:10279000C6F10806111B8E4228BF0E46E10808EB61 +:1027A000D50E415C13F80EC0B94029FA06F721FA9C +:1027B0000AF1FFB28CEA010147FA0AF739408CEAC4 +:1027C000010C03F80EC034443544D5E780EA0120FB +:1027D000082341F2210201B24000002980B203F136 +:1027E000FF33B8BF504013F0FF03F4D1704700002F +:1027F00038B50C468D18A54200D138BD14F8011B20 +:10280000FFF7E4FFF7E7000042684AB1136843604E +:102810004389818901339BB29942438138BF8381C7 +:102820001046704770B588B0202204460D466846B1 +:102830000021FEF775FD20460495FFF7E5FF0246EF +:1028400058B16B46054608AE1C4603CCB44228601E +:102850006960234605F10805F6D1104608B070BD41 +:10286000082817D909280CD00A280CD00B280CD01E +:102870000C280CD00D280CD00E2814BF402030207E +:1028800070470C20704710207047142070471820A4 +:102890007047202070470000082817D90C280CD951 +:1028A00010280CD914280CD918280CD920280CD998 +:1028B00030288CBF0F200E207047092070470A2057 +:1028C00070470B2070470C2070470D2070470000A8 +:1028D0002DE9F843078C072F04461ED9D0E902984A +:1028E00000254FF6FF73C5F12006A5F1200029FA57 +:1028F00005F108FA06F628FA00F031430143C9B29F +:102900001846FFF763FF0835402D0346EBD1E16918 +:102910003A46BDE8F843FFF76BBF4FF6FF70BDE8DE +:10292000F883000010B54B6823B9CA8A63F3090223 +:10293000CA8210BD04691A681C600361C38A013B26 +:10294000C3824A60EFE700002DE9F84F1D46CB8AAD +:102950000F46C3F309010529814692460B4630D044 +:102960000020AAB207F11A049EB2042E1FFA80F8C2 +:102970000FD8904503F1010306D3FB8A0A4462F3A2 +:102980000903FB8201201AE01AF80060E6540130C6 +:10299000EAE79045F1D2A1F1050B1C237C68BBFB53 +:1029A000F3F203FB12BB1FFA8BF6002C45D148460D +:1029B000FFF72AFF044638B978606FF00200BDE8DF +:1029C000F88F4FF00008E6E7002606607860ADB2A9 +:1029D0004FF0000B454510D90AEB0803221D13F8F0 +:1029E000011B9155B1B208F101081B291FFA88F8A3 +:1029F0002BD0454506F10106F1D8FB8AC3F3090245 +:102A0000154465F30903BCE7013292B21C46236802 +:102A1000002BF9D16B1F0B441C21B3FBF1F30133E5 +:102A20009BB29A42D3D2BBF1000FD0D14846FFF7F8 +:102A3000EBFE20B9C4F800B0BFE70122E7E7C0F819 +:102A400000B05E4620600446C1E74545D5D94846FA +:102A5000FFF7DAFE08B92060AFE7C0F800B0002643 +:102A600020600446B6E700002DE9F04F2DED028B03 +:102A70001C4683B05B69019207468846002B00F034 +:102A80009A80238C2BB1E269002A00F09480072BF6 +:102A900035D807F10C00FFF7B7FE054638B96FF0DF +:102AA0000205284603B0BDEC028BBDE8F08F14226E +:102AB0000021FEF735FC228CE16905F10800FEF7E4 +:102AC0001DFC208C013080B2FFF7E6FEFFF7C8FE48 +:102AD000013880B22084013028746369228C1B780D +:102AE0002A4403F01F0363F03F0348F000411372D0 +:102AF000384669602946FFF7EFFD0125D1E700F16F +:102B00000C034FF0000908EE103A4FF0800A4E46D1 +:102B10004D4618EE100AFFF777FE83460028BED018 +:102B200014220021FEF7FCFB002E3AD1019BABF8EA +:102B3000083002220BF1080E1FFA82FC0CF1010092 +:102B4000BCF1060F218C80B201D88E422BD3FFF747 +:102B5000A3FEFFF785FE62691278013802F01F02BA +:102B60008E4208BF4FF0400A42EA49121BFA80F138 +:102B70004AEA020A013048F0004281F808A08BF8C6 +:102B80001000CBF8042059463846FFF7A5FD238CEA +:102B90000135B3422DB289F001094FF0000AB8D1D6 +:102BA0007FE70022C6E7E169895D0EF80210013671 +:102BB000B6B20132C0E76FF0010572E7F8B515460D +:102BC0000E463022002104461F46FEF7A9FB069B55 +:102BD0006360B5F5001F079BA76034BF6A094FF615 +:102BE000FF72A36297B2E66104F1100000239A42DB +:102BF00006D800230360A782E3822383E360F8BD45 +:102C00000660013330462036F1E7000003781BB937 +:102C10004BB2002BC8BF01707047000000787047AE +:102C2000F8B50C46C969074611B9238C002B37D17A +:102C3000257E1F2D34D8387828BB228C072A2CD823 +:102C4000268A36F003032BD14FF6FF70FFF7D0FD35 +:102C500020F001003102400441EA0561400C41EAE4 +:102C600040254FF6FF72234629463846FFF7FCFE03 +:102C7000002807DD626913780133DBB21F2B88BFA0 +:102C800000231370F8BD218A2D0645EA012505436E +:102C90002046FFF71DFE0246E5E76FF00300F1E76F +:102CA0006FF00100EEE7000070B58AB004461646EA +:102CB0000021282268461D46FEF732FBBDF8383059 +:102CC000ADF810300F9B05939DF840308DF818300B +:102CD000119B07936946BDF84830ADF82030204677 +:102CE000CDE90265FFF79CFF0AB070BD2DE9F04108 +:102CF000D36905460C4616460BB9138C5BBB377E71 +:102D00001F2F28D895F80080B8F1000F26D0304644 +:102D1000FFF7DEFD3378210241EAC33141EA0801C1 +:102D2000338A41EA076141EA03410246334641F0F2 +:102D300080012846FFF798FE00280ADD3378012B32 +:102D400007D1726913780133DBB21F2B88BF0023D0 +:102D50001370BDE8F0816FF00100FAE76FF0030037 +:102D6000F7E70000F0B58BB004460D46174600218A +:102D7000282268461E46FEF7D3FA9DF84C305A1EAC +:102D8000534253418DF800309DF84030ADF810307B +:102D9000119B05939DF848308DF81830149B0793CC +:102DA0006A46BDF85430ADF8203029462046CDE9BA +:102DB0000276FFF79BFF0BB0F0BD0000406A00B148 +:102DC00004307047436A1A68426202691A600361FC +:102DD000C38A013BC38270472DE9F041D0F82080BF +:102DE000194E14461D464146002709B9BDE8F08139 +:102DF000D1E90223A21A65EB0303964277EB0303A2 +:102E00001ED2036A8B420DD1FFF78CFD036A1B684B +:102E1000036203690B60C38A0161016A013BC382DB +:102E20008846E2E7FFF77EFD0B68C8F800300369CB +:102E30000B60C38A0161013BC382D8F80010D4E75C +:102E400088460968D1E700BF80841E002DE9F04F55 +:102E50008BB00D46DDF8509014469B468046002806 +:102E600000F01981B9F1000F00F01581531E3F2BBE +:102E700000F21181012A03D1BBF1000F40F00B8158 +:102E80000023CDE90833B8F81430B5EBC30F4FEA8F +:102E9000C30703D300200BB0BDE8F08F2B199F426E +:102EA000D8F80C303ABF7F1BFFB227461BB9D8F8C1 +:102EB0001030002B7AD0272D4ED8C5F12806B74206 +:102EC0004FF000032CBFF6B23E4600932946D8F8D7 +:102ED000080008AB3246FFF741FCA7EB060A354471 +:102EE0005FFA8AFAB8F8143003F10053053BDB00AF +:102EF0000493D8F80C3003932821039B13B1BAF143 +:102F0000000F2CD1D8F8100040B1BAF1000F05D055 +:102F1000009608AB5246691AFFF720FC38B2002F22 +:102F2000B8D066070AD00AAB03EBD401624211F8AD +:102F3000083C02F00702134101F8083C082C3CD978 +:102F4000102C40F2B580202C40F2B780BBF1000F6E +:102F500000F09C80082334E0BA460026C2E7049BB8 +:102F6000E02B28BFE02306930B44AB42059314D912 +:102F70005A1B03980096924534BF5246D2B2691A42 +:102F800008AB04300792FFF7E9FB079A1644AAEB57 +:102F9000020A1544F6B25FFA8AFA049B069A05996A +:102FA0009B1A0493039B1B680393A6E70093D8F82E +:102FB000080008AB3A462946AEE7BBF1000F13D034 +:102FC0000123B4EBC30F6CD0082C12D89DF820302D +:102FD000621E23FA02F2D50706D54FF0FF3202FA3D +:102FE00004F423438DF820309DF8203089F8003018 +:102FF00051E7102C12D8BDF82030621E23FA02F2DD +:10300000D10706D54FF0FF3202FA04F42343ADF89E +:103010002030BDF82030A9F800303CE7202C0FD834 +:103020000899631E21FA03F3DA0705D54FF0FF3242 +:1030300002FA04F40C430894089BC9F800302AE70C +:10304000402C2BD0DDE90865611EC4F12102A4F1FA +:10305000210326FA01F105FA02F225FA03F31143DE +:103060001943CB0712D50122A4F12003C4F120019A +:1030700002FA03F322FA01F1A240524243EA0103A9 +:1030800063EB430332432B43CDE90823DDE90823F7 +:10309000C9E90023FFE66FF00100FCE66FF00800CD +:1030A000F9E6082CA0D9102CB3D9202CEED8C3E710 +:1030B000BBF1000FADD0022383E7BBF1000FBBD003 +:1030C00004237EE730B5012A144638BF0124402C82 +:1030D00085B028BF40240025012ACDE9025518D823 +:1030E0001B788DF8083063070AD004AB03EBD405D6 +:1030F000624215F8083C02F00702934005F8083CCC +:10310000009103462246002102A8FFF727FB05B0E5 +:1031100030BD082AE4D9102A03D81B88ADF808303E +:10312000E1E7202A8DBFD3E900231B680293CDE994 +:103130000223D8E710B5CB681BB98B600B618B827B +:1031400010BD04691A681C600361C38A013BC38215 +:10315000CA60F0E703064CBFC0F3C03002207047DE +:1031600008B50246FFF7F6FF022806D15306C2F360 +:103170000F2001D100F0030008BDC2F30740FBE7B8 +:103180002DE9F04F93B0CDE903230A6804461046B9 +:10319000FFF7E0FF022814BFC2F306260026002A2C +:1031A0000D46824680F2F28112F0C04940F0EE8175 +:1031B000097B002900F0EA81022803D02378B3427A +:1031C00040F0E781C2F304630693104602F07F03E8 +:1031D0000593FFF7C5FF059B29444FEA834848EA5A +:1031E0000A4848EA4668CE7800230022CDE9082341 +:1031F000F309834648EA0008029367D0059B0093D1 +:1032000002466768534608A92046B847002800F0E0 +:10321000C381276A4FB9414604F10C00FFF702FB56 +:10322000074690B96FF0020054E03B6998450DD015 +:103230003F68002FF9D1414604F10C00FFF7F2FA84 +:1032400007460028EED0236A3B60276297F817C034 +:1032500006F01F08CCF3840CACEB08001FFA80FECC +:103260000028B8BF0EF12000A8EB0C031FFA83FE64 +:10327000D7E90221B8BF00B2002B0793BEBF0EF101 +:1032800020031BB2079352EA010338D0039BDFF8F7 +:1032900024E39A1A049B4FF0000C63EB010196455E +:1032A0007CEB01032BD36B7B97F81AE0734519D1A4 +:1032B000029B002B78D0012821DC7868F8B9DFF870 +:1032C000F0C2944570EB010316D337E0276A27B9A3 +:1032D0006FF00C0013B0BDE8F08F3B699845B5D096 +:1032E0003F68F4E7B24890427CEB010301D3002031 +:1032F000F0E7029B002BFAD0079B0F2B17DCFA7D1F +:10330000B30002F0030203F07C031343FB7539465C +:103310002046FFF707FB6B7BBB76029B3BB9FB7D2F +:10332000C3F38402013262F38603FB75D0E76A7B44 +:10333000BB7E9A42DBD1029B002B35D0B309022B16 +:1033400032D0039BBB60049BFB60142200210DA8BC +:10335000FDF7E6FF039B0A93049B0B932B1D0C9335 +:103360002B7BADF83EB0013BDBB2ADF83C30069BA9 +:103370008DF84230059B8DF8433094F82C308DF851 +:1033800040A083F001038DF844308DF84180A3689C +:103390000AA920469847FB7DC3F38403013303F059 +:1033A0001F039B02FB82A2E7FB7DC6F34012B2EB38 +:1033B000D31F40F0F480C3F38403434540F0F28010 +:1033C000029A2B7BB609002A4DD0F2075DD4032B5D +:1033D00040F2EB80039BBB60049BFB602B7BAE1D2C +:1033E000033BDBB23246394604F10C00FFF7ACFA7E +:1033F00000280CDA39462046FFF794FAFB7DC3F328 +:103400008403013303F01F039B02FB820AE7DDE91B +:103410000884AB883B834FF6FF73C9F12000A9F104 +:10342000200228FA09F104FA00F0014324FA02F21A +:1034300011431846C9B2FFF7C9F909F10809B9F1F2 +:10344000400F0346E9D1B8822A7B033AD2B2314613 +:10345000FFF7CEF9FB7DB882DA43C2F3C01262F304 +:10346000C713FB7543E786B92E1D013BDBB232461D +:10347000394604F10C00FFF767FA0028BADB2A7B13 +:10348000B88A013AD2B23146E2E7F98AC1F30901BA +:10349000013B0429DAB25BD8281D002307F11B0683 +:1034A0009A4208D910F801CB06F801C00131013366 +:1034B0000529DBB2F4D103990A9104990B91934247 +:1034C00007F11B010C9138BF043379680D9134BFAB +:1034D00055FA83F300230E93FB8AADF83EB0C3F395 +:1034E00009031A44069B8DF84230059B8DF8433042 +:1034F00094F82C30ADF83C2083F001038DF8443073 +:1035000000238DF840A08DF841807B602A7BB88A2B +:10351000013A291DFFF76CF93B8BB882834203D136 +:10352000A3680AA92046984720460AA9FFF702FE89 +:10353000FB7DBA8AC3F38403013303F01F039B02AC +:10354000FB823B8B9A420CBF00206FF01000C1E65B +:103550007B68002BAFD0052001E01C3033461E688D +:10356000002EFAD1091A081D2E1D184401EB090C72 +:10357000BCF11B0F5FFA89F39DD89A429BD916F8CC +:10358000013B00F8013B09F10109EFE76FF0090089 +:10359000A0E66FF00A009DE66FF00B009AE66FF070 +:1035A0000D0097E66FF00E0094E66FF00F0091E6C5 +:1035B00040420F0080841E00EFF3098305494A6BE7 +:1035C00022F001024A63683383F30988002383F3FE +:1035D0001188704700EF00E0302080F3118862B658 +:1035E0000C4B0D4AD96821F4E0610904090C0A4327 +:1035F000DA60D3F8FC20094942F08072C3F8FC205D +:103600000A6842F001020A602022DA7783F8220079 +:10361000704700BF00ED00E00003FA05001000E075 +:1036200010B5302383F311880E4B5B6813F40063ED +:1036300014D0F1EE103AEFF30984683C4FF0807338 +:10364000E361094BDB6B236684F3098800F0A4F87F +:1036500010B1064BA36110BD054BFBE783F3118846 +:10366000F9E700BF00ED00E000EF00E0030600080E +:10367000060600084FF0E023002258684FF0FF31A3 +:10368000930003F1604303F5614301329042C3F8B4 +:103690008010C3F88011F3D27047000000F160433E +:1036A00003F561430901C9B283F80013012200F058 +:1036B0001F039A4043099B0003F1604303F56143F4 +:1036C000C3F880211A60704700230375826803697C +:1036D0001B6899689142FBD25A680360426010608F +:1036E0005860704700230375826803691B689968F6 +:1036F0009142FBD85A68036042601060586070477E +:1037000008B50846302383F311880B7D032B05D0C1 +:10371000042B0DD02BB983F3118808BD8B690022CF +:103720001A604FF0FF338361FFF7CEFF0023F2E70B +:10373000D1E9003213605A60F3E70000FFF7C4BF1D +:10374000054BD9680875186802681A605360012231 +:103750000275D860FCF740BF2038002030B50C4B14 +:10376000DD684B1C87B004460FD02B46094A6846DB +:1037700000F050F92046FFF7E3FF009B13B16846C5 +:1037800000F052F9A86907B030BDFFF7D9FFF9E79B +:103790002038002001370008044B1A68DB68906865 +:1037A0009B68984294BF0020012070472038002079 +:1037B000084B10B51C68D86822681A605360012253 +:1037C0002275DC60FFF78EFF01462046BDE8104001 +:1037D000FCF702BF20380020044B1A68DB689268AF +:1037E0009B689A4201D9FFF7E3BF70472038002059 +:1037F00038B5074C07490848012300252370656048 +:1038000000F000FC0223237085F3118838BD00BF4F +:10381000483A0020BC4700082038002008B572B69E +:10382000044B186500F0B6FA00F06EFB024B032261 +:103830001A70FEE720380020483A002000F02AB92C +:10384000EFF3118020B9EFF30583302282F3118862 +:103850007047000010B530B9EFF30584C4F30804D5 +:1038600014B180F3118810BDFFF7B6FF84F31188FF +:10387000F9E700008B60022308618B8208467047DD +:103880008368A3F1840243F8142C026943F8442CA2 +:10389000426943F8402C094A43F8242CC26843F893 +:1038A000182C022203F80C2C002203F80B2C044ADB +:1038B00043F8102CA3F12000704700BFF105000869 +:1038C0002038002008B5FFF7DBFFBDE80840FFF710 +:1038D00035BF0000024BDB6898610F20FFF730BF57 +:1038E00020380020302383F31188FFF7F3BF000056 +:1038F00008B50146302383F311880820FFF72EFF17 +:10390000002383F3118808BD10B503689C68A242A8 +:103910000CD85C688A600B604C60216059609968C3 +:103920008A1A9A604FF0FF33836010BD1B68121B28 +:10393000ECE700000A2938BF0A2170B504460D469D +:103940000A26601900F058FB00F044FB041BA54256 +:1039500003D8751C2E460446F3E70A2E04D9BDE8A9 +:103960007040012000F08EBB70BD0000F8B5144B14 +:103970000D46D96103F1100141600A2A196982607C +:1039800038BF0A22016048601861A818144600F088 +:1039900025FB0A2700F01EFB431BA342064606D365 +:1039A0007C1C281900F028FB27463546F2E70A2F31 +:1039B00004D9BDE8F840012000F064BBF8BD00BFA9 +:1039C00020380020F8B506460D4600F003FB0F4AEC +:1039D000134653F8107F9F4206D12A4601463046CF +:1039E000BDE8F840FFF7C2BFD169BB68441A2C1983 +:1039F00028BF2C46A34202D92946FFF79BFF224647 +:103A000031460348BDE8F840FFF77EBF203800206C +:103A10003038002010B4C0E9032300235DF8044BC4 +:103A20004361FFF7CFBF000010B5194C23699842DE +:103A30000DD0D0E90032816813605A609A680A4458 +:103A40009A60002303604FF0FF33A36110BD23464B +:103A5000026843F8102F53600022026022699A42E4 +:103A600003D1BDE8104000F0C1BA936881680B44EF +:103A7000936000F0AFFA2269E1699268441AA242A9 +:103A8000E4D91144BDE81040091AFFF753BF00BF45 +:103A9000203800202DE9F047DFF8BC8008F110073E +:103AA0002C4ED8F8105000F095FAD8F81C40AA68AF +:103AB000031B9A423ED81444D5E900324FF0000966 +:103AC000C8F81C4013605A60C5F80090D8F8103050 +:103AD000B34201D100F08AFA89F31188D5E90331A4 +:103AE00028469847302383F311886B69002BD8D080 +:103AF00000F070FA6A69A0EB04094A4582460DD2CB +:103B0000022000F0BFFA0022D8F81030B34208D1EA +:103B100051462846BDE8F047FFF728BF121A224455 +:103B2000F2E712EB090938BF4A4629463846FFF743 +:103B3000EBFEB5E7D8F81030B34208D01444211A90 +:103B4000C8F81C00A960BDE8F047FFF7F3BEBDE868 +:103B5000F08700BF30380020203800200020704758 +:103B6000FEE70000704700004FF0FF307047000094 +:103B7000BFF34F8F024A1369DB03FCD4704700BFC9 +:103B80000020024008B5094B1B7873B9FFF7F0FF1E +:103B9000074B5A69002ABFBF064A9A6002F1883271 +:103BA0009A601A6822F480621A6008BD603A0020A8 +:103BB000002002402301674508B50B4B1B7893B9E1 +:103BC000FFF7D6FF094B5A6942F000425A611A6862 +:103BD00042F480521A601A6822F480521A601A68FD +:103BE00042F480621A6008BD603A00200020024062 +:103BF0007F289ABF00F58030C00200207047000087 +:103C00004FF4006070470000802070477F2808B59F +:103C10000BD8FFF7EDFF00F500630268013204D115 +:103C200004308342F9D1012008BD0020FCE70000E8 +:103C30007F2810B504461FD8FFF79AFFFFF7A2FFB1 +:103C40000E4BF3221A6102225A615A6942EAC002FB +:103C50005A615A6942F480325A61FFF789FF4FF482 +:103C60000061FFF7C5FF00F04BF9FFF7A5FF204605 +:103C7000BDE81040FFF7CABF002010BD0020024081 +:103C80002DE9F84340EA020313F00703144606D077 +:103C9000304B40F231321A600020BDE8F8838518BD +:103CA0002D4A95420CD92B4A40F236311160F3E788 +:103CB000031D1B684A68934208D1083C083008314C +:103CC000072C14D902680B689A42F1D0FFF75AFF0B +:103CD000FFF74EFF214E08314FF001084FF0000969 +:103CE000012CA1F1080706D8FFF766FF01E0002CC0 +:103CF000ECD10120D1E7C6F81480054651F8083C04 +:103D000045F8043B51F8043C4360FFF731FF336949 +:103D100043F001033361C6F81490026851F8083C7F +:103D20009A420CD00B4B40F25E321A600C4B18607A +:103D30000C4B1C600C4B1F60FFF73EFFACE72D687F +:103D400051F8043C9D4201F10801EBD1083C0830D8 +:103D5000C6E700BF5C3A00200000040800200240D3 +:103D6000503A0020583A0020543A0020084908B53B +:103D70000B7828B11BB9FFF705FF01230B7008BDB5 +:103D8000002BFCD0BDE808400870FFF715BF00BF4E +:103D9000603A00204FF480314FF0005000F0B2B88C +:103DA0000846114600F014BC012000F011BC0000D0 +:103DB000084600F02BBC000070B582B0FFF740FD54 +:103DC0000E4E054600F006F93268904237BF0C4AA5 +:103DD0000B49516814682EBFD1E90041013151608F +:103DE0000419034641F10001284601913360FFF7B1 +:103DF00031FD0199204602B070BD00BF643A002039 +:103E0000683A002070B582B0FFF71AFD104E0546E3 +:103E100000F0E0F83268904237BF0E4A0D49516811 +:103E200014682EBFD1E9004101315160041941F1FC +:103E300000010346284601913360FFF70BFD01990D +:103E40004FF47A7200232046FCF7B2F902B070BD3D +:103E5000643A0020683A002010B50244064BD2B202 +:103E6000904200D110BD441C00B253F8200041F82C +:103E7000040BE0B2F4E700BF50280040114B30B50E +:103E8000D3F89040240409D4D3F89040C3F890406C +:103E9000D3F8904044F40044C3F890400A4C23689F +:103EA00043F4807323600244084BD2B2904200D1A5 +:103EB00030BD441C00B251F8045B43F82050E0B21E +:103EC000F4E700BF0010024000700040502800409E +:103ED00007B5012201A90020FFF7BEFF019803B03A +:103EE0005DF804FB13B50446FFF7F2FFA04205D0CE +:103EF000012201A900200194FFF7C0FF02B010BD0C +:103F0000704700007047000070470000074B45F203 +:103F100055521A6002225A6040F6FF729A604CF6BF +:103F2000CC421A60024B01221A70704700300040E8 +:103F3000743A0020034B1B781BB1034B4AF6AA22AC +:103F40001A607047743A002000300040054B1A6830 +:103F500032B902F1804202F50432D2F894201A609C +:103F6000704700BF703A0020024B4FF40002C3F8C4 +:103F7000942070470010024008B5FFF7E7FF024B9E +:103F80001868C0F3407008BD703A00207047000008 +:103F9000FEE700000A4B0B480B4A90420BD30B4B39 +:103FA000DA1C121AC11E22F003028B4238BF002213 +:103FB0000021FDF7B5B953F8041B40F8041BECE7EA +:103FC0005C480008003B0020003B0020003B002034 +:103FD00000F0BEB84FF08043586A70474FF08043FE +:103FE000002258631A610222DA6070474FF0804362 +:103FF0000022DA60704700004FF08043586370473A +:10400000FEE7000070B51B4B01630025044686B037 +:10401000586085620E46FFF7DFFA04F11003C4E929 +:1040200004334FF0FF33C4E90635C4E90044A5600A +:10403000E562FFF7CFFF2B460246C4E9082304F1EF +:1040400034010D4A256580232046FFF713FC012328 +:10405000E0600A4A0375009272680192B268CDE985 +:104060000223074B6846CDE90435FFF72BFC06B069 +:1040700070BD00BF483A0020C8470008CD4700087F +:1040800001400008024AD36A1843D062704700BF5B +:1040900020380020244B2548DA6A42F0070210B489 +:1040A000DA62DA6A224C22F00702DA62DA6ADA6C41 +:1040B00042F00702DA64DA6E42F00702DA664FF085 +:1040C0009042DB6E4FF0AA31002353609160D060C4 +:1040D0004FF6FF7050611362536214601024C2F8EF +:1040E0000434C2F80814C2F80C444FF6F774C2F84E +:1040F00014449924C2F82034C2F824440D4CC2F868 +:104100000044C2F80438C2F80818C2F80C38C2F8E3 +:104110001408C2F82038C2F82438C2F800385DF814 +:10412000044B00F055B800BF00100240000100240D +:104130000001002850000A0008B500F005FAFFF75A +:1041400057FBBDE80840FFF701BF000070470000C3 +:104150000F4B9A6D42F001029A659A6F42F001028C +:104160009A670C4A9B6F936843F0010393604FF08A +:1041700080434F229A624FF0FF32DA6200229A6146 +:104180005A63DA605A6001225A611A60704700BFB0 +:1041900000100240002004E04FF0804208B5116991 +:1041A000D3680B40D9B2C9439B07116107D53023AF +:1041B00083F31188FFF742FB002383F3118808BDC6 +:1041C00008B5FFF757FABDE8084000F099B90000BC +:1041D0005A4B4FF0FF319A6A99629A6A00229A62AA +:1041E000986AD86A60F00700D862D86A00F00700C1 +:1041F000D862D86A186B1963186B1A63186B986BBE +:104200009963986B9A63986BD86BD963D86BDA63B0 +:10421000D86B186C1964196C1A641A6C484A4FF4FC +:10422000E06111601A6E474942F001021A66D3F844 +:10423000802022F00102C3F88020D3F880209A6DFC +:1042400042F080529A659A6F22F080529A679A6F74 +:104250004FF440720A604A6912F48062FBD14A60EE +:104260001A6822F0F00242F060021A601A6842F006 +:1042700001021A601A689107FCD500229A609A68B8 +:1042800012F00C02FBD1D3F8901011F4407F1EBF46 +:104290004FF48031C3F89010C3F8902061221A6067 +:1042A0001A689207FCD500229A609A6812F00C0FE7 +:1042B000FBD169221A60D3F8942022F4706242F490 +:1042C000C062C3F894201A6842F480321A601A68F7 +:1042D0009003FCD5D3F8902022F00322C3F890205D +:1042E000194ADA601A6842F080721A601A689101FD +:1042F000FCD5164A1A611A6842F080621A601A6880 +:104300001201FCD500229A600D49114AC3F8882099 +:104310000A6822F0070242F004020A600A6802F00A +:104320000702042AFAD19A6842F003029A609A6856 +:1043300002F00C020C2AFAD1704700BF00100240B4 +:10434000002002400070004003140001000C100027 +:1043500055550134074A08B5536903F00103536109 +:1043600023B1054A13680BB150689847BDE808406F +:10437000FFF756B900040140783A0020074A08B513 +:10438000536903F00203536123B1054A93680BB1EB +:10439000D0689847BDE80840FFF742B900040140E3 +:1043A000783A0020074A08B5536903F004035361C3 +:1043B00023B1054A13690BB150699847BDE808401D +:1043C000FFF72EB900040140783A0020074A08B5EB +:1043D000536903F00803536123B1054A93690BB194 +:1043E000D0699847BDE80840FFF71AB900040140BA +:1043F000783A0020074A08B5536903F01003536167 +:1044000023B1054A136A0BB1506A9847BDE80840CA +:10441000FFF706B900040140783A0020164B10B5AA +:104420005C6904F478725A61A30604D5134A936A4E +:104430000BB1D06A9847600604D5104A136B0BB1D4 +:10444000506B9847210604D50C4A936B0BB1D06B87 +:104450009847E20504D5094A136C0BB1506C984794 +:10446000A30504D5054A936C0BB1D06C9847BDE801 +:104470001040FFF7D5B800BF00040140783A002093 +:10448000194B10B55C6904F47C425A61620504D58D +:10449000164A136D0BB1506D9847230504D5134A86 +:1044A000936D0BB1D06D9847E00404D50F4A136E9D +:1044B0000BB1506E9847A10404D50C4A936E0BB112 +:1044C000D06E9847620404D5084A136F0BB1506F41 +:1044D0009847230404D5054A936F0BB1D06F9847D2 +:1044E000BDE81040FFF79CB800040140783A002076 +:1044F00008B5FFF751FEBDE80840FFF791B800008E +:10450000062108B50846FFF7C9F806210720FFF77E +:10451000C5F806210820FFF7C1F806210920FFF79A +:10452000BDF806210A20FFF7B9F806211720FFF78A +:10453000B5F806212820FFF7B1F8BDE808400721AB +:104540001C20FFF7ABB8000008B5FFF739FE00F0FC +:1045500007F8FFF7FBFDBDE80840FFF739BD000095 +:104560000023054A19460133102BC2E9001102F15C +:104570000802F8D1704700BF783A00200B46014688 +:10458000184600F02DB8000000F040B8012838BFF0 +:10459000012010B50446204600F030F830B900F094 +:1045A00007F808B900F00CF88047F4E710BD0000E8 +:1045B000024B1868BFF35B8F704700BFF83A0020CA +:1045C00008B5062000F084F80120FFF7C9FA0000C2 +:1045D000024B0A4601461868FFF7E2BB181100209B +:1045E00010B5054C13462CB10A4601460220AFF324 +:1045F000008010BD2046FCE700000000024B014691 +:104600001868FFF7D1BB00BF18110020024B01460C +:104610001868FFF7CDBB00BF1811002010B5013995 +:104620000244904201D1002005E0037811F8014FC7 +:10463000A34201D0181B10BD0130F2E72DE9F04173 +:10464000A3B1C91A17780144044603F1FF3C8C4218 +:10465000204601D9002009E00578BD4204F101049B +:10466000F5D10CEB0405D618A54201D1BDE8F081C7 +:1046700015F8018D16F801EDF045F5D0E7E70000DB +:104680001F2938B504460D4604D9162303604FF0A0 +:10469000FF3038BD426C12B152F821304BB9204680 +:1046A00000F030F82A4601462046BDE8384000F0C8 +:1046B00017B8012B0AD0591C03D11623036001201F +:1046C000E7E7002442F82540284698470020E0E725 +:1046D000024B01461868FFF7D3BF00BF1811002036 +:1046E00038B5074D00230446084611462B60FFF7F6 +:1046F0003BFA431C02D12B6803B1236038BD00BFD5 +:10470000FC3A0020FFF72ABA034611F8012B03F800 +:10471000012B002AF9D170476F72672E61726475A0 +:1047200070696C6F742E4D6174656B4C3433312D30 +:1047300041697273706565640000000040A2E4F195 +:10474000646891060041A3E5F265699207000000E4 +:104750004261642043414E496661636520696E642D +:1047600065782E00800000000080000000008000BE +:104770000000000000000000291B000811230008B1 +:1047800071220008391B00086D1B0008691D000814 +:104790003D1B00084D1B0008411B0008491B000879 +:1047A000451B0008911C0008511B0008DD2500086E +:1047B000611B0008651C000863300000B847000852 +:1047C00078380020483A00206D61696E0069646C99 +:1047D000650000000CBAFF7F01000000000000002F +:1047E000260400000000000000600300000000003C +:1047F000FE2A0100D20400001C110020000000006D +:1048000000000000000000000000000000000000A8 +:104810000000000000000000000000000000000098 +:104820000000000000000000000000000000000088 +:104830000000000000000000000000000000000078 +:104840000000000000000000000000000000000068 +:0C4850000000000000000000000000005C :00000001FF diff --git a/Tools/bootloaders/MatekL431-BattMon_bl.bin b/Tools/bootloaders/MatekL431-BattMon_bl.bin index 7420cddee348e3..f7b0d44adc7248 100755 Binary files a/Tools/bootloaders/MatekL431-BattMon_bl.bin and b/Tools/bootloaders/MatekL431-BattMon_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-DShot_bl.bin b/Tools/bootloaders/MatekL431-DShot_bl.bin index c83b0b8cebffc6..7120c1086811fe 100755 Binary files a/Tools/bootloaders/MatekL431-DShot_bl.bin and b/Tools/bootloaders/MatekL431-DShot_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-EFI_bl.bin b/Tools/bootloaders/MatekL431-EFI_bl.bin index d57c47b4058eb4..f68f10dc363bad 100755 Binary files a/Tools/bootloaders/MatekL431-EFI_bl.bin and b/Tools/bootloaders/MatekL431-EFI_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-GPS_bl.bin b/Tools/bootloaders/MatekL431-GPS_bl.bin index 770c9a4d449f68..266291e731af4c 100755 Binary files a/Tools/bootloaders/MatekL431-GPS_bl.bin and b/Tools/bootloaders/MatekL431-GPS_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Periph_bl.bin b/Tools/bootloaders/MatekL431-Periph_bl.bin index e8b7eb46b6b0af..c7798ec3909c68 100755 Binary files a/Tools/bootloaders/MatekL431-Periph_bl.bin and b/Tools/bootloaders/MatekL431-Periph_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Periph_bl.hex b/Tools/bootloaders/MatekL431-Periph_bl.hex index 9fc970351050ea..9166fa5402b711 100644 --- a/Tools/bootloaders/MatekL431-Periph_bl.hex +++ b/Tools/bootloaders/MatekL431-Periph_bl.hex @@ -1,19 +1,19 @@ :020000040800F2 -:1000000000090020B5040008E5290008652900085A -:10001000BD2900086529000891290008B7040008D7 -:10002000B7040008B7040008B7040008393800080E +:1000000000090020B5040008CD250008852500085A +:10001000AD25000885250008A5250008B7040008BF +:10002000B7040008B7040008B7040008C135000889 :10003000B7040008B7040008B7040008B7040008B4 :10004000B7040008B7040008B7040008B7040008A4 -:10005000B7040008B7040008714B0008994B00086A -:10006000C14B0008E94B0008114C0008B704000818 +:10005000B7040008B70400085D43000885430008A2 +:10006000AD430008D5430008FD430008B70400086D :10007000B7040008B7040008B7040008B704000874 -:10008000B7040008B7040008B7040008A125000859 -:10009000CD250008DD250008B7040008394C00080C +:10008000B7040008B7040008B704000839250008C1 +:100090006525000875250008B704000825440008F8 :1000A000B7040008B7040008B7040008B704000844 -:1000B000494D0008B7040008B7040008B704000859 +:1000B000F9440008B7040008B7040008B7040008B2 :1000C000B7040008B7040008B7040008B704000824 -:1000D000B70400080D4D0008214D0008354D0008FB -:1000E0009D4C0008B7040008B7040008B7040008D6 +:1000D000B7040008B7040008B7040008B704000814 +:1000E00089440008B7040008B7040008B7040008F2 :1000F000B7040008B7040008B7040008B7040008F4 :10010000B7040008B7040008B7040008B7040008E3 :10011000B7040008B7040008B7040008B7040008D3 @@ -25,7 +25,7 @@ :10017000B7040008B7040008B7040008B704000873 :10018000B7040008B7040008B7040008B704000863 :10019000B7040008B7040008B7040008B704000853 -:1001A000051800080000000000000000000000002A +:1001A0001112000800000000000000000000000024 :1001B00053B94AB9002908BF00281CBF4FF0FF31CE :1001C0004FF0FF3000F074B9ADF1080C6DE904CECA :1001D00000F006F8DDF804E0DDE9022304B0704722 @@ -74,1262 +74,1087 @@ :100480004B45A9D2B9EB020864EB0C0E0138A3E787 :100490004646EAE7204694E74046D1E7D0467BE768 :1004A000023B614432E7304609E76444023842E7E0 -:1004B000704700BF02E000F000F8FEE772B63A486D -:1004C00080F30888394880F3098839484EF6085186 -:1004D000CEF20001086040F20000CCF200004EF6BF -:1004E0003471CEF200010860BFF34F8FBFF36F8FFE -:1004F00040F20000C0F2F0004EF68851CEF200014A -:100500000860BFF34F8FBFF36F8F4FF00000E1EE35 -:10051000100A4EF63C71CEF200010860062080F30E -:100520001488BFF36F8F04F09DF904F079F904F09B -:10053000B3F94FF055301F491B4A91423CBF41F877 -:10054000040BFAE71C49194A91423CBF41F8040BDD -:10055000FAE71A491A4A1B4B9A423EBF51F8040B5C -:1005600042F8040BF8E700201749184A91423CBFB3 -:1005700041F8040BFAE704F057F904F0E5F9144CDC -:10058000144DAC4203DA54F8041B8847F9E700F035 -:1005900041F8114C114DAC4203DA54F8041B884762 -:1005A000F9E704F03FB90000000900200011002025 -:1005B000000000080001002000090020B8520008D7 -:1005C000001100208C110020901100203C390020E7 -:1005D000A0010008A4010008A4010008A40100086B -:1005E0002DE9F04F2DED108AC1F80CD0C3689D465F -:1005F000BDEC108ABDE8F08F002383F311882846F4 -:10060000A047002003F004FEFEE703F07DFD00DFBD -:10061000FEE70000F8B504F0A5F8074604F0F6F888 -:100620000546A0BB1F4B9F4231D001339F4231D0C2 -:100630001D4B27F0FF029A422FD1F8B200F030FD97 -:100640002E4642F2107400F035FF08B10024264611 -:1006500000F02CFD08B90646044635B1134B9F4205 -:1006600003D004F0CBF800242646002004F084F8E0 -:100670000EB100F063F801F051FA00F03FFF01F015 -:100680003DF9204600F0A8F800F058F8F9E72E46AA -:100690000024D8E704460126D5E706464FF47A74CD -:1006A000D1E700BF010007B0000008B0263A09B04A -:1006B00008B501F0EFF8A0F120035842584108BDF9 -:1006C00007B541F21203022101A8ADF8043001F090 -:1006D000FFF803B05DF804FB10B5202383F3118805 -:1006E0001248C3680BB103F00BFE114A0F480023F8 -:1006F0004FF47A7103F0C8FD002383F311880D4C89 -:10070000236813B12368013B2360636813B16368F6 -:10071000013B6360084B1B7833B9636823B902203F -:1007200001F08AF93223636010BD00BF90110020F0 -:10073000D9060008AC120020A4110020214B224A47 -:1007400010B51C46196801313BD004339342F9D1EE -:100750006268A24235D31D4B9B6803F1006303F529 -:1007600020439A422DD204F01BF804F02DF800200B -:1007700001F0DEF8164B0220187001F055F9154B08 -:100780009A6D00229A65996F9A67996FD96DDA65AB -:10079000D96FDA67D96F196E1A66D3F88010C3F86B -:1007A0008020D3F8803072B64FF0E0232021C3F8C8 -:1007B000084DD4E9003281F311889D4683F30888FF -:1007C000104710BD00A0000820A000080011002064 -:1007D000A4110020001002402DE9F04F93B0AC4B63 -:1007E00000902022FF210AA89D6801F041F9A94A42 -:1007F0001378A3B9A8480121C3601170202383F3A3 -:100800001188C3680BB103F07BFDA44AA248002302 -:100810004FF47A7103F038FD002383F31188009BB5 -:100820009F4A03B113609F49009C00230B705360E3 -:1008300098469B461E469A46012001F0F5F824B1E1 -:10084000974B1B68002B00F01C82002001F022F85F -:100850000390039B002B01DA00F094FE039B002B16 -:10086000EDDB012001F0D6F8039B213B162BE3D8EA -:1008700001A252F823F000BFD5080008FD080008C7 -:1008800091090008390800083908000839080008EB -:10089000250A0008F70B0008110B0008730B00086D -:1008A0009B0B0008C10B000839080008D30B000897 -:1008B00039080008450C00087509000839080008C7 -:1008C000890C0008E10800087509000839080008CB -:1008D000730B00080220FFF7EBFE002840F0FB81BD -:1008E000009B0221B8F1000F08BF1C4605A841F289 -:1008F0001233ADF8143000F0EBFF9DE74FF47A703F -:1009000000F0C8FF071EEBDB0220FFF7D1FE002836 -:10091000E6D0013F052F00F2E081DFE807F0030A8F -:100920000D10133605230593042105A800F0D0FF10 -:1009300017E057480421F9E75B480421F6E75B48D4 -:100940000421F3E74FF01C09484600F0F3FF09F1DA -:1009500004090590042105A800F0BAFFB9F12C0F95 -:10096000F2D1012000FA07F747EA0B0B5FFA8BFB85 -:100970004FF0000A01F0C8F826B10BF00B030B2B67 -:1009800008BF0024FFF79CFE56E749480421CDE745 -:10099000002EA5D00BF00B030B2BA1D10220FFF7EB -:1009A00087FE074600289BD001203E4E00F0C0FF86 -:1009B0000220307001F038F84FF000085FFA88F933 -:1009C000484600F0C5FF044690B1484600F0D0FF0D -:1009D00008F101080028F1D1B846044641F212138B -:1009E000022105A8ADF814303E4600F071FF23E760 -:1009F00001230220337001F00DF82546244B9B683B -:100A0000AB4207D9284600F095FF013040F06881DD -:100A10000435F3E7234B00251D70214BB8465D607C -:100A20003E46A7E7002E3FF45BAF0BF00B030B2B0A -:100A30007FF456AF1B4B0220187000F0F5FF3220F8 -:100A400000F028FFB0F10009FFF64AAF19F00307E4 -:100A50007FF446AF0E4A926809EB050393423FF6D6 -:100A60003FAFB9F5807F3FF73BAF124B0193B945DC -:100A700022DD4FF47A7000F00DFF0390039A002AF4 -:100A8000FFF62EAF019B039A03F8012B0137EDE728 -:100A900000110020A812002090110020D9060008A3 -:100AA000AC120020A4110020041100200811002025 -:100AB0000C110020A8110020C820FFF7F9FD0746FF -:100AC00000283FF40DAF1F2D11D8C5F120024A4573 -:100AD0000AAB25F0030028BF4A4683490192184417 -:100AE00000F0B4FF019A8048FF2100F0C1FF4FEAF7 -:100AF000A9037D490193C9F38702284600F0C0FF8E -:100B0000064600283FF46AAF019B05EB830531E7F9 -:100B10000220FFF7CDFD00283FF4E2AE00F044FFD5 -:100B200000283FF4DDAE0027B946704B9B68BB42FE -:100B300018D91F2F11D80A9B01330ED027F00303B9 -:100B400012AA134453F8203C05934846042205A9F1 -:100B500001F056FF04378146E7E7384600F0EAFE29 -:100B60000590F2E7CDF81490042105A800F0B0FE3E -:100B700000E70023642104A8049300F09FFE0028EE -:100B80007FF4AEAE0220FFF793FD00283FF4A8AE3D -:100B9000049800F0FFFE0590E6E70023642104A816 -:100BA000049300F08BFE00287FF49AAE0220FFF73A -:100BB0007FFD00283FF494AE049800F0EDFEEAE7D4 -:100BC0000220FFF775FD00283FF48AAE00F0FCFE1E -:100BD000E1E70220FFF76CFD00283FF481AE05A994 -:100BE000142000F0F7FE04210746049004A800F04A -:100BF0006FFE3946B9E7322000F04CFE071EFFF6C3 -:100C00006FAEBB077FF46CAE384A926807EB0A03FD -:100C100093423FF665AE0220FFF74AFD00283FF4FD -:100C20005FAE27F003075744BA453FF4A3AE5046E2 -:100C300000F080FE0421059005A800F049FE0AF1AD -:100C4000040AF1E74FF47A70FFF732FD00283FF411 -:100C500047AE00F0A9FE002844D00A9B01330BD018 -:100C600008220AA9002000F00BFF00283AD0202219 -:100C7000FF210AA800F0FCFEFFF722FD1C4803F04C -:100C8000CDFA13B0BDE8F08F002E3FF429AE0BF083 -:100C90000B030B2B7FF424AE0023642105A80593DE -:100CA00000F00CFE074600287FF41AAE0220FFF782 -:100CB000FFFC814600283FF413AEFFF701FD41F22F -:100CC000883003F0ABFA059800F042FF4E4600F082 -:100CD0001BFF3C46B0E506464CE64FF0000AFFE538 -:100CE000B8467BE6374679E6A811002000110020BF -:100CF000A0860100094A136849F2690099B21B0CE9 -:100D000000FB01331360064B186844F2506182B255 -:100D1000000C01FB0200186080B270471411002023 -:100D20001011002010B500211022044600F0A0FE92 -:100D3000034B03CB206061601868A06010BD00BF4A -:100D40009075FF1F2DE9F043224DBBB001F052FE1C -:100D5000AB6840F2ED22C31A934232D906AFA860C5 -:100D60002B4628220021384602F022FB05F10E0016 -:100D700000F076FE002604465FFA80F905F10E08C1 -:100D8000F3B2F100994501F1280107D908EB0603F8 -:100D90000822384602F00CFB0136F1E70823012255 -:100DA000CDE9023205340C4B0193A4B230230093F9 -:100DB000CDE9047405A3D3E90023297B074802F099 -:100DC0000FF93BB0BDE8F083AFF3008078F6339FB6 -:100DD00093CACD8DC8330020D5330020CC2200200B -:100DE00070B50D4614461E4602F090F850B9022E1A -:100DF00010D1012C0ED112A3D3E90023C5E90023A1 -:100E0000012007E0282C10D005D8012C09D0052C92 -:100E10000FD0002070BD302CFBD10BA3D3E90023F1 -:100E2000ECE70BA3D3E90023E8E70BA3D3E9002306 -:100E3000E4E70BA3D3E90023E0E700BFAFF30080B2 -:100E4000401DA12026812A0B78F6339F93CACD8DB1 -:100E50009E6AC421818A46EE26417272DF25D7B789 -:100E6000F017304A39059E5613B504462346084606 -:100E700020220021019002F09BFA22790198032A96 -:100E8000234628BF032203F8042F2021022202F068 -:100E90008FFA62790198072A234628BF072203F8B0 -:100EA000052F2221032202F083FAA2790198072A52 -:100EB000234628BF072203F8062F2521032202F02C -:100EC00077FA019804F108031022282102F070FA41 -:100ED000382002B010BD00002DE9F04FADF5017DC6 -:100EE00021AD0EAE40F2751280460F4622A80021B9 -:100EF000296000F0BDFD48220021304600F0B8FD19 -:100F000001F078FD564B4FF47A72B0FBF2F01860A6 -:100F100093E80700012386E807000DF15A003382A9 -:100F2000FFF700FF42F20463338406AB18464D49D5 -:100F300004F0D2F81E2230642946304686F83C2060 -:100F4000FFF792FF12AB044601460822284602F042 -:100F50002FFA0822A1180DF14903284602F028FAB9 -:100F60000DF14A03082204F11001284602F020FA8C -:100F700013AB202204F11801284602F019FA14AB31 -:100F8000402204F13801284602F012FA16AB08227A -:100F900004F17801284602F00BFA0DF159030822FA -:100FA00004F18001284602F003FA04F1880A0DF1E9 -:100FB0005A0904F5847B4B465146082228460AF11B -:100FC000080A02F0F5F9D34509F10109F3D11BAB89 -:100FD00008225946284602F0EBF904F588744FF0D0 -:100FE000000996F834304B450AD9B36B21464B447F -:100FF0000822284602F0DCF9083409F10109F0E77B -:101000004FF0000996F83C304B4504EBC90108D974 -:10101000336C08224B44284602F0CAF909F1010951 -:10102000F0E700230393BB7E0293073107F1190316 -:101030000193C1F3CF010123CDE904510093F97E5F -:1010400005A3D3E90023404601F0CAFF0DF5017D59 -:10105000BDE8F08FAFF300809E6AC421818A46EE1E -:10106000B41200200851000810B50A4B0A4A1A6051 -:1010700003F5805393F860203AB9DC6D2CB120461B -:1010800001F036FB204603F0B9FEBDE810400348EE -:1010900001F02EBBF822002004520008403300204B -:1010A000014B1870704700BFC0120020F0B5334BE1 -:1010B0001C7B85B034B1324B0E221A8100242046AD -:1010C00005B0F0BD2F4A1068516802AB03C3082376 -:1010D0002D492E480DEB030203F0E2FE054630B920 -:1010E000274B2B480A221A8101F080FAE6E70169B2 -:1010F000B1F5583F06D9224B26480B221A8101F040 -:1011000075FADCE7438B40F22642934207D01C4934 -:101110000C2008811946204801F068FACFE71F4AE1 -:10112000024402F11003994204D2154B1C481022CC -:101130001A81E4E710398E1A2046144901F060FC48 -:101140003246074605F11801204601F059FCAB680C -:101150009F4202D1EB6898420AD0094B0D221A81B6 -:101160000090D5E902123B460E4801F03FFAA5E790 -:101170000D4801F03BFA0124A1E700BFC83300206D -:10118000B4120020B9510008DC5F030000A0000881 -:101190002851000834510008465100080860FFF744 -:1011A0006451000881510008AA5100082DE9F04F50 -:1011B000ADB006AF80460C4601F0A8FE05460028FB -:1011C0005AD1237E022B1BD1E38A012B18D101F0C7 -:1011D00011FC0646FFF78EFD03464FF4C870DFF89A -:1011E000D092B3FBF0F206F5167602FB103316FA36 -:1011F00083F3C9F80030E37E33B9A84B00221A709C -:101200009C37BD46BDE8F08FA38AEEB2013BB342E6 -:1012100005F101050BD93B1D1E44E9000096002392 -:10122000082201F0F801204601F086FFECE707F103 -:101230001400FFF777FD324607F11401381D03F063 -:101240001FFE0028D9D10F2E08D8944B1E70D9F854 -:101250000030A3F51673C9F80030D1E7FB1CF87015 -:101260000146009307220346204601F065FFF97806 -:10127000404601F043FEC3E7E38A282B26D010D86E -:10128000012B1ED0052BBBD1BFF34F8F8449854B5B -:10129000CA6802F4E0621343CB60BFF34F8F00BF14 -:1012A000FDE7302BACD1637E7F4D01336A7BDBB22F -:1012B0009342E94603D1E27E2B7B9A4265D0CD462C -:1012C0009EE721464046FFF707FE99E7A38A013BC8 -:1012D0009BB2C92B94D8744D2E7B26BB05F10C0311 -:1012E0000093082233463146204601F025FF731C47 -:1012F000F2B2D9001E46A38A013B9A4205DA0E32A9 -:101300002A44009200230822EEE700230022C5E9C8 -:1013100000230023AB6085F8D730C5F8D8302B7B8D -:101320000BB9E37E2B73002507F114093B1D08223E -:1013300029464846C7E90155FD6002F039F83B7A75 -:1013400005F1010AAB424FEACA0608D9FB68082238 -:101350002B443146484602F02BF85546EFE7C6F3DA -:10136000CF06E17ECDE9049600230393A37E02938A -:10137000193428230093019446A3D3E9002340465F -:1013800001F02EFEFFF7DEFC3AE74FF0000807F110 -:101390001403A7F81480102200934146012320462D -:1013A00001F0CAFEA68A023EB6B2F31C9B109B0057 -:1013B0000733DB08A9EBC3039D460DF1180A1FFA9A -:1013C00088F34FEAC801B34201F110010AD20AEBD7 -:1013D0000803009308220023204601F0ADFE08F127 -:1013E0000108ECE795F8D70000F0B2FAD5F8D8304C -:1013F00004461BB995F8D70000F0BAFAD5F8D830F2 -:1014000033449C4204D295F8D700013000F0B0FA82 -:101410004FEA960B4FF000081FFA88F18B45D5E98B -:10142000003209D90AEB880103EB8800012200F0A1 -:1014300027FB08F10108EFE7F31842F10002C5E9C4 -:101440000032D5F8D83095F8D70006EB0308C5F878 -:10145000D88000F07DFA804509D395F8D730D5F8CB -:10146000D8000133001B85F8D730C5F8D800FF2E0F -:1014700008D800232B7300F097FAFFF717FE08B186 -:10148000FFF75CF92B68094A9B0A0133138100239B -:10149000AB6014E726417272DF25D7B7C522002062 -:1014A00000ED00E00400FA05C8330020B41200206B -:1014B000C822002010B54FF000540C4B22689A420D -:1014C00011D10B4B627D1A700A48237D03730A49C0 -:1014D000C9220E3000F0BAFAE0220021204600F0C6 -:1014E000C7FA012010BD0020FCE700BF9AAD44C53B -:1014F000C0120020C83300201600002037B5184D58 -:1015000018491948022301226B7100F03DFF0023A6 -:101510000193164B164900931648174B4FF480520F -:1015200001F0C6FC154B197811B1124801F0E6FC28 -:1015300001F060FA0446FFF7DDFB4FF4C873B0FB1F -:10154000F3F202FB130304F5167010FA83F00C4B50 -:10155000186003F05BF908B10F232B8103B030BD95 -:10156000B412002040420F00F8220020E10D0008D4 -:10157000C4120020CC220020AD110008C0120020AF -:10158000C82200202DE9F04F2DED028B0FF26429C7 -:10159000D9E900898D4C93B08D4E8E4F204601F0D5 -:1015A00083FD034660B30025CDE90F550E95ADF8D8 -:1015B0004450027B8DF8442099684068DFF83CA2D3 -:1015C0000FAA03C21B6843F000430E9301F014FA04 -:1015D000821941F1000300950EA9384600F002FB84 -:1015E000A84205DD204601F063FD8AF80050D5E7EA -:1015F0009AF80030072B00F2B68001338AF80030E9 -:101600000BAE9FED6E8B0023724FDFF8F4A10A93AF -:10161000ADF834300B9373604FF0000B5B468DEDEB -:10162000008B01250DF11D0207A938468DF81C50CD -:101630008DF81DB000F058FE9DF81C30002B40F0D6 -:101640009680204601F062FC0646002845D1624F94 -:1016500001F0D0F93B6898423FD301F0CBF98246C4 -:10166000FFF748FB4FF4C8730AF5167AB0FBF3F2A4 -:1016700002FB13031AFA83F33B60584F97F800B04C -:10168000CBF1100ABBF1000F14BF33462B465FFAB3 -:101690008AFA0EA88DF82830FFF744FBBAF1060F3E -:1016A00028BF4FF0060A0EAB03EB0B0152460DF1BB -:1016B000290000F0CBF90AAB0393182302930AF137 -:1016C0000102474BD2B2CDE90053049220463DA31C -:1016D000D3E9002301F01CFC3E7001F08BF9414A74 -:1016E000414D1368C31AB3F57A7F2FD3106001F010 -:1016F00083F902460B46204601F0E4FC204601F047 -:1017000005FC18B32B7B394E002B14BF0323022397 -:10171000737101F06FF90EAF4FF47A733946B0FB75 -:10172000F3F030603046FFF79FFB18230730029339 -:101730002F4B0193C0F3CF0040F25513CDE9037056 -:10174000009342464B46204601F0E2FB2B7B2BB137 -:10175000FFF7F8FA2B7B002B7FF41EAF13B0BDEC24 -:10176000028BBDE8F08F204601F0A2FC48E7DAF8D2 -:10177000143083F00803CAF81430594610220EA81A -:1017800000F076F90DF11E0308AA0AA9384600F008 -:1017900027FB96E803000FAB83E803009DF8343085 -:1017A0008DF844300A9B0E930EA9DDE908232046EC -:1017B00001F046FE30E700BFAFF3008000000000FC -:1017C00000000000401DA12026812A0BCC22002011 -:1017D00040420F00F8220020C8220020C52200202D -:1017E000C4220020A8340020C8330020B4120020F6 -:1017F000AC340020F1C6A7C1D068080FAD3400207A -:101800000004004808B5054800F084FBBDE8084026 -:10181000034A0449002003F0EBBA00BFF82200207D -:1018200000350020691000082DE9F84F4FF47A7355 -:10183000DFF85880DFF8589006460D4602FB03F7A4 -:10184000002498F900305A1C5FFA84FA01D0A342B0 -:1018500010D159F8240003682A46D3F820B0314645 -:101860003B46D847854205D1074B012083F800A0AD -:10187000BDE8F88F0134032CE3D14FF4FA7002F085 -:10188000CDFC0020F4E700BFF43400201811002044 -:10189000D051000807B50023024601210DF10700D1 -:1018A0008DF80730FFF7C0FF20B19DF8070003B0A7 -:1018B0005DF804FB4FF0FF30F9E700000A4608B579 -:1018C0000421FFF7B1FF80F00100C0B2404208BD23 -:1018D00030B4074B0A461978064B53F82140236869 -:1018E000DD69054B0146AC46204630BC604700BF71 -:1018F000F4340020D0510008A086010070B502F039 -:10190000CBFD094E094D308000242868338883427E -:1019100008D902F0BDFD2B6804440133B4F5204F13 -:101920002B60F2D370BD00BFF6340020B03400202D -:1019300002F072BE00F1006000F5204000687047C0 -:1019400000F10060920000F5204002F0E9BD0000C7 -:10195000054B1A68054B1B889B1A834202D9104419 -:1019600002F096BD00207047B0340020F63400200D -:1019700038B5074D04462868204402F08FFD28B989 -:1019800028682044BDE8384002F09ABD38BD00BF49 -:10199000B03400200020704700F10050A0F5104046 -:1019A000D0F8900570470000064991F8243033B113 -:1019B0000023086A81F824300822FFF7C1BF012004 -:1019C000704700BFB4340020014B1868704700BF57 -:1019D000002004E070B50E4B5C6893F90860421E6D -:1019E0000A44013C0B46934207D214F9015F581C8C -:1019F0002DB100F8015C0346F5E7184605E02C24FC -:101A000082421C7001D9981C5E70401A70BD00BFE4 -:101A10001C110020022802BF024B4FF400229A61E1 -:101A2000704700BF00040048022802BF014B082293 -:101A30009A61704700040048022801BF024A5369B6 -:101A400083F00803536170470004004810B5002379 -:101A5000934203D0CC5CC4540133F9E710BD0000BD -:101A600003460246D01A12F9011B0029FAD1704729 -:101A700002440346934202D003F8011BFAE7704781 -:101A80002DE9F8431F4D144695F824200746884653 -:101A900052BBDFF870909CB395F824302BB920220C -:101AA000FF2148462F62FFF7E3FF95F82400C0F1BD -:101AB0000802A24228BF2246D6B24146920005EB58 -:101AC0008000FFF7C3FF95F82430A41B1E44F6B234 -:101AD000082E17449044E4B285F82460DBD1FFF768 -:101AE00063FF0028D7D108E02B6A03EB820383420F -:101AF000CFD0FFF759FF0028CBD10020BDE8F883F5 -:101B00000120FBE7B4340020024B1A78024B1A7014 -:101B1000704700BFF43400201811002008B50849B0 -:101B200008484FF461430B6002F012FA044906487A -:101B300002F00EFABDE808400149044802F008BA74 -:101B4000DC3400200435002070350020DC35002016 -:101B5000094B10B51822044600211846FFF788FFEC -:101B6000064A074B127804600146BDE8104053F85E -:101B7000220002F0EDB900BFDC340020F434002074 -:101B8000D0510008202383F3118862B6704700000B -:101B9000002383F3118862B67047000010B4026816 -:101BA00054681A4623465DF8044B184701207047D5 -:101BB0000020704700207047704700007047000009 -:101BC000002070470E20704700F5805090F8C80044 -:101BD000C0F340007047000000F5805090F9C90044 -:101BE000704700002DE9F0410C68BDF8187014F042 -:101BF00000541E466FD10B7B082B6CD8FFF7C2FF39 -:101C00004569AB685B010CD4AB681B0108D4AC68B8 -:101C100014F080545DD1FFF7BBFF2046BDE8F08192 -:101C200001240B6804F1180C002BB8BFDB004FEA4D -:101C30000C1CB4BF43F004035B0545F80C300B6883 -:101C40000FFA84FC13F0804F18BF05EB0C1E05EB58 -:101C50000C1C1EBFDEF8803143F00203CEF8803149 -:101C60000B7BCCF8843105EB04158B68C5F88C31FF -:101C70004B68C5F88831DCF8803143F00103CCF8BB -:101C8000803100EB441541F268031D4403EB44131B -:101C90000344C5E9002608330D4601F10C0C55F844 -:101CA00004EB43F804EB6545F9D184342D881D809D -:101CB00000EB441407F00303257925F00B052B43B3 -:101CC0002371FFF765FF06973346BDE8F04100F04A -:101CD000AFBC0224A5E74FF0FF309FE713B500F536 -:101CE00080540191E06D00F039FD1F280AD9019957 -:101CF000E06D202200F0A8FDA0F1200358425841D9 -:101D000002B010BD0020FBE708B500F58050FFF7DA -:101D100039FFC06D00F0F6FCBDE80840FFF738BFA2 -:101D200000220260828142608260704710B500220A -:101D30000023C0E900230023044603810C30FFF791 -:101D4000EFFF204610BD0000F0B5054600F58050BD -:101D50000C4690F8C83013F0040FC3F3800108BF9D -:101D6000114661F3820304F1840680F8C83005EB64 -:101D7000461389B01B79D8072ED57AB319072DD40D -:101D80006846FFF7D3FF05EB441303F5835303F1D4 -:101D9000180703AA103318685968144603C4083397 -:101DA000BB422246F7D1186820609B88A380DDE9FA -:101DB0000E23CDE900230123ADF808302B686946D6 -:101DC0001B6C2846984705EB46152B791A075CBF14 -:101DD00043F008032B7101E0002AF4D109B0F0BDF3 -:101DE0002DE9F047074688B007F5805468469A46C3 -:101DF0008846FFF7C7FE9146FFF798FFE06D00F0B9 -:101E000093FC1F2829D9E06D2022694600F09EFD31 -:101E1000202822D103AD444605AB2E4603CE9E4278 -:101E200020606160354604F10804F6D13068206016 -:101E3000B388A380DDE90023C9E90023BDF8083099 -:101E4000AAF80030FFF7A4FE4A46534641463846FA -:101E500008B0BDE8F04700F0D9BBFFF799FE0020BD -:101E600008B0BDE8F08700002DE9F84F0023C0E975 -:101E70000133254B044640F8183B0F46FFF750FF4F -:101E800004F12800FFF752FF04F1480804F58255D9 -:101E90004646083530462036FFF748FFAE42F9D1B6 -:101EA00004F580554FF480534FF00009C5E913390C -:101EB000C5F848800123EE6504F5875804F584567B -:101EC000C5F8549085F8583085F86030083608F128 -:101ED00008084FF0000A4FF0000B46E908ABA6F1E6 -:101EE0001800FFF71DFF203646F8289C4645F4D120 -:101EF00085F8C97017B1054800F076FD044B6361A1 -:101F00002046BDE8F88F00BF04520008DC510008ED -:101F10000064004010B5044B197804464A1C1A703E -:101F2000FFF7A2FF204610BDFC3400202DE9F0474A -:101F3000002950D0294B2A4FB7FBF1F599428CBFAD -:101F40000A231123581EB5FBF3FC03FB1C53C4B238 -:101F50002BB102280346F5D80020BDE8F0870CF12C -:101F6000FF36B6F5806FF7D2C4EBC40E0EF1030353 -:101F70004FEAE309C3F3C703A4EB030809F1010A1D -:101F80004FF47A755FFA88F009FB05555AFA88F81C -:101F9000B5FBF8F5B5F5617FC1BF0EF1FF33C3F3B3 -:101FA000C703E01AC0B25C1C50FA84F40CFB04F4C2 -:101FB000B7FBF4F4A142CFD1013BDBB20F2BCBD85E -:101FC0000138C0B20728C7D800211071168091705F -:101FD000D3700120C1E70846BFE700BF3F420F00B2 -:101FE00000B4C40470B505460E464FF47A746B69AC -:101FF0005B6803F00103B34207D04FF47A7002F03C -:102000000DF9013CF3D1204670BD0120FCE7000032 -:1020100030B54269936913F0700F16D000230B4C52 -:10202000936103F1840200EB421211794D0709D547 -:10203000890707D5416954F823508D60117941F023 -:10204000040111710133032BEBD130BDF0510008B5 -:1020500073B51D46436916469A68D207044609D5EA -:102060009A6801219960C2F34002CDE90065002120 -:10207000FFF76AFE63699A68D1050BD59A684FF439 -:1020800080719960C2F34022CDE9006501212046AC -:10209000FFF75AFE63699A68D2030BD59A684FF42A -:1020A00080319960C2F34042CDE9006502212046AB -:1020B000FFF74AFE204602B0BDE87040FFF7A8BF18 -:1020C000F8B50446466900296CD106F10C0738685A -:1020D00080076AD006EB01153868D5F8B00110F01A -:1020E000040FD5F8B0011ABFC00840F00040400D01 -:1020F000A061D5F8B0C11CF0020F1CBF40F08040B9 -:10210000A061D5F8B40106EB011100F00F0084F8CE -:102110002400D1F8B8012077D1F8B801000A60771F -:10212000D1F8B801000CA077D1F8B801000EE07723 -:10213000D1F8BC0184F82000D1F8BC01000A84F871 -:102140002100D1F8BC01000C84F82200D1F8BC11A8 -:10215000090E84F823103821396004F1340004F1A9 -:10216000180104F1240551F8046B40F8046BA942EE -:10217000F9D109880180C4E90A2321460023238676 -:1021800051F8283B20461B6C984704F580522046A6 -:1021900092F8C83043F0040382F8C830BDE8F84034 -:1021A000FFF736BF06F1100791E7F8BD10B50446FA -:1021B00000F022FC02460B4652EA030102D0013A2B -:1021C00063F100030449086820B12146BDE81040CE -:1021D000FFF776BF10BD00BFF8340020F8B500F55A -:1021E00083511E46FFF7CEFCDFF844C008310024BF -:1021F00004F1840500EB45152B795F070ED4DB064F -:102200000CD5D1E900739742B34107D243695CF81A -:1022100024709F602B7943F004032B710134032C4D -:1022200001F12001E4D1BDE8F840FFF7B1BC00BFE7 -:10223000F051000808B5FFF7A5FCFFF7E9FEBDE87F -:102240000840FFF7A5BC0000F8B54369054698684B -:1022500000F0E050B0F1E05F0F461FD0E8B1FFF7AB -:1022600091FC05F583541034002606F1840305EB38 -:1022700043131B791A0706D50136032E04F12004F7 -:10228000F3D1012007E05B07F6D42146384600F081 -:1022900009FA0028F0D1FFF77BFCF8BD0120FCE72C -:1022A00000F5805008B5FFF76DFCC06D00F03CFAFA -:1022B000FFF76EFC43090CBF0120002008BD0000A1 -:1022C000F8B51D46002313700F4606461446FFF767 -:1022D000E7FF80F00100387025B129463046FFF74E -:1022E000B3FF2070F8BD00002DE9B8410C4615463B -:1022F0001F46804600F080FB0B462178024609B954 -:10230000287850B14046FFF769FFFFF793FF3B463F -:102310002A462146FFF7D4FF0120BDE8B88100001E -:1023200010B5FFF72FFC174B9A6D42F000729A65BB -:102330009A6B42F000729A639A6B00F5805422F017 -:1023400000729A63FFF724FC94F8C830DB0718D4B6 -:10235000B9B102211320FFF715FC01F047FC02215F -:10236000142001F043FC0221152001F03FFC94F8F9 -:10237000C83043F0010384F8C830BDE81040FFF7CF -:1023800007BC10BD001002402DE9F04700F5805554 -:1023900088B095F8C930012B04468846164600F2ED -:1023A000FB807E4F57F823200AB947F82300D7F85F -:1023B00000A0C4F80C802674BAF1000F09D141F2D4 -:1023C000D00002F01DFD51468146FFF74DFDC7F8D4 -:1023D000009095F8C930012B5DD001212046FFF710 -:1023E0009FFFFFF7CFFB6269136823F002031360BE -:1023F0006269136843F001031360636900275F613A -:1024000001212046FFF7C4FBFFF7ECFD002800F098 -:102410008480E86D00F076F904F58359BA4609F135 -:102420000809202200216846FFF722FB02A8FFF7D7 -:1024300077FCCDF818A06A4609EB07030DF1180EDA -:102440009446BCE80300F44518605960624603F105 -:102450000803F5D1DCF80000186020379CF8042050 -:102460001A71602FDDD195F8C8306FF38203002711 -:1024700085F8C8306A4641462046ADF80070ADF890 -:1024800002708DF80470FFF751FD6369C0B94FF415 -:1024900000421A6011E0386803685B6B9847014698 -:1024A00000289AD13868FFF73BFF38680368324646 -:1024B0005B684146984700288FD108B0BDE8F08797 -:1024C00061221A609DF802309DF803201B06120459 -:1024D00002F4702203F040731343BDF80020C2F3EE -:1024E000090213439DF804201205022E02F4E002B3 -:1024F0000CBF4FF000410021134362690B43D361CD -:10250000636913225A616269136823F0010313603F -:1025100039462046FFF766FD08B96369B7E795F8C5 -:10252000C93093BB6169D1F8002242F00102C1F8C1 -:1025300000226169D1F8002222F47C5222F00E02BE -:10254000C1F800226169D1F8002242F46062C1F84A -:1025500000226269C2F814326269C2F80432626908 -:1025600041F6FF71C2F80C126269C2F8403262692A -:10257000C2F8443263690122C3F81C226269D2F8AE -:10258000003223F00103C2F8003295F8C83043F05E -:10259000020385F8C83090E700208EE7F834002069 -:1025A00008B500F029FA50EA0103024602D0421EA3 -:1025B00061F10001044B186810B10B46FFF748FDAC -:1025C000BDE8084001F06CB9F834002008B50020DF -:1025D000FFF7ECFDBDE8084001F062B908B5012045 -:1025E000FFF7E4FDBDE8084001F05AB90FB4002040 -:1025F00004B0704713B56C4684E80600031D94E8E8 -:10260000030083E80500012002B010BD73B58568A2 -:10261000019155B11B885B0707D4D0E90036DB6B0D -:102620009847019AC1B23046A847012002B070BD58 -:10263000F0B5866889B005460C465EB1BDF8383005 -:102640005B070AD4D0E90037DB6B98472246C1B25A -:102650003846B047012009B0F0BD00220023CDE983 -:1026600000230023ADF808300A4603AB01F1080649 -:10267000106851681C4603C40832B2422346F7D1A1 -:10268000106820609288A28000F0B8F90423ADF8A9 -:1026900008302B68CDE900011B6C69462846984735 -:1026A000D8E7000030B503680968DD0FB5EBD17FCE -:1026B00023F0604421F060424FEAD1700BD0002B30 -:1026C000B8BFA40C0029B8BF920C944202D034BF0A -:1026D0000120002030BD944205D1C1F38070C3F3C6 -:1026E00080738342F6D194422CBF00200120F1E791 -:1026F00010B5037C044613B9006802F0B9FB20460C -:1027000010BD00000023BFF35B8FC360BFF35B8F7E -:10271000BFF35B8F8360BFF35B8F7047BFF35B8F4B -:102720000068BFF35B8F704770B505460C30FFF74C -:10273000F5FF05F1080604463046FFF7EFFFA0421B -:1027400006D930466D68FFF7E9FF2544281A70BDA9 -:102750003046FFF7E3FF201AF9E7000070B50546A1 -:10276000406898B105F10800FFF7D8FF05F10C06A5 -:1027700004463046FFF7D2FF8442304694BF6D686E -:102780000025FFF7CBFF013C2C44201A70BD000050 -:1027900038B50C460546FFF7C7FFA04210D305F138 -:1027A0000800FFF7BBFF04446868B4FBF0F100FBCE -:1027B0001144BFF35B8F0120AC60BFF35B8F38BD6A -:1027C0000020FCE72DE9F041144607460D46FFF7CF -:1027D000C5FF844228BF0446D4B1B84658F80C6BF4 -:1027E0004046FFF79BFF3044286040467E68FFF775 -:1027F00095FF331A9C4203D86C600120BDE8F0813C -:102800006B60A41B3B68AB602044E8600220F5E7E6 -:102810002046F3E738B50C460546FFF79FFFA04278 -:1028200010D305F10C00FFF779FF04446868B4FB8E -:10283000F0F100FB1144BFF35B8F0120EC60BFF3AC -:102840005B8F38BD0020FCE72DE9FF4188466946D3 -:102850000746FFF7B7FF6C4606B204EBC606002535 -:10286000B44209D06268206808EB0501FFF7EEF872 -:10287000636808341D44F3E729463846FFF7CAFF6A -:10288000284604B0BDE8F081F8B505460C300F4687 -:10289000FFF744FF05F1080604463046FFF73EFF08 -:1028A000A042304688BF6C68FFF738FF201A3860B6 -:1028B00020B130462C68FFF731FF2044F8BD0000FE -:1028C00073B5144606460D46FFF72EFF844228BF17 -:1028D00004460190DCB101A93046FFF7D5FF019B0A -:1028E00033B93268C5E90233C5E9002401200CE0A0 -:1028F0009C4238BF01942860019868608442F5D9F1 -:102900003368AB60241AEC60022002B070BD204630 -:10291000FBE700002DE9FF410F466946FFF7D0FFB6 -:102920006C4600B204EBC0050026AC4209D0D4F8D6 -:10293000048054F8081BB8194246FFF787F846444C -:10294000F3E7304604B0BDE8F081000038B5054635 -:10295000FFF7E0FF044601462846FFF719FF20462F -:1029600038BD000000B59BB0EFF3098168226846CE -:10297000FFF76CF8EFF30583044B9A6BDA6A9A6AF7 -:102980009A6A9A6A9A6A9A6A9B6AFEE700ED00E080 -:1029900000B59BB0EFF3098168226846FFF756F84F -:1029A000EFF30583044B9A6B9A6A9A6A9A6A9A6A59 -:1029B0009A6A9B6AFEE700BF00ED00E000B59BB09D -:1029C000EFF3098168226846FFF740F8EFF30583CB -:1029D000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE7EA -:1029E00000ED00E0FEE700000FB408B5029801F02A -:1029F000AFFBFEE701F050BE01F028BE01F026BE9D -:102A000030B5094D0A4491420DD011F8013B5840B0 -:102A1000082340F30004013B2C4013F0FF0384EA39 -:102A20005000F6D1EFE730BD2083B8ED2DE9F0413D -:102A3000C56915B9C161BDE8F0814B6823F06047F5 -:102A4000C3F38A464FEAD37EC3F3807816EA23069F -:102A500038BF3E46AC462B465A68BEEBD27F22F0CA -:102A600060440AD0002A18DAA40CB44217D19D425F -:102A70000FD10D60DEE71346EEE7A74207D102F063 -:102A80008044C2F3807242450BD054B1EFE708D2C4 -:102A9000EDE7CCF800100B60CDE7B44201D0B442B2 -:102AA000E5D81A689C46002AE5D11960C3E7000002 -:102AB0002DE9F047089D01F007044FEAD5082244AC -:102AC00005F0070500EBD1004FF47F49944201D196 -:102AD000BDE8F08704F0070705F0070A57453E46B2 -:102AE00038BF5646C6F10806111B8E4228BF0E4657 -:102AF000E10808EBD50E415C13F80EC0B94029FA85 -:102B000006F721FA0AF1FFB28CEA010147FA0AF747 -:102B100039408CEA010C03F80EC034443544D5E743 -:102B200080EA0120082341F2210201B2400000297D -:102B300080B203F1FF33B8BF504013F0FF03F4D16C -:102B40007047000038B50C468D18A54200D138BD3D -:102B500014F8011BFFF7E4FFF7E7000002684AB131 -:102B600013680360C388018901339BB29942C38013 -:102B700038BF03811046704770B588B020220446E4 -:102B80000D4668460021FEF773FF20460495FFF7C7 -:102B9000E5FF024658B16B46054608AE1C4603CC1D -:102BA000B44228606960234605F10805F6D1104655 -:102BB00008B070BD082817D909280CD00A280CD0F5 -:102BC0000B280CD00C280CD00D280CD00E2814BFCC -:102BD0004020302070470C20704710207047142090 -:102BE000704718207047202070470000082817D928 -:102BF0000C280CD910280CD914280CD918280CD959 -:102C000020280CD930288CBF0F200E2070470920B7 -:102C100070470A2070470B2070470C2070470D202A -:102C20007047000010B54B6823B9CA8A63F30902E4 -:102C3000CA8210BDC4681A681C60C360438A013B25 -:102C400043824A60EFE700002DE9F84F1D46CB8A2A -:102C50000F46C3F309010629814692460B4630D040 -:102C60000020AAB207F119049EB2052E1FFA80F8BF -:102C70000FD8904503F1010306D3FB8A0A4462F39F -:102C80000903FB8201201AE01AF80060E6540130C3 -:102C9000EAE79045F1D2A1F1060B1C237C68BBFB4F -:102CA000F3F203FB12BB1FFA8BF6002C45D148460A -:102CB000FFF754FF044638B978606FF00200BDE8B2 -:102CC000F88F4FF00008E6E7002606607860ADB2A6 -:102CD0004FF0000B454510D90AEB0803221D13F8ED -:102CE000011B9155B1B208F101081B291FFA88F8A0 -:102CF0002BD0454506F10106F1D8FB8AC3F3090242 -:102D0000154465F30903BCE7013292B21C462368FF -:102D1000002BF9D1AB1F0B441C21B3FBF1F30133A2 -:102D20009BB29A42D3D2BBF1000FD0D14846FFF7F5 -:102D300015FF20B9C4F800B0BFE70122E7E7C0F8EB -:102D400000B05E4620600446C1E74545D5D94846F7 -:102D5000FFF704FF08B92060AFE7C0F800B0002615 -:102D600020600446B6E700002DE9F04F2DED028B00 -:102D700083B0CDE90013BDF83C5007469146002AC8 -:102D800000F092802DB10E9B002B00F08D80072D5E -:102D900032D807F10C00FFF7E1FE044638B96FF0B6 -:102DA0000204204603B0BDEC028BBDE8F08F142274 -:102DB0000021FEF75DFE0E992A4604F10800FEF799 -:102DC00045FE681CC0B2FFF711FFFFF7F3FE207449 -:102DD00099F80030013814FA80F003F01F0363F013 -:102DE0003F030372009B43F0004161603846214677 -:102DF000FFF71CFE0124D4E700F10C034FF000089C -:102E000008EE103A4FF0800A4646444618EE100A83 -:102E1000FFF7A4FE83460028C1D014220021FEF74C -:102E200027FEC6BB019BABF8083002200E9B00F1C9 -:102E3000080299195BFA82F20130C0B2082801D069 -:102E4000AE422AD3FFF7D2FEFFF7B4FE99F8002076 -:102E5000009B411E02F01F0242EA4812AE4208BF28 -:102E60004FF0400A5BFA81F14AEA020A43F000425D -:102E700081F808A08BF81000CBF80420594638469A -:102E8000FFF7D4FD0134AE4224B288F001084FF0C0 -:102E9000000ABBD185E70020C8E711F801CB02F892 -:102EA00001CB0136B6B2C7E76FF0010479E7000045 -:102EB000F8B515460E462822002104461F46FEF7A7 -:102EC000D7FD069B6360B5F5001F079BA76034BF65 -:102ED0006A094FF6FF72236204F10C0097B20023D7 -:102EE0009A4205D80023036027826382A382F8BD3B -:102EF0000660013330462036F2E7000003781BB944 -:102F00004BB2002BC8BF01707047000000787047BB -:102F10002DE9F74FDDF83C90BDF830500D9E9DF83F -:102F20003840BDF84070804692469B46B9F1000F8C -:102F300001D1002F51D11F2C4FD898F80000B0B903 -:102F4000072F47D835F0030347D13A4649464FF695 -:102F5000FF70FFF7F7FD20F001002D02400445EA65 -:102F60000464400C44EA40244FF6FF7321E040EA39 -:102F70000520072F40EA0464F6D900254FF6FF73B9 -:102F8000C5F12000A5F120022AFA05F10BFA00F0A4 -:102F900001432BFA02F211431846C9B2FFF7C0FDF4 -:102FA0000835402D0346EBD13A464946FFF7CAFDA6 -:102FB0000346CDE90097324621464046FFF7D4FE4E -:102FC00033780133DBB21F2B88BF0023337003B08B -:102FD000BDE8F08F6FF00300F9E76FF00100F6E74E -:102FE0002DE9F04F85B09246DDF848800F9D9DF8A1 -:102FF00040209DF84490BDF84C7006469B46B8F1C1 -:10300000000F01D1002F48D11F2A46D83378002B5A -:1030100046D00C0244EA02649DF8381044EAC934F0 -:1030200044EA01441C43072F44F0800432D90023B2 -:103030004FF6FF72C3F1200CA3F120002AFA03F12E -:103040000BFA0CFC41EA0C012BFA00F00143C9B267 -:1030500010460393FFF764FD039B0833402B0246A1 -:10306000E8D13A464146FFF76DFD0346CDE90087BA -:103070002A4621463046FFF777FEB9F1010F06D107 -:103080002B780133DBB21F2B88BF00232B7005B0D8 -:10309000BDE8F08F4FF6FF73E8E76FF00100F6E749 -:1030A0006FF00300F3E70000C06900B1043070471F -:1030B000C3691A68C261C2681A60C360438A013B6F -:1030C000438270472DE9F041D0F81880194E14461C -:1030D0001D464146002709B9BDE8F081D1E9022328 -:1030E000A21A65EB0303964277EB03031ED28369B2 -:1030F0008B420DD1FFF796FD83691B688361C3681E -:103100000B60438AC1608169013B43828846E2E7E4 -:10311000FFF788FD0B68C8F80030C3680B60438A6E -:10312000C160013B4382D8F80010D4E788460968A3 -:10313000D1E700BF80841E002DE9F04F8BB00D4613 -:10314000DDF8509014469B468046002800F0198117 -:10315000B9F1000F00F01581531E3F2B00F21181D1 -:10316000012A03D1BBF1000F40F00B810023CDE910 -:103170000833B8F81430B5EBC30F4FEAC30703D3D5 -:1031800000200BB0BDE8F08F2B199F42D8F80C300F -:103190003ABF7F1BFFB227461BB9D8F81030002B6F -:1031A0007AD02F2D4ED8C5F13006B7424FF000032C -:1031B0002CBFF6B23E4600932946D8F8080008AB6B -:1031C0003246FFF775FCA7EB060A35445FFA8AFA28 -:1031D000B8F8143003F10053063BDB000493D8F831 -:1031E0000C3003933021039B13B1BAF1000F2CD1A3 -:1031F000D8F8100040B1BAF1000F05D0009608AB26 -:103200005246691AFFF754FC38B2002FB8D066074F -:103210000AD00AAB03EBD401624211F8083C02F079 -:103220000702134101F8083C082C3CD9102C40F24D -:10323000B580202C40F2B780BBF1000F00F09C80DD -:10324000082334E0BA460026C2E7049BE02B28BFDF -:10325000E02306930B44AB42059314D95A1B039801 -:103260000096924534BF5246D2B2691A08AB043078 -:103270000792FFF71DFC079A1644AAEB020A1544B1 -:10328000F6B25FFA8AFA049B069A05999B1A049390 -:10329000039B1B680393A6E70093D8F8080008ABCC -:1032A0003A462946AEE7BBF1000F13D00123B4EB39 -:1032B000C30F6CD0082C12D89DF82030621E23FA60 -:1032C00002F2D50706D54FF0FF3202FA04F4234389 -:1032D0008DF820309DF8203089F8003051E7102C0F -:1032E00012D8BDF82030621E23FA02F2D10706D5AB -:1032F0004FF0FF3202FA04F42343ADF82030BDF85A -:103300002030A9F800303CE7202C0FD80899631E24 -:1033100021FA03F3DA0705D54FF0FF3202FA04F47D -:103320000C430894089BC9F800302AE7402C2BD0A6 -:10333000DDE90865611EC4F12102A4F1210326FA2A -:1033400001F105FA02F225FA03F311431943CB0701 -:1033500012D50122A4F12003C4F1200102FA03F3E3 -:1033600022FA01F1A240524243EA010363EB430314 -:1033700032432B43CDE90823DDE90823C9E90023C3 -:10338000FFE66FF00100FCE66FF00800F9E6082C9C -:10339000A0D9102CB3D9202CEED8C3E7BBF1000F75 -:1033A000ADD0022383E7BBF1000FBBD004237EE73F -:1033B00030B5012A144638BF0124402C85B028BFFF -:1033C00040240025012ACDE9025518D81B788DF834 -:1033D000083063070AD004AB03EBD405624215F84A -:1033E000083C02F00702934005F8083C00910346B0 -:1033F0002246002102A8FFF75BFB05B030BD082A7A -:10340000E4D9102A03D81B88ADF80830E1E7202A58 -:103410008DBFD3E900231B680293CDE90223D8E7CF -:1034200010B5CB681BB98B600B618B8210BDC46873 -:103430001A681C60C360438A013B4382CA60F0E79C -:103440002DE9F04FD1F8008093B018F0800FCDE94E -:103450000323C8F3C01219BFC8F3C03BC8F3062644 -:103460004FF0020B1646B8F1000F04460D4680F2ED -:10347000D18118F0C043059340F0CC810B7B002B29 -:1034800000F0C881BBF1020F03D00178B14240F0D7 -:10349000C48108F07F0106916AB3C8F3074A2B4440 -:1034A000069A93F80390760646EA0B4646EA824669 -:1034B0005FEAD91346EA0A06079300F090800022DB -:1034C0000023CDE90A23069B009367685B465246BA -:1034D0000AA92046B84700287ED0A7699FB931467F -:1034E00004F10C00FFF748FB0746E0B96FF002005B -:1034F00013B0BDE8F08FC8F30F2A18F07F0F08BF94 -:103500000AF0030ACBE73B699E420DD03F68002FCB -:10351000F9D1314604F10C00FFF72EFB07460028D5 -:10352000E4D0A3693B60A761DDE90A2300264FF6DA -:10353000FF70C6F1200E22FA06F103FA0EFEA6F184 -:10354000200C23FA0CFC41EA0E0141EA0C01C9B23D -:10355000083609920893FFF7E3FA402EDDE90832B6 -:10356000E7D1B882FB7D09F01F06C3F384039B1BE0 -:10357000D7E9022198B2002BBCBF00F120031BB297 -:1035800052EA0100C8F304680FD00398821A049825 -:1035900060EB0101A74890424FF000028A4104D33A -:1035A000079A002A5BD0012B23DDFA7D4FEA8903BD -:1035B00002F0030203F07C031343FB7539462046F7 -:1035C000FFF730FB079BA3B9FB7DC3F384020132F5 -:1035D00062F38603FB7504E06FF00B0088E7A769D0 -:1035E00017B96FF00C0083E73B699E42BAD03F6881 -:1035F000F6E719F0400F32D0039BBB60049BFB60E1 -:10360000142200210DA8FEF733FA039B0A93049BB2 -:103610000B932B1D0C932B7BADF83EA0013BDBB233 -:10362000ADF83C30069B8DF8433094F824308DF88B -:1036300040B083F001038DF844308DF84160A368F9 -:103640008DF842800AA920469847FB7DC3F3840386 -:10365000013303F01F039B02FB82002048E7FB7D40 -:10366000C9F34012B2EBD31F40F0DA80C3F38403F6 -:10367000B34240F0D88007992B7B4FEA991200297A -:1036800034D0D20741D4032B40F2D080039BBB60DF -:10369000049BFB602B7BAE1D033BDBB232463946FD -:1036A00004F10C00FFF7D0FA00280DDA2046394665 -:1036B000FFF7B8FAFB7DC3F38403013303F01F0364 -:1036C0009B02FB82032013E7AB883B832A7B033AF0 -:1036D000B88AD2B23146FFF735FAFB7DB882DA43B9 -:1036E000C2F3C01262F3C713FB75B6E76AB92E1DA9 -:1036F000013BDBB23246394604F10C00FFF7A4FA75 -:103700000028D3DB2A7B013AE2E7F98AC1F30901F9 -:10371000013B0529DAB259D8281D002307F11A0CFC -:103720009A4208D910F801EB0CF801E0013101339D -:103730000629DBB2F4D103990A9104990B919342C3 -:1037400007F11A010C9138BF043379680D9134BF29 -:1037500055FA83F300230E93FB8AADF83EA0C3F322 -:1037600009031A44069B8DF8433094F82430ADF8D1 -:103770003C2083F001038DF8443000238DF840B0E5 -:103780008DF841608DF842807B602A7BB88A013ACF -:10379000291DFFF7D7F93B8BB882834203D1A36879 -:1037A0000AA92046984720460AA9FFF739FEFB7D63 -:1037B000B88AC3F38403013303F01F039B02FB8227 -:1037C0003B8B984214BF1120002091E67B68002BB0 -:1037D000B1D0062001E01C306346D3F800C0BCF134 -:1037E000000FF8D1091A081D05F1040C00EB0309BC -:1037F00005989DF8143001EB000EBEF11B0F9AD80E -:103800009A4298D91CF8013B09F8013B059B01330A -:103810000593EDE76FF009006AE66FF00A0067E6CE -:103820006FF00D0064E66FF00E0061E66FF00F00C0 -:103830005EE600BF80841E00EFF3098305494A6BF2 -:1038400022F001024A63683383F30988002383F37B -:103850001188704700EF00E0202080F3118862B6E5 -:103860000C4B0D4AD96821F4E0610904090C0A43A4 -:10387000DA60D3F8FC20094942F08072C3F8FC20DA -:103880000A6842F001020A601022DA7783F8220007 -:10389000704700BF00ED00E00003FA05001000E0F3 -:1038A00010B5202383F311880E4B5B6813F400637B -:1038B00014D0F1EE103AEFF30984683C4FF08073B6 -:1038C000E361094BDB6B236684F3098800F0F2FBAC -:1038D00010B1064BA36110BD054BFBE783F31188C4 -:1038E000F9E700BF00ED00E000EF00E00B06000884 -:1038F0000E060008026843681143016003B11847CF -:1039000070470000024A136843F0C0031360704719 -:1039100000380140024A136843F0C0031360704747 -:1039200000440040024A136843F0C003136070472C -:103930000048004037B5244C244D204600F0FCFAE6 -:10394000009404F1140022490023202200F0BEF963 -:1039500020490094202204F138001F4B00F038FA6F -:103960001E4BC4E917351E4C204600F0E5FA0094C2 -:1039700004F114001B490023202200F0A7F91A4982 -:103980000094202204F13800184B00F021FA184B63 -:10399000C4E91735174C204600F0CEFA04F11400A4 -:1039A000154900940023202200F090F9134B14498C -:1039B0000094202204F1380000F00AFA114BC4E907 -:1039C000173503B030BD00BF0435002000B4C40477 -:1039D00048360020A836002005390008003801408C -:1039E0007035002068360020C836002015390008E0 -:1039F00000440040DC3500208836002025390008CE -:103A0000E83600200048004030B5037C304C0029E7 -:103A100018BF0C46012B0FD12E4B984239D12E4B9B -:103A20001A6E42F480421A66D3F8802042F4804233 -:103A3000C3F88020D3F880302268036EC16D84669D -:103A400003EB5203B3FBF2F36268150442BF23F0A9 -:103A5000070503F0070343EA4503CB60A36843F07F -:103A600040034B60E36843F001038B6042F49673BC -:103A700043F001030B604FF0FF330B62510505D596 -:103A800012F010221FD0B2F1805F1ED080F8643097 -:103A900030BD124B98420BD0114B9842CCD10E4BFB -:103AA0009A6D42F480229A659A6F42F4802207E070 -:103AB000094B9A6D42F400329A659A6F42F40032D3 -:103AC0009A679B6FB8E77F23E0E73F23DEE700BFFD -:103AD00048520008043500200010024070350020D4 -:103AE000DC3500202DE9F047C66D3768F469346293 -:103AF0002107054618D014F0080118BF8021E207FD -:103B000048BF41F02001A30748BF41F040016007D2 -:103B100048BF41F48071202383F31188281DFFF7EB -:103B2000E9FE002383F31188E2050AD5202383F3FD -:103B300011884FF40071281DFFF7DCFE002383F38A -:103B400011884FF020094FF0000A14F0200838D1F6 -:103B50003B0616D54FF0200905F1380A200610D58E -:103B600089F31188504600F067F9002836DA0821F9 -:103B7000281DFFF7BFFE27F080033360002383F387 -:103B80001188790614D5620612D5202383F3118893 -:103B9000D5E913239A4208D12B6C33B11021281D8B -:103BA00027F04007FFF7A6FE3760002383F3118854 -:103BB000E30619D5AA6E1369B3B1BDE8F0475069A1 -:103BC000184789F31188B38C95F86410284619407A -:103BD00000F0CCF98AF31188F469B6E780B2308539 -:103BE00088F31188F469B9E7BDE8F08700F1604314 -:103BF00003F561430901C9B283F80013012200F003 -:103C00001F039A4043099B0003F1604303F561439E -:103C1000C3F880211A607047F8B5154682680669B6 -:103C2000AA420B46816938BF8568761AB5420446B8 -:103C30000BD218462A46FDF709FFA3692B44A3615E -:103C4000A3685B1BA3602846F8BD0CD91846324612 -:103C5000FDF7FCFEAF1BE1683A463044FDF7F6FE87 -:103C6000E3683B44EBE718462A46FDF7EFFEE368BE -:103C7000E5E7000083689342F7B51546044638BF70 -:103C80008568D0E90460361AB5420BD22A46FDF7A2 -:103C9000DDFE63692B446361A36828465B1BA36058 -:103CA00003B0F0BD0DD932460191FDF7CFFE019969 -:103CB000E068AF1B3A463144FDF7C8FEE3683B4479 -:103CC000E9E72A46FDF7C2FEE368E4E710B50A44D7 -:103CD0000024C361029B8460C0E90000C0E90511B3 -:103CE000C1600261036210BD08B5D0E9053293429C -:103CF00001D1826882B98268013282605A1C4261B5 -:103D00001970D0E904329A4224BFC368436100218C -:103D100000F0A0FA002008BD4FF0FF30FBE70000E4 -:103D200070B5202304460E4683F31188A568A5B11B -:103D3000A368A269013BA360531CA36115782269A3 -:103D4000934224BFE368A361E3690BB1204698471F -:103D5000002383F31188284607E03146204600F00F -:103D600069FA0028E2DA85F3118870BD2DE9F74F72 -:103D700004460E4617469846D0F81C904FF0200A8D -:103D80008AF311884FF0000B154665B12A4631467B -:103D90002046FFF741FF034660B94146204600F048 -:103DA00049FA0028F1D0002383F31188781B03B06F -:103DB000BDE8F08FB9F1000F03D001902046C8474D -:103DC000019B8BF31188ED1A1E448AF31188DCE7FE -:103DD000C0E90511C160C3611144009B8260C0E964 -:103DE0000000016103627047F8B504460D461646AF -:103DF000202383F31188A768A7B1A368013BA360C0 -:103E000063695A1C62611D70D4E904329A4224BF6E -:103E1000E3686361E3690BB120469847002080F3B3 -:103E2000118807E03146204600F004FA0028E2DA63 -:103E300087F31188F8BD0000D0E905239A4210B538 -:103E400001D182687AB98268013282605A1C82612B -:103E50001C7803699A4224BFC3688361002100F083 -:103E6000F9F9204610BD4FF0FF30FBE72DE9F74F81 -:103E700004460E4617469846D0F81C904FF0200A8C -:103E80008AF311884FF0000B154665B12A4631467A -:103E90002046FFF7EFFE034660B94146204600F09A -:103EA000C9F90028F1D0002383F31188781B03B0EF -:103EB000BDE8F08FB9F1000F03D001902046C8474C -:103EC000019B8BF31188ED1A1E448AF31188DCE7FD -:103ED000026843681143016003B11847704700004E -:103EE0001430FFF743BF00004FF0FF331430FFF7EB -:103EF0003DBF00003830FFF7B9BF00004FF0FF337F -:103F00003830FFF7B3BF00001430FFF709BF0000DF -:103F10004FF0FF311430FFF703BF00003830FFF7D8 -:103F200063BF00004FF0FF323830FFF75DBF000085 -:103F300000207047FFF7FEBC044B03600023C0E97C -:103F40000233436001230374704700BF60520008CE -:103F500010B52023044683F31188FFF755FD022393 -:103F60002374002383F3118810BD000038B5C369A2 -:103F700004460D461BB904210844FFF7A9FF294652 -:103F800004F11400FFF7B0FE002806DA201D4FF4FC -:103F90008061BDE83840FFF79BBF38BD024B00226F -:103FA000C3E900339A607047083700200023037488 -:103FB0008268054B1B6899689142FBD25A6803607E -:103FC00042601060586070470837002008B5202311 -:103FD00083F31188037C032B05D0042B0DD02BB960 -:103FE00083F3118808BD436900221A604FF0FF3344 -:103FF0004361FFF7DBFF0023F2E7D0E900321360F3 -:104000005A60F3E7002303748268054B1B689968C4 -:104010009142FBD85A680360426010605860704754 -:1040200008370020054B19690874186802681A607F -:104030005360186101230374FCF7D2BA08370020DB -:1040400030B54B1C0B4D87B0044610D02B690A4A83 -:1040500001A800F019F92046FFF7E4FF049B13B113 -:1040600001A800F04DF92B69586907B030BDFFF782 -:10407000D9FFF8E708370020CD3F000838B50C4DD0 -:1040800041612B6981689A689142044603D8BDE872 -:104090003840FFF78BBF1846FFF7B4FF01232C61B0 -:1040A000014623742046BDE83840FCF799BA00BFAA -:1040B00008370020044B1A681B6990689B68984277 -:1040C00094BF0020012070470837002010B5084C2D -:1040D000236820691A6822605460012223611A74DF -:1040E000FFF790FF01462069BDE81040FCF778BA61 -:1040F0000837002008B5FFF7DDFF18B1BDE808401C -:10410000FFF7E4BF08BD0000FFF7E0BFFEE70000D7 -:1041100010B50C4CFFF742FF00F0A8F80A498022C6 -:10412000204600F03DF8012344F8180C0374FFF713 -:1041300093FB002383F3118862B60448BDE8104066 -:1041400000F04EB83037002088520008985200081E -:1041500008B572B6034B586200F072FA00F01EFB0D -:10416000FEE700BF0837002000F004B9EFF311802C -:1041700020B9EFF30583202282F3118870470000F5 -:1041800010B530B9EFF30584C4F3080414B180F31B -:10419000118810BDFFF7AEFF84F31188F9E7000026 -:1041A00082600222028270478368A3F17C0243F896 -:1041B0000C2C026943F83C2C426943F8382C074A1E -:1041C00043F81C2CC26843F8102C022203F8082C78 -:1041D000002203F8072CA3F118007047F905000826 -:1041E00010B5202383F31188FFF7DEFF002104467A -:1041F000FFF744FF002383F31188204610BD000021 -:10420000024B1B6958610F20FFF70CBF08370020D5 -:10421000202383F31188FFF7F3BF000008B50146A0 -:10422000202383F311880820FFF70AFF002383F37C -:10423000118808BD49B1064B42681B6918605A6075 -:10424000136043600420FFF7FBBE4FF0FF30704760 -:10425000083700200368984206D01A680260506050 -:1042600059611846FFF7A2BE70470000054B03F1E5 -:104270001402C3E905224FF0FF310022C3E90712FF -:10428000704700BF0837002070B51C4EC0E90323FB -:1042900005460C4600F0FCFA334653F8142F9A42B8 -:1042A0000DD13062C5E901242A600A2C2CBF001907 -:1042B0000A30C6E90555BDE8704000F0D7BA316A4A -:1042C000431AE31838BF1C469368A34202D9081961 -:1042D00000F0DAFA73699A6894420CD85A68AC60B4 -:1042E0002B606A6015609A685D60121B9A604FF0DF -:1042F000FF33F36170BD1B68A41AECE70837002098 -:1043000038B51B4C636998420DD0D0E90032136078 -:104310005A6000228168C2609A680A449A604FF02D -:10432000FF33E36138BD2246036842F8143F0021A1 -:1043300093425A60C16003D1BDE8384000F09EBA94 -:104340009A688168256A0A449A6000F0A1FA636954 -:104350009A68411B8A42E5D9AB181D1A092D206ABB -:1043600098BF01F10A02BDE83840104400F08CBA51 -:10437000083700202DE9F041184C002704F11406FD -:10438000656900F085FA236AAA68C11A8A4215D8BD -:1043900013442362D5E9003213605A606369D5F88B -:1043A0000C80EF60B34201D100F068FA87F3118806 -:1043B0002869C047202383F31188E1E76169B1428E -:1043C00009D013441B1ABDE8F0410A2B2CBFC018BA -:1043D0000A3000F059BABDE8F08100BF083700206C -:1043E0000C2303604FF0FF3070470000002070473F -:1043F000FEE70000704700004FF0FF3070470000FC -:10440000BFF34F8F024A1369DB03FCD4704700BF30 -:104410000020024008B5094B1B7873B9FFF7F0FF85 -:10442000074B5A69002ABFBF064A9A6002F18832D8 -:104430009A601A6822F480621A6008BD90380020E1 -:10444000002002402301674508B50B4B1B7893B948 -:10445000FFF7D6FF094B5A6942F000425A611A68C9 -:1044600042F480521A601A6822F480521A601A6864 -:1044700042F480621A6008BD90380020002002409B -:104480007F289ABF00F58030C002002070470000EE -:104490004FF4006070470000802070477F2808B507 -:1044A0000BD8FFF7EDFF00F500630268013204D17D -:1044B00004308342F9D1012008BD0020FCE7000050 -:1044C0007F2838B5044626D8FFF750FEFFF798FF3F -:1044D000FFF7A0FF114BF3221A6102225A615A69B9 -:1044E00042EAC4025A615A6942F480325A6105466E -:1044F0002046FFF785FF4FF40061FFF7C1FF00F092 -:1045000049F92846FFF7A0FFFFF73AFE2046BDE82D -:104510003840FFF7C3BF002038BD00BF0020024075 -:1045200040EA020313F007032DE9F04705460C4665 -:10453000164606D0324B40F2FB221A600020BDE83E -:10454000F08781182F4A91420CD92D4A4FF44071BF -:104550001160F3E72B1D1B686268934208D1083E87 -:1045600008350834072E19D92A6823689A42F1D0F1 -:10457000FFF7FCFDFFF74EFFFFF742FF04F10801D4 -:10458000214C4FF001084FF00009012EA1F108075E -:1045900008D8FFF759FFFFF7F3FD01E0002EE7D140 -:1045A0000120CCE7C4F81480AA4651F8083C4AF828 -:1045B000043B51F8043C6B60FFF722FFC4F81490F1 -:1045C0002A6851F8083C9A420ED00D4B40F2263230 -:1045D0001A600E4B1D600E4B1E600E4B1F60FFF7E6 -:1045E00033FFFFF7CDFDA9E7DAF800A051F8043C4E -:1045F0009A4501F10801E8D1083E0835C5E700BF3A -:104600008C38002000000408002002408038002080 -:104610008838002084380020084908B50B7828B174 -:104620001BB9FFF7F7FE01230B7008BD002BFCD070 -:10463000BDE808400870FFF707BF00BF90380020B2 -:104640004FF480314FF0005000F0A6B870B582B042 -:10465000FFF78CFD0E4E054600F01AF932689042C5 -:1046600037BF0C4A0B49516814682EBFD1E900418D -:10467000013151600419034641F1000128460191BE -:104680003360FFF77DFD0199204602B070BD00BF89 -:10469000943800209838002070B582B0FFF766FD8E -:1046A000104E054600F0F4F83268904237BF0E4ACB -:1046B0000D49516814682EBFD1E9004101315160A4 -:1046C000041941F100010346284601913360FFF7C8 -:1046D00057FD01994FF47A7200232046FBF768FDDD -:1046E00002B070BD943800209838002010B5024404 -:1046F000064BD2B2904200D110BD441C00B253F818 -:10470000200041F8040BE0B2F4E700BF502800405D -:10471000114B30B5D3F89040240409D4D3F890401D -:10472000C3F89040D3F8904044F40044C3F890405C -:104730000A4C236843F4807323600244084BD2B2CE -:10474000904200D130BD441C00B251F8045B43F8E4 -:104750002050E0B2F4E700BF0010024000700040BB -:104760005028004007B5012201A90020FFF7BEFF35 -:10477000019803B05DF804FB13B50446FFF7F2FFA0 -:10478000A04205D0012201A900200194FFF7C0FF3B -:1047900002B010BD70470000704700007047000075 -:1047A000074B45F255521A6002225A6040F6FF72DA -:1047B0009A604CF6CC421A60024B01221A70704784 -:1047C00000300040A4380020034B1B781BB1034B82 -:1047D0004AF6AA221A607047A43800200030004030 -:1047E000054B1A6832B902F1804202F50432D2F860 -:1047F00094201A60704700BFA0380020024B4FF48D -:104800000002C3F8942070470010024008B5FFF77B -:10481000E7FF024B1868C0F3407008BDA0380020C5 -:1048200070470000FEE700000A4B0B480B4A90421D -:104830000BD30B4BDA1C121AC11E22F003028B425F -:1048400038BF00220021FDF713B953F8041B40F8CC -:10485000041BECE7445300083C3900203C3900209D -:104860003C3900207047000000F07AB84FF08043D8 -:10487000002258631A610222DA6070474FF08043C9 -:104880000022DA60704700004FF0804358637047A1 -:104890004FF08043586A7047264B2748DA6A42F047 -:1048A000070210B4DA62DA6A22F00702DA62DA6A20 -:1048B000DA6C42F00702DA64DA6E42F00702DA6676 -:1048C0004FF09042DB6E4FF0AA31002353604FF45B -:1048D000EE449160D0604FF6FF7050611462174C47 -:1048E00053621460164CC2F80434C2F80814C2F8BB -:1048F0000C444FF6F774C2F814444FF0EE44C2F87B -:10490000204447F29974C2F824440E4CC2F8004483 -:10491000C2F80438C2F80818C2F80C38C2F81408F3 -:10492000C2F82038C2F82438C2F800385DF8044BC9 -:1049300000F09CB80010024050010024A0010028A3 -:104940001050500050A0AA0008B500F035FAFFF74B -:10495000DFFBBDE80840FFF743BF000070470000E1 -:104960000F4B9A6D42F001029A659A6F42F0010274 -:104970009A670C4A9B6F936843F0010393604FF072 -:1049800080434F229A624FF0FF32DA6200229A612E -:104990005A63DA605A6001225A611A60704700BF98 -:1049A00000100240002004E04FF0804208B5116979 -:1049B000D3680B40D9B2C9439B07116107D52023A7 -:1049C00083F31188FFF7D0FB002383F3118808BD20 -:1049D00008B5244B4FF0FF319A6A99629A6A002217 -:1049E0009A62986AD86A60F00700D862D86A00F0C4 -:1049F0000700D862D86A186B1963186B1A63186BB2 -:104A0000986B60F080509863986B00F080509863CA -:104A1000986BD86BD963D86BDA63D86B186C196450 -:104A2000196C1A64196C996D41F080519965996FF0 -:104A300041F080519967996FD3F8901011F4407F3D -:104A40001EBF4FF48031C3F89010C3F89020D3F804 -:104A50009020C3F8902000F07FF9034B00225A60A9 -:104A600008BD00BF0010024000700040394B3A4AB8 -:104A70009A6501221A601A689007FCD500229A6094 -:104A80009A6812F00C0FFBD1344A4FF40071116098 -:104A900051694905FCD41A6842F480321A601A68D8 -:104AA0009203FCD52D490A6842F480720A602C4AB0 -:104AB0004FF4E06111601A6842F060021A601A68EF -:104AC00042F008021A601A689007FCD59A6812F042 -:104AD0000C0FFBD1D3F8942042F4C062C3F89420A9 -:104AE000204ADA601A6842F080721A601A689101EE -:104AF000FCD51D4A1A611A6842F080621A601A6871 -:104B00001201FCD500229A601549184AC3F8882082 -:104B10000A6822F0070242F004020A600A6802F002 -:104B20000702042AFAD19A6842F003029A609A684E -:104B300002F00C020C2AFAD11A6E42F001021A6637 -:104B4000D3F8802042F00102C3F88020D3F88030EF -:104B5000704700BF001002400004001000700040C9 -:104B60000020024003140001000C100055550134D0 -:104B7000074A08B5536903F00103536123B1054A9D -:104B800013680BB150689847BDE80840FEF788BE2F -:104B900000040140A8380020074A08B5536903F013 -:104BA0000203536123B1054A93680BB1D06898475B -:104BB000BDE80840FEF774BE00040140A83800209C -:104BC000074A08B5536903F00403536123B1054A4A -:104BD00013690BB150699847BDE80840FEF760BE05 -:104BE00000040140A8380020074A08B5536903F0C3 -:104BF0000803536123B1054A93690BB1D069984703 -:104C0000BDE80840FEF74CBE00040140A838002073 -:104C1000074A08B5536903F01003536123B1054AED -:104C2000136A0BB1506A9847BDE80840FEF738BEDA -:104C300000040140A8380020164B10B55C6904F44C -:104C400078725A61A30604D5134A936A0BB1D06AED -:104C50009847600604D5104A136B0BB1506B984708 -:104C6000210604D50C4A936B0BB1D06B9847E20533 -:104C700004D5094A136C0BB1506C9847A30504D5B1 -:104C8000054A936C0BB1D06C9847BDE81040FEF715 -:104C900007BE00BF00040140A8380020194B10B522 -:104CA0005C6904F47C425A61620504D5164A136DAE -:104CB0000BB1506D9847230504D5134A936D0BB182 -:104CC000D06D9847E00404D50F4A136E0BB1506EB7 -:104CD0009847A10404D50C4A936E0BB1D06E984747 -:104CE000620404D5084A136F0BB1506F9847230430 -:104CF00004D5054A936F0BB1D06F9847BDE81040BB -:104D0000FEF7CEBD00040140A838002008B50348D6 -:104D1000FEF7E8FEBDE80840FEF7C2BD04350020FE -:104D200008B50348FEF7DEFEBDE80840FEF7B8BD53 -:104D30007035002008B50348FEF7D4FEBDE80840F2 -:104D4000FEF7AEBDDC35002008B5FFF72DFEBDE84F -:104D50000840FEF7A5BD0000062108B50846FEF78D -:104D600045FF06210720FEF741FF06210820FEF738 -:104D70003DFF06210920FEF739FF06210A20FEF734 -:104D800035FF06211720FEF731FF06212820FEF708 -:104D90002DFF07211C20FEF729FF0C212520FEF7FF -:104DA00025FF0C212620FEF721FFBDE808400C213D -:104DB0002720FEF71BBF000008B5FFF709FE00F033 -:104DC00009F8FFF7B7F8FFF7C9FDBDE80840FFF79E -:104DD0004BBD00000023054A19460133102BC2E9E0 -:104DE000001102F10802F8D1704700BFA838002076 -:104DF0000B460146184600F025B8000000F038B810 -:104E0000012838BF012010B50446204600F028F8DC -:104E100030B900F007F808B900F00CF88047F4E763 -:104E200010BD0000024B1868BFF35B8F704700BFD6 -:104E30002839002008B5062000F032F90120FFF7DC -:104E4000D7FA000010B5054C13462CB10A460146AE -:104E50000220AFF3008010BD2046FCE700000000F8 -:104E6000024B0146186800F089B800BF28110020E5 -:104E7000024B0146186800F035B800BF2811002029 -:104E800010B501390244904201D1002005E00378B9 -:104E900011F8014FA34201D0181B10BD0130F2E7F9 -:104EA0002DE9F041A3B1C91A17780144044603F172 -:104EB000FF3C8C42204601D9002009E00578BD4224 -:104EC00004F10104F5D10CEB0405D618A54201D17B -:104ED000BDE8F08115F8018D16F801EDF045F5D02B -:104EE000E7E7000037B5002944D051F8043C0190B1 -:104EF000002BA1F10404B8BFE41800F0F5F81E4A35 -:104F00000198136833B96360146003B0BDE83040A2 -:104F100000F0F0B8A34208D9256861198B4201BF9F -:104F200019685B6849192160EDE71A465B680BB1A7 -:104F3000A342FAD911685518A5420BD1246821441F -:104F40005418A3421160E0D11C685B68536021448F -:104F50001160DAE702D90C230360D6E725686119EE -:104F60008B4204BF19685B68636004BF4919216004 -:104F70005460CAE703B030BD2C390020F8B5CD1C11 -:104F800025F0030508350C2D38BF0C25002D0646ED -:104F900001DBA94203D90C2333600020F8BD00F0E7 -:104FA000A3F821490A6814469CB9204F3B6823B9ED -:104FB0002146304600F03CF838602946304600F083 -:104FC00037F8431C23D10C233360304600F092F8AD -:104FD000E3E723685B1B17D40B2B03D923601C4426 -:104FE000256004E06368A2420CBF0B60536030464A -:104FF00000F080F804F10B00231D20F00700C21A16 -:10500000CCD01B1AA350C9E722466468CCE7C41C65 -:1050100024F00304A042E3D0211A304600F008F83F -:105020000130DDD1CFE700BF2C390020303900201E -:1050300038B5064D0023044608462B60FFF7D0F92B -:10504000431C02D12B6803B1236038BD34390020E2 -:105050001F2938B504460D4604D9162303604FF0C6 -:10506000FF3038BD426C12B152F821304BB92046A6 -:1050700000F030F82A4601462046BDE8384000F0EE -:1050800017B8012B0AD0591C03D116230360012045 -:10509000E7E7002442F82540284698470020E0E74B -:1050A000024B01461868FFF7D3BF00BF281100204C -:1050B00038B5074D00230446084611462B60FFF71C -:1050C0009BF9431C02D12B6803B1236038BD00BF9C -:1050D00034390020FFF78AB9034611F8012B03F891 -:1050E000012B002AF9D17047014800F009B800BF30 -:1050F00038390020014800F005B800BF38390020D9 -:1051000070470000704700006F72672E617264750F -:1051100070696C6F742E4D6174656B4C3433312D36 -:1051200050657269706800004E6F20617070207366 -:1051300069670A00426164206677206C656E677457 -:10514000682025750A0042616420626F6172645FA5 -:1051500069642025752073686F756C642062652012 -:1051600025750A0042616420667720646573637266 -:105170006970746F72206C656E6774682025750A9B -:1051800000426164206170702043524320307825D2 -:105190003038783A307825303878203078253038F3 -:1051A000783A3078253038780A00476F6F64206687 -:1051B00069726D776172650A0040A2E4F1646891DA -:1051C0000600000053544D33324C343F3F00000082 -:1051D0000435002070350020DC3500204261642059 -:1051E00043414E496661636520696E6465782E00AF -:1051F000800000000080000000008000000000002F -:10520000000000009D1B000889230008E922000817 -:10521000AD1B0008E51B0008E11D0008B11B0008DC -:10522000C51B0008B51B0008B91B0008C11B0008FE -:10523000BD1B0008091D0008C91B0008F525000852 -:10524000D91B0008DD1C00080096000000000000CB -:10525000000000000000000000000000000000004E -:1052600000000000FD3E0008E93E0008253F000860 -:10527000113F00081D3F0008093F0008F53E0008E7 -:10528000E13E0008313F00086D61696E00000000DA -:1052900069646C65000000009052000848370020E7 -:1052A00080380020010000000D41000800000000CF -:1052B00030AFFF7F01000000260400000000000066 -:1052C0000060030000000000FE2A0100D20400007C -:1052D000FF00000000000000C45100083F00000073 -:1052E0002C11002000000000000000000000000061 -:1052F00000000000000000000000000000000000AE -:10530000000000000000000000000000000000009D -:10531000000000000000000000000000000000008D -:10532000000000000000000000000000000000007D -:10533000000000000000000000000000000000006D -:045340000000000069 +:1004B000704700BF02E000F000F8FEE772B6374870 +:1004C00080F30888364880F3098836483649086042 +:1004D00040F20000CCF200004EF63471CEF2000182 +:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 +:1004F000F0004EF68851CEF200010860BFF34F8F36 +:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 +:10051000CEF200010860062080F31488BFF36F8FCD +:1005200003F038FD03F0BAFD4FF055301F491B4A68 +:1005300091423CBF41F8040BFAE71D49184A914229 +:100540003CBF41F8040BFAE71A491B4A1B4B9A427D +:100550003EBF51F8040B42F8040BF8E7002018499D +:10056000184A91423CBF41F8040BFAE703F016FD2C +:1005700003F0E6FD144C154DAC4203DA54F8041BAD +:100580008847F9E700F042F8114C124DAC4203DA0B +:1005900054F8041B8847F9E703F0FEBC000900206B +:1005A000001100200000000808ED00E0000100201C +:1005B00000090020E0470008001100207C11002005 +:1005C00080110020003B0020A0010008A4010008C9 +:1005D000A4010008A40100082DE9F04F2DED108AB8 +:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 +:1005F000002383F311882846A047002003F076F9F2 +:10060000FEE703F0D9F800DFFEE70000F8B500F0E0 +:1006100011FE03F061FC074603F0B2FC0546D0BBB7 +:10062000294B9F4237D001339F4237D0274B27F0C9 +:10063000FF029A4235D1F8B200F042FC2E4642F257 +:10064000107400F043FC08B10024264601F0ACF819 +:1006500058B3032000F03EF80024264635B11C4B69 +:100660009F4203D003F084FC00242646002003F0C0 +:100670003DFC0EB100F044F800F05AFC00F0DCFD47 +:1006800001F0ACFF0546B4B900F09AFC4FF47A7063 +:1006900003F032F9F7E72E460024D2E7044601269C +:1006A000CFE706464FF47A74CBE7002CD6D04FF450 +:1006B0007A740126D2E701F091FF431BA342E3D9EC +:1006C00000F01EF8DCE700BF010007B0000008B032 +:1006D000263A09B0084B187003280CD8DFE800F060 +:1006E00008050208022000F005BE022000F0F8BD57 +:1006F000024B00225A6070478011002084110020B4 +:1007000010B501F051F830B1234B03221A70234B7E +:1007100000225A6010BD224B224A1C461968013142 +:10072000F8D004339342F9D16268A242F2D31E4B4F +:100730009B6803F1006303F520439A42EAD203F079 +:10074000E9FB03F0FBFB002000F090FD0220FFF727 +:10075000C1FF164B9A6D00229A65996F9A67996F3F +:10076000D96DDA65D96FDA67D96F196E1A66D3F861 +:100770008010C3F88020D3F8803072B64FF0E023A9 +:100780003021C3F8084DD4E9003281F311889D4629 +:1007900083F308881047BDE78011002084110020F2 +:1007A00000A0000820A00008001100200010024056 +:1007B000094A136849F2690099B21B0C00FB013326 +:1007C0001360064B186844F2506182B2000C01FBC2 +:1007D0000200186080B27047141100201011002030 +:1007E00010B500211022044600F09EFD034B03CB00 +:1007F000206061601868A06010BD00BF9075FF1F89 +:100800002DE9F041ADF5507D0DF13C086EAC40F2A4 +:10081000751207460D4610A80021C8F8001000F018 +:1008200083FD4FF4C4720021204600F07DFD01F0ED +:10083000D5FE274B4FF47A72B0FBF2F0186093E8C4 +:100840000700022384E807000DF5ED702382FFF70F +:10085000C7FF42F204631F49238407A803F058FF2F +:100860001E2384F832310DF2EB2207AB0DF1340C6C +:100870001E4603CE664510605160334602F1080201 +:10088000F6D130681060B38893804146012220463B +:1008900000F096FD00230393AB7E029305F119034C +:1008A000019380B20123CDE904800093E97E06A381 +:1008B000D3E90023384602F059FA0DF5507DBDE822 +:1008C000F08100BFAFF300809E6AC421818A46EEAA +:1008D0008C110020204700082DE9F0412C4C237A90 +:1008E000DAB080460D465BBB27A9284600F078FEAB +:1008F0000746002842D19DF89D60C82E3ED801468B +:100900004FF4A662204600F00FFD4FF48073C4F848 +:10091000F8314FF40073C4F80C334FF44073C4F84B +:10092000203432460DF19E0104F1090000F0EAFC8A +:1009300026449DF89C30777223720BB9EB7E2372AC +:100940008122002106AC27A800F0EEFC01222146FE +:1009500027A800F081FE00230393AB7E029305F1EC +:10096000190380B201932823CDE904400093E97E66 +:1009700005A3D3E90023404602F0F8F95AB0BDE8D8 +:10098000F08100BFAFF3008026417272DF25D7B738 +:10099000A8320020F0B5254E4FF48A7505FB00659E +:1009A000F1B096F8D83085F8DC300024D822214602 +:1009B00085F8E8403AA800F0B7FC06F1090000F01D +:1009C000ABFCD5F8E4308DF8F000C2B206AF06F10A +:1009D00009010DF1F100CDE93A3400F093FC3946FC +:1009E00001223AA800F064FE80B2CDE90470082329 +:1009F0000127CDE9023706F1D80301933023009394 +:100A0000317A0B4807A3D3E9002302F0AFF9A042E3 +:100A100006DD01F0E3FDC5F8E000384671B0F0BD39 +:100A20002046FBE778F6339F93CACD8DA83200208D +:100A3000A42100202DE9F0411D4D1E4E1E4F86B011 +:100A4000284602F0BFF9034658B30024CDE9034419 +:100A5000ADF81440027B8DF8142099684068029428 +:100A600003AA03C21B68DFF8548043F000430293DB +:100A700001F0B6FD821941F10003009402A9384645 +:100A800001F078F8A04205DD284602F09FF988F8C9 +:100A90000040D5E798F80030072B05D8013388F8D7 +:100AA000003006B0BDE8F081014802F08FF9F8E7A8 +:100AB000A421002040420F00D8210020DD37002073 +:100AC00070B50D4614461E4602F0ACF850B9022E21 +:100AD00010D1012C0ED112A3D3E90023C5E90023C4 +:100AE000012007E0282C10D005D8012C09D0052CB6 +:100AF0000FD0002070BD302CFBD10BA3D3E9002315 +:100B0000ECE70BA3D3E90023E8E70BA3D3E9002329 +:100B1000E4E70BA3D3E90023E0E700BFAFF30080D5 +:100B2000401DA12026812A0B78F6339F93CACD8DD4 +:100B30009E6AC421818A46EE26417272DF25D7B7AC +:100B4000F017304A39059E5638B505460E4C00213F +:100B5000013500F0ADFBA4F82C55B4F82C0500F0DD +:100B60008FFB78B1B4F82C0500F09AFB014648B928 +:100B7000B4F82C0500F09CFBB4F82C350133A4F834 +:100B80002C35EAE738BD00BFA832002010B50A4B6B +:100B90000A4A1A6003F5805393F860203AB9DC6D75 +:100BA0002CB1204600F07EFE204603F0F1FCBDE8AB +:100BB0001040034800F076BED82100207C47000892 +:100BC000203200202DE9F04F8FB000AF05460C46D3 +:100BD00002F028F8002849D1237E022B1BD1E38A9A +:100BE000012B18D101F0FAFC0646FFF7E1FD0346A0 +:100BF0004FF4C870DFF8C482B3FBF0F206F5167646 +:100C000002FB103316FA83F3C8F80030E37E33B9E1 +:100C1000A34B00221A703C37BD46BDE8F08F07F1A8 +:100C20002401204600F09AFC0028F4D107F11400BA +:100C3000FFF7D6FD97F8264007F11401224607F189 +:100C4000270003F0EFFC0028E2D10F2C08D8944BCA +:100C50001C70D8F80030A3F51673C8F80030DAE736 +:100C600097F82410284601F0D5FFD4E7E38A282B13 +:100C70002BD010D8012B23D0052BCCD1BFF34F8F15 +:100C80008849894BCA6802F4E0621343CB60BFF322 +:100C90004F8F00BFFDE7302BBDD1844EE17E327A0D +:100CA0009142B8D1607E3146002291F8DC508542F5 +:100CB00000F0A5800132042A01F58A71F5D1AAE776 +:100CC00021462846FFF79CFDA5E721462846FFF769 +:100CD00003FEA0E7B2F8EC507B6005F103094FEA90 +:100CE00099094FEA8902D11DC908A8EBC1039D46A5 +:100CF000EB460021584600F017FB04F1EE012A46AE +:100D00003144584600F0FEFA7B6813B9012000F028 +:100D1000ADFA96F8D20000F0B3FA044630B930725A +:100D200000F0CEFA204600F0A1FAB1E0D6F8D420C7 +:100D30003AB996F8D200B6F82C25824201D8FFF7CE +:100D400003FFD6F8D4202A44944208D296F8D20061 +:100D5000B6F82C250130824201D8FFF7F5FE706805 +:100D60005FFA89F2594600F0E7FA08B9C54679E01A +:100D7000726896F8D2002A447260D6F8D42005EB47 +:100D80000209C6F8D49000F07BFA814509D396F8A1 +:100D9000D220D6F8D4000132001B86F8D220C6F843 +:100DA000D400FF2D0FD80024347200F089FA2046B9 +:100DB00000F05CFA00F0F8FC3D4B188108B9FFF731 +:100DC0009FFCC54627E7BB6896F8D9000AFB03627B +:100DD000FB68D2F8E41082F8E83001F58061C2F8CF +:100DE000E030C2F8E410FFF7D5FDFFF723FE96F8D8 +:100DF000D920013202F0030286F8D920B6E74FF479 +:100E00008A7A0AFB02F505F1EA013144204600F036 +:100E10007BFCF86000287FF4FEAE3544012285F8A3 +:100E2000E82001F0DBFBD5F8E020D6ED007ADFED1D +:100E3000216A801A192838BF192040F6B83290422A +:100E400028BF1046B8EE677A07EE900AF8EEE77A08 +:100E500067EEA67ADFED186AE7EE267AFCEEE77A0F +:100E6000C6ED007A96F8D930BB60BA6873680AFBA1 +:100E700002F4321992F8E81059B1D2F8E4108B421A +:100E8000E8463FF427AF002182F8E810C2F8E010EE +:100E9000C5467368064A9B0A01331381BBE600BF4F +:100EA0009D21002000ED00E00400FA05A83200209A +:100EB0008C110020CDCCCC3D6666663FA021002081 +:100EC000014B1870704700BF9811002038B54FF0E3 +:100ED0000054134B22689A4220D1124B627D124873 +:100EE0001A70237D03724FF48073C0F8F8314FF409 +:100EF0000073C0F80C3300254FF44073C0F8203461 +:100F00000A49C0F8E450C922093000F0FBF9E02298 +:100F10002946204600F008FA012038BD0020FCE7F1 +:100F20009AAD44C598110020A83200201600002078 +:100F300037B500F039FC194D1949288102230122E7 +:100F400018486B7101F0E8F900230193164B17491B +:100F500000931748174B4FF4805201F033FE164BA5 +:100F6000197811B1124801F055FE01F037FB044623 +:100F7000FFF71EFC4FF4C873B0FBF3F202FB130340 +:100F800004F5167010FA83F00C4B186002F0F8FFAD +:100F900008B10F232B8103B030BD00BF8C1100209E +:100FA00040420F00D8210020C10A00089C110020F7 +:100FB000A4210020C50B000898110020A0210020CA +:100FC0002DE9F04F2DED028B0FF23829D9E9008978 +:100FD000834C93B00BAE9FED7E8BFFF72BFD814FC3 +:100FE000DFF828A200230A93ADF834300B93736026 +:100FF0004FF0000B5B468DED008B01250DF11D02BE +:1010000007A938468DF81C508DF81DB001F034F951 +:101010009DF81C30002B40F0A580204601F002FE18 +:101020000646002845D1704F01F0D8FA3B68984237 +:101030003FD301F0D3FA8246FFF7BAFB4FF4C873EF +:10104000B0FBF3F202FB13030AF5167010FA83F0FB +:101050003860664F97F800B0CBF1100ABBF1000F73 +:1010600014BF33462B465FFA8AFA0EA88DF8283053 +:10107000FFF7B6FBBAF1060F28BF4FF0060A0EAB1A +:1010800003EB0B0152460DF1290000F03BF90AABCE +:101090000393182302930AF10102554BD2B2CDE912 +:1010A0000053049220464CA3D3E9002301F000FE34 +:1010B0003E7001F093FA4F4A4F4D1368C31AB3F5CF +:1010C0007A7F2ED3106001F08BFA02460B46204641 +:1010D00001F086FE204601F0A5FD10B32B7A474EA5 +:1010E000002B14BF03230223737101F077FA0EAFB4 +:1010F0004FF47A730122B0FBF3F03946306030468A +:1011000000F004FA182302933D4B019380B240F2A1 +:101110005513CDE90370009342464B46204601F03B +:10112000C7FD2B7A93B101F059FA002607464FF418 +:101130008A7A95F8D900304400F003000AFB005386 +:1011400093F8E82092B30136042EF2D1C82002F0C1 +:10115000D3FB2B7A002B7FF43DAF13B0BDEC028B99 +:10116000BDE8F08FDAF8143083F00803CAF81430C1 +:10117000594610220EA800F0D7F80DF11E0308AA58 +:101180000AA9384600F0F4FD96E803000FAB83E8A7 +:1011900003009DF834308DF844300A9B0E930EA95D +:1011A000DDE90823204601F0EFFF21E7D3F8E02036 +:1011B00042B12B68FA2B38BFFA23BA1A0533B2EBC7 +:1011C000430FC0D3FFF7E6FB0028BCD1BEE700BF4A +:1011D0000000000000000000401DA12026812A0B15 +:1011E000A4210020D8210020A02100209D21002042 +:1011F0009C210020D8370020A83200208C1100202C +:10120000DC370020F1C6A7C1D068080F00040048F1 +:1012100008B5054800F046FEBDE80840034A044909 +:10122000002003F0AFB900BFD821002018380020FB +:101230008D0B00087047000070B502F0E9FC094E04 +:10124000094D3080002428683388834208D902F091 +:10125000DBFC2B6804440133B4F5204F2B60F2D340 +:1012600070BD00BF0C380020E037002002F082BDC6 +:1012700000F10060920000F5204002F005BD000082 +:10128000054B1A68054B1B889B1A834202D91044F0 +:1012900002F0BABC00207047E03700200C38002074 +:1012A000024B1B68184402F0B5BC00BFE0370020B9 +:1012B000024B1B68184402F0BFBC00BFE03700209F +:1012C000064991F8243033B10023086A81F82430AC +:1012D0000822FFF7CDBF0120704700BFE437002090 +:1012E000022802BF024B4FF400229A61704700BFF0 +:1012F00000040048022802BF014B08229A6170478F +:101300000004004810B50023934203D0CC5CC454C1 +:101310000133F9E710BD000003460246D01A12F966 +:10132000011B0029FAD1704702440346934202D0C0 +:1013300003F8011BFAE770472DE9F8431F4D1446E7 +:1013400095F824200746884652BBDFF870909CB37E +:1013500095F824302BB92022FF2148462F62FFF751 +:10136000E3FF95F82400C0F10802A24228BF2246FC +:10137000D6B24146920005EB8000FFF7C3FF95F817 +:101380002430A41B1E44F6B2082E17449044E4B245 +:1013900085F82460DBD1FFF793FF0028D7D108E060 +:1013A0002B6A03EB82038342CFD0FFF789FF00282B +:1013B000CBD10020BDE8F8830120FBE7E437002013 +:1013C0002DE9F0470D46044600219046284640F29C +:1013D0007912FFF7A9FF234620220021284601F0B9 +:1013E00075FE231D02222021284601F06FFE631D99 +:1013F00003222221284601F069FEA31D0322252194 +:10140000284601F063FE04F1080310222821284633 +:1014100001F05CFE04F1100308223821284601F097 +:1014200055FE04F1110308224021284601F04EFE2A +:1014300004F1120308224821284601F047FE04F176 +:10144000140320225021284601F040FE04F1180325 +:1014500040227021284601F039FE04F120030822C1 +:10146000B021284601F032FE04F121030822B82100 +:10147000284601F02BFE04F12207C0263B463146E8 +:1014800008222846083601F021FEB6F5A07F07F1B4 +:101490000107F3D104F1320308223146284601F056 +:1014A00015FE002704F1330A94F832304FEAC709D9 +:1014B0009F4209F5A47615D3B8F1000F08D1314643 +:1014C00004F599730722284601F000FE09F24F1631 +:1014D000274694F832213B1B93420CD3F01DC008E1 +:1014E000BDE8F0870AEB070308223146284601F0E1 +:1014F000EDFD0137D8E707F23313314608222846BD +:1015000001F0E4FD08360137E3E7000013B50446B7 +:101510000846002101602346C0F8031020220190F4 +:1015200001F0D4FD0198231D0222202101F0CEFDFF +:101530000198631D0322222101F0C8FD0198A31D1B +:101540000322252101F0C2FD019804F108031022B5 +:10155000282101F0BBFD072002B010BDF7B5002324 +:10156000047F00910E4607221946054601F072FCE1 +:10157000731C0093012200230721284601F06AFC16 +:10158000C4B9B31C0093052223460821284601F064 +:1015900061FC0D243746B278BB1B934211D32B7FDD +:1015A000A88A0734E408BBB9844294BF0020012014 +:1015B00003B0F0BDAB8ADB00083BDB08B370082446 +:1015C000E8E7FB1C0093214600230822284601F08F +:1015D00041FC08340137DEE7201A18BF0120E7E795 +:1015E000F7B50023047F00910E46082219460546F0 +:1015F00001F030FC731CC4B9082200931146234645 +:10160000284601F027FC1024012372785F1C013B5F +:10161000934211D32B7FA88A0734E408BBB98442D4 +:1016200094BF0020012003B0F0BDAB8ADB00083B73 +:10163000DB0873700824E7E7F319009321460023C1 +:101640000822284601F006FC08343B46DDE7201A54 +:1016500018BF0120E7E70000F8B50E46054614461E +:10166000002181223046FFF75FFE2B460822002131 +:10167000304601F02BFD7CB96B1C07220821304657 +:1016800001F024FD0F2401236A785F1C013B934283 +:1016900004D3E01DC008F8BD0824F4E7EB19214687 +:1016A0000822304601F012FD08343B46ECE700000A +:1016B000F8B50E46054614460021CE223046FFF707 +:1016C00033FE2B4628220021304601F0FFFC7CB976 +:1016D00005F1080308222821304601F0F7FC3024E8 +:1016E0002F462A7A7B1B934204D3E01DC008F8BD25 +:1016F0002824F5E707F1090321460822304601F0C6 +:10170000E5FC08340137ECE7F7B5047F00910E469D +:10171000012310220021054601F09CFBC4B9B31C33 +:101720000093092223461021284601F093FB192437 +:1017300037467288BB1B9A4211D82B7FA88A073480 +:10174000E408BBB9844294BF0020012003B0F0BD7F +:10175000AB8ADB00103BDB0873801024E8E73B1DFD +:101760000093214600230822284601F073FB083429 +:101770000137DEE7201A18BF0120E7E730B5094D31 +:101780000A4491420DD011F8013B5840082340F320 +:101790000004013B2C4013F0FF0384EA5000F6D113 +:1017A000EFE730BD2083B8EDF7B5384A10685168CF +:1017B0006B4603C36A4636493648082302F042FFA7 +:1017C0000446002833D10A25334A106851686B4615 +:1017D00003C36A4631492F48082302F033FF044609 +:1017E000002849D00369B3F5583F45D8B0F86610D2 +:1017F00040F2264291423FD1294A024402F15C0163 +:101800008B4239D35C3B234900209E1AFFF7B6FF79 +:101810003246074604F164010020FFF7AFFFA368DA +:101820009F4229D1E368984208BF002524E003695C +:10183000B3F5583F27D8418B40F22642914220D140 +:10184000174A024402F110018B4218D3103B114990 +:1018500000209D1AFFF792FF2A46064604F1180160 +:101860000020FFF78BFFA3689E4202D1E3689842F5 +:1018700001D00D25A8E70025284603B0F0BD1025AE +:10188000A2E70C25A0E70B259EE700BF4047000814 +:10189000DC5F030000A0000849470008905F0300D8 +:1018A0000860FFF710B5037C044613B9006802F026 +:1018B000B1FE204610BD00000023BFF35B8FC36064 +:1018C000BFF35B8FBFF35B8F8360BFF35B8F7047AA +:1018D000BFF35B8F0068BFF35B8F704770B5054641 +:1018E0000C30FFF7F5FF05F1080604463046FFF718 +:1018F000EFFFA04206D930466D68FFF7E9FF2544A7 +:10190000281A70BD3046FFF7E3FF201AF9E7000000 +:1019100070B50546406898B105F10800FFF7D8FF9B +:1019200005F10C0604463046FFF7D2FF84423046EC +:1019300094BF6D680025FFF7CBFF013C2C44201AB3 +:1019400070BD000038B50C460546FFF7C7FFA04242 +:1019500010D305F10800FFF7BBFF04446868B4FB2F +:10196000F0F100FB1144BFF35B8F0120AC60BFF3CB +:101970005B8F38BD0020FCE72DE9F0411446074697 +:101980000D46FFF7C5FF844228BF0446D4B1B846D0 +:1019900058F80C6B4046FFF79BFF304428604046E8 +:1019A0007E68FFF795FF331A9C4203D86C600120D4 +:1019B000BDE8F0816B60A41B3B68AB602044E8602D +:1019C0000220F5E72046F3E738B50C460546FFF759 +:1019D0009FFFA04210D305F10C00FFF779FF0444EC +:1019E0006868B4FBF0F100FB1144BFF35B8F01208A +:1019F000EC60BFF35B8F38BD0020FCE72DE9FF41B1 +:101A0000884669460746FFF7B7FF6C4606B204EB07 +:101A1000C6060025B44209D06268206808EB0501BB +:101A2000FFF770FC636808341D44F3E72946384625 +:101A3000FFF7CAFF284604B0BDE8F081F8B50546B7 +:101A40000C300F46FFF744FF05F108060446304608 +:101A5000FFF73EFFA042304688BF6C68FFF738FFB3 +:101A6000201A386020B130462C68FFF731FF20443F +:101A7000F8BD000073B5144606460D46FFF72EFF6D +:101A8000844228BF04460190DCB101A93046FFF72B +:101A9000D5FF019B33B93268C5E90233C5E900249B +:101AA00001200CE09C4238BF0194286001986860D6 +:101AB0008442F5D93368AB60241AEC60022002B08E +:101AC00070BD2046FBE700002DE9FF410F46694647 +:101AD000FFF7D0FF6C4600B204EBC0050026AC4215 +:101AE00009D0D4F8048054F8081BB8194246FFF70F +:101AF00009FC4644F3E7304604B0BDE8F08100003D +:101B000038B50546FFF7E0FF044601462846FFF7D3 +:101B100019FF204638BD0000302383F3118862B6D8 +:101B200070470000002383F3118862B670470000FD +:101B300010B4026854681A4623465DF8044B1847EF +:101B40000120704700207047002070477047000058 +:101B5000002070470E20704700F5805090F8C800B4 +:101B6000C0F340007047000000F5805090F9C900B4 +:101B700070470000F7B50C68BDF8207014F00054F1 +:101B80001E466FD10B7B082B6CD8FFF7C5FF45694C +:101B9000AB685B010CD4AB681B0108D4AC6814F0D3 +:101BA00080545DD1FFF7BEFF204603B0F0BD012495 +:101BB0000B6804F1180C002BB8BFDB004FEA0C1CBB +:101BC000B4BF43F004035B0545F80C300B680FFA13 +:101BD00084FC13F0804F18BF05EB0C1E05EB0C1CAA +:101BE0001EBFDEF8803143F00203CEF880310B7B5C +:101BF000CCF8843105EB04158B68C5F88C314B6843 +:101C0000C5F88831DCF8803143F00103CCF880312D +:101C100000EB441541F268031D4403EB44130344F5 +:101C2000C5E9002608330D4601F10C0C55F804EB0C +:101C300043F804EB6545F9D184342D881D8000EB11 +:101C4000441407F00303257925F00B052B4323717A +:101C5000FFF768FF0097334600F0E2FC0120A4E79D +:101C60000224A5E74FF0FF309FE7000013B500F511 +:101C700080540191E06DFFF74BFE1F280AD90199AE +:101C8000E06D2022FFF7BAFEA0F120035842584130 +:101C900002B010BD0020FBE708B500F58050FFF74B +:101CA0003BFFC06DFFF708FEBDE80840FFF73ABFF5 +:101CB00000220260828142608260704710B500227B +:101CC0000023C0E900230023044603810C30FFF702 +:101CD000EFFF204610BD0000F0B5054600F580502E +:101CE0000C4690F8C83013F0040FC3F3800108BF0E +:101CF000114661F3820304F1840680F8C83005EBD5 +:101D0000461389B01B79D8072ED57AB319072DD47D +:101D10006846FFF7D3FF05EB441303F5835303F144 +:101D2000180703AA103318685968144603C4083307 +:101D3000BB422246F7D1186820609B88A380DDE96A +:101D40000E23CDE900230123ADF808302B68694646 +:101D5000DB6B2846984705EB46152B791A075CBFC5 +:101D600043F008032B7101E0002AF4D109B0F0BD63 +:101D70002DE9F047074688B007F5805468469A4633 +:101D80008846FFF7C9FE9146FFF798FFE06DFFF721 +:101D9000A5FD1F2829D9E06D20226946FFF7B0FE76 +:101DA000202822D103AD444605AB2E4603CE9E42E9 +:101DB00020606160354604F10804F6D13068206087 +:101DC000B388A380DDE90023C9E90023BDF808300A +:101DD000AAF80030FFF7A6FE4A4653464146384669 +:101DE00008B0BDE8F04700F009BCFFF79BFE0020FB +:101DF00008B0BDE8F08700002DE9F84F0023C0E9E6 +:101E00000133254B044640F8183B0F46FFF750FFBF +:101E100004F12800FFF752FF04F1480804F5825549 +:101E20004646083530462036FFF748FFAE42F9D126 +:101E300004F580554FF480534FF00009C5E913397C +:101E4000C5F848800123EE6504F5875804F58456EB +:101E5000C5F8549085F8583085F86030083608F198 +:101E600008084FF0000A4FF0000B46E908ABA6F156 +:101E70001800FFF71DFF203646F8289C4645F4D190 +:101E800085F8C97017B1054800F0A2FB044B6361E7 +:101E90002046BDE8F88F00BF7C4700085447000883 +:101EA0000064004010B5044B197804464A1C1A70AF +:101EB000FFF7A2FF204610BD143800202DE9F0479F +:101EC000002950D0294B2A4FB7FBF1F599428CBF1E +:101ED0000A231123581EB5FBF3FC03FB1C53C4B2A9 +:101EE0002BB102280346F5D80020BDE8F0870CF19D +:101EF000FF36B6F5806FF7D2C4EBC40E0EF10303C4 +:101F00004FEAE309C3F3C703A4EB030809F1010A8D +:101F10004FF47A755FFA88F009FB05555AFA88F88C +:101F2000B5FBF8F5B5F5617FC1BF0EF1FF33C3F323 +:101F3000C703E01AC0B25C1C50FA84F40CFB04F432 +:101F4000B7FBF4F4A142CFD1013BDBB20F2BCBD8CE +:101F50000138C0B20728C7D80021107116809170CF +:101F6000D3700120C1E70846BFE700BF3F420F0022 +:101F700000B4C40470B505460E464FF47A746B691C +:101F80005B6803F00103B34207D04FF47A7001F0AD +:101F9000B3FC013CF3D1204670BD0120FCE70000FA +:101FA00030B54269936913F0700F16D000230B4CC3 +:101FB000936103F1840200EB421211794D0709D5B8 +:101FC000890707D5416954F823508D60117941F094 +:101FD000040111710133032BEBD130BD68470008B8 +:101FE00073B51D46436916469A68D207044609D55B +:101FF0009A6801219960C2F34002CDE90065002191 +:10200000FFF76AFE63699A68D1050BD59A684FF4A9 +:1020100080719960C2F34022CDE90065012120461C +:10202000FFF75AFE63699A68D2030BD59A684FF49A +:1020300080319960C2F34042CDE90065022120461B +:10204000FFF74AFE204602B0BDE87040FFF7A8BF88 +:10205000F8B50446466900296CD106F10C073868CA +:1020600080076AD006EB01153868D5F8B00110F08A +:10207000040FD5F8B0011ABFC00840F00040400D71 +:10208000A061D5F8B0C11CF0020F1CBF40F0804029 +:10209000A061D5F8B40106EB011100F00F0084F83F +:1020A0002400D1F8B8012077D1F8B801000A607790 +:1020B000D1F8B801000CA077D1F8B801000EE07794 +:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 +:1020D0002100D1F8BC01000C84F82200D1F8BC1119 +:1020E000090E84F823103821396004F1340004F11A +:1020F000180104F1240551F8046B40F8046BA9425F +:10210000F9D109880180C4E90A23214600232386E6 +:1021100051F8283B2046DB6B984704F58052204657 +:1021200092F8C83043F0040382F8C830BDE8F840A4 +:10213000FFF736BF06F1100791E7F8BD10B504466A +:1021400000F04EFA02460B4652EA030102D0013A71 +:1021500063F100030449086820B12146BDE810403E +:10216000FFF776BF10BD00BF10380020F8B500F5AE +:1021700083511E46FFF7D0FCDFF844C0083100242D +:1021800004F1840500EB45152B795F070ED4DB06BF +:102190000CD5D1E900739742B34107D243695CF88B +:1021A00024709F602B7943F004032B710134032CBE +:1021B00001F12001E4D1BDE8F840FFF7B3BC00BF56 +:1021C0006847000808B5FFF7A7FCFFF7E9FEBDE880 +:1021D0000840FFF7A7BC0000F8B5436905469868BA +:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C +:1021F00093FC05F583541034002606F1840305EBA7 +:1022000043131B791A0706D50136032E04F1200467 +:10221000F3D1012007E05B07F6D42146384600F0F1 +:1022200039FA0028F0D1FFF77DFCF8BD0120FCE76A +:1022300000F5805008B5FFF76FFCC06DFFF74EFB4F +:10224000FFF770FC43090CBF0120002008BD00000F +:10225000F8B51D46002313700F4606461446FFF7D7 +:10226000E7FF80F00100387025B129463046FFF7BE +:10227000B3FF2070F8BD00002DE9B8410C461546AB +:102280001F46804600F0ACF90B462178024609B99A +:10229000287850B14046FFF769FFFFF793FF3B46B0 +:1022A0002A462146FFF7D4FF0120BDE8B88100008F +:1022B00010B5FFF731FC174B9A6D42F000729A652A +:1022C0009A6B42F000729A639A6B00F5805422F088 +:1022D00000729A63FFF726FC94F8C830DB0718D425 +:1022E000B9B103211320FFF717FC01F0DBF903213B +:1022F000142001F0D7F90321152001F0D3F994F847 +:10230000C83043F0010384F8C830BDE81040FFF73F +:1023100009BC10BD001002402DE9F04700F58055C2 +:1023200088B095F8C930012B0446884616467FD8F8 +:10233000804F57F823200AB947F82300D7F800A0A8 +:10234000C4F80C802674BAF1000F63D095F8C93038 +:10235000012B6FD001212046FFF7AAFFFFF7DCFB1E +:102360006269136823F0020313606269136843F023 +:1023700001031360636900275F6101212046FFF7B5 +:10238000D1FBFFF7F7FD002800F09580E86DFFF71F +:1023900093FA04F58359BA4609F10809202200216D +:1023A0006846FEF7C1FF02A8FFF782FCCDF818A02F +:1023B0006A4609EB07030DF1180E9446BCE80300CA +:1023C000F44518605960624603F10803F5D1DCF862 +:1023D0000000186020379CF804201A71602FDDD1AE +:1023E00095F8C8306FF38203002785F8C8306A4635 +:1023F00041462046ADF80070ADF802708DF80470CB +:10240000FFF75CFD636948BB4FF400421A6008B0F7 +:10241000BDE8F08741F2D00002F0BCF8814610B16F +:102420005146FFF7E9FCC7F80090B9F1000F8DD1D4 +:102430000020ECE7386803681B6B984701460028CA +:1024400088D13868FFF734FF3868036832465B6824 +:102450004146984700287FF47DAFE9E761221A6082 +:102460009DF802309DF803201B06120402F470222E +:1024700003F040731343BDF80020C2F30902134375 +:102480009DF804201205022E02F4E0020CBF4FF06A +:1024900000410021134362690B43D3616369132236 +:1024A0005A616269136823F00103136039462046BC +:1024B000FFF760FD08B96369A6E795F8C93093BBDB +:1024C0006169D1F8002242F00102C1F8002261697D +:1024D000D1F8002222F47C5222F00E02C1F8002230 +:1024E0006169D1F8002242F46062C1F80022626999 +:1024F000C2F814326269C2F80432626941F6FF71AF +:10250000C2F80C126269C2F840326269C2F8443201 +:1025100063690122C3F81C226269D2F8003223F0F9 +:102520000103C2F8003295F8C83043F0020385F881 +:10253000C8306CE71038002008B500F051F850EAB8 +:102540000103024602D0421E61F10001044B1868EB +:1025500010B10B46FFF744FDBDE8084001F064B838 +:102560001038002008B50020FFF7E8FDBDE808405E +:1025700001F05AB808B50120FFF7E0FDBDE80840BA +:1025800001F052B800B59BB0EFF3098168226846AC +:10259000FEF7B8FEEFF30583014B9B6BFEE700BF30 +:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF +:1025B000EFF3098168226846FEF7A4FEEFF3058376 +:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 +:1025D0000FB408B5029801F025F9FEE701F016BC2A +:1025E00001F0EEBB13B56C4684E80600031D94E8C9 +:1025F000030083E80500012002B010BD73B58568B3 +:10260000019155B11B885B0707D4D0E900369B6B5D +:102610009847019AC1B23046A847012002B070BD68 +:10262000F0B5866889B005460C465EB1BDF8383015 +:102630005B070AD4D0E900379B6B98472246C1B2AA +:102640003846B047012009B0F0BD00220023CDE993 +:1026500000230023ADF808300A4603AB01F1080659 +:10266000106851681C4603C40832B2422346F7D1B1 +:10267000106820609288A280FFF7B2FF0423ADF8B3 +:1026800008302B68CDE90001DB6B69462846984786 +:10269000D8E7000030B503680968DD0FB5EBD17FDE +:1026A00023F0604421F060424FEAD1700BD0002B40 +:1026B000B8BFA40C0029B8BF920C944202D034BF1A +:1026C0000120002030BD944205D1C1F38070C3F3D6 +:1026D00080738342F6D194422CBF00200120F1E7A1 +:1026E0002DE9F041456A15B94162BDE8F0814B68BA +:1026F00023F06047C3F38A464FEAD37EC3F3807862 +:1027000016EA230638BF3E46AC462B465A68BEEB57 +:10271000D27F22F060440AD0002A18DAA40CB44216 +:1027200017D19D420FD10D60DEE71346EEE7A742B9 +:1027300007D102F08044C2F3807242450BD054B1FD +:10274000EFE708D2EDE7CCF800100B60CDE7B4421C +:1027500001D0B442E5D81A689C46002AE5D1196038 +:10276000C3E700002DE9F047089D01F007044FEA98 +:10277000D508224405F0070500EBD1004FF47F494E +:10278000944201D1BDE8F08704F0070705F0070A7D +:1027900057453E4638BF5646C6F10806111B8E42C5 +:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 +:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 +:1027C00047FA0AF739408CEA010C03F80EC034448A +:1027D0003544D5E780EA0120082341F2210201B205 +:1027E0004000002980B203F1FF33B8BF504013F01E +:1027F000FF03F4D17047000038B50C468D18A54290 +:1028000000D138BD14F8011BFFF7E4FFF7E7000023 +:1028100042684AB1136843604389818901339BB29E +:102820009942438138BF83811046704770B588B0A4 +:10283000202204460D4668460021FEF775FD20461D +:102840000495FFF7E5FF024658B16B46054608AE12 +:102850001C4603CCB44228606960234605F1080594 +:10286000F6D1104608B070BD082817D909280CD039 +:102870000A280CD00B280CD00C280CD00D280CD01A +:102880000E2814BF4020302070470C2070471020C5 +:1028900070471420704718207047202070470000B0 +:1028A000082817D90C280CD910280CD914280CD9B1 +:1028B00018280CD920280CD930288CBF0F200E20C6 +:1028C0007047092070470A2070470B2070470C2082 +:1028D00070470D20704700002DE9F843078C072F43 +:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 +:1028F0002006A5F1200029FA05F108FA06F628FAC3 +:1029000000F031430143C9B21846FFF763FF0835B1 +:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 +:102920006BBF4FF6FF70BDE8F883000010B54B6831 +:1029300023B9CA8A63F30902CA8210BD04691A68FE +:102940001C600361C38A013BC3824A60EFE7000059 +:102950002DE9F84F1D46CB8A0F46C3F3090105291F +:10296000814692460B4630D00020AAB207F11A04E5 +:102970009EB2042E1FFA80F80FD8904503F1010390 +:1029800006D3FB8A0A4462F30903FB8201201AE0A2 +:102990001AF80060E6540130EAE79045F1D2A1F15F +:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 +:1029B0008BF6002C45D14846FFF72AFF044638B96C +:1029C00078606FF00200BDE8F88F4FF00008E6E78E +:1029D000002606607860ADB24FF0000B454510D977 +:1029E0000AEB0803221D13F8011B9155B1B208F13F +:1029F00001081B291FFA88F82BD0454506F101066E +:102A0000F1D8FB8AC3F30902154465F30903BCE757 +:102A1000013292B21C462368002BF9D16B1F0B4484 +:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 +:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 +:102A4000BFE70122E7E7C0F800B05E462060044619 +:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 +:102A6000AFE7C0F800B0002620600446B6E70000DB +:102A70002DE9F04F2DED028B1C4683B05B6901926E +:102A800007468846002B00F09A80238C2BB1E26920 +:102A9000002A00F09480072B35D807F10C00FFF7CF +:102AA000B7FE054638B96FF00205284603B0BDEC05 +:102AB000028BBDE8F08F14220021FEF735FC228C3A +:102AC000E16905F10800FEF71DFC208C013080B2A1 +:102AD000FFF7E6FEFFF7C8FE013880B22084013020 +:102AE00028746369228C1B782A4403F01F0363F067 +:102AF0003F0348F000411372384669602946FFF7EA +:102B0000EFFD0125D1E700F10C034FF0000908EEBD +:102B1000103A4FF0800A4E464D4618EE100AFFF765 +:102B200077FE83460028BED014220021FEF7FCFB6E +:102B3000002E3AD1019BABF8083002220BF1080EAF +:102B40001FFA82FC0CF10100BCF1060F218C80B24F +:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 +:102B60001278013802F01F028E4208BF4FF0400A6F +:102B700042EA49121BFA80F14AEA020A013048F09F +:102B8000004281F808A08BF81000CBF804205946C9 +:102B90003846FFF7A5FD238C0135B3422DB289F0ED +:102BA00001094FF0000AB8D17FE70022C6E7E169CA +:102BB000895D0EF802100136B6B20132C0E76FF03F +:102BC000010572E7F8B515460E463022002104468D +:102BD0001F46FEF7A9FB069B6360B5F5001F079B28 +:102BE000A76034BF6A094FF6FF72A36297B2E6612D +:102BF00004F1100000239A4206D800230360A78244 +:102C0000E3822383E360F8BD06600133304620365B +:102C1000F1E7000003781BB94BB2002BC8BF01706D +:102C20007047000000787047F8B50C46C969074640 +:102C300011B9238C002B37D1257E1F2D34D838783D +:102C400028BB228C072A2CD8268A36F003032BD1E6 +:102C50004FF6FF70FFF7D0FD20F001003102400475 +:102C600041EA0561400C41EA40254FF6FF722346D8 +:102C700029463846FFF7FCFE002807DD6269137815 +:102C80000133DBB21F2B88BF00231370F8BD218AEC +:102C90002D0645EA012505432046FFF71DFE0246A5 +:102CA000E5E76FF00300F1E76FF00100EEE70000E9 +:102CB00070B58AB0044616460021282268461D4693 +:102CC000FEF732FBBDF83830ADF810300F9B05939E +:102CD0009DF840308DF81830119B07936946BDF878 +:102CE0004830ADF820302046CDE90265FFF79CFF63 +:102CF0000AB070BD2DE9F041D36905460C46164671 +:102D00000BB9138C5BBB377E1F2F28D895F800803A +:102D1000B8F1000F26D03046FFF7DEFD33782102F0 +:102D200041EAC33141EA0801338A41EA076141EAD5 +:102D300003410246334641F080012846FFF798FEE2 +:102D400000280ADD3378012B07D17269137801332B +:102D5000DBB21F2B88BF00231370BDE8F0816FF03A +:102D60000100FAE76FF00300F7E70000F0B58BB061 +:102D700004460D4617460021282268461E46FEF7E7 +:102D8000D3FA9DF84C305A1E534253418DF800300F +:102D90009DF84030ADF81030119B05939DF84830F8 +:102DA0008DF81830149B07936A46BDF85430ADF87F +:102DB000203029462046CDE90276FFF79BFF0BB075 +:102DC000F0BD0000406A00B104307047436A1A68E1 +:102DD000426202691A600361C38A013BC382704781 +:102DE0002DE9F041D0F82080194E14461D46414689 +:102DF000002709B9BDE8F081D1E90223A21A65EBE9 +:102E00000303964277EB03031ED2036A8B420DD174 +:102E1000FFF78CFD036A1B68036203690B60C38ABA +:102E20000161016A013BC3828846E2E7FFF77EFD4C +:102E30000B68C8F8003003690B60C38A0161013B6D +:102E4000C382D8F80010D4E788460968D1E700BFEC +:102E500080841E002DE9F04F8BB00D46DDF85090B8 +:102E600014469B468046002800F01981B9F1000FF6 +:102E700000F01581531E3F2B00F21181012A03D16E +:102E8000BBF1000F40F00B810023CDE90833B8F807 +:102E90001430B5EBC30F4FEAC30703D300200BB0C8 +:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A +:102EB000FFB227461BB9D8F81030002B7AD0272D47 +:102EC0004ED8C5F12806B7424FF000032CBFF6B22A +:102ED0003E4600932946D8F8080008AB3246FFF773 +:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 +:102EF00003F10053053BDB000493D8F80C30039337 +:102F00002821039B13B1BAF1000F2CD1D8F810007F +:102F100040B1BAF1000F05D0009608AB5246691ACD +:102F2000FFF720FC38B2002FB8D066070AD00AABF2 +:102F300003EBD401624211F8083C02F0070213418E +:102F400001F8083C082C3CD9102C40F2B580202C0C +:102F500040F2B780BBF1000F00F09C80082334E002 +:102F6000BA460026C2E7049BE02B28BFE023069365 +:102F70000B44AB42059314D95A1B03980096924513 +:102F800034BF5246D2B2691A08AB04300792FFF739 +:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 +:102FA0008AFA049B069A05999B1A0493039B1B6853 +:102FB0000393A6E70093D8F8080008AB3A462946E1 +:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD +:102FD000082C12D89DF82030621E23FA02F2D50781 +:102FE00006D54FF0FF3202FA04F423438DF8203067 +:102FF0009DF8203089F8003051E7102C12D8BDF828 +:103000002030621E23FA02F2D10706D54FF0FF32BC +:1030100002FA04F42343ADF82030BDF82030A9F8BB +:1030200000303CE7202C0FD80899631E21FA03F3E7 +:10303000DA0705D54FF0FF3202FA04F40C43089486 +:10304000089BC9F800302AE7402C2BD0DDE9086541 +:10305000611EC4F12102A4F1210326FA01F105FA4F +:1030600002F225FA03F311431943CB0712D50122CB +:10307000A4F12003C4F1200102FA03F322FA01F1C2 +:10308000A240524243EA010363EB430332432B4322 +:10309000CDE90823DDE90823C9E90023FFE66FF045 +:1030A0000100FCE66FF00800F9E6082CA0D9102C0E +:1030B000B3D9202CEED8C3E7BBF1000FADD002236B +:1030C00083E7BBF1000FBBD004237EE730B5012AB4 +:1030D000144638BF0124402C85B028BF4024002569 +:1030E000012ACDE9025518D81B788DF808306307FE +:1030F0000AD004AB03EBD405624215F8083C02F099 +:103100000702934005F8083C00910346224600213F +:1031100002A8FFF727FB05B030BD082AE4D9102A22 +:1031200003D81B88ADF80830E1E7202A8DBFD3E92A +:1031300000231B680293CDE90223D8E710B5CB68C2 +:103140001BB98B600B618B8210BD04691A681C600F +:103150000361C38A013BC382CA60F0E703064CBF28 +:10316000C0F3C0300220704708B50246FFF7F6FFF3 +:10317000022806D15306C2F30F2001D100F003004C +:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E +:1031900003230A6804461046FFF7E0FF022814BF25 +:1031A000C2F306260026002A0D46824680F2F281EE +:1031B00012F0C04940F0EE81097B002900F0EA815D +:1031C000022803D02378B34240F0E781C2F30463BE +:1031D0000693104602F07F030593FFF7C5FF059B9A +:1031E00029444FEA834848EA0A4848EA4668CE78C4 +:1031F00000230022CDE90823F309834648EA0008AA +:10320000029367D0059B009302466768534608A95E +:103210002046B847002800F0C381276A4FB94146CD +:1032200004F10C00FFF702FB074690B96FF00200B3 +:1032300054E03B6998450DD03F68002FF9D14146D5 +:1032400004F10C00FFF7F2FA07460028EED0236ADB +:103250003B60276297F817C006F01F08CCF3840C78 +:10326000ACEB08001FFA80FE0028B8BF0EF120006A +:10327000A8EB0C031FFA83FED7E90221B8BF00B206 +:10328000002B0793BEBF0EF120031BB2079352EA37 +:10329000010338D0039BDFF824E39A1A049B4FF014 +:1032A000000C63EB010196457CEB01032BD36B7B98 +:1032B00097F81AE0734519D1029B002B78D00128AA +:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF +:1032D00016D337E0276A27B96FF00C0013B0BDE8AA +:1032E000F08F3B699845B5D03F68F4E7B24890420B +:1032F0007CEB010301D30020F0E7029B002BFAD006 +:10330000079B0F2B17DCFA7DB30002F0030203F0DA +:103310007C031343FB7539462046FFF707FB6B7BA5 +:10332000BB76029B3BB9FB7DC3F38402013262F39F +:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A +:10334000002B35D0B309022B32D0039BBB60049B0A +:10335000FB60142200210DA8FDF7E6FF039B0A93F2 +:10336000049B0B932B1D0C932B7BADF83EB0013BC4 +:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 +:10338000433094F82C308DF840A083F001038DF881 +:1033900044308DF84180A3680AA920469847FB7DF8 +:1033A000C3F38403013303F01F039B02FB82A2E7F4 +:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 +:1033C0008403434540F0F280029A2B7BB609002A21 +:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 +:1033E000049BFB602B7BAE1D033BDBB232463946B0 +:1033F00004F10C00FFF7ACFA00280CDA394620463D +:10340000FFF794FAFB7DC3F38403013303F01F033A +:103410009B02FB820AE7DDE90884AB883B834FF619 +:10342000FF73C9F12000A9F1200228FA09F104FA7A +:1034300000F0014324FA02F211431846C9B2FFF723 +:10344000C9F909F10809B9F1400F0346E9D1B88279 +:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 +:10346000DA43C2F3C01262F3C713FB7543E786B9B0 +:103470002E1D013BDBB23246394604F10C00FFF74A +:1034800067FA0028BADB2A7BB88A013AD2B2314601 +:10349000E2E7F98AC1F30901013B0429DAB25BD8FA +:1034A000281D002307F11B069A4208D910F801CB0A +:1034B00006F801C0013101330529DBB2F4D10399CB +:1034C0000A9104990B91934207F11B010C9138BFAB +:1034D000043379680D9134BF55FA83F300230E93BA +:1034E000FB8AADF83EB0C3F309031A44069B8DF87E +:1034F0004230059B8DF8433094F82C30ADF83C20D9 +:1035000083F001038DF8443000238DF840A08DF83E +:1035100041807B602A7BB88A013A291DFFF76CF94C +:103520003B8BB882834203D1A3680AA920469847FF +:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 +:10354000013303F01F039B02FB823B8B9A420CBFAB +:1035500000206FF01000C1E67B68002BAFD0052083 +:1035600001E01C3033461E68002EFAD1091A081DEE +:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 +:103580009DD89A429BD916F8013B00F8013B09F1FE +:103590000109EFE76FF00900A0E66FF00A009DE671 +:1035A0006FF00B009AE66FF00D0097E66FF00E00DB +:1035B00094E66FF00F0091E640420F0080841E00F9 +:1035C000EFF3098305494A6B22F001024A6368332D +:1035D00083F30988002383F31188704700EF00E02C +:1035E000302080F3118862B60C4B0D4AD96821F463 +:1035F000E0610904090C0A43DA60D3F8FC200949A8 +:1036000042F08072C3F8FC200A6842F001020A60AE +:103610002022DA7783F82200704700BF00ED00E037 +:103620000003FA05001000E010B5302383F3118881 +:103630000E4B5B6813F4006314D0F1EE103AEFF315 +:103640000984683C4FF08073E361094BDB6B2366B0 +:1036500084F3098800F0A4F810B1064BA36110BDF3 +:10366000054BFBE783F31188F9E700BF00ED00E0AD +:1036700000EF00E003060008060600084FF0E02314 +:10368000002258684FF0FF31930003F1604303F5C7 +:10369000614301329042C3F88010C3F88011F3D225 +:1036A0007047000000F1604303F561430901C9B2AE +:1036B00083F80013012200F01F039A4043099B0086 +:1036C00003F1604303F56143C3F880211A6070473A +:1036D00000230375826803691B6899689142FBD2D5 +:1036E0005A68036042601060586070470023037599 +:1036F000826803691B6899689142FBD85A68036025 +:10370000426010605860704708B50846302383F364 +:1037100011880B7D032B05D0042B0DD02BB983F31F +:10372000118808BD8B6900221A604FF0FF33836156 +:10373000FFF7CEFF0023F2E7D1E9003213605A60B1 +:10374000F3E70000FFF7C4BF054BD9680875186898 +:1037500002681A60536001220275D860FCF73CBF12 +:103760002038002030B50C4BDD684B1C87B0044678 +:103770000FD02B46094A684600F050F92046FFF763 +:10378000E3FF009B13B1684600F052F9A86907B047 +:1037900030BDFFF7D9FFF9E72038002009370008CE +:1037A000044B1A68DB6890689B68984294BF0020BD +:1037B0000120704720380020084B10B51C68D868DD +:1037C00022681A60536001222275DC60FFF78EFFC9 +:1037D00001462046BDE81040FCF7FEBE2038002020 +:1037E000044B1A68DB6892689B689A4201D9FFF71C +:1037F000E3BF70472038002038B5074C0749084818 +:10380000012300252370656000F000FC0223237073 +:1038100085F3118838BD00BF483A0020C047000832 +:103820002038002008B572B6044B186500F0B6FACF +:1038300000F06EFB024B03221A70FEE720380020D6 +:10384000483A002000F02AB9EFF3118020B9EFF3D5 +:103850000583302282F311887047000010B530B91B +:10386000EFF30584C4F3080414B180F3118810BD8C +:10387000FFF7B6FF84F31188F9E700008B6002239D +:1038800008618B82084670478368A3F1840243F87D +:10389000142C026943F8442C426943F8402C094A2D +:1038A00043F8242CC26843F8182C022203F80C2C8D +:1038B000002203F80B2C044A43F8102CA3F120003B +:1038C000704700BFF10500082038002008B5FFF759 +:1038D000DBFFBDE80840FFF735BF0000024BDB68A7 +:1038E00098610F20FFF730BF20380020302383F38A +:1038F0001188FFF7F3BF000008B50146302383F3BA +:1039000011880820FFF72EFF002383F3118808BDDC +:1039100010B503689C68A2420CD85C688A600B6092 +:103920004C602160596099688A1A9A604FF0FF33A1 +:10393000836010BD1B68121BECE700000A2938BF2A +:103940000A2170B504460D460A26601900F058FB9E +:1039500000F044FB041BA54203D8751C2E46044608 +:10396000F3E70A2E04D9BDE87040012000F08EBBB9 +:1039700070BD0000F8B5144B0D46D96103F110017C +:1039800041600A2A1969826038BF0A2201604860D2 +:103990001861A818144600F025FB0A2700F01EFB4A +:1039A000431BA342064606D37C1C281900F028FBC3 +:1039B00027463546F2E70A2F04D9BDE8F840012032 +:1039C00000F064BBF8BD00BF20380020F8B5064603 +:1039D0000D4600F003FB0F4A134653F8107F9F4239 +:1039E00006D12A4601463046BDE8F840FFF7C2BF7F +:1039F000D169BB68441A2C1928BF2C46A34202D9AE +:103A00002946FFF79BFF224631460348BDE8F840B0 +:103A1000FFF77EBF203800203038002010B4C0E906 +:103A2000032300235DF8044B4361FFF7CFBF000081 +:103A300010B5194C236998420DD0D0E90032816845 +:103A400013605A609A680A449A60002303604FF03A +:103A5000FF33A36110BD2346026843F8102F536063 +:103A60000022026022699A4203D1BDE8104000F0B2 +:103A7000C1BA936881680B44936000F0AFFA226981 +:103A8000E1699268441AA242E4D91144BDE81040A9 +:103A9000091AFFF753BF00BF203800202DE9F04777 +:103AA000DFF8BC8008F110072C4ED8F8105000F059 +:103AB00095FAD8F81C40AA68031B9A423ED81444D1 +:103AC000D5E900324FF00009C8F81C4013605A6075 +:103AD000C5F80090D8F81030B34201D100F08AFA4E +:103AE00089F31188D5E9033128469847302383F3B9 +:103AF00011886B69002BD8D000F070FA6A69A0EBCE +:103B000004094A4582460DD2022000F0BFFA002285 +:103B1000D8F81030B34208D151462846BDE8F047E6 +:103B2000FFF728BF121A2244F2E712EB090938BF47 +:103B30004A4629463846FFF7EBFEB5E7D8F810307D +:103B4000B34208D01444211AC8F81C00A960BDE88B +:103B5000F047FFF7F3BEBDE8F08700BF3038002024 +:103B60002038002000207047FEE70000704700006A +:103B70004FF0FF3070470000BFF34F8F024A1369C8 +:103B8000DB03FCD4704700BF0020024008B5094B9E +:103B90001B7873B9FFF7F0FF074B5A69002ABFBFC4 +:103BA000064A9A6002F188329A601A6822F48062AA +:103BB0001A6008BD603A00200020024023016745DA +:103BC00008B50B4B1B7893B9FFF7D6FF094B5A6921 +:103BD00042F000425A611A6842F480521A601A6830 +:103BE00022F480521A601A6842F480621A6008BD9A +:103BF000603A0020002002407F289ABF00F5803004 +:103C0000C0020020704700004FF4006070470000C1 +:103C1000802070477F2808B50BD8FFF7EDFF00F52F +:103C200000630268013204D104308342F9D10120DB +:103C300008BD0020FCE700007F2810B504461FD80F +:103C4000FFF79AFFFFF7A2FF0E4BF3221A61022241 +:103C50005A615A6942EAC0025A615A6942F4803292 +:103C60005A61FFF789FF4FF40061FFF7C5FF00F0CD +:103C70004BF9FFF7A5FF2046BDE81040FFF7CABF8C +:103C8000002010BD002002402DE9F84340EA020365 +:103C900013F00703144606D0304B40F231321A605D +:103CA0000020BDE8F88385182D4A95420CD92B4A8F +:103CB00040F236311160F3E7031D1B684A689342F6 +:103CC00008D1083C08300831072C14D902680B6869 +:103CD0009A42F1D0FFF75AFFFFF74EFF214E08310D +:103CE0004FF001084FF00009012CA1F1080706D898 +:103CF000FFF766FF01E0002CECD10120D1E7C6F808 +:103D00001480054651F8083C45F8043B51F8043C42 +:103D10004360FFF731FF336943F001033361C6F8B5 +:103D20001490026851F8083C9A420CD00B4B40F2B8 +:103D30005E321A600C4B18600C4B1C600C4B1F6001 +:103D4000FFF73EFFACE72D6851F8043C9D4201F1BE +:103D50000801EBD1083C0830C6E700BF5C3A002000 +:103D60000000040800200240503A0020583A002089 +:103D7000543A0020084908B50B7828B11BB9FFF761 +:103D800005FF01230B7008BD002BFCD0BDE80840E7 +:103D90000870FFF715BF00BF603A00204FF4803174 +:103DA0004FF0005000F0B2B80846114600F014BCC5 +:103DB000012000F011BC0000084600F02BBC000000 +:103DC00070B582B0FFF740FD0E4E054600F006F9D3 +:103DD0003268904237BF0C4A0B49516814682EBFB5 +:103DE000D1E90041013151600419034641F100015C +:103DF000284601913360FFF731FD0199204602B05A +:103E000070BD00BF643A0020683A002070B582B0EF +:103E1000FFF71AFD104E054600F0E0F832689042B8 +:103E200037BF0E4A0D49516814682EBFD1E90041D1 +:103E300001315160041941F1000103462846019106 +:103E40003360FFF70BFD01994FF47A72002320468F +:103E5000FCF7AEF902B070BD643A0020683A002069 +:103E600010B50244064BD2B2904200D110BD441CA2 +:103E700000B253F8200041F8040BE0B2F4E700BFB1 +:103E800050280040114B30B5D3F89040240409D499 +:103E9000D3F89040C3F89040D3F8904044F40044E5 +:103EA000C3F890400A4C236843F4807323600244B3 +:103EB000084BD2B2904200D130BD441C00B251F840 +:103EC000045B43F82050E0B2F4E700BF001002406A +:103ED000007000405028004007B5012201A90020D1 +:103EE000FFF7BEFF019803B05DF804FB13B504466D +:103EF000FFF7F2FFA04205D0012201A900200194A2 +:103F0000FFF7C0FF02B010BD70470000704700000F +:103F100070470000074B45F255521A6002225A6062 +:103F200040F6FF729A604CF6CC421A60024B0122B6 +:103F30001A70704700300040743A0020034B1B7821 +:103F40001BB1034B4AF6AA221A607047743A00204C +:103F500000300040054B1A6832B902F1804202F588 +:103F60000432D2F894201A60704700BF703A0020E3 +:103F7000024B4FF40002C3F8942070470010024037 +:103F800008B5FFF7E7FF024B1868C0F3407008BDA3 +:103F9000703A002070470000FEE700000A4B0B4813 +:103FA0000B4A90420BD30B4BDA1C121AC11E22F0A3 +:103FB00003028B4238BF00220021FDF7B5B953F848 +:103FC000041B40F8041BECE75C480008003B0020A1 +:103FD000003B0020003B002000F0BEB84FF08043C3 +:103FE000586A70474FF08043002258631A610222DA +:103FF000DA6070474FF080430022DA6070470000BB +:104000004FF0804358637047FEE7000070B51B4BCC +:1040100001630025044686B0586085620E46FFF7AE +:10402000DFFA04F11003C4E904334FF0FF33C4E9AD +:104030000635C4E90044A560E562FFF7CFFF2B46D3 +:104040000246C4E9082304F134010D4A25658023A2 +:104050002046FFF713FC0123E0600A4A0375009233 +:1040600072680192B268CDE90223074B6846CDE938 +:104070000435FFF72BFC06B070BD00BF483A0020A6 +:10408000CC470008D147000809400008024AD36A1B +:104090001843D062704700BF20380020244B2548C9 +:1040A000DA6A42F0070210B4DA62DA6A224C22F0CD +:1040B0000702DA62DA6ADA6C42F00702DA64DA6E70 +:1040C00042F00702DA664FF09042DB6E4FF0AA3101 +:1040D000002353609160D0604FF6FF70506113620F +:1040E000536214601024C2F80434C2F80814C2F8F1 +:1040F0000C444FF6F774C2F814449924C2F82034E3 +:10410000C2F824440D4CC2F80044C2F80438C2F886 +:104110000818C2F80C38C2F81408C2F82038C2F8DF +:104120002438C2F800385DF8044B00F055B800BFE1 +:1041300000100240000100240001002850000A0085 +:1041400008B500F005FAFFF757FBBDE80840FFF798 +:1041500001BF0000704700000F4B9A6D42F0010252 +:104160009A659A6F42F001029A670C4A9B6F9368B6 +:1041700043F0010393604FF080434F229A624FF067 +:10418000FF32DA6200229A615A63DA605A600122D1 +:104190005A611A60704700BF00100240002004E01E +:1041A0004FF0804208B51169D3680B40D9B2C943BA +:1041B0009B07116107D5302383F31188FFF742FB7A +:1041C000002383F3118808BD08B5FFF757FABDE84F +:1041D000084000F099B900005A4B4FF0FF319A6A3D +:1041E00099629A6A00229A62986AD86A60F0070017 +:1041F000D862D86A00F00700D862D86A186B1963D1 +:10420000186B1A63186B986B9963986B9A63986B29 +:10421000D86BD963D86BDA63D86B186C1964196CD6 +:104220001A641A6C484A4FF4E06111601A6E4749EB +:1042300042F001021A66D3F8802022F00102C3F88E +:104240008020D3F880209A6D42F080529A659A6F50 +:1042500022F080529A679A6F4FF440720A604A695E +:1042600012F48062FBD14A601A6822F0F00242F038 +:1042700060021A601A6842F001021A601A68910717 +:10428000FCD500229A609A6812F00C02FBD1D3F898 +:10429000901011F4407F1EBF4FF48031C3F890108E +:1042A000C3F8902061221A601A689207FCD5002298 +:1042B0009A609A6812F00C0FFBD169221A60D3F849 +:1042C000942022F4706242F4C062C3F894201A6809 +:1042D00042F480321A601A689003FCD5D3F890201B +:1042E00022F00322C3F89020194ADA601A6842F0DB +:1042F00080721A601A689101FCD5164A1A611A6810 +:1043000042F080621A601A681201FCD500229A609D +:104310000D49114AC3F888200A6822F0070242F0CA +:1043200004020A600A6802F00702042AFAD19A68B5 +:1043300042F003029A609A6802F00C020C2AFAD149 +:10434000704700BF00100240002002400070004093 +:1043500003140001000C100055550134074A08B53C +:10436000536903F00103536123B1054A13680BB18C +:1043700050689847BDE80840FFF756B9000401406F +:10438000783A0020074A08B5536903F002035361E5 +:1043900023B1054A93680BB1D0689847BDE808403F +:1043A000FFF742B900040140783A0020074A08B5F7 +:1043B000536903F00403536123B1054A13690BB138 +:1043C00050699847BDE80840FFF72EB90004014046 +:1043D000783A0020074A08B5536903F0080353618F +:1043E00023B1054A93690BB1D0699847BDE80840ED +:1043F000FFF71AB900040140783A0020074A08B5CF +:10440000536903F01003536123B1054A136A0BB1DA +:10441000506A9847BDE80840FFF706B9000401401C +:10442000783A0020164B10B55C6904F478725A6132 +:10443000A30604D5134A936A0BB1D06A9847600665 +:1044400004D5104A136B0BB1506B9847210604D565 +:104450000C4A936B0BB1D06B9847E20504D5094A1F +:10446000136C0BB1506C9847A30504D5054A936CA7 +:104470000BB1D06C9847BDE81040FFF7D5B800BF2E +:1044800000040140783A0020194B10B55C6904F42F +:104490007C425A61620504D5164A136D0BB1506D0A +:1044A0009847230504D5134A936D0BB1D06D9847F7 +:1044B000E00404D50F4A136E0BB1506E9847A10467 +:1044C00004D50C4A936E0BB1D06E9847620404D5A4 +:1044D000084A136F0BB1506F9847230404D5054A5F +:1044E000936F0BB1D06F9847BDE81040FFF79CB8B1 +:1044F00000040140783A002008B5FFF751FEBDE8FE +:104500000840FFF791B80000062108B50846FFF7FC +:10451000C9F806210720FFF7C5F806210820FFF794 +:10452000C1F806210920FFF7BDF806210A20FFF790 +:10453000B9F806211720FFF7B5F806212820FFF764 +:10454000B1F8BDE8084007211C20FFF7ABB8000018 +:1045500008B5FFF739FE00F007F8FFF7FBFDBDE8EF +:104560000840FFF739BD00000023054A1946013312 +:10457000102BC2E9001102F10802F8D1704700BF08 +:10458000783A00200B460146184600F02DB800008E +:1045900000F040B8012838BF012010B5044620467D +:1045A00000F030F830B900F007F808B900F00CF866 +:1045B0008047F4E710BD0000024B1868BFF35B8F23 +:1045C000704700BFF83A002008B5062000F084F8D4 +:1045D0000120FFF7C9FA0000024B0A46014618689D +:1045E000FFF7E2BB1811002010B5054C13462CB1A3 +:1045F0000A4601460220AFF3008010BD2046FCE7CA +:1046000000000000024B01461868FFF7D1BB00BF55 +:1046100018110020024B01461868FFF7CDBB00BF00 +:104620001811002010B501390244904201D1002038 +:1046300005E0037811F8014FA34201D0181B10BD0B +:104640000130F2E72DE9F041A3B1C91A177801440E +:10465000044603F1FF3C8C42204601D9002009E0CA +:104660000578BD4204F10104F5D10CEB0405D61820 +:10467000A54201D1BDE8F08115F8018D16F801EDD4 +:10468000F045F5D0E7E700001F2938B504460D4690 +:1046900004D9162303604FF0FF3038BD426C12B1CD +:1046A00052F821304BB9204600F030F82A46014636 +:1046B0002046BDE8384000F017B8012B0AD0591C3D +:1046C00003D1162303600120E7E7002442F82540C8 +:1046D000284698470020E0E7024B01461868FFF79C +:1046E000D3BF00BF1811002038B5074D0023044682 +:1046F000084611462B60FFF73BFA431C02D12B689A +:1047000003B1236038BD00BFFC3A0020FFF72ABA8E +:10471000034611F8012B03F8012B002AF9D1704749 +:104720006F72672E6172647570696C6F742E4D6163 +:1047300074656B4C3433312D5065726970680000BC +:1047400040A2E4F1646891060041A3E5F265699234 +:10475000070000004261642043414E496661636581 +:1047600020696E6465782E008000000000800000E3 +:10477000000080000000000000000000311B000865 +:104780001923000879220008411B0008751B000846 +:10479000711D0008451B0008551B0008491B000837 +:1047A000511B00084D1B0008991C0008591B0008EC +:1047B000E5250008691B00086D1C00086330000037 +:1047C000BC47000878380020483A00206D61696EC7 +:1047D0000069646C6500000008BAFF7F01000000FA +:1047E000260400000000000000600300000000003C +:1047F000FE2A0100D20400001C110020000000006D +:1048000000000000000000000000000000000000A8 +:104810000000000000000000000000000000000098 +:104820000000000000000000000000000000000088 +:104830000000000000000000000000000000000078 +:104840000000000000000000000000000000000068 +:0C4850000000000000000000000000005C :00000001FF diff --git a/Tools/bootloaders/MatekL431-Proximity_bl.bin b/Tools/bootloaders/MatekL431-Proximity_bl.bin new file mode 100755 index 00000000000000..ce388fb8439813 Binary files /dev/null and b/Tools/bootloaders/MatekL431-Proximity_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-RC_bl.bin b/Tools/bootloaders/MatekL431-RC_bl.bin new file mode 100755 index 00000000000000..49bf5329c25df3 Binary files /dev/null and b/Tools/bootloaders/MatekL431-RC_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-Rangefinder_bl.bin b/Tools/bootloaders/MatekL431-Rangefinder_bl.bin index dea889eabdb15e..bab890793634ce 100755 Binary files a/Tools/bootloaders/MatekL431-Rangefinder_bl.bin and b/Tools/bootloaders/MatekL431-Rangefinder_bl.bin differ diff --git a/Tools/bootloaders/MatekL431-bdshot_bl.bin b/Tools/bootloaders/MatekL431-bdshot_bl.bin new file mode 100755 index 00000000000000..5c422467a3ca09 Binary files /dev/null and b/Tools/bootloaders/MatekL431-bdshot_bl.bin differ diff --git a/Tools/bootloaders/MazzyStarDrone_bl.bin b/Tools/bootloaders/MazzyStarDrone_bl.bin new file mode 100755 index 00000000000000..921855185a4096 Binary files /dev/null and b/Tools/bootloaders/MazzyStarDrone_bl.bin differ diff --git a/Tools/bootloaders/Nucleo-G491_bl.bin b/Tools/bootloaders/Nucleo-G491_bl.bin index 36f66fcbb86ca4..f7939575c7a403 100755 Binary files a/Tools/bootloaders/Nucleo-G491_bl.bin and b/Tools/bootloaders/Nucleo-G491_bl.bin differ diff --git a/Tools/bootloaders/Nucleo-G491_bl.elf b/Tools/bootloaders/Nucleo-G491_bl.elf index 99fb29a55d46bc..8b3b6d6c5a9112 100755 Binary files a/Tools/bootloaders/Nucleo-G491_bl.elf and b/Tools/bootloaders/Nucleo-G491_bl.elf differ diff --git a/Tools/bootloaders/Nucleo-G491_bl.hex b/Tools/bootloaders/Nucleo-G491_bl.hex index fb3f3c4265061b..048444290b5b45 100644 --- a/Tools/bootloaders/Nucleo-G491_bl.hex +++ b/Tools/bootloaders/Nucleo-G491_bl.hex @@ -1,548 +1,1194 @@ :020000040800F2 -:1000000000060020E1010008490D0008C90C0008A5 -:10001000210D0008C90C0008F50C0008E3010008D8 -:10002000E3010008E3010008E3010008711A000879 -:10003000E3010008E3010008E3010008E301000810 -:10004000E3010008E3010008E3010008E301000800 -:10005000E3010008E30100084D1E0008751E0008BA -:100060009D1E0008C51E0008ED1E0008E3010008E3 -:10007000E3010008E3010008E3010008E3010008D0 -:10008000E3010008E3010008E3010008E3010008C0 -:10009000E3010008E3010008E3010008151F000860 -:1000A000E3010008E3010008E3010008E3010008A0 -:1000B000FD1F0008E3010008E3010008E301000858 -:1000C000E3010008E3010008E3010008E301000880 -:1000D000E3010008E91F0008E3010008E30100084C -:1000E000791F0008E3010008E3010008E3010008AC -:1000F000E3010008E3010008E3010008E301000850 -:10010000E3010008E3010008E3010008E30100083F -:10011000E3010008E3010008E3010008E30100082F -:10012000E3010008E3010008E3010008E30100081F -:10013000E3010008E3010008E3010008E30100080F -:10014000E3010008E3010008E3010008E3010008FF -:10015000E3010008E3010008E3010008E3010008EF -:10016000E3010008E3010008E3010008E3010008DF -:10017000E3010008E3010008E3010008E3010008CF -:10018000E3010008E3010008E3010008E3010008BF -:10019000E3010008E3010008E3010008E3010008AF -:1001A000E3010008E3010008E3010008E30100089F -:1001B000E3010008E3010008E3010008E30100088F -:1001C000E3010008E3010008E3010008E30100087F -:1001D000E3010008E3010008E3010008E30100086F -:1001E00002E000F000F8FEE772B63A4880F30888B3 -:1001F000394880F3098839484EF60851CEF200019B -:10020000086040F20000CCF200004EF63471CEF2ED -:1002100000010860BFF34F8FBFF36F8F40F2000003 -:10022000C0F2F0004EF68851CEF200010860BFF334 -:100230004F8FBFF36F8F4FF00000E1EE100A4EF6C4 -:100240003C71CEF200010860062080F31488BFF3F1 -:100250006F8F01F08DFC01F069FC01F0B3FC4FF0F1 -:1002600055301F491B4A91423CBF41F8040BFAE745 -:100270001C49194A91423CBF41F8040BFAE71A495C -:100280001A4A1B4B9A423EBF51F8040B42F8040B2A -:10029000F8E700201749184A91423CBF41F8040B87 -:1002A000FAE701F047FC01F0D3FC144C144DAC42CA -:1002B00003DA54F8041B8847F9E700F041F8114CC1 -:1002C000114DAC4203DA54F8041B8847F9E701F0FA -:1002D0002FBC0000000600200022002000000008C3 -:1002E0000000002000060020F82100080022002065 -:1002F000202200202022002008280020E001000801 -:10030000E0010008E0010008E00100082DE9F04FDD -:100310002DED108AC1F80CD0C3689D46BDEC108A43 -:10032000BDE8F08F002383F311882846A047002002 -:1003300001F020F9FEE701F0A5F800DFFEE700007C -:1003400038B501F063FB054601F088FB0446D0B9DF -:100350000F4B9D4219D001339D420DBF00254FF434 -:100360007A7504460124002001F05AFB0CB100F01C -:1003700057F800F089FC00F07FFB284600F0A0F859 -:1003800000F04EF8F9E70025EDE70546EBE700BF82 -:10039000010007B008B500F041FBA0F1200358426E -:1003A000584108BD07B541F21203022101A8ADF87A -:1003B000043000F051FB03B05DF804FB10B52023BE -:1003C00083F311881248C3680BB101F04BF9114A4D -:1003D0000F4800234FF47A7101F008F9002383F3EA -:1003E00011880D4C236813B12368013B23606368B7 -:1003F00013B16368013B6360084B1B7833B96368D2 -:1004000023B9022000F0D6FB3223636010BD00BF89 -:1004100020220020BD0300083C23002034220020BD -:1004200038B5214A214B196801313CD0043393423D -:10043000F9D11F4C1D4DD4F80428AA4233D31D4BCB -:100440009B6803F1006303F5F0439A422BD200202E -:1004500000F02CFB184B0220187000F0A3FB174B88 -:100460009A6D00229A65996F9A67996FD96DDA65CE -:10047000D96FDA67D96F196E1A66D3F88010C3F88E -:100480008020D3F8803072B64FF0E0232021C3F8EB -:10049000085DD4F80038D4F8042881F311889D460B -:1004A00083F30888104738BD2078000800780008DA -:1004B00000700008002200203422002000100240BA -:1004C0002DE9F04F93B0A94B00902022FF210AA8FC -:1004D0009D6800F083FBA64A1378A3B9A5480121C3 -:1004E000C3601170202383F31188C3680BB101F03E -:1004F000B9F8A14A9F4800234FF47A7101F076F8C9 -:10050000002383F31188009B9C4A03B113609C492C -:10051000009C00230B70536098469B461E469A46EB -:10052000012000F03FFB24B1944B1B68002B00F02E -:100530001682002000F072FA0390039B002BF2DB7E -:10054000012000F027FB039B213B162BE8D801A2DA -:1005500052F823F0B1050008D90500086D0600081F -:1005600021050008210500082105000801070008F1 -:10057000D3080008ED0700084F08000877080008B6 -:100580009D08000821050008AF08000821050008A3 -:100590002109000851060008210500086509000826 -:1005A000BD05000851060008210500084F08000895 -:1005B0000220FFF7EFFE002840F0FB81009B0221A4 -:1005C000B8F1000F08BF1C4605A841F21233ADF880 -:1005D000143000F041FAA3E74FF47A7000F01EFAED -:1005E000071EEBDB0220FFF7D5FE0028E6D0013F17 -:1005F000052F00F2E081DFE807F0030A0D10133643 -:1006000005230593042105A800F026FA17E05748B2 -:100610000421F9E75B480421F6E75B480421F3E78E -:100620004FF01C09484600F043FA09F1040905900F -:10063000042105A800F010FAB9F12C0FF2D1012025 -:1006400000FA07F747EA0B0B5FFA8BFB4FF0000A43 -:1006500000F010FB26B10BF00B030B2B08BF00249E -:10066000FFF7A0FE5CE749480421CDE7002EA5D0A6 -:100670000BF00B030B2BA1D10220FFF78BFE0746DB -:1006800000289BD001203E4E00F010FA022030706E -:1006900000F088FA4FF000085FFA88F9484600F049 -:1006A00017FA044690B1484600F022FA08F1010812 -:1006B0000028F1D1B846044641F21213022105A8E0 -:1006C000ADF814303E4600F0C7F929E701230220B7 -:1006D000337000F05FFA2546244B9B68AB4207D984 -:1006E000284600F0E5F9013040F068810435F3E771 -:1006F000234B00251D70214BB8465D603E46A7E7A1 -:10070000002E3FF45BAF0BF00B030B2B7FF456AFC7 -:100710001B4B0220187000F045FA322000F07EF9E1 -:10072000B0F10009FFF64AAF19F003077FF446AFB6 -:100730000E4A926809EB050393423FF63FAFB9F5C5 -:10074000807F3FF73BAF124B0193B94522DD4FF459 -:100750007A7000F063F90390039A002AFFF62EAF37 -:10076000019B039A03F8012B0137EDE700220020DB -:100770003823002020220020BD0300083C23002055 -:100780003422002004220020082200200C22002015 -:1007900038220020C820FFF7FDFD074600283FF45F -:1007A0000DAF1F2D11D8C5F120024A450AAB25F027 -:1007B000030028BF4A4683490192184400F004FA16 -:1007C000019A8048FF2100F009FA4FEAA9037D4908 -:1007D0000193C9F38702284600F008FA064600286C -:1007E0003FF46AAF019B05EB830531E70220FFF779 -:1007F000D1FD00283FF4E2AE00F096F900283FF466 -:10080000DDAE0027B946704B9B68BB4218D91F2F3D -:1008100011D80A9B01330ED027F0030312AA134408 -:1008200053F8203C05934846042205A900F08EFAAF -:1008300004378146E7E7384600F03AF90590F2E7D9 -:10084000CDF81490042105A800F006F900E7002374 -:10085000642104A8049300F0F5F800287FF4AEAEFC -:100860000220FFF797FD00283FF4A8AE049800F09F -:1008700051F90590E6E70023642104A8049300F0F1 -:10088000E1F800287FF49AAE0220FFF783FD0028EC -:100890003FF494AE049800F03FF9EAE70220FFF736 -:1008A00079FD00283FF48AAE00F04EF9E1E702201E -:1008B000FFF770FD00283FF481AE05A9142000F079 -:1008C00049F904210746049004A800F0C5F8394608 -:1008D000B9E7322000F0A2F8071EFFF66FAEBB07A3 -:1008E0007FF46CAE384A926807EB0A0393423FF6F6 -:1008F00065AE0220FFF74EFD00283FF45FAE27F003 -:1009000003075744BA453FF4A3AE504600F0D0F871 -:100910000421059005A800F09FF80AF1040AF1E708 -:100920004FF47A70FFF736FD00283FF447AE00F031 -:10093000FBF8002844D00A9B01330BD008220AA9F7 -:10094000002000F053F900283AD02022FF210AA805 -:1009500000F044F9FFF726FD1C4800F011FE13B02B -:10096000BDE8F08F002E3FF429AE0BF00B030B2BEC -:100970007FF424AE0023642105A8059300F062F8FB -:10098000074600287FF41AAE0220FFF703FD8146D8 -:1009900000283FF413AEFFF705FD41F2883000F068 -:1009A000EFFD059800F07CF94E4600F063F93C46F7 -:1009B000B6E506464CE64FF0000AFFE5B8467BE692 -:1009C000374679E63822002000220020A086010068 -:1009D00070B50F4B1B780133DBB2012B0C4611D8DD -:1009E0000C4D29684FF47A730E6AA2FB033201465C -:1009F00022462846B047844204D1074B00221A7091 -:100A0000012070BD4FF4FA7000F0BAFD0020F8E745 -:100A1000102200208C2300208823002007B500230B -:100A2000024601210DF107008DF80730FFF7D0FFD6 -:100A300020B19DF8070003B05DF804FB4FF0FF30D4 -:100A4000F9E700000A4608B50421FFF7C1FF80F06E -:100A50000100C0B2404208BD30B4054C2368DD69D6 -:100A6000044B0A46AC460146204630BC604700BFF6 -:100A70008C230020A086010070B500F0B9FE094E5D -:100A8000094D3080002428683388834208D900F05B -:100A9000ABFE2B6804440133B4F5F04F2B60F2D366 -:100AA00070BD00BF8A2300204423002000F060BFF7 -:100AB00000F1006000F5E040D0F800087047000049 -:100AC00000F10060920000F5F04000F0D5BE00009B -:100AD000054B1A68054B1B889B1A834202D91044A8 -:100AE00000F082BE00207047442300208A230020AB -:100AF00038B5074D04462868204400F07BFE28B92D -:100B000028682044BDE8384000F086BE38BD00BFEC -:100B1000442300200020704700F10050A0F5104051 -:100B2000D0F8900570470000064991F8243033B1A1 -:100B30000023086A81F824300822FFF7C1BF012092 -:100B4000704700BF48230020014B1868704700BF62 -:100B5000002004E070B50E4B5C6893F90860421EFB -:100B60000A44013C0B46934207D214F9015F581C1A -:100B70002DB100F8015C0346F5E7184605E02C248A -:100B800082421C7001D9981C5E70401A70BD00BF73 -:100B900014220020022802BF4FF0904320229A61C5 -:100BA00070470000022802BF4FF090434FF400123C -:100BB0009A617047022801BF4FF09042536983F059 -:100BC000200353617047000010B50023934203D007 -:100BD000CC5CC4540133F9E710BD00000244034665 -:100BE000934202D003F8011BFAE770472DE9F8435E -:100BF0001F4D144695F824200746884652BBDFF85F -:100C000070909CB395F824302BB92022FF214846E0 -:100C10002F62FFF7E3FF95F82400C0F10802A2421B -:100C200028BF2246D6B24146920005EB8000FFF76E -:100C3000CBFF95F82430A41B1E44F6B2082E1744AF -:100C40009044E4B285F82460DBD1FFF76DFF002803 -:100C5000D7D108E02B6A03EB82038342CFD0FFF7A2 -:100C600063FF0028CBD10020BDE8F8830120FBE71B -:100C700048230020024B1A78024B1A70704700BFBD -:100C80008823002010220020034904484FF4E13358 -:100C90000B6000F01BBB00BF702300208C230020E2 -:100CA000074B10B50021044618221846FFF796FF9F -:100CB00004600146BDE81040024800F007BB00BFD9 -:100CC000702300208C23002000B59BB0EFF3098136 -:100CD00068226846FFF778FFEFF30583044B9A6BB1 -:100CE000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE7C2 -:100CF00000ED00E000B59BB0EFF309816822684683 -:100D0000FFF762FFEFF30583044B9A6B9A6A9A6AC6 -:100D10009A6A9A6A9A6A9B6AFEE700BF00ED00E051 -:100D200000B59BB0EFF3098168226846FFF74CFFDE -:100D3000EFF30583034B5A6B9A6A9A6A9A6A9A6A26 -:100D40009B6AFEE700ED00E0FEE7000030B5094DCC -:100D50000A4491420DD011F8013B5840082340F35A -:100D60000004013B2C4013F0FF0384EA5000F6D14D -:100D7000EFE730BD2083B8ED02684368114301609E -:100D800003B1184770470000024A136843F0C003DC -:100D9000136070470038014013B50E4C204600F038 -:100DA00089FA04F114000C49009400234FF4807276 -:100DB00000F04AF9094B0A4900944FF4807204F19B -:100DC000380000F0C3F9074A074BC4E9172302B003 -:100DD00010BD00BF8C230020F8230020890D0008DF -:100DE000F824002000380140007A030A30B5037C63 -:100DF000234C002918BF0C46012B0FD1214B9842E0 -:100E00000CD1214B1A6E42F480421A66D3F880202E -:100E100042F48042C3F88020D3F880302268036E09 -:100E2000C16D846603EB5203B3FBF2F362681504F1 -:100E300042BF23F0070503F0070343EA4503CB60F5 -:100E4000A36843F040034B60E36843F001038B6009 -:100E500042F4967343F001030B604FF0FF330B62D3 -:100E6000510505D512F0102205D0B2F1805F04D0F3 -:100E700080F8643030BD7F23FAE73F23F8E700BFF6 -:100E8000CC2000088C230020001002402DE9F04700 -:100E9000C66D3768F46934622107054618D014F02E -:100EA000080118BF8021E20748BF41F02001A307D5 -:100EB00048BF41F04001600748BF41F480712023E2 -:100EC00083F31188281DFFF757FF002383F3118850 -:100ED000E2050AD5202383F311884FF40071281D01 -:100EE000FFF74AFF002383F311884FF020094FF0EA -:100EF000000A14F0200838D13B0616D54FF020091F -:100F000005F1380A200610D589F31188504600F003 -:100F100051F9002836DA0821281DFFF72DFF27F0A8 -:100F200080033360002383F31188790614D56206A9 -:100F300012D5202383F31188D5E913239A4208D1CF -:100F40002B6C33B11021281D27F04007FFF714FF49 -:100F50003760002383F31188E30618D5AA6E13695E -:100F6000ABB1BDE8F0475069184789F31188736A3F -:100F700095F864102846194000F0B6F98AF31188F4 -:100F8000F469B6E7B06288F31188F469BAE7BDE89E -:100F9000F0870000F8B5154682680669AA420B463C -:100FA000816938BF8568761AB54204460BD2184667 -:100FB0002A46FFF709FEA3692B44A361A3685B1BC4 -:100FC000A3602846F8BD0CD918463246FFF7FCFD51 -:100FD000AF1BE1683A463044FFF7F6FDE3683B4457 -:100FE000EBE718462A46FFF7EFFDE368E5E7000068 -:100FF00083689342F7B51546044638BF8568D0E943 -:101000000460361AB5420BD22A46FFF7DDFD63694C -:101010002B446361A36828465B1BA36003B0F0BD4B -:101020000DD932460191FFF7CFFD0199E068AF1B62 -:101030003A463144FFF7C8FDE3683B44E9E72A46F6 -:10104000FFF7C2FDE368E4E710B50A440024C3617A -:10105000029B8460C0E90000C0E90511C160026123 -:10106000036210BD08B5D0E90532934201D1826810 -:1010700082B98268013282605A1C42611970D0E9DB -:1010800004329A4224BFC3684361002100F094FAFD -:10109000002008BD4FF0FF30FBE7000070B52023B3 -:1010A00004460E4683F31188A568A5B1A368A2691A -:1010B000013BA360531CA36115782269934224BFAE -:1010C000E368A361E3690BB120469847002383F3EB -:1010D0001188284607E03146204600F05DFA0028D6 -:1010E000E2DA85F3118870BD2DE9F74F04460E460C -:1010F00017469846D0F81C904FF0200A8AF31188C2 -:101100004FF0000B154665B12A4631462046FFF7E1 -:1011100041FF034660B94146204600F03DFA0028F1 -:10112000F1D0002383F31188781B03B0BDE8F08F62 -:10113000B9F1000F03D001902046C847019B8BF303 -:101140001188ED1A1E448AF31188DCE7C0E9051105 -:10115000C160C3611144009B8260C0E9000001616D -:1011600003627047F8B504460D461646202383F304 -:101170001188A768A7B1A368013BA36063695A1CE3 -:1011800062611D70D4E904329A4224BFE36863614E -:10119000E3690BB120469847002080F3118807E0EF -:1011A0003146204600F0F8F90028E2DA87F311888A -:1011B000F8BD0000D0E905239A4210B501D182683C -:1011C0007AB98268013282605A1C82611C78036994 -:1011D0009A4224BFC3688361002100F0EDF92046E4 -:1011E00010BD4FF0FF30FBE72DE9F74F04460E46E8 -:1011F00017469846D0F81C904FF0200A8AF31188C1 -:101200004FF0000B154665B12A4631462046FFF7E0 -:10121000EFFE034660B94146204600F0BDF90028C4 -:10122000F1D0002383F31188781B03B0BDE8F08F61 -:10123000B9F1000F03D001902046C847019B8BF302 -:101240001188ED1A1E448AF31188DCE702684368AE -:101250001143016003B11847704700001430FFF7D5 -:1012600043BF00004FF0FF331430FFF73DBF0000D5 -:101270003830FFF7B9BF00004FF0FF333830FFF7C9 -:10128000B3BF00001430FFF709BF00004FF0FF317B -:101290001430FFF703BF00003830FFF763BF0000D2 -:1012A0004FF0FF323830FFF75DBF0000002070477D -:1012B000FFF772BD044B03600023C0E902334360B3 -:1012C00001230374704700BFE420000810B52023F9 -:1012D000044683F31188FFF789FD0223237400235A -:1012E00083F3118810BD000038B5C36904460D466C -:1012F0001BB904210844FFF7A9FF294604F1140093 -:10130000FFF7B0FE002806DA201D4FF48061BDE82B -:101310003840FFF79BBF38BD024B0022C3E90033C2 -:101320009A607047F8250020002303748268054BFB -:101330001B6899689142FBD25A6803604260106052 -:1013400058607047F825002008B5202383F31188E2 -:10135000037C032B05D0042B0DD02BB983F311880C -:1013600008BD436900221A604FF0FF334361FFF765 -:10137000DBFF0023F2E7D0E9003213605A60F3E7A5 -:10138000002303748268054B1B6899689142FBD85F -:101390005A6803604260106058607047F82500206A -:1013A000054B19690874186802681A60536018615F -:1013B00001230374FEF7AABFF825002030B54B1CAB -:1013C0000B4D87B0044610D02B690A4A01A800F0E3 -:1013D0000DF92046FFF7E4FF049B13B101A800F0CC -:1013E00041F92B69586907B030BDFFF7D9FFF8E71D -:1013F000F82500204913000838B50C4D41612B69D0 -:1014000081689A689142044603D8BDE83840FFF7E6 -:101410008BBF1846FFF7B4FF01232C6101462374EC -:101420002046BDE83840FEF771BF00BFF825002018 -:10143000044B1A681B6990689B68984294BF00200F -:1014400001207047F825002010B5084C236820695A -:101450001A6822605460012223611A74FFF790FF1A -:1014600001462069BDE81040FEF750BFF825002076 -:1014700008B5FFF7DDFF18B1BDE80840FFF7E4BF8E -:1014800008BD0000FFF7E0BFFEE7000010B50C4C00 -:10149000FFF742FF00F09CF80A498022204600F046 -:1014A00031F8012344F8180C037400F0F1FA00231A -:1014B00083F3118862B60448BDE8104000F042B8DA -:1014C000202600200C2100081C21000800F004B98F -:1014D000EFF3118020B9EFF30583202282F3118806 -:1014E0007047000010B530B9EFF30584C4F3080469 -:1014F00014B180F3118810BDFFF7BAFF84F311888F -:10150000F9E7000082600222028270478368A3F13B -:101510007C0243F80C2C026943F83C2C426943F8E6 -:10152000382C074A43F81C2CC26843F8102C0222BE -:1015300003F8082C002203F8072CA3F118007047C9 -:101540002503000810B5202383F31188FFF7DEFF81 -:1015500000210446FFF750FF002383F31188204643 -:1015600010BD0000024B1B6958610F20FFF718BF28 -:10157000F8250020202383F31188FFF7F3BF000034 -:1015800008B50146202383F311880820FFF716FFD2 -:10159000002383F3118808BD49B1064B42681B69DB -:1015A00018605A60136043600420FFF707BF4FF0D4 -:1015B000FF307047F82500200368984206D01A686B -:1015C0000260506059611846FFF7AEBE70470000D8 -:1015D000054B03F11402C3E905224FF0FF3100224D -:1015E000C3E90712704700BFF825002070B51C4EF4 -:1015F000C0E9032305460C4600F0D0FA334653F801 -:10160000142F9A420DD13062C5E901242A600A2CB8 -:101610002CBF00190A30C6E90555BDE8704000F03E -:10162000ABBA316A431AE31838BF1C469368A34229 -:1016300002D9081900F0AEFA73699A6894420CD87E -:101640005A68AC602B606A6015609A685D60121B16 -:101650009A604FF0FF33F36170BD1B68A41AECE78A -:10166000F825002038B51B4C636998420DD0D0E9AD -:10167000003213605A6000228168C2609A680A448E -:101680009A604FF0FF33E36138BD2246036842F8A9 -:10169000143F002193425A60C16003D1BDE8384035 -:1016A00000F072BA9A688168256A0A449A6000F06C -:1016B00075FA63699A68411B8A42E5D9AB181D1A0D -:1016C000092D206A98BF01F10A02BDE83840104494 -:1016D00000F060BAF82500202DE9F041184C0027F1 -:1016E00004F11406656900F059FA236AAA68C11A60 -:1016F0008A4215D813442362D5E9003213605A6038 -:101700006369D5F80C80EF60B34201D100F03CFA78 -:1017100087F311882869C047202383F31188E1E704 -:101720006169B14209D013441B1ABDE8F0410A2B8C -:101730002CBFC0180A3000F02DBABDE8F08100BF00 -:10174000F825002000207047FEE7000070470000E9 -:101750004FF0FF3070470000BFF34F8F024A13690C -:10176000DB03FCD4704700BF0020024008B5094BE2 -:101770001B7873B9FFF7F0FF074B5A69002ABFBF08 -:10178000064A9A6002F188329A601A6822F48062EE -:101790001A6008BD80270020002002402301674511 -:1017A00008B50B4B1B7893B9FFF7D6FF094B5A6965 -:1017B00042F000425A611A6842F480521A601A6874 -:1017C00022F480521A601A6842F480621A6008BDDE -:1017D00080270020002002407F289ABF00F580303B -:1017E000C0020020704700004FF400607047000006 -:1017F000802070477F2808B50BD8FFF7EDFF00F574 -:1018000000630268013204D104308342F9D101201F -:1018100008BD0020FCE700007F2838B5044626D824 -:10182000FFF756FEFFF798FFFFF7A0FF114BF322DB -:101830001A6102225A615A6942EAC4025A615A691B -:1018400042F480325A6105462046FFF785FF4FF487 -:101850000061FFF7C1FF00F0F1F82846FFF7A0FF95 -:10186000FFF740FE2046BDE83840FFF7C3BF002029 -:1018700038BD00BF0020024040EA020313F0070316 -:101880002DE9F04705460C46164606D0324B40F28D -:10189000FB221A600020BDE8F08781182F4A914290 -:1018A0000CD92D4A4FF440711160F3E72B1D1B68D2 -:1018B0006268934208D1083E08350834072E19D9CA -:1018C0002A6823689A42F1D0FFF702FEFFF74EFF25 -:1018D000FFF742FF04F10801214C4FF001084FF0DF -:1018E0000009012EA1F1080708D8FFF759FFFFF7FB -:1018F000F9FD01E0002EE7D10120CCE7C4F8148007 -:10190000AA4651F8083C4AF8043B51F8043C6B6085 -:10191000FFF722FFC4F814902A6851F8083C9A4255 -:101920000ED00D4B40F226321A600E4B1D600E4B4E -:101930001E600E4B1F60FFF733FFFFF7D3FDA9E7D3 -:10194000DAF800A051F8043C9A4501F10801E8D109 -:10195000083E0835C5E700BF7C27002000000408CA -:1019600000200240702700207827002074270020E4 -:10197000084908B50B7828B11BB9FFF7F7FE01231A -:101980000B7008BD002BFCD0BDE808400870FFF7C5 -:1019900007BF00BF802700200244D2B2904200D18E -:1019A0007047431C800000F1804000F5145000682F -:1019B00041F8040BD8B2F1E7124B10B5D3F89040C0 -:1019C000240409D4D3F89040C3F89040D3F8904051 -:1019D00044F40044C3F890400B4C2368024443F4A1 -:1019E00080732360D2B2904200D110BD431C8000AE -:1019F00000F1804000F5145051F8044B0460D8B257 -:101A0000F1E700BF001002400070004007B501225E -:101A100001A90020FFF7C0FF019803B05DF804FBA7 -:101A200013B50446FFF7F2FFA04205D0012201A939 -:101A300000200194FFF7C0FF02B010BD7047000006 -:101A4000054B1A6832B902F1804202F50432D2F82D -:101A500094201A60704700BF8427002008B5FFF764 -:101A6000EFFF024B1868C0F3407008BD84270020C8 -:101A7000EFF3098305494A6B22F001024A63683398 -:101A800083F30988002383F31188704700EF00E097 -:101A9000202080F3118862B60C4B0D4AD96821F4DE -:101AA000E0610904090C0A43DA60D3F8FC20094913 -:101AB00042F08072C3F8FC200A6842F001020A601A -:101AC0001022DA7783F82200704700BF00ED00E0B3 -:101AD0000003FA05001000E010B5202383F31188FD -:101AE0000E4B5B6813F4006314D0F1EE103AEFF381 -:101AF0000984683C4FF08073E361094BDB6B23661C -:101B000084F30988FFF794FC10B1064BA36110BD64 -:101B1000054BFBE783F31188F9E700BF00ED00E018 -:101B200000EF00E0370300083A03000870470000A8 -:101B3000FEE700000A4B0B480B4A90420BD30B4BBD -:101B4000DA1C121AC11E22F003028B4238BF002297 -:101B50000021FFF743B853F8041B40F8041BECE7DF -:101B60001822000808280020082800200828002043 -:101B70007047000000F078B84FF0804300225863AF -:101B80001A610222DA6070474FF080430022DA6067 -:101B9000704700004FF08043586370474FF0804318 -:101BA000586A70474B6843608B688360CB68C3603A -:101BB0000B6943614B6903628B6943620B68036085 -:101BC0007047000008B5204BDA6A42F07F02DA6203 -:101BD000DA6A22F07F02DA62DA6ADA6C42F07F02B5 -:101BE000DA64DA6E42F07F02DA66184ADB6E11467A -:101BF0004FF09040FFF7D6FF02F11C0100F5806026 -:101C0000FFF7D0FF02F1380100F58060FFF7CAFF4F -:101C100002F1540100F58060FFF7C4FF02F170018A -:101C200000F58060FFF7BEFF02F18C0100F58060D7 -:101C3000FFF7B8FF02F1A80100F58060FFF7B2FFDF -:101C4000BDE8084000F064B80010024034210008EC -:101C500008B500F019FAFFF719FCBDE80840FFF7D6 -:101C6000EFBE0000704700000F4B9A6D42F001027A -:101C70009A659A6F42F001029A670C4A9B6F9368CB -:101C800043F0010393604FF08043A7229A624FF024 -:101C9000FF32DA6200229A615A63DA605A600122E6 -:101CA0005A611A60704700BF00100240002004E033 -:101CB0004FF0804208B51169D3680B40D9B2C943CF -:101CC0009B07116107D5202383F31188FFF7FEFBE3 -:101CD000002383F3118808BD08B50B4BD3F890207F -:101CE00012F4407F1FBF4FF48032C3F890200022CF -:101CF000C3F89020D3F89020C3F8902000F086F924 -:101D0000024B00225A6008BD0010024000700040E3 -:101D1000484B4FF0FF319A6A99629A6A00229A62A0 -:101D2000986AD86A60F07F00D862D86A00F07F00B5 -:101D3000D862D86A186B1963186B1A63186B986BA2 -:101D40009963986B9A63986BD86BD963D86BDA6395 -:101D5000D86B186C1964196C1A641A6C9A6D42F07D -:101D600080529A659A6F22F080529A679A6F324A2F -:101D70004FF400711160516911F48061FBD14FF48F -:101D80000040516090604FF48070D160C2F88000D4 -:101D9000116251629162D162116351639163D163A7 -:101DA000116451649164D16411655165D3F8982030 -:101DB00042F00102C3F89820D3F898209007FBD591 -:101DC0001A6842F480321A601A689103FCD51A49E5 -:101DD0000A6842F480720A60184ADA601A6842F0AF -:101DE00080721A601A689201FCD5002214499A6028 -:101DF000C3F888101349C3F89C20134A0A600A6884 -:101E000002F00F02042AFAD19A6842F003029A60A3 -:101E10009A6802F00C020C2AFAD11A6E42F0010202 -:101E20001A66D3F8802042F00102C3F88020D3F86C -:101E3000803070470010024000700040232A61018A -:101E4000550100500020024004070400074A08B56D -:101E5000536903F00103536123B1054A13680BB1C1 -:101E600050689847BDE80840FFF736BE00040140BF -:101E700088270020074A08B5536903F0020353611D -:101E800023B1054A93680BB1D0689847BDE8084074 -:101E9000FFF722BE0004014088270020074A08B54A -:101EA000536903F00403536123B1054A13690BB16D -:101EB00050699847BDE80840FFF70EBE0004014096 -:101EC00088270020074A08B5536903F008035361C7 -:101ED00023B1054A93690BB1D0699847BDE8084022 -:101EE000FFF7FABD0004014088270020074A08B523 -:101EF000536903F01003536123B1054A136A0BB110 -:101F0000506A9847BDE80840FFF7E6BD000401406D -:101F100088270020164B10B55C6904F478725A616A -:101F2000A30604D5134A936A0BB1D06A984760069A -:101F300004D5104A136B0BB1506B9847210604D59A -:101F40000C4A936B0BB1D06B9847E20504D5094A54 -:101F5000136C0BB1506C9847A30504D5054A936CDC -:101F60000BB1D06C9847BDE81040FFF7B5BD00BF7E -:101F70000004014088270020194B10B55C6904F467 -:101F80007C425A61620504D5164A136D0BB1506D3F -:101F90009847230504D5134A936D0BB1D06D98472C -:101FA000E00404D50F4A136E0BB1506E9847A1049C -:101FB00004D50C4A936E0BB1D06E9847620404D5D9 -:101FC000084A136F0BB1506F9847230404D5054A94 -:101FD000936F0BB1D06F9847BDE81040FFF77CBD01 -:101FE000000401408827002008B50348FEF74EFF93 -:101FF000BDE80840FFF770BD8C23002008B5FFF74F -:1020000057FEBDE80840FFF767BD0000062108B590 -:10201000084600F023F80621072000F01FF80621EB -:10202000082000F01BF80621092000F017F806210F -:102030000A2000F013F80621172000F00FF80621FF -:10204000282000F00BF807211C2000F007F8BDE85D -:1020500008400C21252000F001B8000000F1604389 -:1020600003F561430901C9B283F80013012200F0AE -:102070001F039A4043099B0003F1604303F561434A -:10208000C3F880211A60704708B5FFF725FE00F0FD -:1020900009F8FFF70DF9FFF7E5FDBDE80840FFF788 -:1020A00069BD00000023054A19460133102BC2E91F -:1020B000001102F10802F8D1704700BF8827002004 -:1020C00053544D333247343F3F0000000096000028 -:1020D0000000000000000000000000000000000000 -:1020E00000000000000000007912000865120008DE -:1020F000A11200088D12000899120008851200082C -:10210000711200085D120008AD1200086D61696E61 -:102110000000000069646C650000000014210008E4 -:1021200038260020702700200100000089140008D4 -:10213000000000000004282800000000AAAABEAA8F -:1021400000001424DFFF0000000000007007000002 -:102150000000000000000000AAAAAAAA00000000D7 -:10216000FFFF000000000000000000000000000071 -:1021700000000000AAAAAAAA00000000FFFF0000B9 -:10218000000000000000000000000000000000004F -:10219000AAAAAAAA00000000FFFF00000000000099 -:1021A000000000000000000000000000AAAAAAAA87 -:1021B00000000000FFFF0000000000000000000021 -:1021C0000000000000000000AAAAAAAA0000000067 -:1021D000FFFF000000000000000000000000000001 -:1021E00000000000AAAAAAAA00000000FFFF000049 -:1021F00000000000000000001004000000000000CB -:102200000088030000000000FF0000000000000044 -:08221000C02000083F0000009F +:1000000000070020F5040008552800080D28000806 +:10001000352800080D2800082D280008F7040008DE +:10002000F7040008F7040008F70400083538000852 +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008A9450008D145000886 +:10006000F94500082146000849460008F704000841 +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F7040008F704000864 +:10009000F7040008ED270008FD2700087146000856 +:1000A000F7040008F7040008F7040008F704000844 +:1000B00045470008F7040008F7040008F7040008A3 +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008F7040008F7040008F704000814 +:1000E000D5460008F7040008F7040008F7040008E4 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008F7040008A3 +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E0006512000800000000000000000000000090 +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600003F052FE03F0E4FE4FF055301F491B4AE2 +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE703F030FED1 +:1005B00003F004FF144C154DAC4203DA54F8041B4D +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E703F018BE0007002011 +:1005E000002300200000000808ED00E000010020CA +:1005F00000070020F8490008002300207C23002089 +:1006000080230020D8500020E0010008E401000809 +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002003F090FA96 +:10064000FEE703F0F3F900DFFEE70000F8B500F085 +:100650001BFE03F07BFD074603F0CCFD0546D0BB37 +:10066000294B9F4237D001339F4237D0274B27F089 +:10067000FF029A4235D1F8B200F03EFC2E4642F21B +:10068000107400F03FFC08B10024264601F0B4F8D5 +:1006900058B3032000F03EF80024264635B11C4B29 +:1006A0009F4203D003F09EFD00242646002003F065 +:1006B00057FD0EB100F044F800F056FC00F0E6FDE6 +:1006C00002F0D0F80546B4B900F096FC4FF47A7009 +:1006D00003F04CFAF7E72E460024D2E70446012641 +:1006E000CFE706464FF47A74CBE7002CD6D04FF410 +:1006F0007A740126D2E702F0B5F8431BA342E3D98E +:1007000000F01EF8DCE700BF010007B0000008B0F1 +:10071000263A09B0084B187003280CD8DFE800F01F +:1007200008050208022000F00DBE022000F002BE03 +:10073000024B00225A60704780230020842300204F +:1007400010B501F059F830B1234B03221A70234B36 +:1007500000225A6010BD224B224A1C461968013102 +:10076000F8D004339342F9D16268A242F2D31E4B0F +:100770009B6803F1006303F520439A42EAD203F039 +:1007800003FD03F015FD002000F09AFD0220FFF7A5 +:10079000C1FF164B9A6D00229A65996F9A67996FFF +:1007A000D96DDA65D96FDA67D96F196E1A66D3F821 +:1007B0008010C3F88020D3F8803072B64FF0E02369 +:1007C0003021C3F8084DD4E9003281F311889D46E9 +:1007D00083F308881047BDE780230020842300208E +:1007E00000A0000820A00008002300200010024004 +:1007F000094A136849F2690099B21B0C00FB0133E6 +:100800001360064B186844F2506182B2000C01FB81 +:100810000200186080B270471423002010230020CB +:1008200010B500211022044600F0A6FD034B03CBB7 +:10083000206061601868A06010BD00BF9075FF1F48 +:100840002DE9F041ADF54E7D0DF134086CAC40F270 +:10085000751207460D460EA80021C8F8001000F0DA +:100860008BFD4FF4C4720021204600F085FD01F09D +:10087000F9FF254B4FF47A72B0FBF2F0186093E861 +:100880000700022384E807000DF5E9702382FFF7D3 +:10089000C7FF41F204031D49238406A803F0E8FFC3 +:1008A000192384F832310DF2E32206AB0DF1300C3E +:1008B0001E4603CE664510605160334602F10802C1 +:1008C000F6D13378137041460122204600F0A0FD96 +:1008D00000230393AB7E029305F11903019380B2C9 +:1008E0000123CDE904800093E97E05A3D3E9002329 +:1008F000384602F075FB0DF54E7DBDE8F08100BF76 +:100900009E6AC421818A46EE8C230020804800081C +:100910002DE9F0412C4C237ADAB080460D465BBBC2 +:1009200027A9284600F084FE0746002842D19DF8FA +:100930009D60C82E3ED801464FF4A662204600F0C6 +:100940001BFD4FF48073C4F8F8314FF40073C4F802 +:100950000C334FF44073C4F8203432460DF19E013D +:1009600004F1090000F0F6FC26449DF89C307772F3 +:1009700023720BB9EB7E23728122002106AC27A8DB +:1009800000F0FAFC0122214627A800F08DFE00238A +:100990000393AB7E029305F1190380B201932823E0 +:1009A000CDE904400093E97E05A3D3E90023404646 +:1009B00002F016FB5AB0BDE8F08100BFAFF3008033 +:1009C00026417272DF25D7B788480020F0B5254E42 +:1009D0004FF48A7505FB0065F1B096F8D83085F8BC +:1009E000DC300024D822214685F8E8403AA800F0FF +:1009F000C3FC06F1090000F0B7FCD5F8E4308DF82F +:100A0000F000C2B206AF06F109010DF1F100CDE927 +:100A10003A3400F09FFC394601223AA800F070FEFB +:100A200080B2CDE9047008230127CDE9023706F131 +:100A3000D803019330230093317A0B4807A3D3E9FD +:100A4000002302F0CDFAA04206DD01F00BFFC5F84D +:100A5000E000384671B0F0BD2046FBE778F6339FE2 +:100A600093CACD8D88480020A43300202DE9F041A1 +:100A70001D4D1E4E1E4F86B0284602F0DDFA03467D +:100A800058B30024CDE90344ADF81440027B8DF83F +:100A9000142099684068029403AA03C21B68DFF817 +:100AA000548043F00043029301F0DEFE821941F1CD +:100AB0000003009402A9384601F0B6F8A04205DD13 +:100AC000284602F0BDFA88F80040D5E798F80030D3 +:100AD000072B05D8013388F8003006B0BDE8F08157 +:100AE000014802F0ADFAF8E7A433002040420F00BD +:100AF000D8330020BD4D002070B50D4614461E466B +:100B000002F0CAF950B9022E10D1012C0ED112A355 +:100B1000D3E90023C5E90023012007E0282C10D0E9 +:100B200005D8012C09D0052C0FD0002070BD302C29 +:100B3000FBD10BA3D3E90023ECE70BA3D3E90023FC +:100B4000E8E70BA3D3E90023E4E70BA3D3E90023F1 +:100B5000E0E700BFAFF30080401DA12026812A0BF3 +:100B600078F6339F93CACD8D9E6AC421818A46EE62 +:100B700026417272DF25D7B7F017304A39059E56E5 +:100B800038B505460E4C0021013500F0BBFBA4F83A +:100B90002C55B4F82C0500F09DFB78B1B4F82C0569 +:100BA00000F0A8FB014648B9B4F82C0500F0AAFBF8 +:100BB000B4F82C350133A4F82C35EAE738BD00BF72 +:100BC0008848002010B50A4B0A4A1A6003F5805382 +:100BD00093F848203AB95C6C2CB1204600F086FEB0 +:100BE000204603F0FBFDBDE81040034800F07EBE48 +:100BF000D8330020CC480008084400202DE9F04FED +:100C00008FB000AF05460C4602F046F9002849D1E6 +:100C1000237E022B1BD1E38A012B18D101F022FE87 +:100C20000646FFF7E5FD03464FF4C870DFF8C482BF +:100C3000B3FBF0F206F5167602FB103316FA83F3D7 +:100C4000C8F80030E37E33B9A34B00221A703C375A +:100C5000BD46BDE8F08F07F12401204600F0A6FC58 +:100C60000028F4D107F11400FFF7DAFD97F82640C9 +:100C700007F11401224607F1270003F0C7FD002801 +:100C8000E2D10F2C08D8944B1C70D8F80030A3F593 +:100C90001673C8F80030DAE797F82410284602F0F7 +:100CA000F3F8D4E7E38A282B2BD010D8012B23D0DC +:100CB000052BCCD1BFF34F8F8849894BCA6802F40A +:100CC000E0621343CB60BFF34F8F00BFFDE7302BD3 +:100CD000BDD1844EE17E327A9142B8D1607E3146F8 +:100CE000002291F8DC50854200F0A5800132042AF0 +:100CF00001F58A71F5D1AAE721462846FFF7A0FD44 +:100D0000A5E721462846FFF703FEA0E7B2F8EC501E +:100D10007B6005F103094FEA99094FEA8902D11D69 +:100D2000C908A8EBC1039D46EB460021584600F0D8 +:100D300023FB04F1EE012A463144584600F00AFB39 +:100D40007B6813B9012000F0BBFA96F8D20000F0DE +:100D5000C1FA044630B9307200F0DCFA204600F0E7 +:100D6000AFFAB1E0D6F8D4203AB996F8D200B6F886 +:100D70002C25824201D8FFF703FFD6F8D4202A445D +:100D8000944208D296F8D200B6F82C25013082425F +:100D900001D8FFF7F5FE70685FFA89F2594600F056 +:100DA000F3FA08B9C54679E0726896F8D2002A4489 +:100DB0007260D6F8D42005EB0209C6F8D49000F092 +:100DC00089FA814509D396F8D220D6F8D4000132A9 +:100DD000001B86F8D220C6F8D400FF2D0FD80024BF +:100DE000347200F097FA204600F06AFA00F004FD31 +:100DF0003D4B188108B9FFF7A3FCC54627E7BB6840 +:100E000096F8D9000AFB0362FB68D2F8E41082F876 +:100E1000E83001F58061C2F8E030C2F8E410FFF775 +:100E2000D5FDFFF723FE96F8D920013202F0030228 +:100E300086F8D920B6E74FF48A7A0AFB02F505F165 +:100E4000EA013144204600F087FCF86000287FF476 +:100E5000FEAE3544012285F8E82001F003FDD5F807 +:100E6000E020D6ED007ADFED216A801A192838BF1C +:100E7000192040F6B832904228BF1046B8EE677A83 +:100E800007EE900AF8EEE77A67EEA67ADFED186AC9 +:100E9000E7EE267AFCEEE77AC6ED007A96F8D930CE +:100EA000BB60BA6873680AFB02F4321992F8E81062 +:100EB00059B1D2F8E4108B42E8463FF427AF002145 +:100EC00082F8E810C2F8E010C5467368064A9B0A2B +:100ED00001331381BBE600BF9D33002000ED00E02D +:100EE0000400FA05884800208C230020CDCCCC3D9E +:100EF0006666663FA0330020014B1870704700BF44 +:100F00009823002038B54FF00054134B22689A42C2 +:100F100020D1124B627D12481A70237D03724FF468 +:100F20008073C0F8F8314FF40073C0F80C3300251B +:100F30004FF44073C0F820340A49C0F8E450C92285 +:100F4000093000F007FAE0222946204600F014FAA2 +:100F5000012038BD0020FCE79AAD44C5982300204D +:100F6000884800201600002037B500F045FC194DD8 +:100F70001949288102236B7100220123174801F0CF +:100F80007BF800230193164B164900931648174B24 +:100F90004FF4805201F050FF154B197811B11248EF +:100FA00001F072FF01F05EFC0446FFF721FC4FF4F4 +:100FB000C873B0FBF3F202FB130304F5167010FACA +:100FC00083F00C4B186003F015F908B10F232B8147 +:100FD00003B030BD8C23002040420F00D8330020E6 +:100FE000F90A00089C230020A4330020FD0B000810 +:100FF00098230020A03300202DE9F04F2DED028B27 +:1010000090A7D7E900670FF24429D9E90089884CF5 +:1010100095B00DAD9FED848BFFF728FDDFF834B25E +:1010200000230C93ADF83C300D936B6000230DF161 +:1010300025028DED008B4FF0010A09A958468DF865 +:1010400025308DF824A001F075FB9DF824200023A5 +:10105000002A40F0AF80204601F01EFF0546002820 +:1010600047D1DFF8F4B101F0FDFBDBF80030984226 +:101070003FD301F0F7FB0790FFF7BAFB079A4FF455 +:10108000C873B0FBF3F101FB130302F5167010FAFD +:1010900083F0CBF80000DFF8C4B19BF80010079193 +:1010A000002914BF2B46534610A88DF83030FFF7A7 +:1010B000B7FB0799C1F11002D2B2062A10AB28BFC4 +:1010C000062219440DF13100079200F043F9079A06 +:1010D0000CAB0393182302930132564BD2B2CDE9E5 +:1010E00000A304923B463246204601F01BFF8BF8DA +:1010F000005001F0B7FB504A504D1368C31AB3F5C6 +:101100007A7F32D3106001F0AFFB02460B462046D7 +:1011100001F0A0FF204601F0BFFE30B32B7ADFF8CC +:1011200040A1002B14BF032302238AF8053001F0ED +:1011300099FB0DF1400B4FF47A730122B0FBF3F0F1 +:101140005946CAF80000504600F008FA18230293E6 +:101150003B4B019380B240F25513CDE903B00093AD +:1011600042464B46204601F0DDFE2B7AB3B101F03A +:1011700079FB4FF0000A83464FF48A7295F8D90044 +:10118000504400F0030002FB005393F8E8100029DC +:1011900034D00AF1010ABAF1040FEFD1C82002F0ED +:1011A000E5FC2B7A002B7FF434AF15B0BDEC028B3D +:1011B000BDE8F08F4FF0904110A84A6982F02002FC +:1011C0004A611946102200F0D7F80DF126030AAA49 +:1011D0000CA9584600F01AFE95E8030011AB83E80D +:1011E00003009DF83C308DF84C300C9B109310A9F7 +:1011F000DDE90A23204602F001F917E7D3F8E010F1 +:1012000049B12B68FA2B38BFFA23ABEB0101053348 +:10121000B1EB430FBDD3FFF7D9FB4FF48A7200281F +:10122000B7D1BBE7AFF30080000000000000000072 +:10123000A43300209C330020B84D002088480020B3 +:10124000BC4D0020401DA12026812A0BF1C6A7C15C +:10125000D068080FD8330020A03300209D33002031 +:101260008C23002008B5054800F074FEBDE8084056 +:10127000034A0449002003F0ABBA00BFD833002072 +:10128000F84D0020C50B00087047000070B502F053 +:10129000F9FD094E094D30800024286833888342C7 +:1012A00008D902F0EBFD2B6804440133B4F5204F5C +:1012B0002B60F2D370BD00BFEC4D0020C04D00206C +:1012C00002F092BE00F10060920000F5204002F0B2 +:1012D00015BE0000054B1A68054B1B889B1A8342FC +:1012E00002D9104402F0CABD00207047C04D002052 +:1012F000EC4D0020024B1B68184402F0C5BD00BF36 +:10130000C04D0020024B1B68184402F0CFBD00BF47 +:10131000C04D0020064991F8243033B10023086AFB +:1013200081F824300822FFF7CDBF0120704700BFAD +:10133000C44D0020022802BF4FF0904320229A6142 +:1013400070470000022802BF4FF090434FF4001294 +:101350009A61704710B50023934203D0CC5CC4540B +:101360000133F9E710BD000003460246D01A12F916 +:10137000011B0029FAD1704702440346934202D070 +:1013800003F8011BFAE770472DE9F8431F4D144697 +:1013900095F824200746884652BBDFF870909CB32E +:1013A00095F824302BB92022FF2148462F62FFF701 +:1013B000E3FF95F82400C0F10802A24228BF2246AC +:1013C000D6B24146920005EB8000FFF7C3FF95F8C7 +:1013D0002430A41B1E44F6B2082E17449044E4B2F5 +:1013E00085F82460DBD1FFF795FF0028D7D108E00E +:1013F0002B6A03EB82038342CFD0FFF78BFF0028D9 +:10140000CBD10020BDE8F8830120FBE7C44D0020CC +:101410002DE9F0470D46044600219046284640F24B +:101420007912FFF7A9FF234620220021284601F068 +:1014300087FF231D02222021284601F081FF631D22 +:1014400003222221284601F07BFFA31D0322252130 +:10145000284601F075FF04F10803102228212846D0 +:1014600001F06EFF04F1100308223821284601F034 +:1014700067FF04F1110308224021284601F060FFB4 +:1014800004F1120308224821284601F059FF04F113 +:10149000140320225021284601F052FF04F11803C2 +:1014A00040227021284601F04BFF04F1200308225E +:1014B000B021284601F044FF04F121030822B8219D +:1014C000284601F03DFF04F12207C0263B46314685 +:1014D00008222846083601F033FFB6F5A07F07F151 +:1014E0000107F3D104F1320308223146284601F006 +:1014F00027FF002704F1330A94F832304FEAC70976 +:101500009F4209F5A47615D3B8F1000F08D13146F2 +:1015100004F599730722284601F012FF09F24F16CD +:10152000274694F832213B1B93420CD3F01DC00890 +:10153000BDE8F0870AEB070308223146284601F090 +:10154000FFFE0137D8E707F2331331460822284659 +:1015500001F0F6FE08360137E3E7000013B5044654 +:101560000846002101602346C0F8031020220190A4 +:1015700001F0E6FE0198231D0222202101F0E0FE89 +:101580000198631D0322222101F0DAFE0198A31DB8 +:101590000322252101F0D4FE019804F10803102252 +:1015A000282101F0CDFE072002B010BDF7B50023C1 +:1015B000047F00910E4607221946054601F084FD7E +:1015C000731C0093012200230721284601F07CFDB3 +:1015D000C4B9B31C0093052223460821284601F014 +:1015E00073FD0D243746B278BB1B934211D32B7F7A +:1015F000A88A0734E408BBB9844294BF00200120C4 +:1016000003B0F0BDAB8ADB00083BDB08B3700824F5 +:10161000E8E7FB1C0093214600230822284601F03E +:1016200053FD08340137DEE7201A18BF0120E7E731 +:10163000F7B50023047F00910E460822194605469F +:1016400001F042FD731CC4B90822009311462346E1 +:10165000284601F039FD1024012372785F1C013BFC +:10166000934211D32B7FA88A0734E408BBB9844284 +:1016700094BF0020012003B0F0BDAB8ADB00083B23 +:10168000DB0873700824E7E7F31900932146002371 +:101690000822284601F018FD08343B46DDE7201AF1 +:1016A00018BF0120E7E70000F8B50E4605461446CE +:1016B000002181223046FFF75FFE2B4608220021E1 +:1016C000304601F03DFE7CB96B1C072208213046F4 +:1016D00001F036FE0F2401236A785F1C013B934220 +:1016E00004D3E01DC008F8BD0824F4E7EB19214637 +:1016F0000822304601F024FE08343B46ECE70000A7 +:10170000F8B50E46054614460021CE223046FFF7B6 +:1017100033FE2B4628220021304601F011FE7CB911 +:1017200005F1080308222821304601F009FE302483 +:101730002F462A7A7B1B934204D3E01DC008F8BDD4 +:101740002824F5E707F1090321460822304601F075 +:10175000F7FD08340137ECE7F7B5047F00910E463A +:10176000012310220021054601F0AEFCC4B9B31CD0 +:101770000093092223461021284601F0A5FC1924D4 +:1017800037467288BB1B9A4211D82B7FA88A073430 +:10179000E408BBB9844294BF0020012003B0F0BD2F +:1017A000AB8ADB00103BDB0873801024E8E73B1DAD +:1017B0000093214600230822284601F085FC0834C6 +:1017C0000137DEE7201A18BF0120E7E730B5094DE1 +:1017D0000A4491420DD011F8013B5840082340F3D0 +:1017E0000004013B2C4013F0FF0384EA5000F6D1C3 +:1017F000EFE730BD2083B8EDF7B5364A1068516881 +:101800006B4603C36A4634493448082303F00EF894 +:10181000044690BB0A25324A106851686B4603C3E0 +:101820006A4630492D48082303F000F80446002892 +:1018300047D00369B3F5583F43D8B0F86620B2F5F6 +:10184000826F3ED1284A024402F15C018B4238D3B8 +:101850005C3B224900209E1AFFF7B8FF324607463C +:1018600004F164010020FFF7B1FFA3689F4228D173 +:10187000E368984208BF002523E00369B3F5583FA9 +:1018800026D8428BB2F5826F20D1174A024402F16A +:1018900010018B4218D3103B104900209D1AFFF70E +:1018A00095FF2A46064604F118010020FFF78EFF37 +:1018B000A3689E4202D1E368984201D00D25AAE7B1 +:1018C0000025284603B0F0BD1025A4E70C25A2E7AB +:1018D0000B25A0E79C480008DC5F030000A000087F +:1018E000A5480008905F03000860FFF710B5037C6F +:1018F000044613B9006802F081FF204610BD0000C5 +:101900000023BFF35B8FC360BFF35B8FBFF35B8FBD +:101910008360BFF35B8F7047BFF35B8F0068BFF3DB +:101920005B8F704770B505460C30FFF7F5FF05F18A +:10193000080604463046FFF7EFFFA04206D93046BE +:101940006D68FFF7E9FF2544281A70BD3046FFF7A0 +:10195000E3FF201AF9E7000070B50546406898B12A +:1019600005F10800FFF7D8FF05F10C0604463046E4 +:10197000FFF7D2FF8442304694BF6D680025FFF721 +:10198000CBFF013C2C44201A70BD000038B50C463A +:101990000546FFF7C7FFA04210D305F10800FFF787 +:1019A000BBFF04446868B4FBF0F100FB1144BFF3D3 +:1019B0005B8F0120AC60BFF35B8F38BD0020FCE77C +:1019C0002DE9F041144607460D46FFF7C5FF844256 +:1019D00028BF0446D4B1B84658F80C6B4046FFF710 +:1019E0009BFF3044286040467E68FFF795FF331A1E +:1019F0009C4203D86C600120BDE8F0816B60A41BA1 +:101A00003B68AB602044E8600220F5E72046F3E73E +:101A100038B50C460546FFF79FFFA04210D305F1ED +:101A20000C00FFF779FF04446868B4FBF0F100FB99 +:101A30001144BFF35B8F0120EC60BFF35B8F38BDB7 +:101A40000020FCE72DE9FF41884669460746FFF77D +:101A5000B7FF6C4606B204EBC6060025B44209D0B7 +:101A60006268206808EB0501FFF774FC63680834BE +:101A70001D44F3E729463846FFF7CAFF284604B05D +:101A8000BDE8F081F8B505460C300F46FFF744FF7E +:101A900005F1080604463046FFF73EFFA0423046F7 +:101AA00088BF6C68FFF738FF201A386020B13046D5 +:101AB0002C68FFF731FF2044F8BD000073B51446D1 +:101AC00006460D46FFF72EFF844228BF04460190CC +:101AD000DCB101A93046FFF7D5FF019B33B932686D +:101AE000C5E90233C5E9002401200CE09C4238BF5F +:101AF00001942860019868608442F5D93368AB602E +:101B0000241AEC60022002B070BD2046FBE7000002 +:101B10002DE9FF410F466946FFF7D0FF6C4600B242 +:101B200004EBC0050026AC4209D0D4F8048054F878 +:101B3000081BB8194246FFF70DFC4644F3E7304650 +:101B400004B0BDE8F081000038B50546FFF7E0FFBE +:101B5000044601462846FFF719FF204638BD00001D +:101B6000302383F3118862B670470000002383F3AB +:101B7000118862B67047000001207047704700006E +:101B800010B41346026814680022A4465DF8044BA2 +:101B90006047000000F5805090F85904704700003D +:101BA00000F5805090F852047047000000F5805016 +:101BB00090F95804704700005020704700F580529B +:101BC00008B5FFF7CDFFD2F89834D2F89404184442 +:101BD000D2F890341844D2F878341844D2F88834C3 +:101BE0001844D2F884341844FFF7C0FF08BD000041 +:101BF00038B5C26A936923F001039361044600F08B +:101C000031FE0546E36A9B69DB0706D500F02AFE34 +:101C1000431BFA2BF6D9002004E004F58054012080 +:101C200084F8520438BD00002DE9F04F0C4600F551 +:101C3000805185B01F4691F85234BDF83890054662 +:101C400090469BB1D1F874340133C1F874342368E1 +:101C50009A0006D4237B082B0BD9627B0AB10F2B89 +:101C600007D9D1F878340133C1F878344FF0FF3018 +:101C70000FE0FFF775FFEB6AD3F8C42012F4001AE7 +:101C80000AD0D1F87C340133C1F87C34FFF76EFF01 +:101C9000002005B0BDE8F08FD3F8C46022686B6AFD +:101CA000C6F301464FF0480B002A1BFB063BB4BFAE +:101CB00042F080429204CBF8002023685B0044BFCE +:101CC00042F00052CBF80020227B330643EA024365 +:101CD000CBF80430607B720118B343F44013CBF8A7 +:101CE0000430D1F8A4340133C1F8A434AB1803F59F +:101CF0008353197B41F020011973207B039200F07C +:101D00000DFE039A033080105FFA8AF383420AF1D2 +:101D1000010A0DDA04EB83010BEB83034968996038 +:101D2000F2E7AB1803F58353197B60F34511E3E742 +:101D3000EB6A0121B140C3F8CC10AB1803F5825314 +:101D4000C3E9048705EB461303F582532146183394 +:101D500004F10C0051F804CB43F804CB8142F9D1D3 +:101D6000098819802A4441F268032846D65002F5B2 +:101D7000805209F0030392F86C1043F0100321F035 +:101D80001F010B4382F86C30FFF7F0FE4246CDF89E +:101D900000903B46214600F087FD012079E70000D6 +:101DA00013B500F580540191606CFFF7D5FD1F2835 +:101DB0000AD90199606C2022FFF744FEA0F12003AC +:101DC0005842584102B010BD0020FBE708B500F5AD +:101DD0008050FFF7C5FE406CFFF792FDBDE808405C +:101DE000FFF7C4BE002202608281426082607047B9 +:101DF00010B500220023C0E900230023044603811C +:101E00000C30FFF7EFFF204610BD00002DE9F04732 +:101E1000074688B007F5805468469A468846FFF71B +:101E20009FFE9146FFF7E4FF606CFFF77BFD1F28E4 +:101E30002CD9606C20226946FFF786FE202825D128 +:101E400094F8523413B303AD444605AB2E4603CE8B +:101E50009E4220606160354604F10804F6D1306886 +:101E60002060B388A380DDE90023C9E90023BDF821 +:101E70000830AAF80030FFF779FE4A46534641463B +:101E8000384608B0BDE8F04700F0FCBCFFF76EFE36 +:101E9000002008B0BDE8F0872DE9F84F0023064682 +:101EA000C0E90133284B46F8303B00F58154054624 +:101EB00088463746103438462037FFF799FFA74247 +:101EC000F9D105F580544FF4805326630026C4E908 +:101ED0000D366764012305F5835705F5A359E663BD +:101EE00084F8403084F84830103709F110094FF079 +:101EF000000A4FF0000B47E908ABA7F11800FFF705 +:101F000071FF203747F8286C4F45F4D184F8588486 +:101F1000A4F85A64A4F85C64A4F85E6484F860646D +:101F2000A4F86264A4F86464A4F8666484F868643D +:101F3000B8F1000F02D0054800F08EFC044BEB62B4 +:101F40002846BDE8F88F00BFCC480008B04800081C +:101F50000064004010B5044B197804464A1C1A70FE +:101F6000FFF79AFF204610BDF54D00202DE9F04304 +:101F700000295FD03048314BB3FBF1F381428CBF75 +:101F80000A201120451EB3FBF0F700FB1730ECB21E +:101F900020B1022D2846F5D8002037E07D1EB5F58A +:101FA000806F33D2C4EBC40808F103034FEAE30E99 +:101FB000C3F3C703A4EB030C0EF101094FF47A70CD +:101FC0005FFA8CF60EFB000E59FA8CFCBEFBFCFC93 +:101FD000BCF5617F1CDC1FFA8CF4581C56FA80F0AB +:101FE00047431648B0FBF7F7B942D5D1013BDBB206 +:101FF0000F2BD1D8711EC9B207294FF0000005D8A8 +:10200000107114805580537191710120BDE8F083E7 +:1020100008F1FF334FEAE30CC3F3C703E41A0CF1F2 +:10202000010EE6B20CFB00005EFA84F4B0FBF4F49F +:10203000A4B2D2E70846E9E73F420F0000366E013E +:102040000B4B10B54FF45472044600211846FFF7AD +:1020500093F9084BA3614033E361D8332362F03333 +:102060006362E36A60610022C3F8C02010BD00BF54 +:1020700000A4004070A400402DE9F04F00F5805509 +:10208000994695F85834012B89B004468A46904603 +:1020900004D90027384609B0BDE8F08F8D4A52F8C0 +:1020A000231009B942F823008B49C4F80CA00B781F +:1020B00084F8109093B9FFF753FD884B9A6D42F066 +:1020C00000729A659A6B42F000729A639A6B22F0E2 +:1020D00000729A6301230B70FFF748FD95F85134A5 +:1020E00073B903211520FFF73BFD01F015FC032117 +:1020F000162001F011FC012385F85134FFF736FD5D +:10210000FFF72EFDE26A936923F01003936100F05C +:10211000A9FB0746E36A9E6916F0080607D000F09F +:10212000A1FBC31BFA2BF5D9FFF720FDB1E79A6994 +:1021300042F001029A6100F095FB0746E36A9A6952 +:10214000D00705D400F08EFBC31BFA2BF6D9EBE7C2 +:102150009A6942F002029A61E36A00275F65FFF71D +:1021600005FD686CFFF7CCFB04F5825B0BF1100BEF +:10217000202200216846FFF7FFF802A8FFF732FE91 +:1021800006976A460BEB06030DF1180E9446BCE861 +:102190000300F44518605960624603F10803F5D165 +:1021A000DCF80000186020369CF804201A71B6F59F +:1021B000806FDDD1002304F5A25285F8503485F8F4 +:1021C00053341A3251462046FFF7D0FE074690B9E5 +:1021D000E26A936923F00103936100F043FB054633 +:1021E000E36A9B69D9077FF554AF00F03BFB431BC3 +:1021F000FA2BF5D94DE795F85F6495F85E24C5F89C +:102200006CA4360246EA426695F86024E36A1643F7 +:10221000B5F85C2446EA0246DE61B8F1000F29D029 +:1022200004F5A352023241462046FFF79FFE90B9C3 +:10223000E26A936923F00103936100F013FB054602 +:10224000E36A9B69DA077FF524AF00F00BFB431BC1 +:10225000FA2BF5D91DE795F8683495F86714C5F899 +:1022600070841B0143EA0123B5F86414E26A43EA6F +:102270000143D3602046FFF7E3FE002385F859347D +:10228000E36A6FF040421A65E36A154A5A65E36AE9 +:1022900044229A65E36A0722C3F8DC20E36A03223A +:1022A0009145DA653FF4F6AEE26A936923F00103E3 +:1022B000936100F0D7FA0646E36A9B69DB0705D510 +:1022C00000F0D0FA831BFA2BF6D9E2E6012385F859 +:1022D0005234DFE6F04D0020F44D002000100240A3 +:1022E0009B0008002DE9F04F054689B090469946BD +:1022F000002741F2680A00F58056EB6AD3F8D43023 +:10230000FB40D8074AD505EB471252444FEA471B1A +:102310001379190742D4D6F880340133C6F88034D3 +:1023200013799A0648BFD6F8A83405EB0B0248BFCC +:102330000133524448BFC6F8A834137943F0080368 +:102340001371DB0722D596F85334FBB105F582549F +:10235000183468465C44FFF74BFD03AB04F1080CEE +:10236000206861681A4603C2083464451346F7D1F1 +:1023700020681060A2889A800123ADF808302B688D +:10238000CDE90089DB6B694628469847D6F8543476 +:1023900023B1D6F89C340133C6F89C340137202F82 +:1023A000ABD109B0BDE8F08F2DE9F04F8DB00446F8 +:1023B0000F4600F059FA82468946002F56D1E36A4B +:1023C000D3F89020920141BF04F58051D1F89424B4 +:1023D0000132C1F89424D3F89020160703D10020CD +:1023E0000DB0BDE8F08FD3F89050E669C5F3012534 +:1023F000482303FB0566E8464046FFF7F3FC3268D6 +:1024000051004ABF22F06043C2F38A4343F00043C5 +:10241000920048BF43F080430093736813F40013A5 +:102420001FBF04F5805201238DF80D30D2F8AC3473 +:102430000EBF8DF80D300133C2F8AC34F38803F0D1 +:102440000F038DF80C304FF0000B9DF80C0000F0DE +:1024500065FA5FFA8BF3984220D9F2180CA90B4465 +:10246000127A03F82C2C0BF1010BEEE7012FB6D1F9 +:10247000E36AD3F89820950141BF04F58051D1F863 +:1024800094240132C1F89424D3F898201007A6D0E0 +:10249000D3F89850266AC5F30125A9E7EFB9E36A96 +:1024A000C3F8945004A8FFF7A3FC98E80F0007AD09 +:1024B00007C52B800023ADF8183023682046CDE9EE +:1024C00004A9DB6B04A9984704F5805458B1D4F8EB +:1024D0008C340133C4F88C3482E7012F04BFE36AE3 +:1024E000C3F89C50DEE7D4F890340133C4F890343C +:1024F000012075E7F8B505460F4600F58054012622 +:1025000039462846FFF750FF10B184F85364F7E7C7 +:10251000D4F8543423B1D4F89C340133C4F89C3437 +:10252000F8BD0000F0B5C36A1A6C12F47F0F2BD00F +:1025300000F580541B6CC4F8A03441F268050023F8 +:1025400047194FF0010C00EB43122A445E01117948 +:1025500011F0020F15D0490713D4B959C66AD6F83D +:10256000C8E00CFA01F111EA0E0F0AD0C6F8D0103B +:10257000117941F004011171D4F888240132C4F8B2 +:1025800088240133202BDED1F0BD000010B5254C8E +:10259000254B226802B338B31A6D12060ED580227D +:1025A0001A6500F061F950EA01020B4602D00138C9 +:1025B00061F1000302462068FFF794FE1A4A136D8A +:1025C0001B032AD523684FF4002103F580531165BE +:1025D000012283F8592420E001221A6508221A6595 +:1025E0004FF480621A6510BD196DC80702D4196DC9 +:1025F000890705D50321196510460021FFF77AFFE9 +:10260000094B1A6D100702D41A6DD10605D5182290 +:102610001A6520680121FFF76DFF2068BDE81040B2 +:10262000FFF780BFF04D00200064004008B5FFF7C1 +:1026300097FAFFF777FFBDE80840FFF797BA000069 +:10264000C36AD3F8C40080F40010C0F34050704750 +:1026500000F5805008B5FFF783FA406CFFF762F988 +:10266000FFF784FA43090CBF0120002008BD0000D9 +:1026700000F5805393F8592462B1C16A8A6922F047 +:1026800001028A61D3F898240132C3F89824002209 +:1026900083F85924704700002DE9F74300F5825173 +:1026A00098461031FFF75CFA002541F2680E4FF0B2 +:1026B000010900F5805C00EB4514744423795E0742 +:1026C0001CD4DB061AD5C36A8E69D3F8C87009FA20 +:1026D00006F63E4212D04F6801970F689742019F5D +:1026E00077EB08070AD2C3F8D060237943F00403DC +:1026F0002371DCF884340133CCF884340135202D87 +:1027000001F12001D7D103B0BDE8F043FFF72EBAA5 +:10271000F8B51E46002313700F4605461446FFF712 +:1027200097FF80F0010038701EB12846FFF788FF40 +:102730002070F8BD2DE9F04F85B09946DDE90EA374 +:102740000D4602931378019391F800B08046164627 +:1027500000F08AF82B7804460F4613B93378002B23 +:1027600042D022463B464046FFF796FFFFF75EFF0A +:10277000FFF77EFF4B4632462946FFF7C9FF2B780D +:1027800033B1BBF1000F03D0012005B0BDE8F08FDD +:10279000337813B1019B002BF6D108F580530393D6 +:1027A000029B544577EB03031ED2039BD3F85404DA +:1027B000D0B10368AAEB0401DB6889B298474B46A5 +:1027C000324629464046FFF7A3FF2B7813B1BBF1F1 +:1027D000000FD9D1337813B1019B002BD4D100F075 +:1027E00043F804460F46DBE70020CEE708B500209B +:1027F000FFF7CCFEBDE8084001F050B808B5012055 +:10280000FFF7C4FEBDE8084001F048B800B59BB032 +:10281000EFF3098168226846FEF79CFDEFF305831C +:10282000014B9B6BFEE700BF00ED00E008B5FFF732 +:10283000EDFF000000B59BB0EFF309816822684608 +:10284000FEF788FDEFF30583014B5B6BFEE700BFEE +:1028500000ED00E0FEE700000FB408B5029801F0BB +:102860001BF9FEE701F00EBC01F0E6BB13B56C46A8 +:1028700084E80600031D94E8030083E805000120B6 +:1028800002B010BD73B58568019155B11B885B0717 +:1028900007D4D0E900369B6B9847019AC1B2304605 +:1028A000A847012002B070BDF0B5866889B0054622 +:1028B0000C465EB1BDF838305B070AD4D0E900376A +:1028C0009B6B98472246C1B23846B047012009B0F9 +:1028D000F0BD00220023CDE900230023ADF808302D +:1028E0000A4603AB01F10806106851681C4603C490 +:1028F0000832B2422346F7D1106820609288A28045 +:10290000FFF7B2FF0423ADF808302B68CDE90001D2 +:10291000DB6B694628469847D8E70000082817D996 +:1029200009280CD00A280CD00B280CD00C280CD06D +:102930000D280CD00E2814BF4020302070470C20EA +:1029400070471020704714207047182070472020CF +:10295000704700002DE9F041456A15B94162BDE8B4 +:10296000F0814B6823F06047C3F38A464FEAD37E79 +:10297000C3F3807816EA230638BF3E46AC462B46A2 +:102980005A68BEEBD27F22F060440AD0002A18DADF +:10299000A40CB44217D19D420FD10D60DEE713465F +:1029A000EEE7A74207D102F08044C2F380724245AD +:1029B0000BD054B1EFE708D2EDE7CCF800100B6074 +:1029C000CDE7B44201D0B442E5D81A689C46002A4B +:1029D000E5D11960C3E700002DE9F047089D01F03B +:1029E00007044FEAD508224405F0070500EBD100A3 +:1029F0004FF47F49944201D1BDE8F08704F0070706 +:102A000005F0070A57453E4638BF5646C6F1080648 +:102A1000111B8E4228BF0E46E10808EBD50E415C23 +:102A200013F80EC0B94029FA06F721FA0AF1FFB2ED +:102A30008CEA010147FA0AF739408CEA010C03F8E5 +:102A40000EC034443544D5E780EA0120082341F222 +:102A5000210201B24000002980B203F1FF33B8BF68 +:102A6000504013F0FF03F4D17047000038B50C4616 +:102A70008D18A54200D138BD14F8011BFFF7E4FF03 +:102A8000F7E7000042684AB11368436043898189CF +:102A900001339BB29942438138BF8381104670470E +:102AA00070B588B0202204460D4668460021FEF726 +:102AB00063FC20460495FFF7E5FF024658B16B46DC +:102AC000054608AE1C4603CCB44228606960234624 +:102AD00005F10805F6D1104608B070BD082817D9D1 +:102AE00009280CD00A280CD00B280CD00C280CD0AC +:102AF0000D280CD00E2814BF4020302070470C2029 +:102B0000704710207047142070471820704720200D +:102B100070470000082817D90C280CD910280CD9A8 +:102B200014280CD918280CD920280CD930288CBF8F +:102B30000F200E207047092070470A2070470B2095 +:102B400070470C2070470D20704700002DE9F843B6 +:102B5000078C072F04461ED9D0E9029800254FF6AE +:102B6000FF73C5F12006A5F1200029FA05F108FA46 +:102B700006F628FA00F031430143C9B21846FFF7C0 +:102B800063FF0835402D0346EBD1E1693A46BDE8C5 +:102B9000F843FFF76BBF4FF6FF70BDE8F883000006 +:102BA00010B54B6823B9CA8A63F30902CA8210BD03 +:102BB00004691A681C600361C38A013BC3824A60CE +:102BC000EFE700002DE9F84F1D46CB8A0F46C3F30F +:102BD00009010529814692460B4630D00020AAB251 +:102BE00007F11A049EB2042E1FFA80F80FD8904500 +:102BF00003F1010306D3FB8A0A4462F30903FB8253 +:102C000001201AE01AF80060E6540130EAE7904526 +:102C1000F1D2A1F1050B1C237C68BBFBF3F203FB93 +:102C200012BB1FFA8BF6002C45D14846FFF72AFF4E +:102C3000044638B978606FF00200BDE8F88F4FF0B5 +:102C40000008E6E7002606607860ADB24FF0000BA2 +:102C5000454510D90AEB0803221D13F8011B9155B5 +:102C6000B1B208F101081B291FFA88F82BD045459D +:102C700006F10106F1D8FB8AC3F30902154465F396 +:102C80000903BCE7013292B21C462368002BF9D13C +:102C90006B1F0B441C21B3FBF1F301339BB29A422F +:102CA000D3D2BBF1000FD0D14846FFF7EBFE20B9DD +:102CB000C4F800B0BFE70122E7E7C0F800B05E4605 +:102CC00020600446C1E74545D5D94846FFF7DAFEFE +:102CD00008B92060AFE7C0F800B0002620600446C5 +:102CE000B6E700002DE9F04F2DED028B1C4683B0B6 +:102CF0005B69019207468846002B00F09A80238C7E +:102D00002BB1E269002A00F09480072B35D807F137 +:102D10000C00FFF7B7FE054638B96FF002052846EC +:102D200003B0BDEC028BBDE8F08F14220021FEF74A +:102D300023FB228CE16905F10800FEF70BFB208CD8 +:102D4000013080B2FFF7E6FEFFF7C8FE013880B21F +:102D50002084013028746369228C1B782A4403F094 +:102D60001F0363F03F0348F0004113723846696067 +:102D70002946FFF7EFFD0125D1E700F10C034FF0E5 +:102D8000000908EE103A4FF0800A4E464D4618EE04 +:102D9000100AFFF777FE83460028BED014220021D8 +:102DA000FEF7EAFA002E3AD1019BABF80830022276 +:102DB0000BF1080E1FFA82FC0CF10100BCF1060FAA +:102DC000218C80B201D88E422BD3FFF7A3FEFFF7F0 +:102DD00085FE62691278013802F01F028E4208BF38 +:102DE0004FF0400A42EA49121BFA80F14AEA020A0D +:102DF000013048F0004281F808A08BF81000CBF8B1 +:102E0000042059463846FFF7A5FD238C0135B3420F +:102E10002DB289F001094FF0000AB8D17FE70022F6 +:102E2000C6E7E169895D0EF802100136B6B20132DB +:102E3000C0E76FF0010572E7F8B515460E4630227F +:102E4000002104461F46FEF797FA069B6360B5F51E +:102E5000001F079BA76034BF6A094FF6FF72A36289 +:102E600097B2E66104F1100000239A4206D80023CD +:102E70000360A782E3822383E360F8BD0660013329 +:102E800030462036F1E7000003781BB94BB2002B27 +:102E9000C8BF01707047000000787047F8B50C4655 +:102EA000C969074611B9238C002B37D1257E1F2D08 +:102EB00034D8387828BB228C072A2CD8268A36F0BA +:102EC00003032BD14FF6FF70FFF7D0FD20F0010078 +:102ED0003102400441EA0561400C41EA40254FF6C9 +:102EE000FF72234629463846FFF7FCFE002807DD1F +:102EF000626913780133DBB21F2B88BF0023137084 +:102F0000F8BD218A2D0645EA012505432046FFF735 +:102F10001DFE0246E5E76FF00300F1E76FF00100E8 +:102F2000EEE7000070B58AB004461646002128225C +:102F300068461D46FEF720FABDF83830ADF810306F +:102F40000F9B05939DF840308DF81830119B079327 +:102F50006946BDF84830ADF820302046CDE902651D +:102F6000FFF79CFF0AB070BD2DE9F041D36905461B +:102F70000C4616460BB9138C5BBB377E1F2F28D827 +:102F800095F80080B8F1000F26D03046FFF7DEFD3F +:102F90003378210241EAC33141EA0801338A41EA28 +:102FA000076141EA03410246334641F08001284669 +:102FB000FFF798FE00280ADD3378012B07D17269EC +:102FC00013780133DBB21F2B88BF00231370BDE8D9 +:102FD000F0816FF00100FAE76FF00300F7E70000FF +:102FE000F0B58BB004460D461746002128226846EE +:102FF0001E46FEF7C1F99DF84C305A1E534253410C +:103000008DF800309DF84030ADF81030119B0593DD +:103010009DF848308DF81830149B07936A46BDF828 +:103020005430ADF8203029462046CDE90276FFF72E +:103030009BFF0BB0F0BD0000406A00B10430704748 +:10304000436A1A68426202691A600361C38A013BDB +:10305000C38270472DE9F041D0F82080194E144604 +:103060001D464146002709B9BDE8F081D1E9022398 +:10307000A21A65EB0303964277EB03031ED2036AA1 +:103080008B420DD1FFF78CFD036A1B680362036955 +:103090000B60C38A0161016A013BC3828846E2E793 +:1030A000FFF77EFD0B68C8F8003003690B60C38A28 +:1030B0000161013BC382D8F80010D4E78846096853 +:1030C000D1E700BF80841E002DE9F04F8BB00D4684 +:1030D000DDF8509014469B468046002800F0198188 +:1030E000B9F1000F00F01581531E3F2B00F2118142 +:1030F000012A03D1BBF1000F40F00B810023CDE981 +:103100000833B8F81430B5EBC30F4FEAC30703D345 +:1031100000200BB0BDE8F08F2B199F42D8F80C307F +:103120003ABF7F1BFFB227461BB9D8F81030002BDF +:103130007AD0272D4ED8C5F12806B7424FF00003AC +:103140002CBFF6B23E4600932946D8F8080008ABDB +:103150003246FFF741FCA7EB060A35445FFA8AFACC +:10316000B8F8143003F10053053BDB000493D8F8A2 +:103170000C3003932821039B13B1BAF1000F2CD11B +:10318000D8F8100040B1BAF1000F05D0009608AB96 +:103190005246691AFFF720FC38B2002FB8D06607F4 +:1031A0000AD00AAB03EBD401624211F8083C02F0EA +:1031B0000702134101F8083C082C3CD9102C40F2BE +:1031C000B580202C40F2B780BBF1000F00F09C804E +:1031D000082334E0BA460026C2E7049BE02B28BF50 +:1031E000E02306930B44AB42059314D95A1B039872 +:1031F0000096924534BF5246D2B2691A08AB0430E9 +:103200000792FFF7E9FB079A1644AAEB020A154456 +:10321000F6B25FFA8AFA049B069A05999B1A049300 +:10322000039B1B680393A6E70093D8F8080008AB3C +:103230003A462946AEE7BBF1000F13D00123B4EBA9 +:10324000C30F6CD0082C12D89DF82030621E23FAD0 +:1032500002F2D50706D54FF0FF3202FA04F42343F9 +:103260008DF820309DF8203089F8003051E7102C7F +:1032700012D8BDF82030621E23FA02F2D10706D51B +:103280004FF0FF3202FA04F42343ADF82030BDF8CA +:103290002030A9F800303CE7202C0FD80899631E95 +:1032A00021FA03F3DA0705D54FF0FF3202FA04F4EE +:1032B0000C430894089BC9F800302AE7402C2BD017 +:1032C000DDE90865611EC4F12102A4F1210326FA9B +:1032D00001F105FA02F225FA03F311431943CB0772 +:1032E00012D50122A4F12003C4F1200102FA03F354 +:1032F00022FA01F1A240524243EA010363EB430385 +:1033000032432B43CDE90823DDE90823C9E9002333 +:10331000FFE66FF00100FCE66FF00800F9E6082C0C +:10332000A0D9102CB3D9202CEED8C3E7BBF1000FE5 +:10333000ADD0022383E7BBF1000FBBD004237EE7AF +:1033400030B5012A144638BF0124402C85B028BF6F +:1033500040240025012ACDE9025518D81B788DF8A4 +:10336000083063070AD004AB03EBD405624215F8BA +:10337000083C02F00702934005F8083C0091034620 +:103380002246002102A8FFF727FB05B030BD082A1E +:10339000E4D9102A03D81B88ADF80830E1E7202AC9 +:1033A0008DBFD3E900231B680293CDE90223D8E740 +:1033B00010B5CB681BB98B600B618B8210BD0469A3 +:1033C0001A681C600361C38A013BC382CA60F0E7CC +:1033D00003064CBFC0F3C0300220704708B5024658 +:1033E000FFF7F6FF022806D15306C2F30F2001D1E2 +:1033F00000F0030008BDC2F30740FBE72DE9F04FE2 +:1034000093B0CDE903230A6804461046FFF7E0FFB6 +:10341000022814BFC2F306260026002A0D46824663 +:1034200080F2F28112F0C04940F0EE81097B002960 +:1034300000F0EA81022803D02378B34240F0E7810C +:10344000C2F304630693104602F07F030593FFF76F +:10345000C5FF059B29444FEA834848EA0A4848EAE1 +:103460004668CE7800230022CDE90823F30983467D +:1034700048EA0008029367D0059B009302466768FC +:10348000534608A92046B847002800F0C381276AA0 +:103490004FB9414604F10C00FFF702FB074690B913 +:1034A0006FF0020054E03B6998450DD03F68002F53 +:1034B000F9D1414604F10C00FFF7F2FA0746002863 +:1034C000EED0236A3B60276297F817C006F01F080A +:1034D000CCF3840CACEB08001FFA80FE0028B8BFC8 +:1034E0000EF12000A8EB0C031FFA83FED7E902219E +:1034F000B8BF00B2002B0793BEBF0EF120031BB272 +:10350000079352EA010338D0039BDFF824E39A1AA9 +:10351000049B4FF0000C63EB010196457CEB01032B +:103520002BD36B7B97F81AE0734519D1029B002BC4 +:1035300078D0012821DC7868F8B9DFF8F0C294452A +:1035400070EB010316D337E0276A27B96FF00C0040 +:1035500013B0BDE8F08F3B699845B5D03F68F4E7FC +:10356000B24890427CEB010301D30020F0E7029BBC +:10357000002BFAD0079B0F2B17DCFA7DB30002F06B +:10358000030203F07C031343FB7539462046FFF723 +:1035900007FB6B7BBB76029B3BB9FB7DC3F38402CD +:1035A000013262F38603FB75D0E76A7BBB7E9A42E9 +:1035B000DBD1029B002B35D0B309022B32D0039B09 +:1035C000BB60049BFB60142200210DA8FDF7D4FE14 +:1035D000039B0A93049B0B932B1D0C932B7BADF841 +:1035E0003EB0013BDBB2ADF83C30069B8DF842307B +:1035F000059B8DF8433094F82C308DF840A083F073 +:1036000001038DF844308DF84180A3680AA9204653 +:103610009847FB7DC3F38403013303F01F039B0230 +:10362000FB82A2E7FB7DC6F34012B2EBD31F40F052 +:10363000F480C3F38403434540F0F280029A2B7B6D +:10364000B609002A4DD0F2075DD4032B40F2EB807F +:10365000039BBB60049BFB602B7BAE1D033BDBB27B +:103660003246394604F10C00FFF7ACFA00280CDAB8 +:1036700039462046FFF794FAFB7DC3F384030133F8 +:1036800003F01F039B02FB820AE7DDE90884AB8895 +:103690003B834FF6FF73C9F12000A9F1200228FAFD +:1036A00009F104FA00F0014324FA02F2114318462A +:1036B000C9B2FFF7C9F909F10809B9F1400F03468A +:1036C000E9D1B8822A7B033AD2B23146FFF7CEF96C +:1036D000FB7DB882DA43C2F3C01262F3C713FB75F5 +:1036E00043E786B92E1D013BDBB23246394604F171 +:1036F0000C00FFF767FA0028BADB2A7BB88A013A88 +:10370000D2B23146E2E7F98AC1F30901013B04294B +:10371000DAB25BD8281D002307F11B069A4208D9AC +:1037200010F801CB06F801C0013101330529DBB2E5 +:10373000F4D103990A9104990B91934207F11B016B +:103740000C9138BF043379680D9134BF55FA83F377 +:1037500000230E93FB8AADF83EB0C3F309031A446D +:10376000069B8DF84230059B8DF8433094F82C3041 +:10377000ADF83C2083F001038DF8443000238DF830 +:1037800040A08DF841807B602A7BB88A013A291DD0 +:10379000FFF76CF93B8BB882834203D1A3680AA977 +:1037A0002046984720460AA9FFF702FEFB7DBA8A09 +:1037B000C3F38403013303F01F039B02FB823B8BA3 +:1037C0009A420CBF00206FF01000C1E67B68002B0E +:1037D000AFD0052001E01C3033461E68002EFAD120 +:1037E000091A081D2E1D184401EB090CBCF11B0F12 +:1037F0005FFA89F39DD89A429BD916F8013B00F8ED +:10380000013B09F10109EFE76FF00900A0E66FF055 +:103810000A009DE66FF00B009AE66FF00D0097E648 +:103820006FF00E0094E66FF00F0091E640420F003B +:1038300080841E00EFF3098305494A6B22F00102E0 +:103840004A63683383F30988002383F31188704740 +:1038500000EF00E0302080F3118862B60C4B0D4A77 +:10386000D96821F4E0610904090C0A43DA60D3F84D +:10387000FC20094942F08072C3F8FC200A6842F03B +:1038800001020A602022DA7783F82200704700BF25 +:1038900000ED00E00003FA05001000E010B5302351 +:1038A00083F311880E4B5B6813F4006314D0F1EEC0 +:1038B000103AEFF30984683C4FF08073E361094BE1 +:1038C000DB6B236684F3098800F0A4F810B1064B83 +:1038D000A36110BD054BFBE783F31188F9E700BF37 +:1038E00000ED00E000EF00E0430600084606000897 +:1038F0004FF0E023002258684FF0FF31930003F1AE +:10390000604303F5614301329042C3F88010C3F86D +:103910008011F3D27047000000F1604303F561436A +:103920000901C9B283F80013012200F01F039A4075 +:1039300043099B0003F1604303F56143C3F8802111 +:103940001A60704700230375826803691B689968D1 +:103950009142FBD25A680360426010605860704721 +:1039600000230375826803691B6899689142FBD83C +:103970005A680360426010605860704708B5084696 +:10398000302383F311880B7D032B05D0042B0DD03E +:103990002BB983F3118808BD8B6900221A604FF0A0 +:1039A000FF338361FFF7CEFF0023F2E7D1E9003256 +:1039B00013605A60F3E70000FFF7C4BF054BD968F6 +:1039C0000875186802681A60536001220275D86091 +:1039D000FCF722BE004E002030B50C4BDD684B1CBE +:1039E00087B004460FD02B46094A684600F050F9CC +:1039F0002046FFF7E3FF009B13B1684600F052F941 +:103A0000A86907B030BDFFF7D9FFF9E7004E0020E5 +:103A10007D390008044B1A68DB6890689B689842FF +:103A200094BF002001207047004E0020084B10B5C5 +:103A30001C68D86822681A60536001222275DC6015 +:103A4000FFF78EFF01462046BDE81040FCF7E4BDBD +:103A5000004E0020044B1A68DB6892689B689A420B +:103A600001D9FFF7E3BF7047004E002038B5074C7F +:103A700007490848012300252370656000F000FC19 +:103A80000223237085F3118838BD00BF2850002021 +:103A900010490008004E002008B572B6044B1865A6 +:103AA00000F0B6FA00F06EFB024B03221A70FEE73C +:103AB000004E00202850002000F02AB9EFF31180BA +:103AC00020B9EFF30583302282F31188704700009C +:103AD00010B530B9EFF30584C4F3080414B180F3D2 +:103AE000118810BDFFF7B6FF84F31188F9E70000D5 +:103AF0008B60022308618B82084670478368A3F1BC +:103B0000840243F8142C026943F8442C426943F8B8 +:103B1000402C094A43F8242CC26843F8182C02228E +:103B200003F80C2C002203F80B2C044A43F8102C49 +:103B3000A3F12000704700BF31060008004E0020AE +:103B400008B5FFF7DBFFBDE80840FFF735BF000011 +:103B5000024BDB6898610F20FFF730BF004E00205A +:103B6000302383F31188FFF7F3BF000008B5014647 +:103B7000302383F311880820FFF72EFF002383F3FF +:103B8000118808BD10B503689C68A2420CD85C6817 +:103B90008A600B604C602160596099688A1A9A604B +:103BA0004FF0FF33836010BD1B68121BECE7000071 +:103BB0000A2938BF0A2170B504460D460A26601945 +:103BC00000F058FB00F044FB041BA54203D8751C11 +:103BD0002E460446F3E70A2E04D9BDE870400120C2 +:103BE00000F08EBB70BD0000F8B5144B0D46D961D6 +:103BF00003F1100141600A2A1969826038BF0A2264 +:103C0000016048601861A818144600F025FB0A27D7 +:103C100000F01EFB431BA342064606D37C1C28195A +:103C200000F028FB27463546F2E70A2F04D9BDE805 +:103C3000F840012000F064BBF8BD00BF004E00203A +:103C4000F8B506460D4600F003FB0F4A134653F83D +:103C5000107F9F4206D12A4601463046BDE8F84013 +:103C6000FFF7C2BFD169BB68441A2C1928BF2C4684 +:103C7000A34202D92946FFF79BFF2246314603485B +:103C8000BDE8F840FFF77EBF004E0020104E002038 +:103C900010B4C0E9032300235DF8044B4361FFF730 +:103CA000CFBF000010B5194C236998420DD0D0E960 +:103CB0000032816813605A609A680A449A6000234F +:103CC00003604FF0FF33A36110BD2346026843F841 +:103CD000102F53600022026022699A4203D1BDE88E +:103CE000104000F0C1BA936881680B44936000F003 +:103CF000AFFA2269E1699268441AA242E4D91144F8 +:103D0000BDE81040091AFFF753BF00BF004E002066 +:103D10002DE9F047DFF8BC8008F110072C4ED8F8E9 +:103D2000105000F095FAD8F81C40AA68031B9A427C +:103D30003ED81444D5E900324FF00009C8F81C40C1 +:103D400013605A60C5F80090D8F81030B34201D122 +:103D500000F08AFA89F31188D5E90331284698479B +:103D6000302383F311886B69002BD8D000F070FAF0 +:103D70006A69A0EB04094A4582460DD2022000F090 +:103D8000BFFA0022D8F81030B34208D15146284675 +:103D9000BDE8F047FFF728BF121A2244F2E712EB02 +:103DA000090938BF4A4629463846FFF7EBFEB5E712 +:103DB000D8F81030B34208D01444211AC8F81C00B7 +:103DC000A960BDE8F047FFF7F3BEBDE8F08700BF8C +:103DD000104E0020004E002000207047FEE700003B +:103DE000704700004FF0FF3070470000BFF34F8F67 +:103DF000024A1369DB03FCD4704700BF0020024075 +:103E000008B5094B1B7873B9FFF7F0FF074B5A69E8 +:103E1000002ABFBF064A9A6002F188329A601A6887 +:103E200022F480621A6008BD405000200020024049 +:103E30002301674508B50B4B1B7893B9FFF7D6FFF5 +:103E4000094B5A6942F000425A611A6842F48052A2 +:103E50001A601A6822F480521A601A6842F480626A +:103E60001A6008BD40500020002002407F289ABF01 +:103E700000F58030C0020020704700004FF4006061 +:103E800070470000802070477F2808B50BD8FFF7E7 +:103E9000EDFF00F500630268013204D10430834273 +:103EA000F9D1012008BD0020FCE700007F2810B5F3 +:103EB00004461FD8FFF79AFFFFF7A2FF0E4BF3222D +:103EC0001A6102225A615A6942EAC0025A615A6969 +:103ED00042F480325A61FFF789FF4FF40061FFF727 +:103EE000C5FF00F04BF9FFF7A5FF2046BDE81040E5 +:103EF000FFF7CABF002010BD002002402DE9F843A3 +:103F000040EA020313F00703144606D0304B40F298 +:103F100031321A600020BDE8F88385182D4A954299 +:103F20000CD92B4A40F236311160F3E7031D1B68B0 +:103F30004A68934208D1083C08300831072C14D94C +:103F400002680B689A42F1D0FFF75AFFFFF74EFF65 +:103F5000214E08314FF001084FF00009012CA1F16A +:103F6000080706D8FFF766FF01E0002CECD101201E +:103F7000D1E7C6F81480054651F8083C45F8043BE3 +:103F800051F8043C4360FFF731FF336943F001030C +:103F90003361C6F81490026851F8083C9A420CD07C +:103FA0000B4B40F25E321A600C4B18600C4B1C60DD +:103FB0000C4B1F60FFF73EFFACE72D6851F8043C47 +:103FC0009D4201F10801EBD1083C0830C6E700BF73 +:103FD0003C50002000000408002002403050002027 +:103FE0003850002034500020084908B50B7828B11B +:103FF0001BB9FFF705FF01230B7008BD002BFCD098 +:10400000BDE808400870FFF715BF00BF4050002012 +:1040100008B54FF4C0314FF0005000F0B1F8BDE8E2 +:1040200008404FF480414FF0805000F0A9B80000E4 +:10403000084600F0E3BB000070B582B0FFF73EFD1C +:104040000E4E054600F004F93268904237BF0C4A24 +:104050000B49516814682EBFD1E90041013151600C +:104060000419034641F10001284601913360FFF72E +:104070002FFD0199204602B070BD00BF44500020C2 +:104080004850002070B582B0FFF718FD104E05466D +:1040900000F0DEF83268904237BF0E4A0D49516891 +:1040A00014682EBFD1E9004101315160041941F17A +:1040B00000010346284601913360FFF709FD01998D +:1040C0004FF47A7200232046FCF792F802B070BDDC +:1040D00044500020485000200244D2B2904200D107 +:1040E0007047431C800000F1804000F514500068C8 +:1040F00041F8040BD8B2F1E7124B10B5D3F8904059 +:10410000240409D4D3F89040C3F89040D3F89040E9 +:1041100044F40044C3F890400B4C2368024443F439 +:1041200080732360D2B2904200D110BD431C800046 +:1041300000F1804000F5145051F8044B0460D8B2EF +:10414000F1E700BF001002400070004007B50122F7 +:1041500001A90020FFF7C0FF019803B05DF804FB40 +:1041600013B50446FFF7F2FFA04205D0012201A9D2 +:1041700000200194FFF7C0FF02B010BD704700009F +:104180007047000070470000074B45F255521A6017 +:1041900002225A6040F6FF729A604CF6CC421A60D6 +:1041A000024B01221A70704700300040545000202A +:1041B000034B1B781BB1034B4AF6AA221A607047C7 +:1041C0005450002000300040054B1A6832B902F10B +:1041D000804202F50432D2F894201A60704700BF82 +:1041E00050500020024B4FF40002C3F89420704757 +:1041F0000010024008B5FFF7E7FF024B1868C0F354 +:10420000407008BD5050002070470000FEE70000DD +:104210000A4B0B480B4A90420BD30B4BDA1C121A79 +:10422000C11E22F003028B4238BF00220021FDF79D +:10423000A3B853F8041B40F8041BECE7744A0008C9 +:10424000D8500020D8500020D850002000F0C2B82C +:104250004FF08043586A70474FF080430022586304 +:104260001A610222DA6070474FF080430022DA6060 +:10427000704700004FF0804358637047FEE700002E +:1042800070B51B4B01630025044686B058608562FB +:104290000E46FFF7DFFA04F11003C4E904334FF0D0 +:1042A000FF33C4E90635C4E90044A560E562FFF7C1 +:1042B000CFFF2B460246C4E9082304F134010D4A1E +:1042C000256580232046FFF713FC0123E0600A4A9E +:1042D0000375009272680192B268CDE90223074B20 +:1042E0006846CDE90435FFF72BFC06B070BD00BF72 +:1042F000285000201C490008214900087D42000880 +:10430000024AD36A1843D062704700BF004E0020B3 +:104310004B6843608B688360CB68C3600B69436103 +:104320004B6903628B6943620B680360704700004E +:1043300008B5204BDA6A42F07F02DA62DA6A22F0CC +:104340007F02DA62DA6ADA6C42F07F02DA64DA6EED +:1043500042F07F02DA66184ADB6E11464FF0904059 +:10436000FFF7D6FF02F11C0100F58060FFF7D0FFD8 +:1043700002F1380100F58060FFF7CAFF02F1540135 +:1043800000F58060FFF7C4FF02F1700100F5806066 +:10439000FFF7BEFF02F18C0100F58060FFF7B8FF68 +:1043A00002F1A80100F58060FFF7B2FFBDE8084008 +:1043B00000F050B8001002402849000808B500F08D +:1043C000EDF9FFF753FBBDE80840FFF7FDBE000025 +:1043D000704700000F4B9A6D42F001029A659A6F88 +:1043E00042F001029A670C4A9B6F936843F0010305 +:1043F00093604FF08043A7229A624FF0FF32DA6257 +:1044000000229A615A63DA605A6001225A611A6086 +:10441000704700BF00100240002004E04FF08042CF +:1044200008B51169D3680B40D9B2C9439B07116124 +:1044300007D5302383F31188FFF73EFB002383F376 +:10444000118808BD08B5FFF753FABDE8084000F031 +:1044500081B900004E4B4FF0FF319A6A99629A6A17 +:1044600000229A62986AD86A60F07F00D862D86A9F +:1044700000F07F00D862D86A186B1963186B1A6352 +:10448000186B986B9963986B9A63986BD86BD96328 +:10449000D86BDA63D86B186C1964196C1A64196CD0 +:1044A000196E41F001011966D3F8801021F0010165 +:1044B000C3F88010D3F88010996D41F08051996550 +:1044C000996F21F080519967996F32494FF40040FC +:1044D0008860CA600A624A628A62CA620A634A6380 +:1044E0008A63CA630A644A648A64CA640A654A655C +:1044F0004A604FF48072C1F880204FF440720A6025 +:104500004A6912F48062FBD1D3F8901011F4407F15 +:104510001EBF4FF48031C3F89010C3F89020D3F839 +:10452000982042F00102C3F89820D3F8982092070F +:10453000FBD51A6842F480321A601A689003FCD5E1 +:10454000D3F8902022F00322C3F89020124ADA60B8 +:104550001A6842F080721A601A689101FCD50F49FE +:104560000F4800229A60C3F888100E49C3F89C20B7 +:10457000016002684A401207FBD19A6842F00302C8 +:104580009A609A6802F00C020C2AFAD1704700BFB8 +:104590000010024000700040232A610155010050C4 +:1045A0000020024004070400074A08B5536903F0DD +:1045B0000103536123B1054A13680BB15068984752 +:1045C000BDE80840FFF76AB90004014058500020D8 +:1045D000074A08B5536903F00203536123B1054A42 +:1045E00093680BB1D0689847BDE80840FFF756B90B +:1045F0000004014058500020074A08B5536903F0F1 +:104600000403536123B1054A13690BB150699847FC +:10461000BDE80840FFF742B90004014058500020AF +:10462000074A08B5536903F00803536123B1054AEB +:1046300093690BB1D0699847BDE80840FFF72EB9E0 +:104640000004014058500020074A08B5536903F0A0 +:104650001003536123B1054A136A0BB1506A98479E +:10466000BDE80840FFF71AB9000401405850002087 +:10467000164B10B55C6904F478725A61A30604D530 +:10468000134A936A0BB1D06A9847600604D5104A62 +:10469000136B0BB1506B9847210604D50C4A936BF2 +:1046A0000BB1D06B9847E20504D5094A136C0BB1E6 +:1046B000506C9847A30504D5054A936C0BB1D06C98 +:1046C0009847BDE81040FFF7E9B800BF000401407B +:1046D00058500020194B10B55C6904F47C425A61B3 +:1046E000620504D5164A136D0BB1506D984723052A +:1046F00004D5134A936D0BB1D06D9847E00404D5EF +:104700000F4A136E0BB1506E9847A10404D50C4AA2 +:10471000936E0BB1D06E9847620404D5084A136FAC +:104720000BB1506F9847230404D5054A936F0BB122 +:10473000D06F9847BDE81040FFF7B0B800040140C3 +:104740005850002008B5FFF769FEBDE80840FFF7A4 +:10475000A5B80000062108B50846FFF7DDF80621D8 +:104760000720FFF7D9F806210820FFF7D5F8062122 +:104770000920FFF7D1F806210A20FFF7CDF806211E +:104780001720FFF7C9F806212820FFF7C5F8BDE874 +:10479000084007211C20FFF7BFB8000008B5FFF74D +:1047A00051FE00F007F8FFF713FEBDE80840FFF7E1 +:1047B0004DBD00000023054A19460133102BC2E904 +:1047C000001102F10802F8D1704700BF58500020D4 +:1047D0000B460146184600F003B8000000F00EB882 +:1047E00010B5054C13462CB10A4601460220AFF322 +:1047F000008010BD2046FCE700000000024B01468F +:104800001868FFF715BC00BF1823002010B5013948 +:104810000244904201D1002005E0037811F8014FD5 +:10482000A34201D0181B10BD0130F2E72DE9F04181 +:10483000A3B1C91A17780144044603F1FF3C8C4226 +:10484000204601D9002009E00578BD4204F10104A9 +:10485000F5D10CEB0405D618A54201D1BDE8F081D5 +:1048600015F8018D16F801EDF045F5D0E7E70000E9 +:10487000034611F8012B03F8012B002AF9D17047E8 +:104880006F72672E6172647570696C6F742E4E75ED +:10489000636C656F2D4734393100000040A2E4F1AC +:1048A000646891060041A3E5F26569920700000083 +:1048B0004261642043414E496661636520696E64CC +:1048C00065782E000000000000000000792000083C +:1048D000811B000835270008791B0008291C0008E7 +:1048E0000D1E0008F11B0008B91B0008BD1B0008C5 +:1048F000951B00087D1B0008CD1D0008A11B0008AA +:104900006D280008AD1B0008A11D000863300000E1 +:104910000C490008584E0020285000206D61696E37 +:104920000069646C650000000004002800000000BD +:10493000AAAAAAAA00000024DFFF000000000000CD +:104940000000000000000A0000000000AAAAAAAAB5 +:1049500000000000FFFF00000000000099000000C0 +:104960000000000000000000AAAAAAAA000000009F +:10497000FFFF000000000000000000000000000039 +:1049800000000000AAAAAAAA00000000FFFF000081 +:104990000000000000000000000000000000000017 +:1049A000AAAAAAAA00000000FFFF00000000000061 +:1049B000000000000000000000000000AAAAAAAA4F +:1049C00000000000FFFF00000000000000000000E9 +:1049D0000000000000000000AAAAAAAA000000002F +:1049E000FFFF0000000000000000000034B8FF7F5F +:1049F00001000000000000001004000000000000A2 +:104A00000060030000000000FE2A0100D204000044 +:104A10001C23002000000000000000000000000037 +:104A20000000000000000000000000000000000086 +:104A30000000000000000000000000000000000076 +:104A40000000000000000000000000000000000066 +:104A50000000000000000000000000000000000056 +:104A60000000000000000000000000000000000046 +:044A70000000000042 :00000001FF diff --git a/Tools/bootloaders/PH4-mini-bdshot_bl.bin b/Tools/bootloaders/PH4-mini-bdshot_bl.bin new file mode 100755 index 00000000000000..021118dba0738e Binary files /dev/null and b/Tools/bootloaders/PH4-mini-bdshot_bl.bin differ diff --git a/Tools/bootloaders/PixFlamingo_bl.bin b/Tools/bootloaders/PixFlamingo_bl.bin new file mode 100755 index 00000000000000..a367bc20a2e8f8 Binary files /dev/null and b/Tools/bootloaders/PixFlamingo_bl.bin differ diff --git a/Tools/bootloaders/PixSurveyA1_bl.bin b/Tools/bootloaders/PixSurveyA1_bl.bin new file mode 100755 index 00000000000000..b788a106056f7e Binary files /dev/null and b/Tools/bootloaders/PixSurveyA1_bl.bin differ diff --git a/Tools/bootloaders/Pixhawk1-bdshot_bl.bin b/Tools/bootloaders/Pixhawk1-bdshot_bl.bin new file mode 100755 index 00000000000000..8486aa6b1b89a3 Binary files /dev/null and b/Tools/bootloaders/Pixhawk1-bdshot_bl.bin differ diff --git a/Tools/bootloaders/Pixhawk6X-bdshot_bl.bin b/Tools/bootloaders/Pixhawk6X-bdshot_bl.bin new file mode 100755 index 00000000000000..aec73925bb513c Binary files /dev/null and b/Tools/bootloaders/Pixhawk6X-bdshot_bl.bin differ diff --git a/Tools/bootloaders/Pixhawk6X_bl.bin b/Tools/bootloaders/Pixhawk6X_bl.bin index e423fa530e8c3e..f476675a51da26 100755 Binary files a/Tools/bootloaders/Pixhawk6X_bl.bin and b/Tools/bootloaders/Pixhawk6X_bl.bin differ diff --git a/Tools/bootloaders/Pixhawk6X_bl.elf b/Tools/bootloaders/Pixhawk6X_bl.elf new file mode 100755 index 00000000000000..d206e9bb647b33 Binary files /dev/null and b/Tools/bootloaders/Pixhawk6X_bl.elf differ diff --git a/Tools/bootloaders/Pixracer-periph_bl.bin b/Tools/bootloaders/Pixracer-periph_bl.bin index 8996c42e28f2ca..a1c5cc5e4a347a 100755 Binary files a/Tools/bootloaders/Pixracer-periph_bl.bin and b/Tools/bootloaders/Pixracer-periph_bl.bin differ diff --git a/Tools/bootloaders/Pixracer-periph_bl.hex b/Tools/bootloaders/Pixracer-periph_bl.hex index 3a75e01b2a8d9d..33a8a8e4b61199 100644 --- a/Tools/bootloaders/Pixracer-periph_bl.hex +++ b/Tools/bootloaders/Pixracer-periph_bl.hex @@ -1,25 +1,25 @@ :020000040800F2 -:1000000000070020F5040008652C0008E52B000817 -:100010003D2C0008E52B0008112C0008F70400080F -:10002000F7040008F7040008F70400081D3B000867 +:1000000000070020F5040008912F0008492F000880 +:10001000712F0008492F0008692F0008F704000815 +:10002000F7040008F7040008F7040008853F0008FB :10003000F7040008F7040008F7040008F7040008B4 :10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008AD650008D96500083A -:1000600005660008316600085D660008F7040008B0 +:10005000F7040008F7040008396B0008616B00081A +:10006000896B0008B16B0008D96B0008F704000821 :10007000F7040008F7040008F7040008F704000874 -:10008000F7040008F7040008F70400082128000816 -:100090004D2800085D280008F7040008896600085C +:10008000F7040008F7040008F7040008FD2E000834 +:10009000292F0008392F0008F7040008016C000818 :1000A000F7040008F7040008F7040008F704000844 -:1000B0001D640008F7040008F7040008F7040008AE +:1000B000E96C0008F7040008F7040008F7040008DA :1000C000F7040008F7040008F7040008F704000824 -:1000D000F7040008F7040008013C0008F7040008D2 -:1000E000F1660008F7040008F7040008F7040008A8 +:1000D000F7040008F7040008D56C0008F7040008CE +:1000E000656C0008F7040008F7040008F70400082E :1000F000F7040008F7040008F7040008F7040008F4 :10010000F7040008F7040008F7040008F7040008E3 :10011000F7040008F7040008F7040008F7040008D3 :10012000F7040008F7040008F7040008F7040008C3 :10013000F7040008F7040008F7040008F7040008B3 -:10014000F7040008F7040008F7040008455C0008FD +:10014000F7040008F7040008F70400082961000814 :10015000F7040008F7040008F7040008F704000893 :10016000F7040008F7040008F7040008F704000883 :10017000F7040008F7040008F7040008F704000873 @@ -29,7 +29,7 @@ :1001B000F7040008F7040008F7040008F704000833 :1001C000F7040008F7040008F7040008F704000823 :1001D000F7040008F7040008F7040008F704000813 -:1001E00001190008000000000000000000000000ED +:1001E000911800080000000000000000000000005E :1001F00053B94AB9002908BF00281CBF4FF0FF318E :100200004FF0FF3000F074B9ADF1080C6DE904CE89 :1002100000F006F8DDF804E0DDE9022304B07047E1 @@ -78,1725 +78,1782 @@ :1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 :1004D0004646EAE7204694E74046D1E7D0467BE728 :1004E000023B614432E7304609E76444023842E7A0 -:1004F000704700BF02E000F000F8FEE772B63A482D -:1005000080F30888394880F3098839484EF6085145 -:10051000CEF20001086040F20000CCF200004EF67E -:100520003471CEF200010860BFF34F8FBFF36F8FBD -:1005300040F20000C0F2F0004EF68851CEF2000109 -:100540000860BFF34F8FBFF36F8F4FF00000E1EEF5 -:10055000100A4EF63C71CEF200010860062080F3CE -:100560001488BFF36F8F05F051F805F02DF805F0F2 -:10057000B9FE4FF055301F491B4A91423CBF41F82C -:10058000040BFAE71C49194A91423CBF41F8040B9D -:10059000FAE71A491A4A1B4B9A423EBF51F8040B1C -:1005A00042F8040BF8E700201749184A91423CBF73 -:1005B00041F8040BFAE705F00BF805F0E7FE144CE0 -:1005C000144DAC4203DA54F8041B8847F9E700F0F5 -:1005D00041F8114C114DAC4203DA54F8041B884722 -:1005E000F9E704F0F3BF000000070020002300201B -:1005F000000000080001002000070020D06F000864 -:1006000000230020B0230020B0230020EC53002062 -:10061000E0010008E4010008E4010008E40100082A -:100620002DE9F04F2DED108AC1F80CD0C3689D461E -:10063000BDEC108ABDE8F08F002383F311882846B3 -:10064000A047002004F028FBFEE704F097FA00DF43 -:10065000FEE70000F8B501F0ABFA30B1294B0022FB -:100660000F211A725A729972DA7204F047FF074624 -:1006700004F096FF0546C8BB234B9F4236D001339A -:100680009F4236D0214B27F0FF029A4234D1F8B274 -:1006900000F048FD2E4642F2107400F04DFF08B104 -:1006A0000024264600F044FD08B90646044635B14C -:1006B000174B9F4203D004F06BFF00242646002016 -:1006C00004F026FF134B1B6913F4807318D00EB18E -:1006D00000F068F801F042FB00F08CFF01F092F9A5 -:1006E000204600F0BBF800F05DF8F9E72E46002444 -:1006F000D3E704460126D0E7064641F28834CCE72A -:100700001C46E7E700230020010007B0000008B006 -:10071000263A09B00004024008B501F03FF9A0F103 -:1007200020035842584108BD07B541F21203022187 -:1007300001A8ADF8043001F04FF903B05DF804FBF7 -:1007400010B5202383F311881248C3680BB104F05D -:1007500029FB114A0F4800234FF47A7104F0E6FA9E -:10076000002383F311880D4C236813B12368013BE8 -:100770002360636813B16368013B6360084B1B78B7 -:1007800033B9636823B9022001F05AFA3223636057 -:1007900010BD00BFB023002041070008CC2400207A -:1007A000C4230020274B284A10B51C461968013184 -:1007B00046D004339342F9D16268244B9A423FD920 -:1007C000234B9B6803F1006303F580339A4237D2D1 -:1007D00004F0B2FE04F0C4FE002001F02DF91D4B20 -:1007E0000220187001F01CFA1B4B1A6C00221A64CC -:1007F000196E1A66196E596C5A64596E5A665A6E99 -:100800005A6942F080025A615A6922F080025A61A4 -:100810005A691A6942F000521A611A6922F00052AC -:100820001A611B6972B64FF0E0232021C3F8084D0E -:10083000D4E9003281F311889D4683F3088810477C -:1008400010BD00BF0000010820000108FFFF0008E4 -:1008500000230020C4230020003802402DE9F04F7F -:1008600093B0AC4B00902022FF210AA89D6801F0B4 -:100870001FFAA94A1378A3B9A8480121C3601170CF -:10088000202383F31188C3680BB104F08BFAA44AC8 -:10089000A24800234FF47A7104F048FA002383F34E -:1008A0001188009B9F4A03B113609F49009C00235D -:1008B0000B70536098469B461E469A46012001F0F5 -:1008C000AFF924B1974B1B68002B00F01C8200206D -:1008D00001F064F80390039B002B01DA00F0D0FED6 -:1008E000039B002BEDDB012001F08CF9039B213BE6 -:1008F000162BE3D801A252F823F000BF59090008D3 -:1009000081090008150A0008BD080008BD08000894 -:10091000BD080008A90A00087B0C0008950B000818 -:10092000F70B00081F0C0008450C0008BD08000864 -:10093000570C0008BD080008C90C0008F909000898 -:10094000BD0800080D0D000865090008F909000838 -:10095000BD080008F70B00080220FFF7DDFE0028A5 -:1009600040F0FB81009B0221B8F1000F08BF1C463C -:1009700005A841F21233ADF8143001F02DF89DE7CF -:100980004FF47A7001F00AF8071EEBDB0220FFF744 -:10099000C3FE0028E6D0013F052F00F2E081DFE82A -:1009A00007F0030A0D10133605230593042105A84B -:1009B00001F012F817E057480421F9E75B480421D9 -:1009C000F6E75B480421F3E74FF01C09484601F0C5 -:1009D00035F809F104090590042105A800F0FCFF91 -:1009E000B9F12C0FF2D1012000FA07F747EA0B0BFF -:1009F0005FFA8BFB4FF0000A01F0A6F926B10BF06D -:100A00000B030B2B08BF0024FFF78EFE56E7494867 -:100A10000421CDE7002EA5D00BF00B030B2BA1D1A9 -:100A20000220FFF779FE074600289BD001203E4EAA -:100A300001F002F80220307001F0F2F84FF00008E7 -:100A40005FFA88F9484601F007F8044690B1484635 -:100A500001F012F808F101080028F1D1B846044667 -:100A600041F21213022105A8ADF814303E4600F001 -:100A7000B3FF23E701230220337001F0C3F82546BA -:100A8000244B9B68AB4207D9284600F0D7FF0130C2 -:100A900040F068810435F3E7234B00251D70214B9E -:100AA000B8465D603E46A7E7002E3FF45BAF0BF013 -:100AB0000B030B2B7FF456AF1B4B0220187001F079 -:100AC000AFF8322000F06AFFB0F10009FFF64AAF3C -:100AD00019F003077FF446AF0E4A926809EB05034D -:100AE00093423FF63FAFB9F5807F3FF73BAF124BE4 -:100AF0000193B94522DD4FF47A7000F04FFF039067 -:100B0000039A002AFFF62EAF019B039A03F8012BEC -:100B10000137EDE700230020C8240020B023002087 -:100B200041070008CC240020C42300200423002017 -:100B3000082300200C230020C8230020C820FFF732 -:100B4000EBFD074600283FF40DAF1F2D11D8C5F16E -:100B500020024A450AAB25F0030028BF4A468349D4 -:100B60000192184401F07EF8019A8048FF2101F0BB -:100B70009FF84FEAA9037D490193C9F387022846EC -:100B800001F09EF8064600283FF46AAF019B05EB92 -:100B9000830531E70220FFF7BFFD00283FF4E2AEF6 -:100BA00000F094FF00283FF4DDAE0027B946704BFB -:100BB0009B68BB4218D91F2F11D80A9B01330ED056 -:100BC00027F0030312AA134453F8203C0593484628 -:100BD000042205A902F054F804378146E7E73846B5 -:100BE00000F02CFF0590F2E7CDF81490042105A841 -:100BF00000F0F2FE00E70023642104A8049300F053 -:100C0000E1FE00287FF4AEAE0220FFF785FD00284C -:100C10003FF4A8AE049800F041FF0590E6E70023FA -:100C2000642104A8049300F0CDFE00287FF49AAE5E -:100C30000220FFF771FD00283FF494AE049800F005 -:100C40003DFFEAE70220FFF767FD00283FF48AAE88 -:100C500000F04CFFE1E70220FFF75EFD00283FF4C3 -:100C600081AE05A9142000F047FF04210746049037 -:100C700004A800F0B1FE3946B9E7322000F08EFE3C -:100C8000071EFFF66FAEBB077FF46CAE384A926862 -:100C900007EB0A0393423FF665AE0220FFF73CFDE7 -:100CA00000283FF45FAE27F003075744BA453FF4EE -:100CB000A3AE504600F0C2FE0421059005A800F046 -:100CC0008BFE0AF1040AF1E74FF47A70FFF724FD76 -:100CD00000283FF447AE00F0F9FE002844D00A9BFC -:100CE00001330BD008220AA9002000F0E9FF0028F8 -:100CF0003AD02022FF210AA800F0DAFFFFF714FD06 -:100D00001C4803F0CFFF13B0BDE8F08F002E3FF476 -:100D100029AE0BF00B030B2B7FF424AE00236421D0 -:100D200005A8059300F04EFE074600287FF41AAE92 -:100D30000220FFF7F1FC814600283FF413AEFFF7D5 -:100D4000F3FC41F2883003F0ADFF059801F03AF86A -:100D50004E4600F0F9FF3C46B0E506464CE64FF043 -:100D6000000AFFE5B8467BE6374679E6C82300204F -:100D700000230020A0860100094A136849F2690097 -:100D800099B21B0C00FB01331360064B186844F248 -:100D9000506182B2000C01FB0200186080B2704703 -:100DA000182300201423002010B50021102204462F -:100DB00000F07EFF034B03CB206061601868A060E9 -:100DC00010BD00BF107AFF1F2DE9F043224DBBB0CC -:100DD00001F050FFAB6840F2ED22C31A934232D9C2 -:100DE00006AFA8602B4628220021384602F052FCAC -:100DF00005F10E0000F054FF002604465FFA80F96A -:100E000005F10E08F3B2F100994501F1280107D967 -:100E100008EB06030822384602F03CFC0136F1E7F5 -:100E200008230122CDE9023205340C4B0193A4B210 -:100E300030230093CDE9047405A3D3E90023297B73 -:100E4000074802F03FFA3BB0BDE8F083AFF3008003 -:100E500078F6339F93CACD8DE8450020F5450020F4 -:100E6000EC34002070B50D4614461E4602F0C0F961 -:100E700050B9022E10D1012C0ED112A3D3E90023B8 -:100E8000C5E90023012007E0282C10D005D8012C4B -:100E900009D0052C0FD0002070BD302CFBD10BA346 -:100EA000D3E90023ECE70BA3D3E90023E8E70BA386 -:100EB000D3E90023E4E70BA3D3E90023E0E700BF75 -:100EC000AFF30080401DA12026812A0B78F6339FC6 -:100ED00093CACD8D9E6AC421818A46EE26417272E4 -:100EE000DF25D7B7F017304A39059E5613B50446AB -:100EF0002346084620220021019002F0CBFB2279F4 -:100F00000198032A234628BF032203F8042F202137 -:100F1000022202F0BFFB62790198072A234628BF0C -:100F2000072203F8052F2221032202F0B3FBA27946 -:100F30000198072A234628BF072203F8062F2521F8 -:100F4000032202F0A7FB019804F1080310222821D4 -:100F500002F0A0FB382002B010BD00002DE9F04FD8 -:100F6000ADF5017D21AD0EAE40F2751280460F4603 -:100F700022A80021296000F09BFE48220021304673 -:100F800000F096FE01F076FE564B4FF47A72B0FBFD -:100F9000F2F0186093E80700012386E807000DF1DE -:100FA0005A003382FFF700FF47F60523338406AB70 -:100FB00018464D4905F08AFD1D2230642946304609 -:100FC00086F83C20FFF792FF12AB04460146082248 -:100FD000284602F05FFB0822A1180DF149032846BC -:100FE00002F058FB0DF14A03082204F110012846D3 -:100FF00002F050FB13AB202204F11801284602F046 -:1010000049FB14AB402204F13801284602F042FBB0 -:1010100016AB082204F17801284602F03BFB0DF1E3 -:101020005903082204F18001284602F033FB04F141 -:10103000880A0DF15A0904F5847B4B465146082273 -:1010400028460AF1080A02F025FBD34509F10109F7 -:10105000F3D11BAB08225946284602F01BFB04F5CE -:1010600088744FF0000996F834304B450AD9B36BB9 -:1010700021464B440822284602F00CFB083409F1B3 -:101080000109F0E74FF0000996F83C304B4504EBBE -:10109000C90108D9336C08224B44284602F0FAFAF9 -:1010A00009F10109F0E700230393BB7E02930731A6 -:1010B00007F119030193C1F3CF010123CDE90451D5 -:1010C0000093F97E05A3D3E90023404602F0FAF825 -:1010D0000DF5017DBDE8F08FAFF300809E6AC4215D -:1010E000818A46EED4240020FC6A000810B50A4B21 -:1010F0000A4A1A6003F5805393F860203AB9DC6D10 -:101100002CB1204601F034FC204605F071FBBDE80F -:101110001040034801F02CBC18350020586C000822 -:1011200060450020014B1870704700BFE02400208C -:10113000F0B5334B1C7B85B034B1324B0E221A8193 -:101140000024204605B0F0BD2F4A1068516802AB5C -:1011500003C308232D492E480DEB030205F09AFB2B -:10116000054630B9274B2B480A221A8101F07EFB35 -:10117000E6E70169B1F5F81F06D9224B26480B2294 -:101180001A8101F073FBDCE7438B40F27A52934201 -:1011900007D01C490C2008811946204801F066FB45 -:1011A000CFE71F4A024402F11003994204D2154BC3 -:1011B0001C4810221A81E4E710398E1A204614497F -:1011C00001F05EFD3246074605F11801204601F0A8 -:1011D00057FDAB689F4202D1EB6898420AD0094B99 -:1011E0000D221A810090D5E902123B460E4801F00B -:1011F0003DFBA5E70D4801F039FB0124A1E700BF45 -:10120000E8450020D4240020AD6B0008DCFF1E0060 -:10121000000001081C6B0008286B00083A6B0008EE -:101220000800FFF7586B0008756B00089E6B0008FC -:101230002DE9F04FADB006AF80460C4601F0D8FF67 -:10124000054600285AD1237E022B1BD1E38A012BAD -:1012500018D101F00FFD0646FFF78EFD03464FF44F -:10126000C870DFF8D092B3FBF0F206F5167602FBF9 -:10127000103316FA83F3C9F80030E37E33B9A84B74 -:1012800000221A709C37BD46BDE8F08FA38AEEB2EB -:10129000013BB34205F101050BD93B1D1E44E9009A -:1012A00000960023082201F0F801204602F0B6F86B -:1012B000ECE707F11400FFF777FD324607F1140160 -:1012C000381D05F0D7FA0028D9D10F2E08D8944B35 -:1012D0001E70D9F80030A3F51673C9F80030D1E7B5 -:1012E000FB1CF8700146009307220346204602F0DB -:1012F00095F8F978404601F073FFC3E7E38A282B9D -:1013000026D010D8012B1ED0052BBBD1BFF34F8F99 -:101310008449854BCA6802F4E0621343CB60BFF393 -:101320004F8F00BFFDE7302BACD1637E7F4D013383 -:101330006A7BDBB29342E94603D1E27E2B7B9A4281 -:1013400065D0CD469EE721464046FFF707FE99E768 -:10135000A38A013B9BB2C92B94D8744D2E7B26BB2C -:1013600005F10C030093082233463146204602F073 -:1013700055F8731CF2B2D9001E46A38A013B9A426B -:1013800005DA0E322A44009200230822EEE70023F9 -:101390000022C5E900230023AB6085F8D730C5F8EB -:1013A000D8302B7B0BB9E37E2B73002507F1140992 -:1013B0003B1D082229464846C7E90155FD6002F059 -:1013C00069F93B7A05F1010AAB424FEACA0608D92E -:1013D000FB6808222B443146484602F05BF955462B -:1013E000EFE7C6F3CF06E17ECDE904960023039331 -:1013F000A37E0293193428230093019446A3D3E9D2 -:101400000023404601F05EFFFFF7DEFC3AE74FF0B5 -:10141000000807F11403A7F8148010220093414636 -:101420000123204601F0FAFFA68A023EB6B2F31C61 -:101430009B109B000733DB08A9EBC3039D460DF10E -:10144000180A1FFA88F34FEAC801B34201F11001EC -:101450000AD20AEB0803009308220023204601F079 -:10146000DDFF08F10108ECE795F8D70000F0F4FA89 -:10147000D5F8D83004461BB995F8D70000F0FCFA2F -:10148000D5F8D83033449C4204D295F8D7000130C7 -:1014900000F0F2FA4FEA960B4FF000081FFA88F1BD -:1014A0008B45D5E9003209D90AEB880103EB8800A6 -:1014B000012200F005FC08F10108EFE7F31842F102 -:1014C0000002C5E90032D5F8D83095F8D70006EB10 -:1014D0000308C5F8D88000F0BFFA804509D395F815 -:1014E000D730D5F8D8000133001B85F8D730C5F8C0 -:1014F000D800FF2E08D800232B7300F0E7FAFFF77F -:1015000017FE08B1FFF74EF92B68094A9B0A013311 -:1015100013810023AB6014E726417272DF25D7B731 -:10152000E534002000ED00E00400FA05E845002065 -:10153000D4240020E834002030B54FF00054244B70 -:1015400022689A4285B007D004F034F80446A8B95E -:101550000024204605B030BD1E4B627D1A701E4827 -:10156000237D03731D49C9220E3000F07BFB20460A -:10157000E022002100F09CFB0124EAE7184A194D03 -:10158000136C43F000731364AA6D174B9A42DFD1BA -:101590002B6E013B7E2BDBD8144A07CA01AB83E8D4 -:1015A00007001846032101F081FB6B6D83424FF069 -:1015B0000003CDD12A6D8A4201BFAB65054B2A6E6F -:1015C0001A7003BF0A4BEA6D1A601C46C1E700BFE0 -:1015D0009AAD44C5E0240020E84500201600002014 -:1015E00000380240006600405041A0B058660040FC -:1015F0001023002037B5194D194802236B71194B80 -:101600000122196801F000F800230193164B1749D5 -:1016100000931748174B4FF4805201F0BBFD164B57 -:10162000197811B1124801F0DBFD01F023FB0446EB -:10163000FFF7A2FB4FF4C873B0FBF3F202FB1303F6 -:1016400004F5167010FA83F00C4B186003F0A8FF35 -:1016500008B10F232B8103B030BD00BFD42400207C -:101660001835002010230020650E0008E424002017 -:10167000EC34002031120008E0240020E83400207F -:101680002DE9F04F2DED028B0FF26429D9E9008985 -:101690008D4C93B08D4E8E4F204601F077FE034661 -:1016A00060B30025CDE90F550E95ADF84450027B8F -:1016B0008DF8442099684068DFF83CA20FAA03C265 -:1016C0001B6843F000430E9301F0D6FA821941F1F2 -:1016D000000300950EA9384600F0C4FBA84205DDC2 -:1016E000204601F057FE8AF80050D5E79AF80030FE -:1016F000072B00F2B68001338AF800300BAE9FED65 -:101700006E8B0023724FDFF8F4A10A93ADF83430EA -:101710000B9373604FF0000B5B468DED008B012542 -:101720000DF11D0207A938468DF81C508DF81DB02B -:1017300000F01AFF9DF81C30002B40F096802046E8 -:1017400001F056FD0646002845D1624F01F092FA9D -:101750003B6898423FD301F08DFA8246FFF70CFBBD -:101760004FF4C8730AF5167AB0FBF3F202FB1303C9 -:101770001AFA83F33B60584F97F800B0CBF1100A88 -:10178000BBF1000F14BF33462B465FFA8AFA0EA84E -:101790008DF82830FFF708FBBAF1060F28BF4FF08D -:1017A000060A0EAB03EB0B0152460DF1290000F0C7 -:1017B00059FA0AAB0393182302930AF10102474B2B -:1017C000D2B2CDE90053049220463DA3D3E90023D1 -:1017D00001F010FD3E7001F04DFA414A414D136891 -:1017E000C31AB3F57A7F2FD3106001F045FA024691 -:1017F0000B46204601F0D8FD204601F0F9FC18B355 -:101800002B7B394E002B14BF03230223737101F08D -:1018100031FA0EAF4FF47A733946B0FBF3F0306013 -:101820003046FFF763FB1823073002932F4B0193D9 -:10183000C0F3CF0040F25513CDE903700093424648 -:101840004B46204601F0D6FC2B7B2BB1FFF7BCFAB0 -:101850002B7B002B7FF41EAF13B0BDEC028BBDE8D9 -:10186000F08F204601F096FD48E7DAF8143083F057 -:101870000203CAF81430594610220EA800F018FAD4 -:101880000DF11E0308AA0AA9384600F0E9FB96E804 -:1018900003000FAB83E803009DF834308DF844302B -:1018A0000A9B0E930EA9DDE90823204601F03AFFBA -:1018B00030E700BFAFF30080000000000000000030 -:1018C000401DA12026812A0BEC34002040420F004D -:1018D00018350020E8340020E5340020E4340020EE -:1018E000C8460020E8450020D4240020CC46002033 -:1018F000F1C6A7C1D068080FCD4600200004024001 -:1019000008B5054800F046FCBDE80840034A044914 -:10191000002004F067BF00BF183500201C470020DE -:10192000ED100008F7B5194E0C464FF47A7102FB22 -:1019300001F396F900200546501C0BD11448019381 -:1019400002682946176A2246B8478442019B03D1A0 -:10195000002310E0002AF1D096F90020511C01D09C -:10196000012A0DD10B4802682946166A2246B04763 -:10197000844205D10123084A0120137003B0F0BD51 -:101980004FF4FA7003F08EF90020F7E71C230020D3 -:10199000404B0020204700201047002007B50023BF -:1019A000024601210DF107008DF80730FFF7BAFF5D -:1019B00020B19DF8070003B05DF804FB4FF0FF3045 -:1019C000F9E700000A4608B50421FFF7ABFF80F0F5 -:1019D0000100C0B2404208BD30B4074B0A46197836 -:1019E000064B53F821402368DD69054B0146AC46A0 -:1019F000204630BC604700BF10470020286C00081C -:101A0000A086010070B503F005FC094E094D308039 -:101A1000002428683388834208D903F0F5FB2B683B -:101A200004440133B4F5803F2B60F2D370BD00BF96 -:101A300012470020D046002003F0B4BC00F1006043 -:101A400000F580300068704700F10060920000F5FA -:101A5000803003F033BC0000054B1A68054B1B882F -:101A60009B1A834202D9104403F0CEBB002070477A -:101A7000D04600201247002038B5074D044628689C -:101A8000204403F0C9FB28B928682044BDE8384049 -:101A900003F0DABB38BD00BFD046002010F00303CE -:101AA0000AD1B0F5047F05D200F10050A0F5104036 -:101AB000D0F80038184670470023FBE700F10050CB -:101AC000A0F51040D0F8100A70470000064991F8C0 -:101AD000243033B10023086A81F824300822FFF74C -:101AE000B3BF0120704700BFD4460020014B1868E7 -:101AF000704700BF002004E070B52A4B1B68C3F399 -:101B00000B0204461B0C62B140F21340824230D0FB -:101B100040F2194082422ED040F2214082422CD124 -:101B20000322214D0C2000FB0252556842F20102B3 -:101B3000934224D0B3F5805F23D041F20102934257 -:101B400021D041F2030293421FD041F20702934297 -:101B500014BF3F233123013C0C44013D0A46A242FD -:101B600015D215F9016F501C9EB100F8016C0246A8 -:101B7000F5E70122D5E70222D3E70C4DD6E7332360 -:101B8000E9E74123E7E75A23E5E75923E3E710466E -:101B900005E02C258442157001D9901C5370401A21 -:101BA00070BD00BF002004E0F86B0008B86B0008AF -:101BB000124B5A8842F201018A42134614D0B2F500 -:101BC000805F13D041F20102934211D041F203022F -:101BD00093420FD041F2070293420DD10423084AE9 -:101BE00002EB8303D87870470023F8E70123F6E778 -:101BF0000223F4E70323F2E700207047002004E00B -:101C0000E46B0008022802D1044B98617047012858 -:101C100002BF024B08229A61704700BF00040240D5 -:101C2000022804D1054B4FF400329A617047012815 -:101C3000FCD1024B4FF40022F7E700BF0004024042 -:101C4000022805D1064A536983F0020353617047A5 -:101C50000128FCD1024A536983F00803F6E700BF6C -:101C60000004024010B50023934203D0CC5CC4545E -:101C70000133F9E710BD000010B5013810F9013F3C -:101C80003BB191F900409C4203D11AB10131013AB4 -:101C9000F4E71AB191F90020981A10BD1046FCE73C -:101CA00003460246D01A12F9011B0029FAD17047E7 -:101CB00002440346934202D003F8011BFAE770473F -:101CC0002DE9F8431F4D144695F824200746884611 -:101CD00052BBDFF870909CB395F824302BB92022CA -:101CE000FF2148462F62FFF7E3FF95F82400C0F17B -:101CF0000802A24228BF2246D6B24146920005EB16 -:101D00008000FFF7AFFF95F82430A41B1E44F6B205 -:101D1000082E17449044E4B285F82460DBD1FFF725 -:101D2000D5FE0028D7D108E02B6A03EB820383425B -:101D3000CFD0FFF7CBFE0028CBD10020BDE8F88341 -:101D40000120FBE7D4460020024B1A78024B1A70A0 -:101D5000704700BF104700201C23002038B5134CEB -:101D6000134D204602F0A8FA2946204602F0D0FA88 -:101D70002D6810486A6D936B23F40023936302F07F -:101D800091FF0D49284602F0C9FB6A6D0B48936B21 -:101D90000B4943F400239363A0424FF4E1330B60FB -:101DA00003D0BDE8384002F0E7B938BD404B002011 -:101DB0009C6D000840420F00A46D000820470020E1 -:101DC000FC46002038B50B4B1A780B4B53F82250C9 -:101DD0000A4B9D4204460CD0094B002118461422A0 -:101DE000FFF766FF046001462846BDE8384002F070 -:101DF000C3B938BD10470020286C0008404B0020B4 -:101E0000FC460020202383F3118862B6704700004F -:101E1000002383F3118862B67047000010B4026893 -:101E200054681A4623465DF8044B18470120704752 -:101E30000020704700207047704700007047000086 -:101E4000002070470E20704700F5805090F8C800C1 -:101E5000C0F340007047000000F5805090F9C900C1 -:101E6000704700002DE9F0410C68BDF8187014F0BF -:101E700000541E466FD10B7B082B6CD8FFF7C2FFB6 -:101E80004569AB685B010CD4AB681B0108D4AC6836 -:101E900014F080545DD1FFF7BBFF2046BDE8F08110 -:101EA00001240B6804F1180C002BB8BFDB004FEACB -:101EB0000C1CB4BF43F004035B0545F80C300B6801 -:101EC0000FFA84FC13F0804F18BF05EB0C1E05EBD6 -:101ED0000C1C1EBFDEF8803143F00203CEF88031C7 -:101EE0000B7BCCF8843105EB04158B68C5F88C317D -:101EF0004B68C5F88831DCF8803143F00103CCF839 -:101F0000803100EB441541F268031D4403EB441398 -:101F10000344C5E9002608330D4601F10C0C55F8C1 -:101F200004EB43F804EB6545F9D184342D881D801A -:101F300000EB441407F00303257925F00B052B4330 -:101F40002371FFF765FF06973346BDE8F04100F0C7 -:101F5000AFBC0224A5E74FF0FF309FE713B500F5B3 -:101F600080540191E06D00F039FD1F280AD90199D4 -:101F7000E06D202200F0A8FDA0F120035842584156 -:101F800002B010BD0020FBE708B500F58050FFF758 -:101F900039FFC06D00F0F6FCBDE80840FFF738BF20 -:101FA00000220260828142608260704710B5002288 -:101FB0000023C0E900230023044603810C30FFF70F -:101FC000EFFF204610BD0000F0B5054600F580503B -:101FD0000C4690F8C83013F0040FC3F3800108BF1B -:101FE000114661F3820304F1840680F8C83005EBE2 -:101FF000461389B01B79D8072ED57AB319072DD48B -:102000006846FFF7D3FF05EB441303F5835303F151 -:10201000180703AA103318685968144603C4083314 -:10202000BB422246F7D1186820609B88A380DDE977 -:102030000E23CDE900230123ADF808302B68694653 -:102040001B6C2846984705EB46152B791A075CBF91 -:1020500043F008032B7101E0002AF4D109B0F0BD70 -:102060002DE9F047074688B007F5805468469A4640 -:102070008846FFF7C7FE9146FFF798FFE06D00F036 -:1020800093FC1F2829D9E06D2022694600F09EFDAF -:10209000202822D103AD444605AB2E4603CE9E42F6 -:1020A00020606160354604F10804F6D13068206094 -:1020B000B388A380DDE90023C9E90023BDF8083017 -:1020C000AAF80030FFF7A4FE4A4653464146384678 -:1020D00008B0BDE8F04700F0D9BBFFF799FE00203B -:1020E00008B0BDE8F08700002DE9F84F0023C0E9F3 -:1020F0000133254B044640F8183B0F46FFF750FFCD -:1021000004F12800FFF752FF04F1480804F5825556 -:102110004646083530462036FFF748FFAE42F9D133 -:1021200004F580554FF480534FF00009C5E9133989 -:10213000C5F848800123EE6504F5875804F58456F8 -:10214000C5F8549085F8583085F86030083608F1A5 -:1021500008084FF0000A4FF0000B46E908ABA6F163 -:102160001800FFF71DFF203646F8289C4645F4D19D -:1021700085F8C97017B1054800F076FD044B63611E -:102180002046BDE8F88F00BF586C0008306C00088E -:102190000064004010B5044B197804464A1C1A70BC -:1021A000FFF7A2FF204610BD184700202DE9F04799 -:1021B000002950D0294B2A4FB7FBF1F599428CBF2B -:1021C0000A231123581EB5FBF3FC03FB1C53C4B2B6 -:1021D0002BB102280346F5D80020BDE8F0870CF1AA -:1021E000FF36B6F5806FF7D2C4EBC40E0EF10303D1 -:1021F0004FEAE309C3F3C703A4EB030809F1010A9B -:102200004FF47A755FFA88F009FB05555AFA88F899 -:10221000B5FBF8F5B5F5617FC1BF0EF1FF33C3F330 -:10222000C703E01AC0B25C1C50FA84F40CFB04F43F -:10223000B7FBF4F4A142CFD1013BDBB20F2BCBD8DB -:102240000138C0B20728C7D80021107116809170DC -:10225000D3700120C1E70846BFE700BF3F420F002F -:1022600080DE800270B505460E464FF47A746B69C5 -:102270005B6803F00103B34207D04FF47A7002F0B9 -:1022800011FD013CF3D1204670BD0120FCE70000A8 -:1022900030B54269936913F0700F16D000230B4CD0 -:1022A000936103F1840200EB421211794D0709D5C5 -:1022B000890707D5416954F823508D60117941F0A1 -:1022C000040111710133032BEBD130BD446C0008C4 -:1022D00073B51D46436916469A68D207044609D568 -:1022E0009A6801219960C2F34002CDE9006500219E -:1022F000FFF76AFE63699A68D1050BD59A684FF4B7 -:1023000080719960C2F34022CDE900650121204629 -:10231000FFF75AFE63699A68D2030BD59A684FF4A7 -:1023200080319960C2F34042CDE900650221204628 -:10233000FFF74AFE204602B0BDE87040FFF7A8BF95 -:10234000F8B50446466900296CD106F10C073868D7 -:1023500080076AD006EB01153868D5F8B00110F097 -:10236000040FD5F8B0011ABFC00840F00040400D7E -:10237000A061D5F8B0C11CF0020F1CBF40F0804036 -:10238000A061D5F8B40106EB011100F00F0084F84C -:102390002400D1F8B8012077D1F8B801000A60779D -:1023A000D1F8B801000CA077D1F8B801000EE077A1 -:1023B000D1F8BC0184F82000D1F8BC01000A84F8EF -:1023C0002100D1F8BC01000C84F82200D1F8BC1126 -:1023D000090E84F823103821396004F1340004F127 -:1023E000180104F1240551F8046B40F8046BA9426C -:1023F000F9D109880180C4E90A23214600232386F4 -:1024000051F8283B20461B6C984704F58052204623 -:1024100092F8C83043F0040382F8C830BDE8F840B1 -:10242000FFF736BF06F1100791E7F8BD10B5044677 -:1024300000F022FC02460B4652EA030102D0013AA8 -:1024400063F100030449086820B12146BDE810404B -:10245000FFF776BF10BD00BF14470020F8B500F5A8 -:1024600083511E46FFF7CEFCDFF844C0083100243C -:1024700004F1840500EB45152B795F070ED4DB06CC -:102480000CD5D1E900739742B34107D243695CF898 -:1024900024709F602B7943F004032B710134032CCB -:1024A00001F12001E4D1BDE8F840FFF7B1BC00BF65 -:1024B000446C000808B5FFF7A5FCFFF7E9FEBDE88E -:1024C0000840FFF7A5BC0000F8B5436905469868C9 -:1024D00000F0E050B0F1E05F0F461FD0E8B1FFF729 -:1024E00091FC05F583541034002606F1840305EBB6 -:1024F00043131B791A0706D50136032E04F1200475 -:10250000F3D1012007E05B07F6D42146384600F0FE -:1025100009FA0028F0D1FFF77BFCF8BD0120FCE7A9 -:1025200000F5805008B5FFF76DFCC06D00F03CFA77 -:10253000FFF76EFC43090CBF0120002008BD00001E -:10254000F8B51D46002313700F4606461446FFF7E4 -:10255000E7FF80F00100387025B129463046FFF7CB -:10256000B3FF2070F8BD00002DE9B8410C461546B8 -:102570001F46804600F080FB0B462178024609B9D1 -:10258000287850B14046FFF769FFFFF793FF3B46BD -:102590002A462146FFF7D4FF0120BDE8B88100009C -:1025A00010B5FFF72FFC174B1A6C42F000721A643B -:1025B0001A6A42F000721A621A6A00F5805422F018 -:1025C00000721A62FFF724FC94F8C830DB0718D4B5 -:1025D000B9B102211320FFF715FC01F005FC02211F -:1025E000142001F001FC0221152001F0FDFB94F8FC -:1025F000C83043F0010384F8C830BDE81040FFF74D -:1026000007BC10BD003802402DE9F04700F58055A9 -:1026100088B095F8C930012B04468846164600F26A -:10262000FB807E4F57F823200AB947F82300D7F8DC -:1026300000A0C4F80C802674BAF1000F09D141F251 -:10264000D00004F0D7F851468146FFF74DFDC7F89A -:10265000009095F8C930012B5DD001212046FFF78D -:102660009FFFFFF7CFFB6269136823F0020313603B -:102670006269136843F001031360636900275F61B7 -:1026800001212046FFF7C4FBFFF7ECFD002800F016 -:102690008480E86D00F076F904F58359BA4609F1B3 -:1026A0000809202200216846FFF702FB02A8FFF775 -:1026B00077FCCDF818A06A4609EB07030DF1180E58 -:1026C0009446BCE80300F44518605960624603F183 -:1026D0000803F5D1DCF80000186020379CF80420CE -:1026E0001A71602FDDD195F8C8306FF3820300278F -:1026F00085F8C8306A4641462046ADF80070ADF80E -:1027000002708DF80470FFF751FD6369C0B94FF492 -:1027100000421A6011E0386803685B6B9847014615 -:1027200000289AD13868FFF73BFF386803683246C3 -:102730005B684146984700288FD108B0BDE8F08714 -:1027400061221A609DF802309DF803201B061204D6 -:1027500002F4702203F040731343BDF80020C2F36B -:10276000090213439DF804201205022E02F4E00230 -:102770000CBF4FF000410021134362690B43D3614A -:10278000636913225A616269136823F001031360BD -:1027900039462046FFF766FD08B96369B7E795F843 -:1027A000C93093BB6169D1F8002242F00102C1F83F -:1027B00000226169D1F8002222F47C5222F00E023C -:1027C000C1F800226169D1F8002242F46062C1F8C8 -:1027D00000226269C2F814326269C2F80432626986 -:1027E00041F6FF71C2F80C126269C2F840326269A8 -:1027F000C2F8443263690122C3F81C226269D2F82C -:10280000003223F00103C2F8003295F8C83043F0DB -:10281000020385F8C83090E700208EE714470020B7 -:1028200008B500F029FA50EA0103024602D0421E20 -:1028300061F10001044B186810B10B46FFF748FD29 -:10284000BDE8084001F09EB91447002008B50020FB -:10285000FFF7ECFDBDE8084001F094B908B5012090 -:10286000FFF7E4FDBDE8084001F08CB90FB400208B -:1028700004B0704713B56C4684E80600031D94E865 -:10288000030083E80500012002B010BD73B5856820 -:10289000019155B11B885B0707D4D0E90036DB6B8B -:1028A0009847019AC1B23046A847012002B070BDD6 -:1028B000F0B5866889B005460C465EB1BDF8383083 -:1028C0005B070AD4D0E90037DB6B98472246C1B2D8 -:1028D0003846B047012009B0F0BD00220023CDE901 -:1028E00000230023ADF808300A4603AB01F10806C7 -:1028F000106851681C4603C40832B2422346F7D11F -:10290000106820609288A28000F0B8F90423ADF826 -:1029100008302B68CDE900011B6C694628469847B2 -:10292000D8E7000030B503680968DD0FB5EBD17F4B -:1029300023F0604421F060424FEAD1700BD0002BAD -:10294000B8BFA40C0029B8BF920C944202D034BF87 -:102950000120002030BD944205D1C1F38070C3F343 -:1029600080738342F6D194422CBF00200120F1E70E -:1029700010B5037C044613B9006803F073FF2046CA -:1029800010BD00000023BFF35B8FC360BFF35B8FFC -:10299000BFF35B8F8360BFF35B8F7047BFF35B8FC9 -:1029A0000068BFF35B8F704770B505460C30FFF7CA -:1029B000F5FF05F1080604463046FFF7EFFFA04299 -:1029C00006D930466D68FFF7E9FF2544281A70BD27 -:1029D0003046FFF7E3FF201AF9E7000070B505461F -:1029E000406898B105F10800FFF7D8FF05F10C0623 -:1029F00004463046FFF7D2FF8442304694BF6D68EC -:102A00000025FFF7CBFF013C2C44201A70BD0000CD -:102A100038B50C460546FFF7C7FFA04210D305F1B5 -:102A20000800FFF7BBFF04446868B4FBF0F100FB4B -:102A30001144BFF35B8F0120AC60BFF35B8F38BDE7 -:102A40000020FCE72DE9F041144607460D46FFF74C -:102A5000C5FF844228BF0446D4B1B84658F80C6B71 -:102A60004046FFF79BFF3044286040467E68FFF7F2 -:102A700095FF331A9C4203D86C600120BDE8F081B9 -:102A80006B60A41B3B68AB602044E8600220F5E764 -:102A90002046F3E738B50C460546FFF79FFFA042F6 -:102AA00010D305F10C00FFF779FF04446868B4FB0C -:102AB000F0F100FB1144BFF35B8F0120EC60BFF32A -:102AC0005B8F38BD0020FCE72DE9FF418846694651 -:102AD0000746FFF7B7FF6C4606B204EBC6060025B3 -:102AE000B44209D06268206808EB0501FFF7BAF824 -:102AF000636808341D44F3E729463846FFF7CAFFE8 -:102B0000284604B0BDE8F081F8B505460C300F4604 -:102B1000FFF744FF05F1080604463046FFF73EFF85 -:102B2000A042304688BF6C68FFF738FF201A386033 -:102B300020B130462C68FFF731FF2044F8BD00007B -:102B400073B5144606460D46FFF72EFF844228BF94 -:102B500004460190DCB101A93046FFF7D5FF019B87 -:102B600033B93268C5E90233C5E9002401200CE01D -:102B70009C4238BF01942860019868608442F5D96E -:102B80003368AB60241AEC60022002B070BD2046AE -:102B9000FBE700002DE9FF410F466946FFF7D0FF34 -:102BA0006C4600B204EBC0050026AC4209D0D4F854 -:102BB000048054F8081BB8194246FFF753F84644FE -:102BC000F3E7304604B0BDE8F081000038B50546B3 -:102BD000FFF7E0FF044601462846FFF719FF2046AD -:102BE00038BD000000B59BB0EFF30981682268464C -:102BF000FFF738F8EFF30583044B9A6BDA6A9A6AA9 -:102C00009A6A9A6A9A6A9A6A9B6AFEE700ED00E0FD -:102C100000B59BB0EFF3098168226846FFF722F800 -:102C2000EFF30583044B9A6B9A6A9A6A9A6A9A6AD6 -:102C30009A6A9B6AFEE700BF00ED00E000B59BB01A -:102C4000EFF3098168226846FFF70CF8EFF305837C -:102C5000034B5A6B9A6A9A6A9A6A9A6A9B6AFEE767 -:102C600000ED00E0FEE700000FB408B5029801F0A7 -:102C7000A9FFFEE702F0E0BB02F0B8BB02F0B6BB72 -:102C800030B5094D0A4491420DD011F8013B58402E -:102C9000082340F30004013B2C4013F0FF0384EAB7 -:102CA0005000F6D1EFE730BD2083B8EDF7B54FF017 -:102CB000FF33DFF854C0DFF854E000EB81011A461F -:102CC00088421CD050F8044B019401AF042417F83B -:102CD000015B82EA05620825DB18164605F1FF351F -:102CE0005241002EBCBF83EA0C0382EA0E0215F0AB -:102CF000FF05F1D1013C14F0FF04E8D1E0E7D8432F -:102D0000D14303B0F0BD00BF9336EAA9EBE1F04236 -:102D10002DE9F041C56915B9C161BDE8F0814B6885 -:102D200023F06047C3F38A464FEAD37EC3F380782B -:102D300016EA230638BF3E46AC462B465A68BEEB21 -:102D4000D27F22F060440AD0002A18DAA40CB442E0 -:102D500017D19D420FD10D60DEE71346EEE7A74283 -:102D600007D102F08044C2F3807242450BD054B1C7 -:102D7000EFE708D2EDE7CCF800100B60CDE7B442E6 -:102D800001D0B442E5D81A689C46002AE5D1196002 -:102D9000C3E700002DE9F047089D01F007044FEA62 -:102DA000D508224405F0070500EBD1004FF47F4918 -:102DB000944201D1BDE8F08704F0070705F0070A47 -:102DC00057453E4638BF5646C6F10806111B8E428F -:102DD00028BF0E46E10808EBD50E415C13F80EC083 -:102DE000B94029FA06F721FA0AF1FFB28CEA01018B -:102DF00047FA0AF739408CEA010C03F80EC0344454 -:102E00003544D5E780EA0120082341F2210201B2CE -:102E10004000002980B203F1FF33B8BF504013F0E7 -:102E2000FF03F4D17047000038B50C468D18A54259 -:102E300000D138BD14F8011BFFF7E4FFF7E70000ED -:102E400002684AB113680360C388018901339BB2E9 -:102E50009942C38038BF03811046704770B588B06F -:102E6000202204460D4668460021FEF721FF204639 -:102E70000495FFF7E5FF024658B16B46054608AEDC -:102E80001C4603CCB44228606960234605F108055E -:102E9000F6D1104608B070BD082817D909280CD003 -:102EA0000A280CD00B280CD00C280CD00D280CD0E4 -:102EB0000E2814BF4020302070470C20704710208F -:102EC000704714207047182070472020704700007A -:102ED000082817D90C280CD910280CD914280CD97B -:102EE00018280CD920280CD930288CBF0F200E2090 -:102EF0007047092070470A2070470B2070470C204C -:102F000070470D207047000010B54B6823B9CA8A7E -:102F100063F30902CA8210BDC4681A681C60C360EA -:102F2000438A013B43824A60EFE700002DE9F84FF6 -:102F30001D46CB8A0F46C3F30901062981469246F6 -:102F40000B4630D00020AAB207F119049EB2052E1C -:102F50001FFA80F80FD8904503F1010306D3FB8ACE -:102F60000A4462F30903FB8201201AE01AF80060A8 -:102F7000E6540130EAE79045F1D2A1F1060B1C239B -:102F80007C68BBFBF3F203FB12BB1FFA8BF6002C31 -:102F900045D14846FFF754FF044638B978606FF0D2 -:102FA0000200BDE8F88F4FF00008E6E70026066053 -:102FB0007860ADB24FF0000B454510D90AEB08031D -:102FC000221D13F8011B9155B1B208F101081B290C -:102FD0001FFA88F82BD0454506F10106F1D8FB8A87 -:102FE000C3F30902154465F30903BCE7013292B249 -:102FF0001C462368002BF9D1AB1F0B441C21B3FBEB -:10300000F1F301339BB29A42D3D2BBF1000FD0D17E -:103010004846FFF715FF20B9C4F800B0BFE701220A -:10302000E7E7C0F800B05E4620600446C1E74545CA -:10303000D5D94846FFF704FF08B92060AFE7C0F8CC -:1030400000B0002620600446B6E700002DE9F04FEE -:103050002DED028B83B0CDE90013BDF83C5007463F -:103060009146002A00F092802DB10E9B002B00F0BB -:103070008D80072D32D807F10C00FFF7E1FE0446E2 -:1030800038B96FF00204204603B0BDEC028BBDE8F6 -:10309000F08F14220021FEF70BFE0E992A4604F150 -:1030A0000800FEF7DFFD681CC0B2FFF711FFFFF755 -:1030B000F3FE207499F80030013814FA80F003F020 -:1030C0001F0363F03F030372009B43F00041616004 -:1030D00038462146FFF71CFE0124D4E700F10C031B -:1030E0004FF0000808EE103A4FF0800A464644467A -:1030F00018EE100AFFF7A4FE83460028C1D0142260 -:103100000021FEF7D5FDC6BB019BABF808300220BD -:103110000E9B00F1080299195BFA82F20130C0B2ED -:10312000082801D0AE422AD3FFF7D2FEFFF7B4FE43 -:1031300099F80020009B411E02F01F0242EA48124B -:10314000AE4208BF4FF0400A5BFA81F14AEA020A38 -:1031500043F0004281F808A08BF81000CBF804205F -:1031600059463846FFF7D4FD0134AE4224B288F008 -:1031700001084FF0000ABBD185E70020C8E711F82D -:1031800001CB02F801CB0136B6B2C7E76FF00104FC -:1031900079E70000F8B515460E46282200210446BE -:1031A0001F46FEF785FD069B6360B5F5001F079B74 -:1031B000A76034BF6A094FF6FF72236204F10C0066 -:1031C00097B200239A4205D80023036027826382C6 -:1031D000A382F8BD0660013330462036F2E70000D6 -:1031E00003781BB94BB2002BC8BF017070470000B9 -:1031F000007870472DE9F74FDDF83C90BDF830506E -:103200000D9E9DF83840BDF84070804692469B4622 -:10321000B9F1000F01D1002F51D11F2C4FD898F8D0 -:103220000000B0B9072F47D835F0030347D13A461D -:1032300049464FF6FF70FFF7F7FD20F001002D0221 -:10324000400445EA0464400C44EA40244FF6FF730E -:1032500021E040EA0520072F40EA0464F6D9002562 -:103260004FF6FF73C5F12000A5F120022AFA05F1FF -:103270000BFA00F001432BFA02F211431846C9B2CF -:10328000FFF7C0FD0835402D0346EBD13A464946CD -:10329000FFF7CAFD0346CDE9009732462146404676 -:1032A000FFF7D4FE33780133DBB21F2B88BF002336 -:1032B000337003B0BDE8F08F6FF00300F9E76FF0F3 -:1032C0000100F6E72DE9F04F85B09246DDF8488021 -:1032D0000F9D9DF840209DF84490BDF84C70064627 -:1032E0009B46B8F1000F01D1002F48D11F2A46D8C4 -:1032F0003378002B46D00C0244EA02649DF8381063 -:1033000044EAC93444EA01441C43072F44F08004D2 -:1033100032D900234FF6FF72C3F1200CA3F1200035 -:103320002AFA03F10BFA0CFC41EA0C012BFA00F02B -:103330000143C9B210460393FFF764FD039B0833B2 -:10334000402B0246E8D13A464146FFF76DFD034661 -:10335000CDE900872A4621463046FFF777FEB9F1CE -:10336000010F06D12B780133DBB21F2B88BF00235E -:103370002B7005B0BDE8F08F4FF6FF73E8E76FF0F4 -:103380000100F6E76FF00300F3E70000C06900B149 -:1033900004307047C3691A68C261C2681A60C360AA -:1033A000438A013B438270472DE9F041D0F81880F1 -:1033B000194E14461D464146002709B9BDE8F08163 -:1033C000D1E90223A21A65EB0303964277EB0303CC -:1033D0001ED283698B420DD1FFF796FD83691B686E -:1033E0008361C3680B60438AC1608169013B43828A -:1033F0008846E2E7FFF788FD0B68C8F80030C3682D -:103400000B60438AC160013B4382D8F80010D4E7C7 -:1034100088460968D1E700BF80841E002DE9F04F7F -:103420008BB00D46DDF8509014469B468046002830 -:1034300000F01981B9F1000F00F01581531E3F2BE8 -:1034400000F21181012A03D1BBF1000F40F00B8182 -:103450000023CDE90833B8F81430B5EBC30F4FEAB9 -:10346000C30703D300200BB0BDE8F08F2B199F4298 -:10347000D8F80C303ABF7F1BFFB227461BB9D8F8EB -:103480001030002B7AD02F2D4ED8C5F13006B74220 -:103490004FF000032CBFF6B23E4600932946D8F801 -:1034A000080008AB3246FFF775FCA7EB060A354467 -:1034B0005FFA8AFAB8F8143003F10053063BDB00D8 -:1034C0000493D8F80C3003933021039B13B1BAF165 -:1034D000000F2CD1D8F8100040B1BAF1000F05D080 -:1034E000009608AB5246691AFFF754FC38B2002F19 -:1034F000B8D066070AD00AAB03EBD401624211F8D8 -:10350000083C02F00702134101F8083C082C3CD9A2 -:10351000102C40F2B580202C40F2B780BBF1000F98 -:1035200000F09C80082334E0BA460026C2E7049BE2 -:10353000E02B28BFE02306930B44AB42059314D93C -:103540005A1B03980096924534BF5246D2B2691A6C -:1035500008AB04300792FFF71DFC079A1644AAEB4C -:10356000020A1544F6B25FFA8AFA049B069A059994 -:103570009B1A0493039B1B680393A6E70093D8F858 -:10358000080008AB3A462946AEE7BBF1000F13D05E -:103590000123B4EBC30F6CD0082C12D89DF8203057 -:1035A000621E23FA02F2D50706D54FF0FF3202FA67 -:1035B00004F423438DF820309DF8203089F8003042 -:1035C00051E7102C12D8BDF82030621E23FA02F207 -:1035D000D10706D54FF0FF3202FA04F42343ADF8C9 -:1035E0002030BDF82030A9F800303CE7202C0FD85F -:1035F0000899631E21FA03F3DA0705D54FF0FF326D -:1036000002FA04F40C430894089BC9F800302AE736 -:10361000402C2BD0DDE90865611EC4F12102A4F124 -:10362000210326FA01F105FA02F225FA03F3114308 -:103630001943CB0712D50122A4F12003C4F12001C4 -:1036400002FA03F322FA01F1A240524243EA0103D3 -:1036500063EB430332432B43CDE90823DDE9082321 -:10366000C9E90023FFE66FF00100FCE66FF00800F7 -:10367000F9E6082CA0D9102CB3D9202CEED8C3E73A -:10368000BBF1000FADD0022383E7BBF1000FBBD02D -:1036900004237EE730B5012A144638BF0124402CAC -:1036A00085B028BF40240025012ACDE9025518D84D -:1036B0001B788DF8083063070AD004AB03EBD40500 -:1036C000624215F8083C02F00702934005F8083CF6 -:1036D000009103462246002102A8FFF75BFB05B0DC -:1036E00030BD082AE4D9102A03D81B88ADF8083069 -:1036F000E1E7202A8DBFD3E900231B680293CDE9BF -:103700000223D8E710B5CB681BB98B600B618B82A5 -:1037100010BDC4681A681C60C360438A013B4382C1 -:10372000CA60F0E72DE9F04FD1F8008093B018F0AF -:10373000800FCDE90323C8F3C01219BFC8F3C03B03 -:10374000C8F306264FF0020B1646B8F1000F0446E8 -:103750000D4680F2D18118F0C043059340F0CC8132 -:103760000B7B002B00F0C881BBF1020F03D0017866 -:10377000B14240F0C48108F07F0106916AB3C8F3FA -:10378000074A2B44069A93F80390760646EA0B46BE -:1037900046EA82465FEAD91346EA0A06079300F032 -:1037A000908000220023CDE90A23069B00936768DE -:1037B0005B4652460AA92046B84700287ED0A76932 -:1037C0009FB9314604F10C00FFF748FB0746E0B90A -:1037D0006FF0020013B0BDE8F08FC8F30F2A18F0A5 -:1037E0007F0F08BF0AF0030ACBE73B699E420DD06A -:1037F0003F68002FF9D1314604F10C00FFF72EFB92 -:1038000007460028E4D0A3693B60A761DDE90A23ED -:1038100000264FF6FF70C6F1200E22FA06F103FAD9 -:103820000EFEA6F1200C23FA0CFC41EA0E0141EA3F -:103830000C01C9B2083609920893FFF7E3FA402E4B -:10384000DDE90832E7D1B882FB7D09F01F06C3F33A -:1038500084039B1BD7E9022198B2002BBCBF00F167 -:1038600020031BB252EA0100C8F304680FD003988A -:10387000821A049860EB0101A74890424FF00002C1 -:103880008A4104D3079A002A5BD0012B23DDFA7DFD -:103890004FEA890302F0030203F07C031343FB7534 -:1038A00039462046FFF730FB079BA3B9FB7DC3F3E6 -:1038B0008402013262F38603FB7504E06FF00B00B3 -:1038C00088E7A76917B96FF00C0083E73B699E4250 -:1038D000BAD03F68F6E719F0400F32D0039BBB60C7 -:1038E000049BFB60142200210DA8FEF7E1F9039B65 -:1038F0000A93049B0B932B1D0C932B7BADF83EA0DE -:10390000013BDBB2ADF83C30069B8DF8433094F8B8 -:1039100024308DF840B083F001038DF844308DF8E9 -:103920004160A3688DF842800AA920469847FB7D34 -:10393000C3F38403013303F01F039B02FB820020C7 -:1039400048E7FB7DC9F34012B2EBD31F40F0DA80A9 -:10395000C3F38403B34240F0D88007992B7B4FEA2E -:103960009912002934D0D20741D4032B40F2D080E1 -:10397000039BBB60049BFB602B7BAE1D033BDBB258 -:103980003246394604F10C00FFF7D0FA00280DDA70 -:1039900020463946FFF7B8FAFB7DC3F384030133B1 -:1039A00003F01F039B02FB82032013E7AB883B83DA -:1039B0002A7B033AB88AD2B23146FFF735FAFB7D4B -:1039C000B882DA43C2F3C01262F3C713FB75B6E7DD -:1039D0006AB92E1D013BDBB23246394604F10C00B8 -:1039E000FFF7A4FA0028D3DB2A7B013AE2E7F98A41 -:1039F000C1F30901013B0529DAB259D8281D00237A -:103A000007F11A0C9A4208D910F801EB0CF801E002 -:103A1000013101330629DBB2F4D103990A910499EB -:103A20000B91934207F11A010C9138BF0433796866 -:103A30000D9134BF55FA83F300230E93FB8AADF842 -:103A40003EA0C3F309031A44069B8DF8433094F853 -:103A50002430ADF83C2083F001038DF8443000237E -:103A60008DF840B08DF841608DF842807B602A7BF4 -:103A7000B88A013A291DFFF7D7F93B8BB8828342F8 -:103A800003D1A3680AA92046984720460AA9FFF750 -:103A900039FEFB7DB88AC3F38403013303F01F03AF -:103AA0009B02FB823B8B984214BF1120002091E6C1 -:103AB0007B68002BB1D0062001E01C306346D3F8B0 -:103AC00000C0BCF1000FF8D1091A081D05F1040C63 -:103AD00000EB030905989DF8143001EB000EBEF1D0 -:103AE0001B0F9AD89A4298D91CF8013B09F8013B60 -:103AF000059B01330593EDE76FF009006AE66FF06F -:103B00000A0067E66FF00D0064E66FF00E0061E6F4 -:103B10006FF00F005EE600BF80841E00EFF30983A4 -:103B200005494A6B22F001024A63683383F309882E -:103B3000002383F31188704700EF00E0202080F31A -:103B4000118862B60C4B0D4AD96821F4E061090472 -:103B5000090C0A43DA60D3F8FC20094942F080726C -:103B6000C3F8FC200A6842F001020A601022DA77EA -:103B700083F82200704700BF00ED00E00003FA0563 -:103B8000001000E010B5202383F311880E4B5B6812 -:103B900013F4006314D0F1EE103AEFF30984683C9B -:103BA0004FF08073E361094BDB6B236684F3098874 -:103BB00000F0BAFF10B1064BA36110BD054BFBE747 -:103BC00083F31188F9E700BF00ED00E000EF00E0AB -:103BD0004B0600084E060008024AD36843F0C003B3 -:103BE000D360704700440040044B5A6810439A6801 -:103BF00058600AB1181D1047704700BF20470020C9 -:103C00002DE9F0413C4ED6F85C52EF682B68DA059E -:103C10009CB20CD5202383F311884FF40070FFF77A -:103C2000E3FF6FF480732B60002383F3118820235C -:103C300083F31188DFF8C08014F02F0339D183F3A8 -:103C40001188380613D5210611D5202383F3118856 -:103C50002A4800F0EFF900284CDA0820FFF7C4FFEB -:103C60004FF67F733B40EB60002383F311887A06A5 -:103C700015D5630613D5202383F31188D6E91323C2 -:103C80009A4209D1336C3BB127F040073F04102022 -:103C90003F0CFFF7A9FFEF60002383F31188D6F8EC -:103CA0006422D3680BB110699847BDE8F041FFF773 -:103CB00069BF230712D014F0080F0CBF002080202A -:103CC000E10748BF40F02000A20748BF40F0400095 -:103CD000630748BF40F48070FFF786FFA4066B6857 -:103CE00005D596F860124046194000F053FA2C684A -:103CF000A4B2A1E76860B7E720470020584700203A -:103D000010B5054C054A0021204600F013FA044B7B -:103D1000C4F85C3210BD00BF20470020D93B00082A -:103D20000044004038B52A4C037C002918BF0C46DB -:103D3000012B0546C0F8644210D1264B98420DD1A4 -:103D4000254B1A6C42F400321A641A6E42F40032A7 -:103D50001A660B2126201B6E00F046F8D5F85C226F -:103D60001E4923688A424FEA530003D001F580615F -:103D70008A422AD11A490144B4F90400B1FBF3F391 -:103D80000028BEBF23F0070003F0070343EA400307 -:103D9000A1889360E38843F040031361238943F0D3 -:103DA0000103536141F4045343F02C03D36001F445 -:103DB000A05100231360B1F5806F136853680CBFE6 -:103DC0007F23FF2385F8603238BD0649D3E700BF63 -:103DD0009C6C000820470020003802400010014081 -:103DE00000BD010580DE800200F1604303F5614300 -:103DF0000901C9B283F80013012200F01F039A40A1 -:103E000043099B0003F1604303F56143C3F880213C -:103E10001A607047F8B5154682680669AA420B46D3 -:103E2000816938BF8568761AB54204460BD21846B8 -:103E30002A46FDF717FFA3692B44A361A3685B1B08 -:103E4000A3602846F8BD0CD918463246FDF70AFF94 -:103E5000AF1BE1683A463044FDF704FFE3683B449A -:103E6000EBE718462A46FDF7FDFEE368E5E70000AC -:103E700083689342F7B51546044638BF8568D0E994 -:103E80000460361AB5420BD22A46FDF7EBFE636991 -:103E90002B446361A36828465B1BA36003B0F0BD9D -:103EA0000DD932460191FDF7DDFE0199E068AF1BA7 -:103EB0003A463144FDF7D6FEE3683B44E9E72A463B -:103EC000FDF7D0FEE368E4E710B50A440024C361BF -:103ED000029B8460C0E90000C0E90511C160026175 -:103EE000036210BD08B5D0E90532934201D1826862 -:103EF00082B98268013282605A1C42611970D0E92D -:103F000004329A4224BFC3684361002100F0E6FEF8 -:103F1000002008BD4FF0FF30FBE7000070B5202304 -:103F200004460E4683F31188A568A5B1A368A2696B -:103F3000013BA360531CA36115782269934224BFFF -:103F4000E368A361E3690BB120469847002383F33C -:103F50001188284607E03146204600F0AFFE0028D1 -:103F6000E2DA85F3118870BD2DE9F74F04460E465D -:103F700017469846D0F81C904FF0200A8AF3118813 -:103F80004FF0000B154665B12A4631462046FFF733 -:103F900041FF034660B94146204600F08FFE0028ED -:103FA000F1D0002383F31188781B03B0BDE8F08FB4 -:103FB000B9F1000F03D001902046C847019B8BF355 -:103FC0001188ED1A1E448AF31188DCE7C0E9051157 -:103FD000C160C3611144009B8260C0E900000161BF -:103FE00003627047F8B504460D461646202383F356 -:103FF0001188A768A7B1A368013BA36063695A1C35 -:1040000062611D70D4E904329A4224BFE36863619F -:10401000E3690BB120469847002080F3118807E040 -:104020003146204600F04AFE0028E2DA87F3118884 -:10403000F8BD0000D0E905239A4210B501D182688D -:104040007AB98268013282605A1C82611C780369E5 -:104050009A4224BFC3688361002100F03FFE2046DE -:1040600010BD4FF0FF30FBE72DE9F74F04460E4639 -:1040700017469846D0F81C904FF0200A8AF3118812 -:104080004FF0000B154665B12A4631462046FFF732 -:10409000EFFE034660B94146204600F00FFE0028BF -:1040A000F1D0002383F31188781B03B0BDE8F08FB3 -:1040B000B9F1000F03D001902046C847019B8BF354 -:1040C0001188ED1A1E448AF31188DCE70268436800 -:1040D0001143016003B11847704700001430FFF727 -:1040E00043BF00004FF0FF331430FFF73DBF000027 -:1040F0003830FFF7B9BF00004FF0FF333830FFF71B -:10410000B3BF00001430FFF709BF00004FF0FF31CC -:104110001430FFF703BF00003830FFF763BF000023 -:104120004FF0FF323830FFF75DBF000000207047CE -:10413000FFF7E6BD37B515460E4A02600022426021 -:10414000C0E902220122044602740B46009000F1ED -:104150005C014FF480721430FFF7B6FE00942B46DA -:104160004FF4807204F5AE7104F13800FFF72EFFB2 -:1041700003B030BDB06C000810B52023044683F3B3 -:104180001188FFF7CFFD02232374002383F31188E6 -:1041900010BD000038B5C36904460D461BB90421A3 -:1041A0000844FFF793FF294604F11400FFF79AFE35 -:1041B000002806DA201D4FF48061BDE83840FFF783 -:1041C00085BF38BD026843681143016003B11847D9 -:1041D0007047000013B5446BD4F894341A68117812 -:1041E000042915D1217C022912D1197912890123C0 -:1041F0008B4013420CD101A904F14C0001F078FF6F -:10420000D4F89444019B21790246206800F0CEF94D -:1042100002B010BD143001F0FBBE00004FF0FF33C0 -:10422000143001F0F5BE00004C3001F0CDBF0000AD -:104230004FF0FF334C3001F0C7BF0000143001F0E5 -:10424000C9BE00004FF0FF31143001F0C3BE0000C2 -:104250004C3001F099BF00004FF0FF324C3001F0BC -:1042600093BF00000020704710B5D0F894341A684E -:1042700011780429044617D1017C022914D15979F7 -:10428000528901238B4013420ED1143001F05CFEA1 -:10429000024648B1D4F894444FF4807361792068A1 -:1042A000BDE8104000F070B910BD0000406BFFF792 -:1042B000DBBF0000704700007FB5124B0360002396 -:1042C0004360C0E90233012502260F4B0574044602 -:1042D0000290019300F18402294600964FF4807306 -:1042E000143001F00DFE094B0294CDE9006304F592 -:1042F00023724FF48073294604F14C0001F0D4FE80 -:1043000004B070BDD86C0008AD420008D54100086B -:104310000B68202282F311880A7903EB82029061F4 -:104320004A79093243F822008A7912B103EB8203F9 -:10433000986102230374C0F89414002383F3118856 -:104340007047000038B5037F044613B190F854302D -:10435000ABB9201D01250221FFF734FF04F1140041 -:1043600025776FF0010100F0C5FC84F8545004F18A -:104370004C006FF00101BDE8384000F0BBBC38BD17 -:1043800010B5012104460430FFF71CFF00232377FA -:1043900084F8543010BD000038B5044600251430B0 -:1043A00001F0C6FD04F14C00257701F095FE201DBB -:1043B00084F854500121FFF705FF2046BDE838403E -:1043C000FFF752BF90F8443003F06003202B07D171 -:1043D00090F84520212A4FF0000303D81F2A06D861 -:1043E00000207047222AFBD1C0E90E3303E0034AC4 -:1043F00082630722C2630364012070471D230020EB -:1044000037B5D0F894341A681178042904461AD1C3 -:10441000017C022917D11979128901238B4013429B -:1044200011D100F14C05284601F016FF58B101A941 -:10443000284601F05DFED4F89444019B21790246A0 -:10444000206800F0B3F803B030BD0000F0B500EB19 -:10445000810385B09E6904460D46FEB1202383F397 -:10446000118804EB8507301D0821FFF7ABFEFB68C0 -:104470005B691B6806F14C001BB1019001F046FE20 -:10448000019803A901F034FE024648B1039B294676 -:10449000204600F08BF8002383F3118805B0F0BDAF -:1044A000FB685A691268002AF5D01B8A013B134049 -:1044B000F1D104F14402EAE7093138B550F821405E -:1044C000DCB1202383F31188D4F894241368527943 -:1044D00003EB8203DB689B695D6845B104216018CA -:1044E000FFF770FE294604F1140001F037FD204665 -:1044F000FFF7BAFE002383F3118838BD7047000030 -:1045000001F0FAB8012303700023C0E90133C3614D -:1045100083620362C36243620363704738B5044633 -:10452000202383F311880025C0E90355C0E9055510 -:10453000416001F0F1F80223237085F3118838BD42 -:1045400070B500EB810305465069DA600E461446EB -:1045500018B110220021FDF7ABFBA06918B11022A1 -:104560000021FDF7A5FB31462846BDE8704001F06B -:104570009DB90000826802F0011282600022C0E949 -:104580000422826101F01EBAF0B400EB8104478975 -:10459000E4680125A4698D403D43458123600023E3 -:1045A000A2606360F0BC01F039BA0000F0B400EB27 -:1045B00081040789E468012564698D403D430581D4 -:1045C00023600023A2606360F0BC01F0B3BA000076 -:1045D00070B50223002504460370C0E90255C0E906 -:1045E0000455C564856180F8345001F0FBF86368B8 -:1045F0001B6823B129462046BDE87040184770BDAE -:10460000037880F850300523037043681B6810B5A9 -:1046100004460BB1042198470023A36010BD00009D -:1046200090F85020436802701B680BB105211847B1 -:104630007047000070B590F83430044613B1002381 -:1046400080F8343004F14402204601F0DDF963685B -:104650009B68B3B994F8443013F0600535D000215D -:10466000204601F02FFC0021204601F021FC636868 -:104670001B6813B1062120469847062384F834307E -:1046800070BD204698470028E4D0B4F84A30E26B69 -:104690009A4288BFE36394F94430E56B002B4FF0F6 -:1046A000200380F20381002D00F0F280092284F8BB -:1046B000342083F311880021D4E90E232046FFF72C -:1046C00075FF002383F31188DAE794F8452003F09F -:1046D0007F0343EA022340F20232934200F0C58096 -:1046E00021D8B3F5807F48D00DD8012B3FD0022BC5 -:1046F00000F09380002BB2D104F14C02A26302229D -:10470000E2632364C1E7B3F5817F00F09B80B3F5DA -:10471000407FA4D194F84630012BA0D1B4F84C309E -:1047200043F0020332E0B3F5006F4DD017D8B3F574 -:10473000A06F31D0A3F5C063012B90D8636894F8C3 -:1047400046205E6894F84710B4F848302046B047D9 -:10475000002884D04368A3630368E3631AE0B3F5D9 -:10476000106F36D040F6024293427FF478AF5C4B34 -:10477000A3630223E3630023C3E794F84630012BCD -:104780007FF46DAFB4F84C3023F00203C4E90E554A -:10479000A4F84C30256478E7B4F84430B3F5A06F42 -:1047A0000ED194F8463084F84E30204601F072F86D -:1047B00063681B6813B101212046984703232370C7 -:1047C0000023C4E90E339CE704F14F03A3630123E4 -:1047D000C3E72378042B10D1202383F311882046CC -:1047E000FFF7C8FE85F311880321636884F84F50F2 -:1047F00021701B680BB12046984794F84630002B77 -:10480000DED084F84F300423237063681B68002BCC -:10481000D6D0022120469847D2E794F848301D06AA -:1048200003F00F0120460AD501F0E0F8012804D07A -:1048300002287FF414AF2B4B9AE72B4B98E701F03B -:10484000C7F8F3E794F84630002B7FF408AF94F8EC -:10485000483013F00F01B3D01A06204602D501F0FC -:1048600045FBADE701F038FBAAE794F84630002B92 -:104870007FF4F5AE94F8483013F00F01A0D01B067A -:10488000204602D501F01EFB9AE701F011FB97E7E5 -:10489000142284F8342083F311882B462A462946B3 -:1048A0002046FFF771FE85F31188E9E65DB1152218 -:1048B00084F8342083F311880021D4E90E232046A4 -:1048C000FFF762FEFDE60B2284F8342083F31188A3 -:1048D0002B462A4629462046FFF768FEE3E700BF3D -:1048E000086D0008006D0008046D000838B590F8E8 -:1048F00034300446002B3ED0063BDAB20F2A34D8BF -:104900000F2B32D8DFE803F0373131082232313152 -:104910003131313131313737C56BB0F84A309D42D2 -:1049200014D2C3681B8AB5FBF3F203FB12556DB9B1 -:10493000202383F311882B462A462946FFF736FEAB -:1049400085F311880A2384F834300EE0142384F8A8 -:104950003430202383F3118800231A461946204659 -:10496000FFF712FE002383F3118838BD036C03B1F7 -:1049700098470023E7E70021204601F0A3FA002131 -:10498000204601F095FA63681B6813B106212046A2 -:1049900098470623D7E7000010B590F83430142B61 -:1049A000044629D017D8062B05D001D81BB110BD5D -:1049B000093B022BFBD80021204601F083FA00219D -:1049C000204601F075FA63681B6813B10621204682 -:1049D0009847062319E0152BE9D10B2380F83430D2 -:1049E000202383F3118800231A461946FFF7DEFDC2 -:1049F000002383F31188DAE7C3689B695B68002BA7 -:104A0000D5D1036C03B19847002384F83430CEE746 -:104A1000024B0022C3E900339A60704788490020A6 -:104A2000002303748268054B1B6899689142FBD28E -:104A30005A680360426010605860704788490020DF -:104A400008B5202383F31188037C032B05D0042BA6 -:104A50000DD02BB983F3118808BD436900221A6079 -:104A60004FF0FF334361FFF7DBFF0023F2E7D0E9AC -:104A7000003213605A60F3E7002303748268054B29 -:104A80001B6899689142FBD85A68036042601060C5 -:104A90005860704788490020054B196908741868E8 -:104AA00002681A605360186101230374FBF7B8BDF4 -:104AB0008849002030B54B1C0B4D87B0044610D000 -:104AC0002B690A4A01A800F031F92046FFF7E4FFFC -:104AD000049B13B101A800F065F92B69586907B070 -:104AE00030BDFFF7D9FFF8E788490020414A0008A8 -:104AF00038B50C4D41612B6981689A689142044632 -:104B000003D8BDE83840FFF78BBF1846FFF7B4FF66 -:104B100001232C61014623742046BDE83840FBF791 -:104B20007FBD00BF88490020044B1A681B6990684C -:104B30009B68984294BF002001207047884900205C -:104B400010B5084C236820691A682260546001225D -:104B500023611A74FFF790FF01462069BDE81040F9 -:104B6000FBF75EBD8849002008B5FFF7DDFF18B1EF -:104B7000BDE80840FFF7E4BF08BD0000FFF7E0BF55 -:104B8000FEE7000010B50C4CFFF742FF00F0C0F844 -:104B90000A498022204600F047F8012344F8180C07 -:104BA0000374FEF7CBFF002383F3118862B6044839 -:104BB000BDE8104000F058B8B04900200C6D000866 -:104BC0001C6D000808B572B6034B586200F0FEFB7E -:104BD00000F0B0FCFEE700BF8849002000F01CB9DF -:104BE000EFF3118020B9EFF30583202282F31188BF -:104BF0007047000010B530B9EFF30584C4F3080422 -:104C000014B180F3118810BDFFF7AEFF84F3118853 -:104C1000F9E70000034A516853685B1A9842FBD8D1 -:104C2000704700BF001000E08260022202827047DD -:104C30008368A3F17C0243F80C2C026943F83C2CF6 -:104C4000426943F8382C074A43F81C2CC26843F8E1 -:104C5000102C022203F8082C002203F8072CA3F1E1 -:104C6000180070473906000810B5202383F3118817 -:104C7000FFF7DEFF00210446FFF73AFF002383F32E -:104C80001188204610BD0000024B1B6958610F209F -:104C9000FFF702BF88490020202383F31188FFF724 -:104CA000F3BF000008B50146202383F311880820D4 -:104CB000FFF700FF002383F3118808BD49B1064BBD -:104CC00042681B6918605A60136043600420FFF754 -:104CD000F1BE4FF0FF3070478849002003689842CA -:104CE00006D01A680260506059611846FFF798BEF6 -:104CF0007047000038B504460D462068844200D154 -:104D000038BD036823605C604561FFF789FEF4E706 -:104D1000054B03F11402C3E905224FF0FF310022D5 -:104D2000C3E90712704700BF8849002070B51C4EC8 -:104D3000C0E9032305460C4601F0C0FA334653F898 -:104D4000142F9A420DD13062C5E901242A600A2C41 -:104D50002CBF00190A30C6E90555BDE8704001F0C6 -:104D60009BBA316A431AE31838BF1C469368A342C2 -:104D700002D9081901F09EFA73699A6894420CD816 -:104D80005A68AC602B606A6015609A685D60121B9F -:104D90009A604FF0FF33F36170BD1B68A41AECE713 -:104DA0008849002038B51B4C636998420DD0D0E982 -:104DB000003213605A6000228168C2609A680A4417 -:104DC0009A604FF0FF33E36138BD2246036842F832 -:104DD000143F002193425A60C16003D1BDE83840BE -:104DE00001F062BA9A688168256A0A449A6001F003 -:104DF00065FA63699A68411B8A42E5D9AB181D1AA6 -:104E0000092D206A98BF01F10A02BDE8384010441C -:104E100001F050BA884900202DE9F041184C0027D4 -:104E200004F11406656901F049FA236AAA68C11AF7 -:104E30008A4215D813442362D5E9003213605A60C0 -:104E40006369D5F80C80EF60B34201D101F02CFA10 -:104E500087F311882869C047202383F31188E1E78D -:104E60006169B14209D013441B1ABDE8F0410A2B15 -:104E70002CBFC0180A3001F01DBABDE8F08100BF98 -:104E8000884900200C2303604FF0FF30704700007A -:104E900000207047FEE70000704700004FF0FF3031 -:104EA0007047000002290CD0032904D001290748CB -:104EB00018BF00207047032A05D8054800EBC20040 -:104EC0007047044870470020704700BF006E00081C -:104ED0002C230020B46D000870B59AB00546084632 -:104EE00001A9144600F0C2F801A8FCF7D9FE431C42 -:104EF0005B00C5E900340022237003236370C6B24F -:104F000001AB02341046D1B28E4204F1020401D842 -:104F10001AB070BD13F8011B04F8021C04F8010C50 -:104F20000132F0E708B5202383F311880348FFF727 -:104F300067FA002383F3118808BD00BF404B0020AF -:104F400090F8443003F01F02012A07D190F8452061 -:104F50000B2A03D10023C0E90E3315E003F06003F0 -:104F6000202B08D1B0F848302BB990F84520212AE1 -:104F700003D81F2A04D8FFF725BA222AEBD0FAE774 -:104F8000034A82630722C26303640120704700BFA3 -:104F90002423002007B5052917D8DFE801F01916EA -:104FA00003191920202383F31188104A019001214D -:104FB000FFF7C6FA01980E4A0221FFF7C1FA0D4821 -:104FC000FFF7EAF9002383F3118803B05DF804FBCF -:104FD000202383F311880748FFF7B4F9F2E7202371 -:104FE00083F311880348FFF7CBF9EBE7546D000812 -:104FF000786D0008404B002038B50C4D0C4C0D4925 -:105000002A4604F10800FFF767FF05F1CA0204F120 -:1050100010000949FFF760FF05F5CA7204F1180096 -:105020000649BDE83840FFF757BF00BF08500020D1 -:105030002C230020346D00083E6D0008496D0008E7 -:1050400070B5044608460D46FCF72AFEC6B2204657 -:10505000013403780BB9184670BD32462946FCF777 -:105060000BFE0028F3D10120F6E700002DE9F04700 -:1050700005460C46FCF714FE2C49C6B22846FFF73D -:10508000DFFF08B10836F6B229492846FFF7D8FFF6 -:1050900008B11036F6B2632E0BD8DFF89080DFF837 -:1050A0009090244FDFF898A02E7846B92670BDE87E -:1050B000F08729462046BDE8F04701F007BD252EC0 -:1050C00030D1072241462846FCF7D6FD80B91A4B5D -:1050D000224603F10C0153F8040B42F8040B8B42F7 -:1050E000F9D119889B781180937007350F34DBE76D -:1050F000082249462846FCF7BFFD98B90F4BA21C71 -:10510000197809090232C95D02F8041C13F8011B61 -:1051100001F00F015345C95D02F8031CF0D11834AA -:105120000835C1E704F8016B0135BDE7206E0008C2 -:10513000496D0008286E00080A6B0008107AFF1FEE -:105140001C7AFF1FBFF34F8F024AD368DB03FCD4E6 -:10515000704700BF003C024008B5094B1B7873B98B -:10516000FFF7F0FF074B1A69002ABFBF064A5A60D3 -:1051700002F188325A601A6822F480621A6008BD0F -:1051800066520020003C02402301674508B50B4BE6 -:105190001B7893B9FFF7D6FF094B1A6942F000421A -:1051A0001A611A6842F480521A601A6822F4805216 -:1051B0001A601A6842F480621A6008BD66520020C4 -:1051C000003C02401728F0B516D80C4C0C49237847 -:1051D0007BB90C4D0E4618234FF0006255F8047B46 -:1051E00046F8042B013B13F0FF033A44F6D10123A8 -:1051F000237051F82000F0BD0020FCE7C8520020C9 -:10520000685200203C6E0008014B53F820007047A4 -:105210003C6E000818207047172810B5044601D9C5 -:10522000002010BDFFF7CEFF064B53F82430184482 -:10523000C21A0BB90120F4E712680132F0D1043B25 -:10524000F6E700BF3C6E0008172870B504462FD85B -:10525000FFF7C6FC1749FFF775FFFFF77DFFF32344 -:10526000CB600C23B4FBF3F203FB1245D30143EAFA -:10527000C503DBB243F4007343F002030B610B6917 -:1052800043F480330B6106462046FFF75BFFFFF7D0 -:1052900099FF094B53F8241000F048F93046FFF706 -:1052A00075FFFFF7A7FC2046BDE87040FFF7B4BFCD -:1052B000002070BD003C02403C6E000812F001036B -:1052C0002DE9F04105460E4614464BD18218B2F145 -:1052D000026F61D8314B1B6813F001035CD0304F73 -:1052E000FFF77EFCFFF738FFF323FB60FFF72AFF91 -:1052F000314640F20128032C18D824F00104284E2E -:105300000C446D1A40F20118A142336905EB010704 -:105310002AD123F001033361FFF738FFFFF76AFC5E -:105320000120BDE8F081043C0435E4E7AB07E4D19B -:105330003B6923F440733B613B6943EA08033B61EB -:1053400051F8046B2E60BFF34F8FFFF7FBFE2B6805 -:105350009E42E8D03B6923F001033B61FFF716FF53 -:10536000FFF748FC0020DCE723F440733361336926 -:1053700043EA080333610B883B80BFF34F8FFFF78D -:10538000E1FE3F8831F8023BBFB2BB42BCD033697B -:1053900023F001033361E1E71846C2E70038024019 -:1053A000003C0240084908B50B7828B11BB9FFF74B -:1053B000D3FE01230B7008BD002BFCD0BDE80840D4 -:1053C0000870FFF7E3BE00BF6652002008B54FF437 -:1053D00040314FF0005000F0ABF8BDE808404FF40A -:1053E00080314FF0805000F0A3B8000070B582B05B -:1053F000FFF7F6FB0E4E054600F060FF3268904264 -:1054000037BF0C4A0B49516814682EBFD1E90041DF -:10541000013151600419034641F100012846019110 -:105420003360FFF7E7FB0199204602B070BD00BF73 -:10543000CC520020D052002070B582B0FFF7D0FBD4 -:10544000104E054600F03AFF3268904237BF0E4AD0 -:105450000D49516814682EBFD1E9004101315160F6 -:10546000041941F100010346284601913360FFF71A -:10547000C1FB01994FF47A7200232046FAF7B8FE77 -:1054800002B070BDCC520020D052002010B50244B2 -:10549000064BD2B2904200D110BD441C00B253F86A -:1054A000200041F8040BE0B2F4E700BF50280040B0 -:1054B0000F4B30B51C6F240407D41C6F44F40074E8 -:1054C0001C671C6F44F400441C670A4C236843F4B7 -:1054D000807323600244084BD2B2904200D130BDA9 -:1054E000441C00B251F8045B43F82050E0B2F4E7EA -:1054F00000380240007000405028004007B50122EB -:1055000001A90020FFF7C2FF019803B05DF804FB7A -:1055100013B50446FFF7F2FFA04205D0012201A90E -:1055200000200194FFF7C4FF02B010BD70470000D7 -:105530007047000070470000074B45F255521A6053 -:1055400002225A6040F6FF729A604CF6CC421A6012 -:10555000024B01221A70704700300040DC520020DC -:10556000034B1B781BB1034B4AF6AA221A60704703 -:10557000DC52002000300040034B1A681AB9034A7D -:10558000D2F874281A607047D852002000300240C8 -:10559000024B4FF08072C3F874287047003002400D -:1055A00008B5FFF7E9FF024B1868C0F3407008BD6B -:1055B000D852002008B5FFF7DFFF024B1868C0F390 -:1055C000007008BDD852002070470000FEE70000C0 -:1055D0000A4B0B480B4A90420BD30B4BDA1C121AA6 -:1055E000C11E22F003028B4238BF00220021FCF7CB -:1055F0005FBB53F8041B40F8041BECE78070000805 -:10560000EC530020EC530020EC53002070470000C6 -:1056100070B5D0E915439E6800224FF0FF3504EBCA -:1056200042135101D3F800090028BEBFD3F8000986 -:1056300040F08040C3F80009D3F8000B0028BEBF3B -:10564000D3F8000B40F08040C3F8000B0132631820 -:105650009642C3F80859C3F8085BE0D24FF0011333 -:10566000C4F81C3870BD00001D4B03EB80022DE90F -:10567000F043D2F80CC05D6DDCF81420461CD2F863 -:1056800000E005EB063605EB4018516871450AD37A -:10569000D5F83438012202FA00F023EA0000C5F8F8 -:1056A0003408BDE8F083BCF81040AEEB0103A34220 -:1056B00028BF2346D8F81849A4B2B3EB840FF0D81A -:1056C0009468A4F1040959F8047F3760A4EB090732 -:1056D0001F44042FF7D81C440B4494605360D4E754 -:1056E000E0520020890141F02001016103699B061D -:1056F000FCD41220FFF78EBA10B5054C2046FEF7F9 -:1057000001FF4FF0A0436365024BA36510BD00BFCE -:10571000E0520020C06E000870B50378012B0546EA -:1057200050D12A4B446D98421BD1294B5A6B42F001 -:1057300080025A635A6D42F080025A655A6D5A6966 -:1057400042F080025A615A6922F080025A610E21A9 -:1057500043205B69FEF748FB1E4BE3601E4BC4F819 -:1057600000380023C4F8003EC02323606E6D4FF460 -:105770005023A3633369002BFCDA012333610C202F -:10578000FFF748FA3369DB07FCD41220FFF742FA2F -:105790003369002BFCDA0026A6602846FFF738FFA5 -:1057A0006B68C4F81068DB68C4F81468C4F81C6837 -:1057B0004BB90A4BA3614FF0FF336361A36843F019 -:1057C0000103A36070BD064BF4E700BFE052002068 -:1057D000003802404014004003002002003C30C06A -:1057E000083C30C0F8B5446D054600212046FFF75F -:1057F00079FFA96D00234FF001128F68C4F8343887 -:105800004FF00066C4F81C284FF0FF3004EB431241 -:1058100001339F42C2F80069C2F8006BC2F8080960 -:10582000C2F8080BF2D20B686A6DEB656362102355 -:105830001361166916F01006FBD11220FFF7EAF982 -:10584000D4F8003823F4FE63C4F80038A36943F4A5 -:10585000402343F01003A3610923C4F81038C4F8AF -:1058600014380A4BEB604FF0C043C4F8103B084BB0 -:10587000C4F8003BC4F81069C4F80039EB6D03F1BB -:10588000100243F48013EA65A362F8BD9C6E000821 -:1058900040800010426D90F84E10D2F8003823F48A -:1058A000FE6343EA0113C2F8003870472DE9F8435C -:1058B00000EB8103456DDA68166806F00306731E77 -:1058C000022B05EB41130C4680460FFA81F94FEA93 -:1058D00041104FF00001C3F8101B4FF0010104F11B -:1058E000100398BFB60401FA03F391698EBF334EDB -:1058F00006F1805606F5004600293AD0578A04F191 -:105900005801490137436F50D5F81C180B43C5F8AF -:105910001C382B180021C3F8101953690127611E88 -:10592000A7409BB3138A928B9B08012A88BF5343DD -:10593000D8F85C20981842EA034301F1400205EBD5 -:105940008202C8F85C00214653602846FFF7CAFE71 -:1059500008EB8900C3681B8A43EA84534834640116 -:105960001E432E51D5F81C381F43C5F81C78BDE8DE -:10597000F88305EB4917D7F8001B21F40041C7F85D -:10598000001BD5F81C1821EA0303C0E704F13F030C -:1059900005EB83030A4A5A6028462146FFF7A2FE18 -:1059A00005EB4910D0F8003923F40043C0F8003962 -:1059B000D5F81C3823EA0707D7E700BF008000109E -:1059C00000040002826D1268C265FFF721BE00006C -:1059D0005831436D49015B5813F4004004D013F46F -:1059E000001F0CBF02200120704700004831436DAA -:1059F00049015B5813F4004004D013F4001F0CBF9E -:105A0000022001207047000000EB8101CB68196A79 -:105A10000B6813604B6853607047000000EB810314 -:105A200030B5DD68AA691368D36019B9402B84BF0B -:105A3000402313606B8A1468426D1C44013CB4FB24 -:105A4000F3F46343033323F0030302EB411043EA0F -:105A5000C44343F0C043C0F8103B2B6803F003037A -:105A6000012B09B20ED1D2F8083802EB411013F421 -:105A7000807FD0F8003B14BF43F0805343F00053C5 -:105A8000C0F8003B02EB4112D2F8003B43F0044364 -:105A9000C2F8003B30BD00002DE9F041244D6E6D91 -:105AA00006EB40130446D3F8087BC3F8087B38079D -:105AB0000AD5D6F81438190706D505EB8403214614 -:105AC000DB6828465B689847FA071FD5D6F8143874 -:105AD000DB071BD505EB8403D968CCB98B69488AF1 -:105AE0005A68B2FBF0F600FB16228AB91868DA6829 -:105AF00090420DD2121AC3E90024202383F31188A7 -:105B00000B482146FFF78AFF84F31188BDE8F08136 -:105B1000012303FA04F26B8923EA02036B81CB6849 -:105B2000002BF3D021460248BDE8F041184700BFE2 -:105B3000E052002000EB810370B5DD68436D6C69B5 -:105B40002668E6604A0156BB1A444FF40020C2F8AA -:105B500010092A6802F00302012A0AB20ED1D3F812 -:105B6000080803EB421410F4807FD4F8000914BF36 -:105B700040F0805040F00050C4F8000903EB42129E -:105B8000D2F8000940F00440C2F80009D3F8340804 -:105B9000012202FA01F10143C3F8341870BD19B9AA -:105BA000402E84BF4020206020682E8A8419013C4A -:105BB000B4FBF6F440EAC44040F000501A44C6E793 -:105BC000F8B504461E48456D05EB4413D3F8086943 -:105BD000C3F80869F10717D5D5F81038DA0713D5D7 -:105BE00000EB8403D9684B691F68DA68974218D2C2 -:105BF000D21B00271A605F60202383F3118821469F -:105C0000FFF798FF87F31188330617D5D5F83428A6 -:105C10000123A340134211D02046BDE8F840FFF70E -:105C200023BD012303FA04F2038923EA020303815B -:105C30008B68002BE8D021469847E5E7F8BD00BF08 -:105C4000E05200202DE9F74F984C666D7569B369F5 -:105C50001D4015F48058756107D02046FEF7B8FC4A -:105C600003B0BDE8F04FFDF78DBF002D12DAD6F876 -:105C7000003E8E489F071EBFD6F8003E23F0030368 -:105C8000C6F8003ED6F8043823F00103C6F80438FD -:105C9000FEF7C6FC280505D58448FFF7B9FC834804 -:105CA000FEF7AEFCA9040CD5D6F8083813F0060FA1 -:105CB000F36823F470530CBF43F4105343F4A05320 -:105CC000F3602A0704D56368DB680BB1774898470F -:105CD000EB0274D4AF0227D5D4F85490DFF8CCB1DE -:105CE00000274FF0010A09EB4712D2F8003B03F4FA -:105CF0004023B3F5802F11D1D2F8003B002B0DDAF1 -:105D000062890AFA07F322EA0303638104EB87033B -:105D1000DB68DB6813B1394658469847A36D0137F5 -:105D20009B68FFB29F42DED9E80617D5676D3A6AD5 -:105D3000C2F30A1002F00F0302F4F012B2F5802F42 -:105D400000F08880B2F5402F08D104EB83030022D5 -:105D5000DB681B6A07F5805790426DD12903D6F89E -:105D6000184813D5E20302D50020FFF795FEA303E0 -:105D700002D50120FFF790FE670302D50220FFF74E -:105D80008BFE260302D50320FFF786FE6D037FF509 -:105D900067AFE00702D50020FFF712FFA10702D589 -:105DA0000120FFF70DFF620702D50220FFF708FF71 -:105DB00023077FF555AF0320FFF702FF50E7636D20 -:105DC000DFF8E8B0019300274FF0010AA36D9B684C -:105DD0005FFA87F999453FF67DAF019B03EB4913C5 -:105DE000D3F8002902F44022B2F5802F22D1D3F853 -:105DF0000029002A1EDAD3F8002942F09042C3F8A5 -:105E00000029D3F80029002AFBDB606D4946FFF723 -:105E100069FC22890AFA09F322EA0303238104EBCD -:105E20008903DB689B6813B1494658469847484642 -:105E3000FFF71AFC0137C9E7910708BFD7F80080C0 -:105E4000072A98BF03F8018B02F1010298BF4FEABD -:105E5000182881E7023304EB830207F58057526864 -:105E6000D2F818C0DCF80820DCE9001CA1EB0C0C0F -:105E7000002188420AD104EB830463689B699A6815 -:105E800002449A605A6802445A6067E711F0030FAF -:105E900008BFD7F800808C4588BF02F8018B01F15C -:105EA000010188BF4FEA1828E3E700BFE052002055 -:105EB000436D03EB4111D1F8003B43F40013C1F8EB -:105EC000003B7047436D03EB4111D1F8003943F4B7 -:105ED0000013C1F800397047436D03EB4111D1F84D -:105EE000003B23F40013C1F8003B7047436D03EB04 -:105EF0004111D1F8003923F40013C1F8003970477B -:105F000030B5039C0172043304FB0325C0E906533A -:105F1000049B03630021059BC160C0E90000C0E948 -:105F20000422C0E90842C0E90A11436330BD000001 -:105F3000416A0022C0E90411C0E90A22C2606FF080 -:105F40000101FEF7D7BE0000D0E90432934201D12F -:105F5000C2680AB9181D70470020704703691960AC -:105F6000C2680132C260C26913448269036193420C -:105F700024BF436A03610021FEF7B0BE38B5044672 -:105F80000D46E3683BB16269131D1268A3621344B6 -:105F9000E362002007E0237A33B929462046FEF762 -:105FA0008DFE0028EDDA38BD6FF00100FBE7000040 -:105FB000C368C269013BC36043691344826943619A -:105FC000934224BF436A436100238362036B03B19E -:105FD0001847704770B52023044683F31188866AFA -:105FE0003EB9FFF7CBFF054618B186F31188284666 -:105FF00070BDA36AE26A13F8015BA362934202D305 -:106000002046FFF7D5FF002383F31188EFE7000058 -:106010002DE9F84F04460E46174698464FF02009E2 -:1060200089F311880025AA46D4F828B0BBF1000FE7 -:1060300009D141462046FFF7A1FF20B18BF311881B -:106040002846BDE8F88FD4E90A12A7EB050B521ACF -:10605000934528BF9346BBF1400F1BD9334601F14E -:10606000400251F8040B43F8040B9142F9D1A36AA2 -:1060700040334036A3624035D4E90A239A4202D322 -:106080002046FFF795FF8AF31188BD42D8D289F3E5 -:106090001188C9E730465A46FBF7E4FDA36A5B4422 -:1060A0005E44A3625D44E7E710B5029C01720433CD -:1060B00004FB0321C0E906130023C0E90A33039B54 -:1060C0000363049BC460C0E90000C0E90422C0E986 -:1060D0000842436310BD0000026AC260426AC0E920 -:1060E00004220022C0E90A226FF00101FEF702BE7D -:1060F000D0E904239A4201D1C26822B9184650F867 -:10610000043B0B607047002070470000C368C26901 -:106110000133C3604369134482694361934224BFDE -:10612000436A43610021FEF7D9BD000038B504463B -:106130000D46E3683BB123691A1DA262E26913446C -:10614000E362002007E0237A33B929462046FEF7B0 -:10615000B5FD0028EDDA38BD6FF00100FBE7000067 -:1061600003691960C268013AC260C2691344826956 -:106170000361934224BF436A036100238362036B7C -:1061800003B118477047000070B520230D46044640 -:10619000114683F31188866A2EB9FFF7C7FF10B145 -:1061A00086F3118870BDA36A1D70A36AE26A013389 -:1061B0009342A36204D3E16920460439FFF7D0FF7C -:1061C000002080F31188EDE72DE9F84F04460D46D5 -:1061D000904699464FF0200A8AF311880026B3466C -:1061E000A76A4FB949462046FFF7A0FF20B187F3C1 -:1061F00011883046BDE8F88FD4E90A073A1AA8EBAF -:106200000607974228BF1746402F1BD905F14003C8 -:1062100055F8042B40F8042B9D42F9D1A36A403372 -:10622000A3624036D4E90A239A4204D3E1692046A6 -:106230000439FFF795FF8BF311884645D9D28AF3CD -:106240001188CDE729463A46FBF70CFDA36A3B448B -:106250003D44A3623E44E5E7D0E904239A4217D1C6 -:10626000C3689BB1836A8BB1043B9B1A0ED0136049 -:10627000C368013BC360C3691A44836902619A42DF -:1062800024BF436A036100238362012318467047D9 -:106290000023FBE700F088B84FF0804300225863EA -:1062A0001A610222DA6070474FF080430022DA6000 -:1062B000704700004FF08043586370474FF08043B1 -:1062C000586A70474B6843608B688360CB68C360D3 -:1062D0000B6943614B6903628B6943620B6803601E -:1062E0007047000008B5264B26481A6940F2FF1196 -:1062F0000A431A611A6922F4FF7222F001021A613C -:106300001A691A6B0A431A631A6D0A431A651E4A00 -:106310001B6D1146FFF7D6FF02F11C0100F58060EE -:10632000FFF7D0FF02F1380100F58060FFF7CAFFE8 -:1063300002F1540100F58060FFF7C4FF02F1700123 -:1063400000F58060FFF7BEFF02F18C0100F5806070 -:10635000FFF7B8FF02F1A80100F58060FFF7B2FF78 -:1063600002F1C40100F58060FFF7ACFF02F1E0012B -:1063700000F58060FFF7A6FFBDE8084000F09AB87E -:106380000038024000000240CC6E000808B500F062 -:1063900009FAFEF7F7FBFFF7EFF8BDE80840FEF754 -:1063A0002BBE000070470000104B1A6C42F0010237 -:1063B0001A641A6E42F001021A660D4A1B6E936847 -:1063C00043F0010393604FF0804353229A624FF0F1 -:1063D000FF32DA6200229A615A63DA605A6001225F -:1063E0005A6108211A601C20FDF7FEBC00380240EB -:1063F000002004E04FF0804208B51169D3680B40DB -:10640000D9B2C9439B07116107D5202383F31188B3 -:10641000FEF7E4FB002383F3118808BD08B5FFF7FE -:10642000E9FFBDE80840FDF7ADBB00001F4B1A694E -:106430006FEAC2526FEAD2521A611A69C2F30802B5 -:106440001A614FF0FF301A695A69586100215A6980 -:1064500059615A691A6A62F080521A621A6A02F025 -:1064600080521A621A6A5A6A58625A6A59625A6A99 -:106470001A6C42F080521A641A6E42F080521A6608 -:106480001A6E0B4A106840F480701060186F00F4A8 -:106490004070B0F5007F1EBF4FF480301867196759 -:1064A000536823F40073536000F05CB90038024075 -:1064B00000700040344B4FF080521A64334A4FF45E -:1064C000404111601A6842F001021A601A6891078F -:1064D000FCD59A6822F003029A602B4B9A6812F05E -:1064E0000C02FBD1196801F0F90119609A601A6871 -:1064F00042F480321A601A689203FCD55A6F42F057 -:1065000001025A67204B5A6F9007FCD5204A5A6007 -:106510001A6842F080721A601C4A53685904FCD50C -:10652000194B1A689201FCD51A4A9A600322C3F8E3 -:106530008C20194B1A68194B9A42194B21D1194AD0 -:106540001168194A91421CD140F205121A60144A8E -:10655000136803F00F03052BFAD10B4B9A6842F036 -:1065600002029A609A6802F00C02082AFAD15A6C68 -:1065700042F480425A645A6E42F480425A665B6E1C -:10658000704740F20572E1E70038024000700040B9 -:106590001854400700948838002004E0116400205B -:1065A000003C024000ED00E041C20F41084A08B53E -:1065B000516913680B4003F00103536123B1054A8D -:1065C00013680BB150689847BDE80840FDF7DABA88 -:1065D000003C014058530020084A08B5516913682F -:1065E0000B4003F00203536123B1054A93680BB1DA -:1065F000D0689847BDE80840FDF7C4BA003C0140A8 -:1066000058530020084A08B5516913680B4003F03D -:106610000403536123B1054A13690BB150699847CC -:10662000BDE80840FDF7AEBA003C014058530020D9 -:10663000084A08B5516913680B4003F00803536119 -:1066400023B1054A93690BB1D0699847BDE808406A -:10665000FDF798BA003C014058530020084A08B59D -:10666000516913680B4003F01003536123B1054ACD -:10667000136A0BB1506A9847BDE80840FDF782BA2B -:10668000003C014058530020174B10B55A691C6854 -:10669000144004F478725A61A30604D5134A936A2D -:1066A0000BB1D06A9847600604D5104A136B0BB142 -:1066B000506B9847210604D50C4A936B0BB1D06BF5 -:1066C0009847E20504D5094A136C0BB1506C984702 -:1066D000A30504D5054A936C0BB1D06C9847BDE86F -:1066E0001040FDF74FBA00BF003C01405853002056 -:1066F0001A4B10B55A691C68144004F47C425A6164 -:10670000620504D5164A136D0BB1506D98472305E9 -:1067100004D5134A936D0BB1D06D9847E00404D5AE -:106720000F4A136E0BB1506E9847A10404D50C4A62 -:10673000936E0BB1D06E9847620404D5084A136F6C -:106740000BB1506F9847230404D5054A936F0BB1E2 -:10675000D06F9847BDE81040FDF714BA003C0140E7 -:1067600058530020062108B50846FDF73DFB0621D9 -:106770000720FDF739FB06210820FDF735FB062130 -:106780000920FDF731FB06210A20FDF72DFB06212C -:106790001720FDF729FBBDE8084006212820FDF75A -:1067A00023BB000008B5FFF741FE00F00DF8FDF730 -:1067B000BFFCFDF7A5FEFDF77DFDFFF7F3FDBDE88E -:1067C0000840FFF767BD00000023054A1946013362 -:1067D000102BC2E9001102F10802F8D1704700BF86 -:1067E000585300200B460146184600F025B800001B -:1067F00000F038B8012838BF012010B50446204603 -:1068000000F028F830B900F007F808B900F00CF8EB -:106810008047F4E710BD0000024B1868BFF35B8FA0 -:10682000704700BFD853002008B5062000F032F9A9 -:106830000120FEF72FFB000010B5054C13462CB1CC -:106840000A4601460220AFF3008010BD2046FCE757 -:1068500000000000024B0146186800F089B800BF34 -:106860004C230020024B0146186800F035B800BFE9 -:106870004C23002010B501390244904201D1002080 -:1068800005E0037811F8014FA34201D0181B10BD99 -:106890000130F2E72DE9F041A3B1C91A177801449C -:1068A000044603F1FF3C8C42204601D9002009E058 -:1068B0000578BD4204F10104F5D10CEB0405D618AE -:1068C000A54201D1BDE8F08115F8018D16F801ED62 -:1068D000F045F5D0E7E7000037B5002944D051F87E -:1068E000043C0190002BA1F10404B8BFE41800F0AF -:1068F000F5F81E4A0198136833B96360146003B059 -:10690000BDE8304000F0F0B8A34208D9256861190D -:106910008B4201BF19685B6849192160EDE71A468F -:106920005B680BB1A342FAD911685518A5420BD187 -:10693000246821445418A3421160E0D11C685B68AC -:10694000536021441160DAE702D90C230360D6E7D3 -:10695000256861198B4204BF19685B68636004BFD6 -:10696000491921605460CAE703B030BDDC530020F0 -:10697000F8B5CD1C25F0030508350C2D38BF0C25C6 -:10698000002D064601DBA94203D90C233360002009 -:10699000F8BD00F0A3F821490A6814469CB9204FBD -:1069A0003B6823B92146304600F03CF83860294660 -:1069B000304600F037F8431C23D10C2333603046B7 -:1069C00000F092F8E3E723685B1B17D40B2B03D985 -:1069D00023601C44256004E06368A2420CBF0B6086 -:1069E0005360304600F080F804F10B00231D20F0C6 -:1069F0000700C21ACCD01B1AA350C9E7224664680C -:106A0000CCE7C41C24F00304A042E3D0211A304692 -:106A100000F008F80130DDD1CFE700BFDC530020E3 -:106A2000E053002038B5064D0023044608462B608D -:106A3000FEF728FA431C02D12B6803B1236038BD4E -:106A4000E45300201F2938B504460D4604D9162307 -:106A500003604FF0FF3038BD426C12B152F8213064 -:106A60004BB9204600F030F82A4601462046BDE8E2 -:106A7000384000F017B8012B0AD0591C03D1162357 -:106A800003600120E7E7002442F8254028469847A4 -:106A90000020E0E7024B01461868FFF7D3BF00BFB4 -:106AA0004C23002038B5074D002304460846114604 -:106AB0002B60FEF7F3F9431C02D12B6803B123606E -:106AC00038BD00BFE4530020FEF7E2B9034611F8D9 -:106AD000012B03F8012B002AF9D17047014800F07F -:106AE00009B800BFE8530020014800F005B800BF16 -:106AF000E853002070470000704700006F72672E57 -:106B00006172647570696C6F742E5069787261631C -:106B100065722D7065726970680000004E6F2061AB -:106B20007070207369670A00426164206677206C88 -:106B3000656E6774682025750A0042616420626F83 -:106B40006172645F69642025752073686F756C6479 -:106B50002062652025750A00426164206677206402 -:106B6000657363726970746F72206C656E677468A8 -:106B70002025750A004261642061707020435243F1 -:106B8000203078253038783A307825303878203001 -:106B900078253038783A3078253038780A00476FD1 -:106BA0006F64206669726D776172650A0040A2E4C5 -:106BB000F16468910600000053544D3332463F3F64 -:106BC0003F00000053544D33324634307800535464 -:106BD0004D3332463432780053544D3332463434D8 -:106BE00036585800012033000010410101105A01AD -:106BF000031059010710310100000000B86B0008B4 -:106C00003F00000013040000C46B00083F000000B8 -:106C100019040000CE6B00083F00000021040000B2 -:106C2000D86B00083F000000404B002020470020A8 -:106C30004261642043414E496661636520696E6428 -:106C400065782E00800000000080000000008000B9 -:106C500000000000000000001D1E000809260008BA -:106C6000692500082D1E0008651E00086120000827 -:106C7000311E0008451E0008351E0008391E000898 -:106C8000411E00083D1E0008891F0008491E00081B -:106C900075280008591E00085D1F000800960000B6 -:106CA00000000000000000000000000000000000E4 -:106CB00000000000F9400008E540000821410008FC -:106CC0000D4100081941000805410008F140000885 -:106CD000DD4000082D41000800000000314200089E -:106CE0001D42000859420008454200085142000870 -:106CF0003D4200082942000815420008654200088C -:106D00000000000001000000000000006D61696EDD -:106D10000000000069646C6500000000146D00084C -:106D2000C8490020404B002001000000814B0008B2 -:106D3000000000004172647550696C6F7400254258 -:106D40004F415244252D424C002553455249414C58 -:106D50002500000002000000000000004D44000873 -:106D6000B944000840004000D84F0020E84F002000 -:106D7000020000000000000003000000000000000E -:106D8000FD4400080000000010000000F84F002043 -:106D9000000000000100000000000000E0520020A0 -:106DA00001010200954F0008A54E0008414F000860 -:106DB000254F000843000000BC6D00080902430095 -:106DC000020100C032090400000102020100052492 -:106DD000001001052401000104240202052406001C -:106DE00001070582030800FF09040100020A0000F0 -:106DF0000007050102400000070581024000000075 -:106E000012000000086E000812011001020000408C -:106E100009124157000201020301000004030904A2 -:106E200025424F4152442500303132333435363714 -:106E3000383941424344454600000000004000000C -:106E40000040000000400000004000000000010081 -:106E5000000002000000020000000200000002002A -:106E600000000200000002000000020000400000DC -:106E70000040000000400000004000000000010051 -:106E800000000200000002000000020000000200FA -:106E900000000200000002000000020000000000EC -:106EA00035460008ED4800089949000840004000B8 -:106EB00040530020405300200100000050530020A8 -:106EC0008000000040010000030000000000802A54 -:106ED00000000000AAAAAAAA00000024FFFF0000E8 -:106EE0000000000000A00A004400000000000000B4 -:106EF000AAAAAAAA00000000FFFF000000000000EC -:106F0000000000001000004000000000AAAAAAAA89 -:106F100010000040FFFF0000000000000000000023 -:106F20000A68100000000000AAAAAAAA00541000D3 -:106F3000FFFF000099007007000000000000004003 -:106F400000000000AAAAAAAA00000040FFFF00005B -:106F50000000000000000000000000000000000031 -:106F6000AAAAAAAA00000000FFFF0000000000007B -:106F7000000000000000000000000000AAAAAAAA69 -:106F800000000000FFFF0000000000000000000003 -:106F900000000000000000000A00000000000000E7 -:106FA00003000000000000000000000000000000DE -:106FB00000000000000000000000000000000000D1 -:106FC00000000000000000005892FF7F0100000058 -:106FD0007A0500000000000000001F000000000013 -:106FE00040420F00FE2A0100D2040000FF0096007C -:106FF00000000008009600000000080004000000E7 -:107000001C6E0008000000000000000000000000EE -:1070100000000000000000000000000050230020DD -:107020000000000000000000000000000000000060 -:107030000000000000000000000000000000000050 -:107040000000000000000000000000000000000040 -:107050000000000000000000000000000000000030 -:107060000000000000000000000000000000000020 -:107070000000000000000000000000000000000010 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600005F0AAFA06F08EF94FF055301F491B4AE4 +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE705F088FA7B +:1005B00006F0BCF9144C154DAC4203DA54F8041B98 +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E705F070BA00070020BB +:1005E000002300200000000808ED00E000010020CA +:1005F000000700204873000800230020BC230020CF +:10060000C023002008590020E0010008E401000890 +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002004F02AFDF8 +:10064000FEE704F083FC00DFFEE70000F8B501F0F0 +:1006500031F905F0D3F930B12B4B00220F211A727A +:100660005A729972DA7205F0ABF9074605F010FA82 +:10067000054600283CD1254B9F4239D001339F428B +:1006800039D0234B27F0FF029A4237D1F8B200F05D +:100690001DFF2E4642F2107400F01EFF08B1002428 +:1006A000264601F063FD20B1032000F087F8002406 +:1006B000264635B1174B9F4203D005F0E1F90024DF +:1006C0002646002005F086F9134B1B6913F480734E +:1006D00018D00EB100F088F801F0C6FA00F068FFFB +:1006E00001F064F9204600F0DBF800F07DF8F9E74E +:1006F0002E460024D0E704460126CDE7064641F207 +:100700008834C9E71C46E7E700230020010007B052 +:10071000000008B0263A09B00004024008B501F014 +:1007200011F9A0F120035842584108BD07B541F224 +:100730001203022101A8ADF8043001F021F903B041 +:100740005DF804FB38B5302383F31188174803683C +:100750000BB104F06BFD164A144800234FF47A7174 +:1007600004F05AFD002383F31188124C236813B15F +:100770002368013B2360636813B16368013B6360D6 +:100780000D4D2B7833B963687BB9022001F0DEF997 +:10079000322363602B78032B07D163682BB90220C7 +:1007A00001F0D4F94FF47A73636038BDC0230020A0 +:1007B00045070008E0240020D8230020084B1870CB +:1007C00003280CD8DFE800F008050208022001F039 +:1007D000ADB9022001F09CB9024B00225A6070476B +:1007E000D8230020E024002010B501F0BFFC30B178 +:1007F000244B03221A70244B00225A6010BD234B55 +:10080000234A1C4619680131F8D004339342F9D1C8 +:100810006268204B9A42F1D91F4B9B6803F1006339 +:1008200003F580339A42E9D205F0FEF805F010F99D +:10083000002001F0D5F80220FFF7C0FF174B1A6C1B +:1008400000221A64196E1A66196E596C5A64596E30 +:100850005A665A6E1A6942F000521A611A6922F0F9 +:1008600000521A611B6972B64FF0E0233021C3F8C1 +:10087000084DD4E9003281F311889D4683F308883E +:100880001047BBE7D8230020E02400200000010827 +:1008900020000108FFFF000800230020003802406C +:1008A0002DE9F04F93B0AC4B00902022FF210AA815 +:1008B0009D6801F083F9A94A1378A3B9A8480121DA +:1008C00003601170302383F3118803680BB104F0C7 +:1008D000ADFCA44AA24800234FF47A7104F09CFCBA +:1008E000002383F31188009B13B19F4B009A1A6079 +:1008F0009E4A009C1378032B1EBF002313709A4A54 +:100900004FF0000A18BF5360D3465646D146012027 +:1009100001F00CF924B1944B1B68002B00F01582F8 +:10092000002001F00FF80390039B002B01DA00F088 +:1009300087FE039B002BEDDB012001F0E9F8039B10 +:10094000213B162BE3D801A252F823F0A909000895 +:10095000D1090008650A00080F0900080F090008FE +:100960000F090008EF0A0008BF0C0008D90B0008A7 +:100970003B0C0008630C0008890C00080F090008F4 +:100980009B0C00080F0900080D0D0008490A00081B +:100990000F090008510D0008B5090008490A0008B0 +:1009A0000F0900083B0C00080220FFF7B7FE0028E3 +:1009B00040F0F581009B0221BAF1000F08BF1C46F0 +:1009C00005A841F21233ADF8143000F0D9FF9EE7CC +:1009D0004FF47A7000F0B6FF071EEBDB0220FFF742 +:1009E0009DFE0028E6D0013F052F00F2DA81DFE806 +:1009F00007F0030A0D10133605230593042105A8FB +:100A000000F0BEFF17E054480421F9E758480421DC +:100A1000F6E758480421F3E74FF01C08404600F081 +:100A2000E1FF08F104080590042105A800F0A8FFE3 +:100A3000B8F12C0FF2D1012000FA07F747EA0B0BAF +:100A40005FFA8BFB4FF0000901F004F926B10BF0BF +:100A50000B030B2B08BF0024FFF768FE57E746483F +:100A60000421CDE7002EA5D00BF00B030B2BA1D159 +:100A70000220FFF753FE074600289BD0012000F01C +:100A8000AFFF0220FFF79AFE00261FFA86F84046C5 +:100A900000F0B6FF044690B10021404600F0C8FFC8 +:100AA00001360028F1D1BA46044641F21213022160 +:100AB00005A8ADF814303E4600F062FF27E701209C +:100AC000FFF77CFE2546244B9B68AB4207D928469E +:100AD00000F088FF013040F067810435F3E7234BD5 +:100AE00000251D70204BBA465D603E46ACE7002EE7 +:100AF0003FF460AF0BF00B030B2B7FF45BAF0220D6 +:100B0000FFF75CFE322000F01DFFB0F10008FFF699 +:100B100051AF18F003077FF44DAF0F4A926808EB0E +:100B2000050393423FF646AFB8F5807F3FF742AFEB +:100B3000124B0193B84523DD4FF47A7000F002FFA9 +:100B40000390039A002AFFF635AF019B039A03F83E +:100B5000012B0137EDE700BF00230020DC2400203B +:100B6000C023002045070008E0240020D8230020EF +:100B700004230020082300200C230020DC23002075 +:100B8000C820FFF7CBFD074600283FF413AF1F2D09 +:100B900011D8C5F1200242450AAB25F0030028BF59 +:100BA000424683490192184400F0E2FF019A8048CE +:100BB000FF2101F003F84FEAA8037D490193C8F330 +:100BC0008702284601F002F8064600283FF46DAF80 +:100BD000019B05EB830537E70220FFF79FFD002807 +:100BE0003FF4E8AE00F044FF00283FF4E3AE0027F6 +:100BF000B846704B9B68BB4218D91F2F11D80A9B6F +:100C000001330ED027F0030312AA134453F8203CFB +:100C100005934046042205A901F060FA0437804696 +:100C2000E7E7384600F0DEFE0590F2E7CDF81480E5 +:100C3000042105A800F0A4FE06E70023642104A80F +:100C4000049300F093FE00287FF4B4AE0220FFF777 +:100C500065FD00283FF4AEAE049800F0F1FE05906B +:100C6000E6E70023642104A8049300F07FFE002837 +:100C70007FF4A0AE0220FFF751FD00283FF49AAEAA +:100C8000049800F0EDFEEAE70220FFF747FD002898 +:100C90003FF490AE00F0FCFEE1E70220FFF73EFDDE +:100CA00000283FF487AE05A9142000F0F7FE0421C8 +:100CB0000746049004A800F063FE3946B9E73220E5 +:100CC00000F040FE071EFFF675AEBB077FF472AE64 +:100CD000384A926807EB090393423FF66BAE022055 +:100CE000FFF71CFD00283FF465AE27F003074F44D3 +:100CF000B9453FF4A9AE484600F074FE04210590C2 +:100D000005A800F03DFE09F10409F1E74FF47A70FF +:100D1000FFF704FD00283FF44DAE00F0A9FE0028C7 +:100D200044D00A9B01330BD008220AA9002000F00E +:100D30004DFF00283AD02022FF210AA800F03EFFF4 +:100D4000FFF7F4FC1C4804F0ABF913B0BDE8F08FDA +:100D5000002E3FF42FAE0BF00B030B2B7FF42AAECB +:100D60000023642105A8059300F000FE0746002833 +:100D70007FF420AE0220FFF7D1FC804600283FF42C +:100D800019AEFFF7D3FC41F2883004F089F90598D9 +:100D900000F0A4FF464600F05DFF3C46B7E506467E +:100DA00052E64FF0000905E6BA467EE637467CE695 +:100DB000DC23002000230020A0860100094A1368DC +:100DC00049F2690099B21B0C00FB01331360064B1A +:100DD000186844F2506182B2000C01FB02001860F6 +:100DE00080B27047182300201423002010B5002182 +:100DF0001022044600F0E2FE034B03CB206061604A +:100E00001868A06010BD00BF107AFF1F2DE9F041E7 +:100E1000ADF5507D0DF13C086EAC40F27512074601 +:100E20000D4610A80021C8F8001000F0C7FE4FF4CE +:100E3000C4720021204600F0C1FE02F0B1F8274B39 +:100E40004FF47A72B0FBF2F0186093E807000223C7 +:100E500084E807000DF5ED702382FFF7C7FF47F622 +:100E600005231F49238407A806F054F81D2384F89E +:100E700032310DF2EB2207AB0DF1340C1E4603CEDE +:100E8000664510605160334602F10802F6D13068C1 +:100E900010603379137141460122204600F040FF73 +:100EA00000230393AB7E029305F11903019380B2F3 +:100EB0000123CDE904800093E97E06A3D3E9002352 +:100EC000384602F035FC0DF5507DBDE8F08100BFDD +:100ED000AFF300809E6AC421818A46EEE824002098 +:100EE000246F00082DE9F0412C4C237ADAB08046BB +:100EF0000D465BBB27A9284601F022F807460028CB +:100F000042D19DF89D60C82E3ED801464FF4A6629E +:100F1000204600F053FE4FF48073C4F8F8314FF4CC +:100F20000073C4F80C334FF44073C4F820343246D5 +:100F30000DF19E0104F1090000F01AFE26449DF80F +:100F40009C30777223720BB9EB7E237281220021D1 +:100F500006AC27A800F032FE0122214627A801F0A6 +:100F60002BF800230393AB7E029305F1190380B2A3 +:100F700001932823CDE904400093E97E05A3D3E93A +:100F80000023404602F0D4FB5AB0BDE8F08100BF18 +:100F9000AFF3008026417272DF25D7B700460020EC +:100FA000F0B5254E4FF48A7505FB0065F1B096F853 +:100FB000D83085F8DC300024D822214685F8E84076 +:100FC0003AA800F0FBFD06F1090000F0EFFDD5F8AE +:100FD000E4308DF8F000C2B206AF06F109010DF160 +:100FE000F100CDE93A3400F0C3FD394601223AA8B8 +:100FF00001F00EF880B2CDE9047008230127CDE995 +:10100000023706F1D803019330230093317A0B485D +:1010100007A3D3E9002302F08BFBA04206DD01F019 +:10102000BFFFC5F8E000384671B0F0BD2046FBE7D1 +:1010300078F6339F93CACD8D0046002000350020FE +:101040002DE9F0411D4D1E4E1E4F86B0284602F080 +:101050009BFB034658B30024CDE90344ADF814408C +:10106000027B8DF8142099684068029403AA03C299 +:101070001B68DFF8548043F00043029301F092FFB5 +:10108000821941F10003009402A9384601F054FA94 +:10109000A04205DD284602F07BFB88F80040D5E73A +:1010A00098F80030072B05D8013388F8003006B0D7 +:1010B000BDE8F081014802F06BFBF8E70035002045 +:1010C00040420F0030350020354B002070B50D46F2 +:1010D00014461E4602F088FA50B9022E10D1012C97 +:1010E0000ED112A3D3E90023C5E90023012007E0B4 +:1010F000282C10D005D8012C09D0052C0FD00020A9 +:1011000070BD302CFBD10BA3D3E90023ECE70BA37C +:10111000D3E90023E8E70BA3D3E90023E4E70BA31B +:10112000D3E90023E0E700BFAFF30080401DA1201A +:1011300026812A0B78F6339F93CACD8D9E6AC421EF +:10114000818A46EE26417272DF25D7B7F017304A02 +:1011500039059E5638B505460E4C0021013500F084 +:1011600067FCA4F82C55B4F82C0500F049FC78B1C4 +:10117000B4F82C0500F054FC014648B9B4F82C052D +:1011800000F056FCB4F82C350133A4F82C35EAE70E +:1011900038BD00BF0046002010B50A4B0A4A1A604D +:1011A00003F5805393F860203AB9DC6D2CB12046EA +:1011B00001F05AF8204605F0EDFDBDE81040034867 +:1011C00001F052B830350020E06F0008784500206B +:1011D0002DE9F04F8FB000AF05460C4602F004FA3F +:1011E000002849D1237E022B1BD1E38A012B18D181 +:1011F00001F0D6FE0646FFF7E1FD03464FF4C87046 +:10120000DFF8C482B3FBF0F206F5167602FB10336A +:1012100016FA83F3C8F80030E37E33B9A34B0022FB +:101220001A703C37BD46BDE8F08F07F12401204617 +:1012300000F044FE0028F4D107F11400FFF7D6FDBA +:1012400097F8264007F11401224607F1270005F020 +:10125000EBFD0028E2D10F2C08D8944B1C70D8F875 +:101260000030A3F51673C8F80030DAE797F82410B9 +:10127000284602F0B1F9D4E7E38A282B2BD010D806 +:10128000012B23D0052BCCD1BFF34F8F8849894B3D +:10129000CA6802F4E0621343CB60BFF34F8F00BF14 +:1012A000FDE7302BBDD1844EE17E327A9142B8D138 +:1012B000607E3146002291F8DC50854200F0A58026 +:1012C0000132042A01F58A71F5D1AAE721462846A0 +:1012D000FFF79CFDA5E721462846FFF703FEA0E7A0 +:1012E000B2F8EC507B6005F103094FEA99094FEA27 +:1012F0008902D11DC908A8EBC1039D46EB46002118 +:10130000584600F05BFC04F1EE012A463144584691 +:1013100000F02EFC7B6813B9012000F061FB96F809 +:10132000D20000F06DFB044630B9307200F0A0FB33 +:10133000204600F055FBB1E0D6F8D4203AB996F833 +:10134000D200B6F82C25824201D8FFF703FFD6F869 +:10135000D4202A44944208D296F8D200B6F82C251C +:101360000130824201D8FFF7F5FE70685FFA89F21A +:10137000594600F02BFC08B9C54679E0726896F82A +:10138000D2002A447260D6F8D42005EB0209C6F8D0 +:10139000D49000F035FB814509D396F8D220D6F8D9 +:1013A000D4000132001B86F8D220C6F8D400FF2DED +:1013B0000FD80024347200F05BFB204600F010FBD5 +:1013C00000F0D4FE3D4B188108B9FFF70DFAC54671 +:1013D00027E7BB6896F8D9000AFB0362FB68D2F8DE +:1013E000E41082F8E83001F58061C2F8E030C2F81C +:1013F000E410FFF7D5FDFFF723FE96F8D920013260 +:1014000002F0030286F8D920B6E74FF48A7A0AFB85 +:1014100002F505F1EA013144204600F025FEF860AE +:1014200000287FF4FEAE3544012285F8E82001F063 +:10143000B7FDD5F8E020D6ED007ADFED216A801AFD +:10144000192838BF192040F6B832904228BF1046FC +:10145000B8EE677A07EE900AF8EEE77A67EEA67ABA +:10146000DFED186AE7EE267AFCEEE77AC6ED007A41 +:1014700096F8D930BB60BA6873680AFB02F4321977 +:1014800092F8E81059B1D2F8E4108B42E8463FF4E4 +:1014900027AF002182F8E810C2F8E010C546736853 +:1014A000064A9B0A01331381BBE600BFF9340020D2 +:1014B00000ED00E00400FA0500460020E8240020CA +:1014C000CDCCCC3D6666663FFC340020014B1870E5 +:1014D000704700BFF424002030B54FF000542B4B70 +:1014E00022689A4285B007D004F0DCFA044620BB9B +:1014F0000024204605B030BD254B627D25481A707A +:10150000237D03724FF48073C0F8F8314FF40073F9 +:10151000C0F80C3300254FF44073C0F820341E4946 +:10152000C0F8E450C922093000F022FB2046E02236 +:10153000294600F043FB0124DBE7184A184D136CE1 +:1015400043F000731364AA6D164B9A42D0D12B6EF0 +:10155000013B7E2BCCD8144A07CA01AB83E80700B5 +:101560001846032100F0D0FD6B6D83424FF000035D +:10157000BED12A6D8A4201BFAB65054B2A6E1A7037 +:1015800003BF0A4BEA6D1A601C46B2E79AAD44C528 +:10159000F4240020004600201600002000380240FD +:1015A000006600405041A0B0586600401023002063 +:1015B00037B51A4D00F0DAFD02236B71184B288104 +:1015C00019681848012201F089FB00230193164B8A +:1015D000164900931648174B4FF4805201F0D4FF80 +:1015E000154B197811B1124801F0F6FF01F0D8FC43 +:1015F0000446FFF7E3FB4FF4C873B0FBF3F202FBC2 +:10160000130304F5167010FA83F00C4B186004F005 +:101610003FFA08B10F232B8103B030BDE82400202E +:101620001023002030350020CD100008F8240020C1 +:1016300000350020D1110008F4240020FC340020E3 +:101640002DE9F04F2DED028B0FF23829D9E90089F1 +:10165000834C93B00BAE9FED7E8BFFF7F1FC814F77 +:10166000DFF828A200230A93ADF834300B9373609F +:101670004FF0000B5B468DED008B01250DF11D0237 +:1016800007A938468DF81C508DF81DB001F0D6FA28 +:101690009DF81C30002B40F0A580204601F0A4FFEF +:1016A0000646002845D1704F01F07AFC3B6898420D +:1016B0003FD301F075FC8246FFF780FB4FF4C873FF +:1016C000B0FBF3F202FB13030AF5167010FA83F075 +:1016D0003860664F97F800B0CBF1100ABBF1000FED +:1016E00014BF33462B465FFA8AFA0EA88DF82830CD +:1016F000FFF77CFBBAF1060F28BF4FF0060A0EABCE +:1017000003EB0B0152460DF1290000F031FA0AAB50 +:101710000393182302930AF10102554BD2B2CDE98B +:101720000053049220464CA3D3E9002301F0A2FF0A +:101730003E7001F035FC4F4A4F4D1368C31AB3F5A4 +:101740007A7F2ED3106001F02DFC02460B46204616 +:1017500002F028F8204601F047FF10B32B7A474EDD +:10176000002B14BF03230223737101F019FC0EAF89 +:101770004FF47A730122B0FBF3F039463060304603 +:1017800000F074FB182302933D4B019380B240F2AA +:101790005513CDE90370009342464B46204601F0B5 +:1017A00069FF2B7A93B101F0FBFB002607464FF44B +:1017B0008A7A95F8D900304400F003000AFB005300 +:1017C00093F8E82092B30136042EF2D1C82003F03A +:1017D00067FC2B7A002B7FF43DAF13B0BDEC028B7E +:1017E000BDE8F08FDAF8143083F00203CAF8143041 +:1017F000594610220EA800F0E1F90DF11E0308AAC7 +:101800000AA9384600F096FF96E803000FAB83E87C +:1018100003009DF834308DF844300A9B0E930EA9D6 +:10182000DDE90823204602F091F921E7D3F8E02012 +:1018300042B12B68FA2B38BFFA23BA1A0533B2EB40 +:10184000430FC0D3FFF7ACFB0028BCD1BEE700BFFD +:101850000000000000000000401DA12026812A0B8E +:101860000035002030350020FC340020F934002001 +:10187000F8340020304B002000460020E8240020EF +:10188000344B0020F1C6A7C1D068080F0004024005 +:1018900008B5054800F0E8FFBDE80840034A0449E0 +:1018A000002005F071BA00BF30350020844B0020C5 +:1018B00099110008704700002DE9F84F4FF47A7332 +:1018C000DFF85880DFF8589006460D4602FB03F714 +:1018D000002498F900305A1C5FFA84FA01D0A34220 +:1018E00012D159F8240003682A46D3F820B03146B3 +:1018F0003B46D847854207D1074B012083F800A01B +:10190000BDE8F88F0124E4E7002CFBD04FF4FA7017 +:1019100003F0C6FB0020F3E7784B00201C230020D7 +:101920002023002070B504464FF47A76412C2546DA +:1019300028BF412506FB05F003F0B2FB641BF5D17F +:1019400070BD000007B50023024601210DF107001C +:101950008DF80730FFF7B0FF20B19DF8070003B006 +:101960005DF804FB4FF0FF30F9E700000A4608B5C8 +:101970000421FFF7A1FF80F00100C0B2404208BD82 +:1019800030B4074B0A461978064B53F821402368B8 +:10199000DD69054B0146AC46204630BC604700BFC0 +:1019A000784B002020230020A086010070B503F0B2 +:1019B00099FE094E094D30800024286833888342FF +:1019C00008D903F089FE2B6804440133B4F5803F45 +:1019D0002B60F2D370BD00BF7A4B0020384B002043 +:1019E00003F036BF00F1006000F5803000687047FA +:1019F00000F10060920000F5803003F0C1BE0000ED +:101A0000054B1A68054B1B889B1A834202D9104468 +:101A100003F062BE00207047384B00207A4B002054 +:101A2000024B1B68184403F05FBE00BF384B002018 +:101A3000024B1B68184403F06FBE00BF384B0020F8 +:101A400010F003030AD1B0F5047F05D200F1005075 +:101A5000A0F51040D0F80038184670470023FBE787 +:101A600000F10050A0F51040D0F8100A70470000B7 +:101A7000064991F8243033B10023086A81F82430F4 +:101A80000822FFF7B5BF0120704700BF3C4B002084 +:101A9000014B1868704700BF002004E070B5194B77 +:101AA0001D68194B0138C5F30B0408442D0C0422A2 +:101AB0001E88A6420BD15C680A46013C824213464E +:101AC0000FD214F9016F4EB102F8016BF6E7013A3B +:101AD00003F10803ECD181420B4602D22C2203F819 +:101AE000012B0A4A05241688AE4204D1984284BFCD +:101AF000967803F8016B013C02F10402F3D1581A05 +:101B000070BD00BF002004E0846F0008706F000803 +:101B1000022802D1044B98617047012802BF024B92 +:101B200008229A61704700BF00040240022804D1D5 +:101B3000054B4FF400329A6170470128FCD1024BEB +:101B40004FF40022F7E700BF00040240022805D14D +:101B5000064A536983F00203536170470128FCD1A0 +:101B6000024A536983F00803F6E700BF000402400D +:101B700010B50023934203D0CC5CC4540133F9E781 +:101B800010BD000010B5013810F9013F3BB191F9CB +:101B900000409C4203D11AB10131013AF4E71AB175 +:101BA00091F90020981A10BD1046FCE70346024642 +:101BB000D01A12F9011B0029FAD1704702440346DA +:101BC000934202D003F8011BFAE770472DE9F8436E +:101BD0001F4D144695F824200746884652BBDFF86F +:101BE00070909CB395F824302BB92022FF214846F1 +:101BF0002F62FFF7E3FF95F82400C0F10802A2422C +:101C000028BF2246D6B24146920005EB8000FFF77E +:101C1000AFFF95F82430A41B1E44F6B2082E1744DB +:101C20009044E4B285F82460DBD1FFF721FF00285F +:101C3000D7D108E02B6A03EB82038342CFD0FFF7B2 +:101C400017FF0028CBD10020BDE8F8830120FBE777 +:101C50003C4B0020024B1A78024B1A70704700BFB1 +:101C6000784B00201C23002038B5174C174D204618 +:101C700002F046FD2946204602F06EFD2D686A6D91 +:101C8000936B23F4002393634FF47A70FFF74AFEBB +:101C90000F49284602F066FE6A6D0E4D936B286868 +:101CA0000D4943F400239363A0424FF4E1330B60EA +:101CB00001D002F085FC6868A04204D0BDE838403D +:101CC000054902F07DBC38BD68500020087100084D +:101CD0001071000820230020644B002070B50C4BCD +:101CE0000C4D1E780C4B55F826209A4204460DD018 +:101CF0000A4B002114221846FFF760FF04600146DA +:101D000055F82600BDE8704002F05ABC70BD00BF17 +:101D1000784B00202023002068500020644B0020D6 +:101D20002DE9F0470D46044600219046284640F232 +:101D30007912FFF743FF234620220021284601F0B5 +:101D4000A7FE231D02222021284601F0A1FE631DCB +:101D500003222221284601F09BFEA31D03222521F8 +:101D6000284601F095FE04F1080310222821284698 +:101D700001F08EFE04F1100308223821284601F0FC +:101D800087FE04F1110308224021284601F080FE5D +:101D900004F1120308224821284601F079FE04F1DB +:101DA000140320225021284601F072FE04F118038A +:101DB00040227021284601F06BFE04F12003082226 +:101DC000B021284601F064FE04F121030822B82165 +:101DD000284601F05DFE04F12207C0263B4631464D +:101DE00008222846083601F053FEB6F5A07F07F119 +:101DF0000107F3D104F1320308223146284601F0ED +:101E000047FE002704F1330A94F832304FEAC7093D +:101E10009F4209F5A47615D3B8F1000F08D13146D9 +:101E200004F599730722284601F032FE09F24F1695 +:101E3000274694F832213B1B93420CD3F01DC00877 +:101E4000BDE8F0870AEB070308223146284601F077 +:101E50001FFE0137D8E707F2331331460822284620 +:101E600001F016FE08360137E3E7000013B504461B +:101E70000846002101602346C0F80310202201908B +:101E800001F006FE0198231D0222202101F000FE30 +:101E90000198631D0322222101F0FAFD0198A31D80 +:101EA0000322252101F0F4FD019804F1080310221A +:101EB000282101F0EDFD072002B010BDF7B5002389 +:101EC000047F00910E4607221946054601F0A4FC46 +:101ED000731C0093012200230721284601F09CFC7B +:101EE000C4B9B31C0093052223460821284601F0FB +:101EF00093FC0D243746B278BB1B934211D32B7F42 +:101F0000A88A0734E408BBB9844294BF00200120AA +:101F100003B0F0BDAB8ADB00083BDB08B3700824DC +:101F2000E8E7FB1C0093214600230822284601F025 +:101F300073FC08340137DEE7201A18BF0120E7E7F9 +:101F4000F7B50023047F00910E4608221946054686 +:101F500001F062FC731CC4B90822009311462346A9 +:101F6000284601F059FC1024012372785F1C013BC4 +:101F7000934211D32B7FA88A0734E408BBB984426B +:101F800094BF0020012003B0F0BDAB8ADB00083B0A +:101F9000DB0873700824E7E7F31900932146002358 +:101FA0000822284601F038FC08343B46DDE7201AB9 +:101FB00018BF0120E7E70000F8B50E4605461446B5 +:101FC000002181223046FFF7F9FD2B46082200212F +:101FD000304601F05DFD7CB96B1C072208213046BC +:101FE00001F056FD0F2401236A785F1C013B9342E8 +:101FF00004D3E01DC008F8BD0824F4E7EB1921461E +:102000000822304601F044FD08343B46ECE700006E +:10201000F8B50E46054614460021CE223046FFF79D +:10202000CDFD2B4628220021304601F031FD7CB940 +:1020300005F1080308222821304601F029FD30244B +:102040002F462A7A7B1B934204D3E01DC008F8BDBB +:102050002824F5E707F1090321460822304601F05C +:1020600017FD08340137ECE7F7B5047F00910E4601 +:10207000012310220021054601F0CEFBC4B9B31C98 +:102080000093092223461021284601F0C5FB19249C +:1020900037467288BB1B9A4211D82B7FA88A073417 +:1020A000E408BBB9844294BF0020012003B0F0BD16 +:1020B000AB8ADB00103BDB0873801024E8E73B1D94 +:1020C0000093214600230822284601F0A5FB08348E +:1020D0000137DEE7201A18BF0120E7E730B5094DC8 +:1020E0000A4491420DD011F8013B5840082340F3B7 +:1020F0000004013B2C4013F0FF0384EA5000F6D1AA +:10210000EFE730BD2083B8EDF7B54FF0FF33DFF8D0 +:1021100054C0DFF854E000EB81011A4688421CD01D +:1021200050F8044B019401AF042417F8015B82EAD4 +:1021300005620825DB18164605F1FF355241002ED1 +:10214000BCBF83EA0C0382EA0E0215F0FF05F1D151 +:10215000013C14F0FF04E8D1E0E7D843D14303B0D9 +:10216000F0BD00BF9336EAA9EBE1F042F7B5384A7B +:10217000106851686B4603C36A46364936480823DF +:1021800004F062FE0446002833D10A25334A106861 +:1021900051686B4603C36A4631492F48082304F04F +:1021A00053FE0446002849D00369B3F5F81F45D80B +:1021B000B0F8661040F27A5291423FD1294A024467 +:1021C00002F15C018B4239D35C3B234900209E1A0B +:1021D000FFF784FF3246074604F164010020FFF751 +:1021E0007DFFA3689F4229D1E368984208BF00257C +:1021F00024E00369B3F5F81F27D8418B40F27A52E7 +:10220000914220D1174A024402F110018B4218D3A7 +:10221000103B114900209D1AFFF760FF2A46064631 +:1022200004F118010020FFF759FFA3689E4202D174 +:10223000E368984201D00D25A8E70025284603B0A1 +:10224000F0BD1025A2E70C25A0E70B259EE700BFF7 +:10225000A46F0008DCFF1E0000000108AD6F00083D +:1022600090FF1E000800FFF710B5037C044613B969 +:10227000006804F0D1FD204610BD00000023BFF32C +:102280005B8FC360BFF35B8FBFF35B8F8360BFF374 +:102290005B8F7047BFF35B8F0068BFF35B8F704746 +:1022A00070B505460C30FFF7F5FF05F1080604464A +:1022B0003046FFF7EFFFA04206D930466D68FFF7C2 +:1022C000E9FF2544281A70BD3046FFF7E3FF201AC6 +:1022D000F9E7000070B50546406898B105F10800BF +:1022E000FFF7D8FF05F10C0604463046FFF7D2FF92 +:1022F0008442304694BF6D680025FFF7CBFF013C58 +:102300002C44201A70BD000038B50C460546FFF776 +:10231000C7FFA04210D305F10800FFF7BBFF04443C +:102320006868B4FBF0F100FB1144BFF35B8F012040 +:10233000AC60BFF35B8F38BD0020FCE72DE9F041B6 +:10234000144607460D46FFF7C5FF844228BF0446E2 +:10235000D4B1B84658F80C6B4046FFF79BFF3044A9 +:10236000286040467E68FFF795FF331A9C4203D8E9 +:102370006C600120BDE8F0816B60A41B3B68AB6022 +:102380002044E8600220F5E72046F3E738B50C4624 +:102390000546FFF79FFFA04210D305F10C00FFF7A1 +:1023A00079FF04446868B4FBF0F100FB1144BFF30B +:1023B0005B8F0120EC60BFF35B8F38BD0020FCE732 +:1023C0002DE9FF41884669460746FFF7B7FF6C468F +:1023D00006B204EBC6060025B44209D06268206844 +:1023E00008EB0501FFF7C4FB636808341D44F3E7FD +:1023F00029463846FFF7CAFF284604B0BDE8F081F9 +:10240000F8B505460C300F46FFF744FF05F1080606 +:1024100004463046FFF73EFFA042304688BF6C6856 +:10242000FFF738FF201A386020B130462C68FFF7DC +:1024300031FF2044F8BD000073B5144606460D4632 +:10244000FFF72EFF844228BF04460190DCB101A9AA +:102450003046FFF7D5FF019B33B93268C5E9023337 +:10246000C5E9002401200CE09C4238BF019428609B +:10247000019868608442F5D93368AB60241AEC6037 +:10248000022002B070BD2046FBE700002DE9FF41AD +:102490000F466946FFF7D0FF6C4600B204EBC0055B +:1024A0000026AC4209D0D4F8048054F8081BB819AF +:1024B0004246FFF75DFB4644F3E7304604B0BDE813 +:1024C000F081000038B50546FFF7E0FF04460146FD +:1024D0002846FFF719FF204638BD0000302383F35C +:1024E000118862B670470000002383F3118862B63A +:1024F0007047000010B4026854681A4623465DF81D +:10250000044B184701207047002070470020704797 +:1025100070470000002070470E20704700F5805083 +:1025200090F8C800C0F340007047000000F58050EC +:1025300090F9C90070470000F7B50C68BDF820702D +:1025400014F000541E466FD10B7B082B6CD8FFF79C +:10255000C5FF4569AB685B010CD4AB681B0108D4AF +:10256000AC6814F080545DD1FFF7BEFF204603B085 +:10257000F0BD01240B6804F1180C002BB8BFDB0080 +:102580004FEA0C1CB4BF43F004035B0545F80C3064 +:102590000B680FFA84FC13F0804F18BF05EB0C1E7C +:1025A00005EB0C1C1EBFDEF8803143F00203CEF8B1 +:1025B00080310B7BCCF8843105EB04158B68C5F8B2 +:1025C0008C314B68C5F88831DCF8803143F0010369 +:1025D000CCF8803100EB441541F268031D4403EB55 +:1025E00044130344C5E9002608330D4601F10C0CE1 +:1025F00055F804EB43F804EB6545F9D184342D8894 +:102600001D8000EB441407F00303257925F00B052A +:102610002B432371FFF768FF0097334600F0E2FC7D +:102620000120A4E70224A5E74FF0FF309FE7000058 +:1026300013B500F580540191E06DFFF74BFE1F28A4 +:102640000AD90199E06D2022FFF7BAFEA0F120031C +:102650005842584102B010BD0020FBE708B500F514 +:102660008050FFF73BFFC06DFFF708FEBDE8084054 +:10267000FFF73ABF002202608281426082607047A9 +:1026800010B500220023C0E9002300230446038183 +:102690000C30FFF7EFFF204610BD0000F0B50546F7 +:1026A00000F580500C4690F8C83013F0040FC3F3C7 +:1026B000800108BF114661F3820304F1840680F8AB +:1026C000C83005EB461389B01B79D8072ED57AB3ED +:1026D00019072DD46846FFF7D3FF05EB441303F524 +:1026E000835303F1180703AA103318685968144676 +:1026F00003C40833BB422246F7D1186820609B8888 +:10270000A380DDE90E23CDE900230123ADF80830D5 +:102710002B686946DB6B2846984705EB46152B79F5 +:102720001A075CBF43F008032B7101E0002AF4D1C3 +:1027300009B0F0BD2DE9F047074688B007F5805491 +:1027400068469A468846FFF7C9FE9146FFF798FF0C +:10275000E06DFFF7A5FD1F2829D9E06D202269460D +:10276000FFF7B0FE202822D103AD444605AB2E462C +:1027700003CE9E4220606160354604F10804F6D124 +:1027800030682060B388A380DDE90023C9E9002315 +:10279000BDF80830AAF80030FFF7A6FE4A465346B7 +:1027A0004146384608B0BDE8F04700F009BCFFF7E5 +:1027B0009BFE002008B0BDE8F08700002DE9F84F2F +:1027C0000023C0E90133254B044640F8183B0F466F +:1027D000FFF750FF04F12800FFF752FF04F148080B +:1027E00004F582554646083530462036FFF748FF47 +:1027F000AE42F9D104F580554FF480534FF00009F3 +:10280000C5E91339C5F848800123EE6504F58758FA +:1028100004F58456C5F8549085F8583085F8603032 +:10282000083608F108084FF0000A4FF0000B46E99F +:1028300008ABA6F11800FFF71DFF203646F8289CCC +:102840004645F4D185F8C97017B1054800F0A2FBE0 +:10285000044B63612046BDE8F88F00BFE06F0008BD +:10286000B86F00080064004010B5044B19780446A6 +:102870004A1C1A70FFF7A2FF204610BD804B0020B3 +:102880002DE9F047002950D0294B2A4FB7FBF1F52D +:1028900099428CBF0A231123581EB5FBF3FC03FB9E +:1028A0001C53C4B22BB102280346F5D80020BDE862 +:1028B000F0870CF1FF36B6F5806FF7D2C4EBC40E8B +:1028C0000EF103034FEAE309C3F3C703A4EB0308C4 +:1028D00009F1010A4FF47A755FFA88F009FB055592 +:1028E0005AFA88F8B5FBF8F5B5F5617FC1BF0EF16E +:1028F000FF33C3F3C703E01AC0B25C1C50FA84F480 +:102900000CFB04F4B7FBF4F4A142CFD1013BDBB2E2 +:102910000F2BCBD80138C0B20728C7D800211071BF +:1029200016809170D3700120C1E70846BFE700BF51 +:102930003F420F0080DE800270B505460E464FF420 +:102940007A746B695B6803F00103B34207D04FF4FC +:102950007A7002F0A5FB013CF3D1204670BD012046 +:10296000FCE7000030B54269936913F0700F16D090 +:1029700000230B4C936103F1840200EB42121179A6 +:102980004D0709D5890707D5416954F823508D6053 +:10299000117941F0040111710133032BEBD130BDEA +:1029A000CC6F000873B51D46436916469A68D20776 +:1029B000044609D59A6801219960C2F34002CDE925 +:1029C00000650021FFF76AFE63699A68D1050BD59F +:1029D0009A684FF480719960C2F34022CDE9006596 +:1029E00001212046FFF75AFE63699A68D2030BD58E +:1029F0009A684FF480319960C2F34042CDE9006596 +:102A000002212046FFF74AFE204602B0BDE8704092 +:102A1000FFF7A8BFF8B50446466900296CD106F156 +:102A20000C07386880076AD006EB01153868D5F8BE +:102A3000B00110F0040FD5F8B0011ABFC00840F083 +:102A40000040400DA061D5F8B0C11CF0020F1CBFC2 +:102A500040F08040A061D5F8B40106EB011100F010 +:102A60000F0084F82400D1F8B8012077D1F8B8011C +:102A7000000A6077D1F8B801000CA077D1F8B8014E +:102A8000000EE077D1F8BC0184F82000D1F8BC0139 +:102A9000000A84F82100D1F8BC01000C84F822005F +:102AA000D1F8BC11090E84F823103821396004F1E3 +:102AB000340004F1180104F1240551F8046B40F8C6 +:102AC000046BA942F9D109880180C4E90A2321468F +:102AD0000023238651F8283B2046DB6B984704F5FA +:102AE0008052204692F8C83043F0040382F8C83080 +:102AF000BDE8F840FFF736BF06F1100791E7F8BDD3 +:102B000010B5044600F04EFA02460B4652EA0301A5 +:102B100002D0013A63F100030449086820B121465C +:102B2000BDE81040FFF776BF10BD00BF7C4B002012 +:102B3000F8B500F583511E46FFF7D0FCDFF844C01E +:102B40000831002404F1840500EB45152B795F075B +:102B50000ED4DB060CD5D1E900739742B34107D2FE +:102B600043695CF824709F602B7943F004032B7158 +:102B70000134032C01F12001E4D1BDE8F840FFF756 +:102B8000B3BC00BFCC6F000808B5FFF7A7FCFFF788 +:102B9000E9FEBDE80840FFF7A7BC0000F8B54369AF +:102BA0000546986800F0E050B0F1E05F0F461FD096 +:102BB000E8B1FFF793FC05F583541034002606F1C5 +:102BC000840305EB43131B791A0706D50136032E40 +:102BD00004F12004F3D1012007E05B07F6D421467D +:102BE000384600F039FA0028F0D1FFF77DFCF8BD37 +:102BF0000120FCE700F5805008B5FFF76FFCC06DC1 +:102C0000FFF74EFBFFF770FC43090CBF01200020CB +:102C100008BD0000F8B51D46002313700F46064698 +:102C20001446FFF7E7FF80F00100387025B1294610 +:102C30003046FFF7B3FF2070F8BD00002DE9B84122 +:102C40000C4615461F46804600F0ACF90B4621782D +:102C5000024609B9287850B14046FFF769FFFFF7EF +:102C600093FF3B462A462146FFF7D4FF0120BDE8EB +:102C7000B881000010B5FFF731FC174B1A6C42F019 +:102C800000721A641A6A42F000721A621A6A00F537 +:102C9000805422F000721A62FFF726FC94F8C830C4 +:102CA000DB0718D4B9B103211320FFF717FC01F09B +:102CB000BBFA0321142001F0B7FA0321152001F01B +:102CC000B3FA94F8C83043F0010384F8C830BDE883 +:102CD0001040FFF709BC10BD003802402DE9F04755 +:102CE00000F5805588B095F8C930012B0446884618 +:102CF00016467FD8804F57F823200AB947F823009B +:102D0000D7F800A0C4F80C802674BAF1000F63D085 +:102D100095F8C930012B6FD001212046FFF7AAFF9B +:102D2000FFF7DCFB6269136823F00203136062693A +:102D3000136843F001031360636900275F61012199 +:102D40002046FFF7D1FBFFF7F7FD002800F0958044 +:102D5000E86DFFF793FA04F58359BA4609F10809BB +:102D6000202200216846FEF729FF02A8FFF782FC17 +:102D7000CDF818A06A4609EB07030DF1180E94462A +:102D8000BCE80300F44518605960624603F108038B +:102D9000F5D1DCF80000186020379CF804201A7187 +:102DA000602FDDD195F8C8306FF38203002785F8D6 +:102DB000C8306A4641462046ADF80070ADF8027052 +:102DC0008DF80470FFF75CFD636948BB4FF4004267 +:102DD0001A6008B0BDE8F08741F2D00003F0DCFFD4 +:102DE000814610B15146FFF7E9FCC7F80090B9F1F0 +:102DF000000F8DD10020ECE7386803681B6B984703 +:102E00000146002888D13868FFF734FF3868036826 +:102E100032465B684146984700287FF47DAFE9E77A +:102E200061221A609DF802309DF803201B061204EF +:102E300002F4702203F040731343BDF80020C2F384 +:102E4000090213439DF804201205022E02F4E00249 +:102E50000CBF4FF000410021134362690B43D36163 +:102E6000636913225A616269136823F001031360D6 +:102E700039462046FFF760FD08B96369A6E795F873 +:102E8000C93093BB6169D1F8002242F00102C1F858 +:102E900000226169D1F8002222F47C5222F00E0255 +:102EA000C1F800226169D1F8002242F46062C1F8E1 +:102EB00000226269C2F814326269C2F8043262699F +:102EC00041F6FF71C2F80C126269C2F840326269C1 +:102ED000C2F8443263690122C3F81C226269D2F845 +:102EE000003223F00103C2F8003295F8C83043F0F5 +:102EF000020385F8C8306CE77C4B002008B500F071 +:102F000051F850EA0103024602D0421E61F100016D +:102F1000044B186810B10B46FFF744FDBDE80840AC +:102F200001F064B87C4B002008B50020FFF7E8FDF5 +:102F3000BDE8084001F05AB808B50120FFF7E0FDF0 +:102F4000BDE8084001F052B800B59BB0EFF309812D +:102F500068226846FEF70CFEEFF30583014B9B6B7E +:102F6000FEE700BF00ED00E008B5FFF7EDFF000051 +:102F700000B59BB0EFF3098168226846FEF7F8FDC3 +:102F8000EFF30583014B5B6BFEE700BF00ED00E054 +:102F9000FEE700000FB408B5029802F00DF8FEE756 +:102FA00002F0ACBC02F084BC13B56C4684E80600A9 +:102FB000031D94E8030083E80500012002B010BD62 +:102FC00073B58568019155B11B885B0707D4D0E9BB +:102FD00000369B6B9847019AC1B23046A847012042 +:102FE00002B070BDF0B5866889B005460C465EB18A +:102FF000BDF838305B070AD4D0E900379B6B98479F +:103000002246C1B23846B047012009B0F0BD0022C7 +:103010000023CDE900230023ADF808300A4603ABB6 +:1030200001F10806106851681C4603C40832B24218 +:103030002346F7D1106820609288A280FFF7B2FF84 +:103040000423ADF808302B68CDE90001DB6B69463D +:1030500028469847D8E7000030B503680968DD0FB7 +:10306000B5EBD17F23F0604421F060424FEAD1708C +:103070000BD0002BB8BFA40C0029B8BF920C94420F +:1030800002D034BF0120002030BD944205D1C1F3ED +:103090008070C3F380738342F6D194422CBF00202A +:1030A0000120F1E72DE9F041456A15B94162BDE81B +:1030B000F0814B6823F06047C3F38A464FEAD37E22 +:1030C000C3F3807816EA230638BF3E46AC462B464B +:1030D0005A68BEEBD27F22F060440AD0002A18DA88 +:1030E000A40CB44217D19D420FD10D60DEE7134608 +:1030F000EEE7A74207D102F08044C2F38072424556 +:103100000BD054B1EFE708D2EDE7CCF800100B601C +:10311000CDE7B44201D0B442E5D81A689C46002AF3 +:10312000E5D11960C3E700002DE9F047089D01F0E3 +:1031300007044FEAD508224405F0070500EBD1004B +:103140004FF47F49944201D1BDE8F08704F00707AE +:1031500005F0070A57453E4638BF5646C6F10806F1 +:10316000111B8E4228BF0E46E10808EBD50E415CCC +:1031700013F80EC0B94029FA06F721FA0AF1FFB296 +:103180008CEA010147FA0AF739408CEA010C03F88E +:103190000EC034443544D5E780EA0120082341F2CB +:1031A000210201B24000002980B203F1FF33B8BF11 +:1031B000504013F0FF03F4D17047000038B50C46BF +:1031C0008D18A54200D138BD14F8011BFFF7E4FFAC +:1031D000F7E7000042684AB1136843604389818978 +:1031E00001339BB29942438138BF838110467047B7 +:1031F00070B588B0202204460D4668460021FEF7CF +:10320000DDFC20460495FFF7E5FF024658B16B460A +:10321000054608AE1C4603CCB442286069602346CC +:1032200005F10805F6D1104608B070BD082817D979 +:1032300009280CD00A280CD00B280CD00C280CD054 +:103240000D280CD00E2814BF4020302070470C20D1 +:1032500070471020704714207047182070472020B6 +:1032600070470000082817D90C280CD910280CD951 +:1032700014280CD918280CD920280CD930288CBF38 +:103280000F200E207047092070470A2070470B203E +:1032900070470C2070470D20704700002DE9F8435F +:1032A000078C072F04461ED9D0E9029800254FF657 +:1032B000FF73C5F12006A5F1200029FA05F108FAEF +:1032C00006F628FA00F031430143C9B21846FFF769 +:1032D00063FF0835402D0346EBD1E1693A46BDE86E +:1032E000F843FFF76BBF4FF6FF70BDE8F8830000AF +:1032F00010B54B6823B9CA8A63F30902CA8210BDAC +:1033000004691A681C600361C38A013BC3824A6076 +:10331000EFE700002DE9F84F1D46CB8A0F46C3F3B7 +:1033200009010529814692460B4630D00020AAB2F9 +:1033300007F11A049EB2042E1FFA80F80FD89045A8 +:1033400003F1010306D3FB8A0A4462F30903FB82FB +:1033500001201AE01AF80060E6540130EAE79045CF +:10336000F1D2A1F1050B1C237C68BBFBF3F203FB3C +:1033700012BB1FFA8BF6002C45D14846FFF72AFFF7 +:10338000044638B978606FF00200BDE8F88F4FF05E +:103390000008E6E7002606607860ADB24FF0000B4B +:1033A000454510D90AEB0803221D13F8011B91555E +:1033B000B1B208F101081B291FFA88F82BD0454546 +:1033C00006F10106F1D8FB8AC3F30902154465F33F +:1033D0000903BCE7013292B21C462368002BF9D1E5 +:1033E0006B1F0B441C21B3FBF1F301339BB29A42D8 +:1033F000D3D2BBF1000FD0D14846FFF7EBFE20B986 +:10340000C4F800B0BFE70122E7E7C0F800B05E46AD +:1034100020600446C1E74545D5D94846FFF7DAFEA6 +:1034200008B92060AFE7C0F800B00026206004466D +:10343000B6E700002DE9F04F2DED028B1C4683B05E +:103440005B69019207468846002B00F09A80238C26 +:103450002BB1E269002A00F09480072B35D807F1E0 +:103460000C00FFF7B7FE054638B96FF00205284695 +:1034700003B0BDEC028BBDE8F08F14220021FEF7F3 +:103480009DFB228CE16905F10800FEF771FB208CA1 +:10349000013080B2FFF7E6FEFFF7C8FE013880B2C8 +:1034A0002084013028746369228C1B782A4403F03D +:1034B0001F0363F03F0348F0004113723846696010 +:1034C0002946FFF7EFFD0125D1E700F10C034FF08E +:1034D000000908EE103A4FF0800A4E464D4618EEAD +:1034E000100AFFF777FE83460028BED01422002181 +:1034F000FEF764FB002E3AD1019BABF808300222A4 +:103500000BF1080E1FFA82FC0CF10100BCF1060F52 +:10351000218C80B201D88E422BD3FFF7A3FEFFF798 +:1035200085FE62691278013802F01F028E4208BFE0 +:103530004FF0400A42EA49121BFA80F14AEA020AB5 +:10354000013048F0004281F808A08BF81000CBF859 +:10355000042059463846FFF7A5FD238C0135B342B8 +:103560002DB289F001094FF0000AB8D17FE700229F +:10357000C6E7E169895D0EF802100136B6B2013284 +:10358000C0E76FF0010572E7F8B515460E46302228 +:10359000002104461F46FEF711FB069B6360B5F54C +:1035A000001F079BA76034BF6A094FF6FF72A36232 +:1035B00097B2E66104F1100000239A4206D8002376 +:1035C0000360A782E3822383E360F8BD06600133D2 +:1035D00030462036F1E7000003781BB94BB2002BD0 +:1035E000C8BF01707047000000787047F8B50C46FE +:1035F000C969074611B9238C002B37D1257E1F2DB1 +:1036000034D8387828BB228C072A2CD8268A36F062 +:1036100003032BD14FF6FF70FFF7D0FD20F0010020 +:103620003102400441EA0561400C41EA40254FF671 +:10363000FF72234629463846FFF7FCFE002807DDC7 +:10364000626913780133DBB21F2B88BF002313702C +:10365000F8BD218A2D0645EA012505432046FFF7DE +:103660001DFE0246E5E76FF00300F1E76FF0010091 +:10367000EEE7000070B58AB0044616460021282205 +:1036800068461D46FEF79AFABDF83830ADF810309E +:103690000F9B05939DF840308DF81830119B0793D0 +:1036A0006946BDF84830ADF820302046CDE90265C6 +:1036B000FFF79CFF0AB070BD2DE9F041D3690546C4 +:1036C0000C4616460BB9138C5BBB377E1F2F28D8D0 +:1036D00095F80080B8F1000F26D03046FFF7DEFDE8 +:1036E0003378210241EAC33141EA0801338A41EAD1 +:1036F000076141EA03410246334641F08001284612 +:10370000FFF798FE00280ADD3378012B07D1726994 +:1037100013780133DBB21F2B88BF00231370BDE881 +:10372000F0816FF00100FAE76FF00300F7E70000A7 +:10373000F0B58BB004460D46174600212822684696 +:103740001E46FEF73BFA9DF84C305A1E5342534139 +:103750008DF800309DF84030ADF81030119B059386 +:103760009DF848308DF81830149B07936A46BDF8D1 +:103770005430ADF8203029462046CDE90276FFF7D7 +:103780009BFF0BB0F0BD0000406A00B104307047F1 +:10379000436A1A68426202691A600361C38A013B84 +:1037A000C38270472DE9F041D0F82080194E1446AD +:1037B0001D464146002709B9BDE8F081D1E9022341 +:1037C000A21A65EB0303964277EB03031ED2036A4A +:1037D0008B420DD1FFF78CFD036A1B6803620369FE +:1037E0000B60C38A0161016A013BC3828846E2E73C +:1037F000FFF77EFD0B68C8F8003003690B60C38AD1 +:103800000161013BC382D8F80010D4E788460968FB +:10381000D1E700BF80841E002DE9F04F8BB00D462C +:10382000DDF8509014469B468046002800F0198130 +:10383000B9F1000F00F01581531E3F2B00F21181EA +:10384000012A03D1BBF1000F40F00B810023CDE929 +:103850000833B8F81430B5EBC30F4FEAC30703D3EE +:1038600000200BB0BDE8F08F2B199F42D8F80C3028 +:103870003ABF7F1BFFB227461BB9D8F81030002B88 +:103880007AD0272D4ED8C5F12806B7424FF0000355 +:103890002CBFF6B23E4600932946D8F8080008AB84 +:1038A0003246FFF741FCA7EB060A35445FFA8AFA75 +:1038B000B8F8143003F10053053BDB000493D8F84B +:1038C0000C3003932821039B13B1BAF1000F2CD1C4 +:1038D000D8F8100040B1BAF1000F05D0009608AB3F +:1038E0005246691AFFF720FC38B2002FB8D066079D +:1038F0000AD00AAB03EBD401624211F8083C02F093 +:103900000702134101F8083C082C3CD9102C40F266 +:10391000B580202C40F2B780BBF1000F00F09C80F6 +:10392000082334E0BA460026C2E7049BE02B28BFF8 +:10393000E02306930B44AB42059314D95A1B03981A +:103940000096924534BF5246D2B2691A08AB043091 +:103950000792FFF7E9FB079A1644AAEB020A1544FF +:10396000F6B25FFA8AFA049B069A05999B1A0493A9 +:10397000039B1B680393A6E70093D8F8080008ABE5 +:103980003A462946AEE7BBF1000F13D00123B4EB52 +:10399000C30F6CD0082C12D89DF82030621E23FA79 +:1039A00002F2D50706D54FF0FF3202FA04F42343A2 +:1039B0008DF820309DF8203089F8003051E7102C28 +:1039C00012D8BDF82030621E23FA02F2D10706D5C4 +:1039D0004FF0FF3202FA04F42343ADF82030BDF873 +:1039E0002030A9F800303CE7202C0FD80899631E3E +:1039F00021FA03F3DA0705D54FF0FF3202FA04F497 +:103A00000C430894089BC9F800302AE7402C2BD0BF +:103A1000DDE90865611EC4F12102A4F1210326FA43 +:103A200001F105FA02F225FA03F311431943CB071A +:103A300012D50122A4F12003C4F1200102FA03F3FC +:103A400022FA01F1A240524243EA010363EB43032D +:103A500032432B43CDE90823DDE90823C9E90023DC +:103A6000FFE66FF00100FCE66FF00800F9E6082CB5 +:103A7000A0D9102CB3D9202CEED8C3E7BBF1000F8E +:103A8000ADD0022383E7BBF1000FBBD004237EE758 +:103A900030B5012A144638BF0124402C85B028BF18 +:103AA00040240025012ACDE9025518D81B788DF84D +:103AB000083063070AD004AB03EBD405624215F863 +:103AC000083C02F00702934005F8083C00910346C9 +:103AD0002246002102A8FFF727FB05B030BD082AC7 +:103AE000E4D9102A03D81B88ADF80830E1E7202A72 +:103AF0008DBFD3E900231B680293CDE90223D8E7E9 +:103B000010B5CB681BB98B600B618B8210BD04694B +:103B10001A681C600361C38A013BC382CA60F0E774 +:103B200003064CBFC0F3C0300220704708B5024600 +:103B3000FFF7F6FF022806D15306C2F30F2001D18A +:103B400000F0030008BDC2F30740FBE72DE9F04F8A +:103B500093B0CDE903230A6804461046FFF7E0FF5F +:103B6000022814BFC2F306260026002A0D4682460C +:103B700080F2F28112F0C04940F0EE81097B002909 +:103B800000F0EA81022803D02378B34240F0E781B5 +:103B9000C2F304630693104602F07F030593FFF718 +:103BA000C5FF059B29444FEA834848EA0A4848EA8A +:103BB0004668CE7800230022CDE90823F309834626 +:103BC00048EA0008029367D0059B009302466768A5 +:103BD000534608A92046B847002800F0C381276A49 +:103BE0004FB9414604F10C00FFF702FB074690B9BC +:103BF0006FF0020054E03B6998450DD03F68002FFC +:103C0000F9D1414604F10C00FFF7F2FA074600280B +:103C1000EED0236A3B60276297F817C006F01F08B2 +:103C2000CCF3840CACEB08001FFA80FE0028B8BF70 +:103C30000EF12000A8EB0C031FFA83FED7E9022146 +:103C4000B8BF00B2002B0793BEBF0EF120031BB21A +:103C5000079352EA010338D0039BDFF824E39A1A52 +:103C6000049B4FF0000C63EB010196457CEB0103D4 +:103C70002BD36B7B97F81AE0734519D1029B002B6D +:103C800078D0012821DC7868F8B9DFF8F0C29445D3 +:103C900070EB010316D337E0276A27B96FF00C00E9 +:103CA00013B0BDE8F08F3B699845B5D03F68F4E7A5 +:103CB000B24890427CEB010301D30020F0E7029B65 +:103CC000002BFAD0079B0F2B17DCFA7DB30002F014 +:103CD000030203F07C031343FB7539462046FFF7CC +:103CE00007FB6B7BBB76029B3BB9FB7DC3F3840276 +:103CF000013262F38603FB75D0E76A7BBB7E9A4292 +:103D0000DBD1029B002B35D0B309022B32D0039BB1 +:103D1000BB60049BFB60142200210DA8FDF74EFF41 +:103D2000039B0A93049B0B932B1D0C932B7BADF8E9 +:103D30003EB0013BDBB2ADF83C30069B8DF8423023 +:103D4000059B8DF8433094F82C308DF840A083F01B +:103D500001038DF844308DF84180A3680AA92046FC +:103D60009847FB7DC3F38403013303F01F039B02D9 +:103D7000FB82A2E7FB7DC6F34012B2EBD31F40F0FB +:103D8000F480C3F38403434540F0F280029A2B7B16 +:103D9000B609002A4DD0F2075DD4032B40F2EB8028 +:103DA000039BBB60049BFB602B7BAE1D033BDBB224 +:103DB0003246394604F10C00FFF7ACFA00280CDA61 +:103DC00039462046FFF794FAFB7DC3F384030133A1 +:103DD00003F01F039B02FB820AE7DDE90884AB883E +:103DE0003B834FF6FF73C9F12000A9F1200228FAA6 +:103DF00009F104FA00F0014324FA02F211431846D3 +:103E0000C9B2FFF7C9F909F10809B9F1400F034632 +:103E1000E9D1B8822A7B033AD2B23146FFF7CEF914 +:103E2000FB7DB882DA43C2F3C01262F3C713FB759D +:103E300043E786B92E1D013BDBB23246394604F119 +:103E40000C00FFF767FA0028BADB2A7BB88A013A30 +:103E5000D2B23146E2E7F98AC1F30901013B0429F4 +:103E6000DAB25BD8281D002307F11B069A4208D955 +:103E700010F801CB06F801C0013101330529DBB28E +:103E8000F4D103990A9104990B91934207F11B0114 +:103E90000C9138BF043379680D9134BF55FA83F320 +:103EA00000230E93FB8AADF83EB0C3F309031A4416 +:103EB000069B8DF84230059B8DF8433094F82C30EA +:103EC000ADF83C2083F001038DF8443000238DF8D9 +:103ED00040A08DF841807B602A7BB88A013A291D79 +:103EE000FFF76CF93B8BB882834203D1A3680AA920 +:103EF0002046984720460AA9FFF702FEFB7DBA8AB2 +:103F0000C3F38403013303F01F039B02FB823B8B4B +:103F10009A420CBF00206FF01000C1E67B68002BB6 +:103F2000AFD0052001E01C3033461E68002EFAD1C8 +:103F3000091A081D2E1D184401EB090CBCF11B0FBA +:103F40005FFA89F39DD89A429BD916F8013B00F895 +:103F5000013B09F10109EFE76FF00900A0E66FF0FE +:103F60000A009DE66FF00B009AE66FF00D0097E6F1 +:103F70006FF00E0094E66FF00F0091E640420F00E4 +:103F800080841E00EFF3098305494A6B22F0010289 +:103F90004A63683383F30988002383F311887047E9 +:103FA00000EF00E0302080F3118862B60C4B0D4A20 +:103FB000D96821F4E0610904090C0A43DA60D3F8F6 +:103FC000FC20094942F08072C3F8FC200A6842F0E4 +:103FD00001020A602022DA7783F82200704700BFCE +:103FE00000ED00E00003FA05001000E010B53023FA +:103FF00083F311880E4B5B6813F4006314D0F1EE69 +:10400000103AEFF30984683C4FF08073E361094B89 +:10401000DB6B236684F3098800F08CFF10B1064B3C +:10402000A36110BD054BFBE783F31188F9E700BFDF +:1040300000ED00E000EF00E043060008460600083F +:10404000026843681143016003B1184770470000DC +:10405000024AD36843F0C003D36070470044004075 +:1040600010B5054C054A0021204600F087FA044AA5 +:10407000044BC4E9972310BD884B00205140000831 +:104080000044004080DE8002234A037C002918BFE0 +:104090000A46012B30B5C0F868220CD11F4B98425C +:1040A00009D11F4B196C41F400311964196E41F4A8 +:1040B000003119661B6EB2F904501468D0F86032F2 +:1040C000D0F85C12002D03EB5403B3FBF4F3BEBF36 +:1040D00023F0070503F0070343EA450394888B6048 +:1040E000D38843F040030B61138943F001034B6114 +:1040F00044F4045343F02C03CB6004F4A054002395 +:104100000B60B4F5806F0B684B680CBF7F23FF23F7 +:1041100080F8643230BD00BF20700008884B00205A +:10412000003802402DE9F041D0F85C62F76833684E +:10413000DA0504469DB20DD5302383F311884FF480 +:1041400080610430FFF77CFF6FF4807333600023DD +:1041500083F31188302383F3118804F1040815F0E8 +:104160002F033AD183F31188380615D5290613D5C4 +:10417000302383F3118804F1380000F07BF9002824 +:104180004EDA0821201DFFF75BFF4FF67F733B409F +:10419000F360002383F311887A0616D56B0614D5D5 +:1041A000302383F31188D4E913239A420AD1236C74 +:1041B00043B127F040073F041021201D3F0CFFF7BB +:1041C0003FFFF760002383F31188D4F86822D36897 +:1041D00043B3BDE8F041106918472B0714D015F020 +:1041E000080F0CBF00214FF48071E80748BF41F071 +:1041F0002001AA0748BF41F040016B0748BF41F0CA +:1042000080014046FFF71CFFAD06736805D594F8A2 +:1042100064122046194000F0E1F93568ADB29EE71E +:104220007060B6E7BDE8F08100F1604303F56143DB +:104230000901C9B283F80013012200F01F039A405C +:1042400043099B0003F1604303F56143C3F88021F8 +:104250001A607047F8B5154682680669AA420B468F +:10426000816938BF8568761AB54204460BD2184674 +:104270002A46FDF77DFCA3692B44A361A3685B1B61 +:10428000A3602846F8BD0CD918463246FDF770FCED +:10429000AF1BE1683A463044FDF76AFCE3683B44F3 +:1042A000EBE718462A46FDF763FCE368E5E7000004 +:1042B00083689342F7B51546044638BF8568D0E950 +:1042C0000460361AB5420BD22A46FDF751FC6369E9 +:1042D0002B446361A36828465B1BA36003B0F0BD59 +:1042E0000DD932460191FDF743FC0199E068AF1BFF +:1042F0003A463144FDF73CFCE3683B44E9E72A4693 +:10430000FDF736FCE368E4E710B50A440024C36116 +:10431000029B8460C0E90000C0E90511C160026130 +:10432000036210BD08B5D0E90532934201D182681D +:1043300082B98268013282605A1C42611970D0E9E8 +:1043400004329A4224BFC3684361002100F0C4FED6 +:10435000002008BD4FF0FF30FBE7000070B53023B0 +:1043600004460E4683F31188A568A5B1A368A26927 +:10437000013BA360531CA36115782269934224BFBB +:10438000E368A361E3690BB120469847002383F3F8 +:104390001188284607E03146204600F08DFE0028AF +:1043A000E2DA85F3118870BD2DE9F74F04460E4619 +:1043B00017469846D0F81C904FF0300A8AF31188BF +:1043C0004FF0000B154665B12A4631462046FFF7EF +:1043D00041FF034660B94146204600F06DFE0028CB +:1043E000F1D0002383F31188781B03B0BDE8F08F70 +:1043F000B9F1000F03D001902046C847019B8BF311 +:104400001188ED1A1E448AF31188DCE7C0E9051112 +:10441000C160C3611144009B8260C0E9000001617A +:1044200003627047F8B504460D461646302383F301 +:104430001188A768A7B1A368013BA36063695A1CF0 +:1044400062611D70D4E904329A4224BFE36863615B +:10445000E3690BB120469847002080F3118807E0FC +:104460003146204600F028FE0028E2DA87F3118862 +:10447000F8BD0000D0E905239A4210B501D1826849 +:104480007AB98268013282605A1C82611C780369A1 +:104490009A4224BFC3688361002100F01DFE2046BC +:1044A00010BD4FF0FF30FBE72DE9F74F04460E46F5 +:1044B00017469846D0F81C904FF0300A8AF31188BE +:1044C0004FF0000B154665B12A4631462046FFF7EE +:1044D000EFFE034660B94146204600F0EDFD00289E +:1044E000F1D0002383F31188781B03B0BDE8F08F6F +:1044F000B9F1000F03D001902046C847019B8BF310 +:104500001188ED1A1E448AF31188DCE702684368BB +:104510001143016003B11847704700001430FFF7E2 +:1045200043BF00004FF0FF331430FFF73DBF0000E2 +:104530003830FFF7B9BF00004FF0FF333830FFF7D6 +:10454000B3BF00001430FFF709BF00004FF0FF3188 +:104550001430FFF703BF00003830FFF763BF0000DF +:104560004FF0FF323830FFF75DBF0000012914BF64 +:104570006FF0130000207047FFF772BD37B5154686 +:104580000E4A026000224260C0E902220122044673 +:1045900002740B46009000F15C014FF480721430FD +:1045A000FFF7B2FE00942B464FF4807204F5AE7113 +:1045B00004F13800FFF72AFF03B030BD3470000863 +:1045C00010B53023044683F31188FFF75DFD022305 +:1045D0002374002080F3118810BD000038B5C36932 +:1045E00004460D461BB904210844FFF78FFF2946F6 +:1045F00004F11400FFF796FE002806DA201D4FF4A0 +:104600000061BDE83840FFF781BF38BD02684368EC +:104610001143016003B118477047000013B5446BA4 +:10462000D4F894341A681178042915D1217C022910 +:1046300012D11979128901238B4013420CD101A99F +:1046400004F14C0001F0DAFFD4F89444019B217985 +:104650000246206800F0D0F902B010BD143001F01D +:104660005DBF00004FF0FF33143001F057BF000072 +:104670004C3002F02FB800004FF0FF334C3002F006 +:1046800029B80000143001F02BBF00004FF0FF31BB +:10469000143001F025BF00004C3001F0FBBF0000DA +:1046A0004FF0FF324C3001F0F5BF000000207047A2 +:1046B00010B5D0F894341A6811780429044617D13B +:1046C000017C022914D15979528901238B4013426C +:1046D0000ED1143001F0BEFE024648B1D4F8944425 +:1046E0004FF4807361792068BDE8104000F072B922 +:1046F00010BD0000406BFFF7DBBF000070470000FB +:104700007FB5124B036000234360C0E902330125EB +:1047100002260F4B057404460290019300F18402B7 +:10472000294600964FF48073143001F06FFE094B58 +:104730000294CDE9006304F523724FF48073294697 +:1047400004F14C0001F036FF04B070BD5C7000084D +:10475000F54600081D4600080B68302282F31188D8 +:104760000A7903EB820290614A79093243F8220008 +:104770008A7912B103EB820398610223C0F8941482 +:104780000374002080F311887047000038B5037F60 +:10479000044613B190F85430ABB9201D0125022115 +:1047A000FFF734FF04F1140025776FF0010100F0EA +:1047B0009FFC84F8545004F14C006FF00101BDE8F7 +:1047C000384000F095BC38BD10B5012104460430D6 +:1047D000FFF71CFF0023237784F8543010BD00003E +:1047E00038B504460025143001F028FE04F14C00D1 +:1047F000257701F0F7FE201D84F854500121FFF7C2 +:1048000005FF2046BDE83840FFF752BF90F844301E +:1048100003F06003202B07D190F84520212A4FF0A8 +:10482000000303D81F2A06D800207047222AFBD194 +:10483000C0E90E3303E0034A82630722C2630364C4 +:10484000012070472823002037B5D0F894341A6827 +:104850001178042904461AD1017C022917D119794B +:10486000128901238B40134211D100F14C052846D7 +:1048700001F078FF58B101A9284601F0BFFED4F835 +:104880009444019B21790246206800F0B5F803B0FA +:1048900030BD0000F0B500EB810385B09E69044691 +:1048A0000D46FEB1302383F3118804EB8507301DDC +:1048B0000821FFF7ABFEFB685B691B6806F14C0043 +:1048C0001BB1019001F0A8FE019803A901F096FE2A +:1048D000024648B1039B2946204600F08DF800238C +:1048E00083F3118805B0F0BDFB685A691268002A8D +:1048F000F5D01B8A013B1340F1D104F14402EAE7F1 +:10490000093138B550F82140DCB1302383F31188E8 +:10491000D4F894241368527903EB8203DB689B6913 +:104920005D6845B104216018FFF770FE294604F167 +:10493000140001F099FD2046FFF7BAFE002383F32F +:10494000118838BD7047000001F00EB901230370D3 +:104950000023C0E90133C36183620362C36243621F +:104960000363704738B50446302383F3118800256C +:10497000C0E90355C0E90555416001F005F902237E +:10498000237085F31188284638BD000070B500EB10 +:10499000810305465069DA600E46144618B11022AC +:1049A0000021FDF70BF9A06918B110220021FDF7D5 +:1049B00005F931462846BDE8704001F0AFB9000066 +:1049C000826802F0011282600022C0E90422826142 +:1049D00001F030BAF0B400EB81044789E4680125A6 +:1049E000A4698D403D43458123600023A26063603C +:1049F000F0BC01F04BBA0000F0B400EB8104078971 +:104A0000E468012564698D403D43058123600023EE +:104A1000A2606360F0BC01F0C5BA000070B502236B +:104A2000002504460370C0E90255C0E90455C56479 +:104A3000856180F8345001F00DF963681B6823B17B +:104A400029462046BDE87040184770BD0378052B05 +:104A500010B504460AD080F850300523037043682F +:104A60001B680BB1042198470023A36010BD000010 +:104A70000178052906D190F85020436802701B6820 +:104A800003B118477047000070B590F83430044601 +:104A900013B1002380F8343004F14402204601F0C1 +:104AA000EBF963689B68B3B994F8443013F0600580 +:104AB00035D00021204601F08BFC0021204601F07A +:104AC0007DFC63681B6813B10621204698470623C6 +:104AD00084F8343070BD204698470028E4D0B4F8FC +:104AE0004A30E26B9A4288BFE36394F94430E56B45 +:104AF000002B4FF0300380F20381002D00F0F28094 +:104B0000092284F8342083F311880021D4E90E238C +:104B10002046FFF771FF002383F31188DAE794F84A +:104B2000452003F07F0343EA022340F2023293421E +:104B300000F0C58021D8B3F5807F48D00DD8012B77 +:104B40003FD0022B00F09380002BB2D104F14C0235 +:104B5000A2630222E2632364C1E7B3F5817F00F020 +:104B60009B80B3F5407FA4D194F84630012BA0D1AF +:104B7000B4F84C3043F0020332E0B3F5006F4DD08F +:104B800017D8B3F5A06F31D0A3F5C063012B90D82F +:104B9000636894F846205E6894F84710B4F848308B +:104BA0002046B047002884D04368A3630368E363CA +:104BB0001AE0B3F5106F36D040F6024293427FF40C +:104BC00078AF5C4BA3630223E3630023C3E794F84D +:104BD0004630012B7FF46DAFB4F84C3023F0020364 +:104BE000C4E90E55A4F84C30256478E7B4F8443095 +:104BF000B3F5A06F0ED194F8463084F84E302046BD +:104C000001F080F863681B6813B1012120469847C2 +:104C1000032323700023C4E90E339CE704F14F0300 +:104C2000A3630123C3E72378042B10D1302383F33C +:104C300011882046FFF7C4FE85F3118803216368BD +:104C400084F84F5021701B680BB12046984794F8A8 +:104C50004630002BDED084F84F3004232370636885 +:104C60001B68002BD6D0022120469847D2E794F843 +:104C700048301D0603F00F0120460AD501F0EEF87A +:104C8000012804D002287FF414AF2B4B9AE72B4B5A +:104C900098E701F0D5F8F3E794F84630002B7FF45D +:104CA00008AF94F8483013F00F01B3D01A0620462D +:104CB00002D501F0A1FBADE701F094FBAAE794F85F +:104CC0004630002B7FF4F5AE94F8483013F00F0116 +:104CD000A0D01B06204602D501F07AFB9AE701F02E +:104CE0006DFB97E7142284F8342083F311882B4658 +:104CF0002A4629462046FFF76DFE85F31188E9E62E +:104D00005DB1152284F8342083F311880021D4E9A1 +:104D10000E232046FFF75EFEFDE60B2284F83420CA +:104D200083F311882B462A4629462046FFF764FE66 +:104D3000E3E700BF8C7000088470000888700008EA +:104D400038B590F834300446002B3ED0063BDAB23A +:104D50000F2A34D80F2B32D8DFE803F0373131086F +:104D6000223231313131313131313737C56BB0F821 +:104D70004A309D4214D2C3681B8AB5FBF3F203FB91 +:104D800012556DB9302383F311882B462A462946E4 +:104D9000FFF732FE85F311880A2384F834300EE0E1 +:104DA000142384F83430302383F3118800231A4607 +:104DB00019462046FFF70EFE002383F3118838BD05 +:104DC000036C03B198470023E7E70021204601F078 +:104DD000FFFA0021204601F0F1FA63681B6813B165 +:104DE0000621204698470623D7E7000010B590F823 +:104DF0003430142B044629D017D8062B05D001D8FF +:104E00001BB110BD093B022BFBD80021204601F04D +:104E1000DFFA0021204601F0D1FA63681B6813B164 +:104E2000062120469847062319E0152BE9D10B23CC +:104E300080F83430302383F3118800231A46194652 +:104E4000FFF7DAFD002383F31188DAE7C3689B6973 +:104E50005B68002BD5D1036C03B19847002384F81D +:104E60003430CEE700230375826803691B689968B4 +:104E70009142FBD25A6803604260106058607047EC +:104E800000230375826803691B6899689142FBD807 +:104E90005A680360426010605860704708B5084661 +:104EA000302383F311880B7D032B05D0042B0DD009 +:104EB0002BB983F3118808BD8B6900221A604FF06B +:104EC000FF338361FFF7CEFF0023F2E7D1E9003221 +:104ED00013605A60F3E70000FFF7C4BF054BD968C1 +:104EE0000875186802681A60536001220275D8605C +:104EF000FBF792BBF84D002030B50C4BDD684B1C26 +:104F000087B004460FD02B46094A684600F084F962 +:104F10002046FFF7E3FF009B13B1684600F086F9D7 +:104F2000A86907B030BDFFF7D9FFF9E7F84D0020B9 +:104F30009D4E0008044B1A68DB6890689B68984295 +:104F400094BF002001207047F84D0020084B10B599 +:104F50001C68D86822681A60536001222275DC60E0 +:104F6000FFF78EFF01462046BDE81040FBF754BB1B +:104F7000F84D0020044B1A68DB6892689B689A42DF +:104F800001D9FFF7E3BF7047F84D002038B5074C53 +:104F900007490848012300252370656001F01AFCC9 +:104FA0000223237085F3118838BD00BF60500020B4 +:104FB00094700008F84D002008B572B6044B1865CF +:104FC00000F05AFC00F018FD024B03221A70FEE7B5 +:104FD000F84D00206050002000F05EB9EFF3118022 +:104FE00020B9EFF30583302282F311887047000067 +:104FF00010B530B9EFF30584C4F3080414B180F39D +:10500000118810BDFFF7B6FF84F31188F9E700009F +:10501000034A516853685B1A9842FBD8704700BF37 +:10502000001000E08B60022308618B820846704705 +:105030008368A3F1840243F8142C026943F8442CDA +:10504000426943F8402C094A43F8242CC26843F8CB +:10505000182C022203F80C2C002203F80B2C044A13 +:1050600043F8102CA3F12000704700BF3106000860 +:10507000F84D002008B5FFF7DBFFBDE80840FFF75B +:105080002BBF0000024BDB6898610F20FFF726BFA3 +:10509000F84D0020302383F31188FFF7F3BF0000A1 +:1050A00008B50146302383F311880820FFF724FF59 +:1050B000002383F3118808BD064BDB6839B14268D1 +:1050C00018605A60136043600420FFF715BF4FF06B +:1050D000FF307047F84D00200368984206D01A68E8 +:1050E0000260506099611846FFF7F6BE70470000F5 +:1050F00038B504460D462068844200D138BD0368A7 +:1051000023605C608561FFF7E7FEF4E710B5036894 +:105110009C68A2420CD85C688A600B604C6021607D +:10512000596099688A1A9A604FF0FF33836010BD06 +:105130001B68121BECE700000A2938BF0A2170B572 +:1051400004460D460A26601901F03EFB01F02AFBD9 +:10515000041BA54203D8751C2E460446F3E70A2E0D +:1051600004D9BDE87040012001F074BB70BD00009F +:10517000F8B5144B0D46D96103F1100141600A2ABC +:105180001969826038BF0A22016048601861A81856 +:10519000144601F00BFB0A2701F004FB431BA3425A +:1051A000064606D37C1C281901F00EFB274635461F +:1051B000F2E70A2F04D9BDE8F840012001F04ABB0C +:1051C000F8BD00BFF84D0020F8B506460D4601F0C9 +:1051D000E9FA0F4A134653F8107F9F4206D12A4638 +:1051E00001463046BDE8F840FFF7C2BFD169BB6851 +:1051F000441A2C1928BF2C46A34202D92946FFF78E +:105200009BFF224631460348BDE8F840FFF77EBFCA +:10521000F84D0020084E002010B4C0E903230023FD +:105220005DF8044B4361FFF7CFBF000010B5194C88 +:10523000236998420DD0D0E90032816813605A602A +:105240009A680A449A60002303604FF0FF33A36119 +:1052500010BD2346026843F8102F536000220260FD +:1052600022699A4203D1BDE8104001F0A7BA9368C1 +:1052700081680B44936001F095FA2269E1699268B4 +:10528000441AA242E4D91144BDE81040091AFFF7BC +:1052900053BF00BFF84D00202DE9F047DFF8BC8078 +:1052A00008F110072C4ED8F8105001F07BFAD8F80E +:1052B0001C40AA68031B9A423ED81444D5E9003228 +:1052C0004FF00009C8F81C4013605A60C5F8009000 +:1052D000D8F81030B34201D101F070FA89F3118887 +:1052E000D5E9033128469847302383F311886B6949 +:1052F000002BD8D001F056FA6A69A0EB04094A45A0 +:1053000082460DD2022001F0A5FA0022D8F8103012 +:10531000B34208D151462846BDE8F047FFF728BF01 +:10532000121A2244F2E712EB090938BF4A4629460D +:105330003846FFF7EBFEB5E7D8F81030B34208D097 +:105340001444211AC8F81C00A960BDE8F047FFF713 +:10535000F3BEBDE8F08700BF084E0020F84D0020E6 +:1053600000207047FEE70000704700004FF0FF305C +:105370007047000002290CD0032904D001290748F6 +:1053800018BF00207047032A05D8054800EBC2006B +:105390007047044870470020704700BF6C710008D8 +:1053A000382300202071000870B59AB005460846E1 +:1053B00001A9144600F0C2F801A8FCF7F7FB431C52 +:1053C0005B00C5E900340022237003236370C6B27A +:1053D00001AB02341046D1B28E4204F1020401D86E +:1053E0001AB070BD13F8011B04F8021C04F8010C7C +:1053F0000132F0E708B5302383F311880348FFF743 +:1054000023FA002383F3118808BD00BF68500020F1 +:1054100090F8443003F01F02012A07D190F845208C +:105420000B2A03D10023C0E90E3315E003F060031B +:10543000202B08D1B0F848302BB990F84520212A0C +:1054400003D81F2A04D8FFF7E1B9222AEBD0FAE7E4 +:10545000034A82630722C26303640120704700BFCE +:105460002F23002007B5052917D8DFE801F019160A +:1054700003191920302383F31188104A0190012168 +:10548000FFF784FA01980E4A0221FFF77FFA0D48D0 +:10549000FFF7A6F9002383F3118803B05DF804FB3E +:1054A000302383F311880748FFF770F9F2E73023C0 +:1054B00083F311880348FFF787F9EBE7C070000812 +:1054C000E47000086850002038B50C4D0C4C0D49B4 +:1054D0002A4604F10800FFF767FF05F1CA0204F14C +:1054E00010000949FFF760FF05F5CA7204F11800C2 +:1054F0000649BDE83840FFF757BF00BF30550020D0 +:1055000038230020A0700008AA700008B5700008B9 +:1055100070B5044608460D46FCF748FBC6B2204667 +:10552000013403780BB9184670BD32462946FCF7A2 +:1055300029FB0028F3D10120F6E700002DE9F04710 +:1055400005460C46FCF732FB2C49C6B22846FFF74D +:10555000DFFF08B10836F6B229492846FFF7D8FF21 +:1055600008B11036F6B2632E0BD8DFF89080DFF862 +:105570009090244FDFF898A02E7846B92670BDE8A9 +:10558000F08729462046BDE8F04701F0C3BC252E30 +:1055900030D1072241462846FCF7F4FA80B91A4B6D +:1055A000224603F10C0153F8040B42F8040B8B4222 +:1055B000F9D119889B781180937007350F34DBE798 +:1055C000082249462846FCF7DDFA98B90F4BA21C81 +:1055D000197809090232C95D02F8041C13F8011B8D +:1055E00001F00F015345C95D02F8031CF0D11834D6 +:1055F0000835C1E704F8016B0135BDE78C7100087F +:10560000B570000894710008326F0008107AFF1F0F +:105610001C7AFF1FBFF34F8F024AD368DB03FCD411 +:10562000704700BF003C024008B5094B1B7873B9B6 +:10563000FFF7F0FF074B1A69002ABFBF064A5A60FE +:1056400002F188325A601A6822F480621A6008BD3A +:105650008E570020003C02402301674508B50B4BE4 +:105660001B7893B9FFF7D6FF094B1A6942F0004245 +:105670001A611A6842F480521A601A6822F4805241 +:105680001A601A6842F480621A6008BD8E570020C2 +:10569000003C02401728F0B516D80C4C0C49237872 +:1056A0007BB90C4D0E4618234FF0006255F8047B71 +:1056B00046F8042B013B13F0FF033A44F6D10123D3 +:1056C000237051F82000F0BD0020FCE7F0570020C7 +:1056D00090570020A8710008014B53F82000704734 +:1056E000A871000818207047172810B5044601D982 +:1056F000002010BDFFF7CEFF064B53F824301844AE +:10570000C21A0BB90120F4E712680132F0D1043B50 +:10571000F6E700BFA8710008172838B5044628D856 +:105720001549FFF777FFFFF77FFFF323CB600C23CB +:10573000B0FBF3F203FB1205D30143EAC503DBB26E +:1057400043F4007343F002030B610B6943F48033AD +:105750000B61FFF75FFFFFF79DFF084B53F8241025 +:1057600000F046F9FFF77AFF2046BDE83840FFF722 +:10577000BBBF002038BD00BF003C0240A87100083C +:10578000F8B512F00103144642D18218B2F1026F4B +:1057900057D82D4B1B6813F0010352D02B4DFFF748 +:1057A00043FFF323EB60FFF735FF40F20127032CA3 +:1057B00015D824F001046618244C401A40F2011751 +:1057C000B142236900EB010524D123F001032361D9 +:1057D000FFF744FF0120F8BD043C0430E7E78307EE +:1057E000E7D12B6923F440732B612B693B432B6179 +:1057F00051F8046B0660BFF34F8FFFF70BFF036890 +:105800009E42E9D02B6923F001032B61FFF726FFAD +:105810000020E0E723F44073236123693B432361C5 +:105820000B882B80BFF34F8FFFF7F4FE2D8831F8E4 +:10583000023BADB2AB42C3D0236923F00103236125 +:10584000E4E71846C7E700BF00380240003C0240CA +:10585000084908B50B7828B11BB9FFF7E5FE01230D +:105860000B7008BD002BFCD0BDE808400870FFF7A6 +:10587000F5BE00BF8E57002008B54FF440314FF001 +:10588000005000F0B7F8BDE808404FF480314FF009 +:10589000805000F0AFB800000846114601F09EBAF3 +:1058A000012001F09BBA0000084601F0B5BA0000E3 +:1058B00070B582B0FFF792FB0E4E054600F072FF06 +:1058C0003268904237BF0C4A0B49516814682EBFAA +:1058D000D1E90041013151600419034641F1000151 +:1058E000284601913360FFF783FB0199204602B0FF +:1058F00070BD00BFF4570020F857002070B582B08B +:10590000FFF76CFB104E054600F04CFF32689042EA +:1059100037BF0E4A0D49516814682EBFD1E90041C6 +:1059200001315160041941F10001034628460191FB +:105930003360FFF75DFB01994FF47A720023204634 +:10594000FAF756FC02B070BDF4570020F85700205B +:1059500010B50244064BD2B2904200D110BD441C97 +:1059600000B253F8200041F8040BE0B2F4E700BFA6 +:10597000502800400F4B30B51C6F240407D41C6F17 +:1059800044F400741C671C6F44F400441C670A4C08 +:10599000236843F4807323600244084BD2B29042E0 +:1059A00000D130BD441C00B251F8045B43F82050D4 +:1059B000E0B2F4E700380240007000405028004098 +:1059C00007B5012201A90020FFF7C2FF019803B02B +:1059D0005DF804FB13B50446FFF7F2FFA04205D0C3 +:1059E000012201A900200194FFF7C4FF02B010BDFD +:1059F000704700007047000070470000094B5A884C +:105A0000B2F5805F10460BD022F0020341F2010292 +:105A1000934205D041F20703C31A584258417047D8 +:105A200001207047002004E0074B45F255521A60F0 +:105A300002225A6040F6FF729A604CF6CC421A601D +:105A4000024B01221A7070470030004004580020B9 +:105A5000034B1B781BB1034B4AF6AA221A6070470E +:105A60000458002000300040034B1A681AB9034A5A +:105A7000D2F874281A6070470058002000300240A5 +:105A8000024B4FF08072C3F8742870470030024018 +:105A900008B5FFF7E9FF024B1868C0F3407008BD76 +:105AA0000058002008B5FFF7DFFF024B1868C0F36D +:105AB000007008BD0058002070470000FEE700009D +:105AC0000A4B0B480B4A90420BD30B4BDA1C121AB1 +:105AD000C11E22F003028B4238BF00220021FCF7D6 +:105AE0006DB853F8041B40F8041BECE7047400087D +:105AF00008590020085900200859002070B5D0E945 +:105B000015439E6800224FF0FF3504EB421351010C +:105B1000D3F800090028BEBFD3F8000940F0804048 +:105B2000C3F80009D3F8000B0028BEBFD3F8000B60 +:105B300040F08040C3F8000B013263189642C3F86E +:105B40000859C3F8085BE0D24FF00113C4F81C38C1 +:105B500070BD0000890141F02001016103699B06CD +:105B6000FCD41220FFF754BA10B5054C2046FEF7BE +:105B7000EDFE4FF0A0436365024BA36510BD00BF6F +:105B8000085800202C72000870B50378012B0546D8 +:105B900050D12A4B446D98421BD1294B5A6B42F08D +:105BA00080025A635A6D42F080025A655A6D5A69F2 +:105BB00042F080025A615A6922F080025A610E2135 +:105BC00043205B69FEF730FB1E4BE3601E4BC4F8BD +:105BD00000380023C4F8003EC02323606E6D4FF4EC +:105BE0005023A3633369002BFCDA012333610C20BB +:105BF000FFF70EFA3369DB07FCD41220FFF708FA2F +:105C00003369002BFCDA0026A6602846FFF776FFF2 +:105C10006B68C4F81068DB68C4F81468C4F81C68C2 +:105C20004BB90A4BA3614FF0FF336361A36843F0A4 +:105C30000103A36070BD064BF4E700BF08580020C5 +:105C4000003802404014004003002002003C30C0F5 +:105C5000083C30C0F8B5446D054600212046FFF7EA +:105C600079FFA96D00234FF001128F68C4F8343812 +:105C70004FF00066C4F81C284FF0FF3004EB4312CD +:105C800001339F42C2F80069C2F8006BC2F80809EC +:105C9000C2F8080BF2D20B686A6DEB6563621023E1 +:105CA0001361166916F01006FBD11220FFF7B0F948 +:105CB000D4F8003823F4FE63C4F80038A36943F431 +:105CC000402343F01003A3610923C4F81038C4F83B +:105CD00014380A4BEB604FF0C043C4F8103B084B3C +:105CE000C4F8003BC4F81069C4F80039EB6D03F147 +:105CF000100243F48013EA65A362F8BD087200083D +:105D000040800010426D90F84E10D2F8003823F415 +:105D1000FE6343EA0113C2F8003870472DE9F843E7 +:105D200000EB8103456DDA68166806F00306731E02 +:105D3000022B05EB41130C4680460FFA81F94FEA1E +:105D400041104FF00001C3F8101B4FF0010104F1A6 +:105D5000100398BFB60401FA03F391698EBF334E66 +:105D600006F1805606F5004600293AD0578A04F11C +:105D70005801490137436F50D5F81C180B43C5F83B +:105D80001C382B180021C3F8101953690127611E14 +:105D9000A7409BB3138A928B9B08012A88BF534369 +:105DA000D8F85C20981842EA034301F1400205EB61 +:105DB0008202C8F85C00214653602846FFF7CAFEFD +:105DC00008EB8900C3681B8A43EA845348346401A2 +:105DD0001E432E51D5F81C381F43C5F81C78BDE86A +:105DE000F88305EB4917D7F8001B21F40041C7F8E9 +:105DF000001BD5F81C1821EA0303C0E704F13F0398 +:105E000005EB83030A4A5A6028462146FFF7A2FEA3 +:105E100005EB4910D0F8003923F40043C0F80039ED +:105E2000D5F81C3823EA0707D7E700BF0080001029 +:105E300000040002826D1268C265FFF75FBE0000B9 +:105E40005831436D49015B5813F4004004D013F4FA +:105E5000001F0CBF02200120704700004831436D35 +:105E600049015B5813F4004004D013F4001F0CBF29 +:105E7000022001207047000000EB8101CB68196A05 +:105E80000B6813604B6853607047000000EB8103A0 +:105E900030B5DD68AA691368D36019B9402B84BF97 +:105EA000402313606B8A1468426D1C44013CB4FBB0 +:105EB000F3F46343033323F0030302EB411043EA9B +:105EC000C44343F0C043C0F8103B2B6803F0030306 +:105ED000012B09B20ED1D2F8083802EB411013F4AD +:105EE000807FD0F8003B14BF43F0805343F0005351 +:105EF000C0F8003B02EB4112D2F8003B43F00443F0 +:105F0000C2F8003B30BD00002DE9F041244D6E6D1C +:105F100006EB40130446D3F8087BC3F8087B380728 +:105F20000AD5D6F81438190706D505EB840321469F +:105F3000DB6828465B689847FA071FD5D6F81438FF +:105F4000DB071BD505EB8403D968CCB98B69488A7C +:105F50005A68B2FBF0F600FB16228AB91868DA68B4 +:105F600090420DD2121AC3E90024302383F3118822 +:105F70000B482146FFF78AFF84F31188BDE8F081C2 +:105F8000012303FA04F26B8923EA02036B81CB68D5 +:105F9000002BF3D021460248BDE8F041184700BF6E +:105FA0000858002000EB810370B5DD68436D6C6913 +:105FB0002668E6604A0156BB1A444FF40020C2F836 +:105FC00010092A6802F00302012A0AB20ED1D3F89E +:105FD000080803EB421410F4807FD4F8000914BFC2 +:105FE00040F0805040F00050C4F8000903EB42122A +:105FF000D2F8000940F00440C2F80009D3F8340890 +:10600000012202FA01F10143C3F8341870BD19B935 +:10601000402E84BF4020206020682E8A8419013CD5 +:10602000B4FBF6F440EAC44040F000501A44C6E71E +:106030002DE9F8433B4D6E6D06EB40130446D3F853 +:106040000889C3F8088918F0010F4FEA40171AD0E1 +:10605000D6F81038DB0716D505EB8003D9684B69F5 +:106060001868DA68904230D2121A4FF000091A60AC +:10607000C3F80490302383F3118821462846FFF7A4 +:1060800091FF89F3118818F0800F1CD0D6F83438AE +:106090000126A640334216D005EB84036D6DD3F87C +:1060A0000CC0DCF814200134E4B2D2F800E005EBB7 +:1060B00004342F445168714515D3D5F8343823EA98 +:1060C0000606C5F83468BDE8F883012303FA04F234 +:1060D0002B8923EA02032B818B68002BD3D0214626 +:1060E00028469847CFE7BCF81000AEEB0103834287 +:1060F00028BF0346D7F8180980B2B3EB800FE2D867 +:106100009068A0F1040959F8048FC4F80080A0EB4E +:1061100009089844B8F1040FF5D818440B4490606E +:106120005360C7E7085800202DE9F74FA24C656D72 +:106130006E69AB691E4016F480586E6107D0204628 +:10614000FEF76CFC03B0BDE8F04FFDF74FBF002E2B +:1061500012DAD5F8003E98489B071EBFD5F8003EDE +:1061600023F00303C5F8003ED5F8043823F00103FB +:10617000C5F80438FEF77CFC370505D58E48FFF7D7 +:10618000BDFC8D48FEF762FCB0040CD5D5F808388C +:1061900013F0060FEB6823F470530CBF43F4105355 +:1061A00043F4A053EB6031071BD56368DB681BB970 +:1061B000AB6923F00803AB612378052B0CD1D5F82C +:1061C000003E7D489A071EBFD5F8003E23F003032A +:1061D000C5F8003EFEF74CFC6368DB680BB17648FF +:1061E0009847F30274D4B70227D5D4F85490DFF857 +:1061F000C8B100274FF0010A09EB4712D2F8003B63 +:1062000003F44023B3F5802F11D1D2F8003B002BCB +:106210000DDA62890AFA07F322EA0303638104EBC9 +:106220008703DB68DB6813B1394658469847A36D8E +:1062300001379B68FFB29F42DED9F00617D5676D24 +:106240003A6AC2F30A1002F00F0302F4F012B2F538 +:10625000802F00F08580B2F5402F08D104EB830336 +:106260000022DB681B6A07F5805790426AD1300331 +:10627000D5F8184813D5E10302D50020FFF744FEF6 +:10628000A20302D50120FFF73FFE630302D50220DF +:10629000FFF73AFE270302D50320FFF735FE75030B +:1062A0007FF550AFE00702D50020FFF7C1FEA10740 +:1062B00002D50120FFF7BCFE620702D50220FFF7DE +:1062C000B7FE23077FF53EAF0320FFF7B1FE39E7A6 +:1062D000636DDFF8E4A0019300274FF00109A36D7F +:1062E0009B685FFA87FB9B453FF67DAF019B03EB05 +:1062F0004B13D3F8001901F44021B1F5802F1FD1C1 +:10630000D3F8001900291BDAD3F8001941F09041A5 +:10631000C3F80019D3F800190029FBDB5946606D5A +:10632000FFF718FC218909FA0BF321EA0303238103 +:1063300004EB8B03DB689B6813B1594650469847C2 +:106340000137CCE7910708BFD7F80080072A98BF2C +:1063500003F8018B02F1010298BF4FEA182884E785 +:10636000023304EB830207F580575268D2F818C055 +:10637000DCF80820DCE9001CA1EB0C0C00218842B1 +:106380000AD104EB830463689B699A6802449A60AB +:106390005A6802445A606AE711F0030F08BFD7F841 +:1063A00000808C4588BF02F8018B01F1010188BF94 +:1063B0004FEA1828E3E700BF08580020436D03EBBD +:1063C0004111D1F8003B43F40013C1F8003B704782 +:1063D000436D03EB4111D1F8003943F40013C1F8C8 +:1063E00000397047436D03EB4111D1F8003B23F4B2 +:1063F0000013C1F8003B7047436D03EB4111D1F826 +:10640000003923F40013C1F80039704730B5039CFC +:106410000172043304FB0325C0E90653049B0363A4 +:106420000021059BC160C0E90000C0E90422C0E969 +:106430000842C0E90A11436330BD0000416A0022EE +:10644000C0E90411C0E90A22C2606FF00101FEF741 +:106450004FBE0000D0E90432934201D1C2680AB9AC +:10646000181D70470020704703691960C268013227 +:10647000C260C269134482690361934224BF436AC4 +:1064800003610021FEF728BE38B504460D46E368D7 +:106490003BB16269131D1268A3621344E3620020DA +:1064A00007E0237A33B929462046FEF705FE002887 +:1064B000EDDA38BD6FF00100FBE70000C368C26988 +:1064C000013BC3604369134482694361934224BF23 +:1064D000436A436100238362036B03B1184770472B +:1064E00070B53023044683F31188866A3EB9FFF7FE +:1064F000CBFF054618B186F31188284670BDA36A04 +:10650000E26A13F8015BA362934202D32046FFF7CD +:10651000D5FF002383F31188EFE700002DE9F84F42 +:1065200004460E46174698464FF0300989F3118805 +:106530000025AA46D4F828B0BBF1000F09D1414686 +:106540002046FFF7A1FF20B18BF311882846BDE854 +:10655000F88FD4E90A12A7EB050B521A934528BF0E +:106560009346BBF1400F1BD9334601F1400251F86D +:10657000040B43F8040B9142F9D1A36A403340362F +:10658000A3624035D4E90A239A4202D32046FFF79A +:1065900095FF8AF31188BD42D8D289F31188C9E7E3 +:1065A00030465A46FBF7E4FAA36A5B445E44A362B2 +:1065B0005D44E7E710B5029C0172043303FB04213C +:1065C000C0E906130023C0E90A33039B0363049B5D +:1065D000C460C0E90000C0E90422C0E90842436386 +:1065E00010BD0000026AC260426AC0E904220022B3 +:1065F000C0E90A226FF00101FEF77ABDD0E9042359 +:106600009A4201D1C26822B9184650F8043B0B6087 +:10661000704700231846FAE7C368C2690133C360B4 +:106620004369134482694361934224BF436A4361CF +:106630000021FEF751BD000038B504460D46E36861 +:106640003BB123691A1DA262E2691344E362002090 +:1066500007E0237A33B929462046FEF72DFD0028AE +:10666000EDDA38BD6FF00100FBE700000369196047 +:10667000C268013AC260C2691344826903619342ED +:1066800024BF436A036100238362036B03B118478D +:106690007047000070B530230D460446114683F361 +:1066A0001188866A2EB9FFF7C7FF10B186F31188EB +:1066B00070BDA36A1D70A36AE26A01339342A362AC +:1066C00004D3E16920460439FFF7D0FF002080F3AE +:1066D0001188EDE72DE9F84F04460D46904699469E +:1066E0004FF0300A8AF311880026B346A76A4FB9E3 +:1066F00049462046FFF7A0FF20B187F311883046B6 +:10670000BDE8F88FD4E90A073A1AA8EB06079742C2 +:1067100028BF1746402F1BD905F1400355F8042B1D +:1067200040F8042B9D42F9D1A36A4033A36240365E +:10673000D4E90A239A4204D3E16920460439FFF7D9 +:1067400095FF8BF311884645D9D28AF31188CDE79E +:1067500029463A46FBF70CFAA36A3B443D44A36240 +:106760003E44E5E7D0E904239A4217D1C3689BB1C0 +:10677000836A8BB1043B9B1A0ED01360C368013B44 +:10678000C360C3691A44836902619A4224BF436AA1 +:106790000361002383620123184670470023FBE74F +:1067A00000F0D2B84FF08043586A70474FF08043F2 +:1067B000002258631A610222DA6070474FF080436A +:1067C0000022DA60704700004FF080435863704742 +:1067D000FEE7000070B51B4B01630025044686B040 +:1067E000586085620E46FDF7DDFB04F11003C4E935 +:1067F00004334FF0FF33C4E90635C4E90044A56013 +:10680000E562FFF7CFFF2B460246C4E9082304F1F7 +:1068100034010D4A256580232046FEF703FC012341 +:10682000E0600A4A0375009272680192B268CDE98D +:106830000223074B6846CDE90435FEF71BFC06B082 +:1068400070BD00BF60500020387200083D72000823 +:10685000D1670008024AD36A1843D062704700BF6C +:10686000F84D00204B6843608B688360CB68C36041 +:106870000B6943614B6903628B6943620B68036078 +:106880007047000008B5264B26481A6940F2FF11F0 +:106890000A431A611A6922F4FF7222F001021A6196 +:1068A0001A691A6B0A431A631A6D0A431A651E4A5B +:1068B0001B6D1146FFF7D6FF02F11C0100F5806049 +:1068C000FFF7D0FF02F1380100F58060FFF7CAFF43 +:1068D00002F1540100F58060FFF7C4FF02F170017E +:1068E00000F58060FFF7BEFF02F18C0100F58060CB +:1068F000FFF7B8FF02F1A80100F58060FFF7B2FFD3 +:1069000002F1C40100F58060FFF7ACFF02F1E00185 +:1069100000F58060FFF7A6FFBDE8084000F090B8E2 +:1069200000380240000002404472000808B500F040 +:106930000BFAFEF72BFBFFF797F8BDE80840FEF7D0 +:10694000C3BD0000704700000F4B1A6C42F00102FB +:106950001A641A6E42F001021A660C4A1B6E9368A2 +:1069600043F0010393604FF0804353229A624FF04B +:10697000FF32DA6200229A615A63DA605A600122B9 +:106980005A611A60704700BF00380240002004E0DE +:106990004FF0804208B51169D3680B40D9B2C943A2 +:1069A0009B07116107D5302383F31188FEF714FB91 +:1069B000002383F3118808BD1F4B1A696FEAC25286 +:1069C0006FEAD2521A611A69C2F308021A614FF0D3 +:1069D000FF301A695A69586100215A6959615A6928 +:1069E0001A6A62F080521A621A6A02F080521A62BF +:1069F0001A6A5A6A58625A6A59625A6A1A6C42F09A +:106A000080521A641A6E42F080521A661A6E0B4A4D +:106A1000106840F480701060186F00F44070B0F59A +:106A2000007F1EBF4FF4803018671967536823F446 +:106A30000073536000F060B90038024000700040FD +:106A4000344B4FF080521A64334A4FF44041116086 +:106A50001A6842F001021A601A689107FCD59A6818 +:106A600022F003029A602B4B9A6812F00C02FBD1C1 +:106A7000196801F0F90119609A601A6842F48032CD +:106A80001A601A689203FCD55A6F42F001025A67E5 +:106A9000204B5A6F9007FCD5204A5A601A6842F082 +:106AA00080721A601C4A53685904FCD5194B1A6845 +:106AB0009201FCD51A4A9A600322C3F88C20194B24 +:106AC0001A68194B9A42194B21D1194A1168194A6F +:106AD00091421CD140F205121A60144A136803F067 +:106AE0000F03052BFAD10B4B9A6842F002029A6011 +:106AF0009A6802F00C02082AFAD15A6C42F48042D9 +:106B00005A645A6E42F480425A665B6E704740F295 +:106B10000572E1E700380240007000401854400759 +:106B200000948838002004E011640020003C0240FA +:106B300000ED00E041C20F41074A08B5536903F078 +:106B40000103536123B1054A13680BB1506898479C +:106B5000BDE80840FDF74ABA003C014080580020DB +:106B6000074A08B5536903F00203536123B1054A8C +:106B700093680BB1D0689847BDE80840FDF736BA76 +:106B8000003C014080580020074A08B5536903F0D3 +:106B90000403536123B1054A13690BB15069984747 +:106BA000BDE80840FDF722BA003C014080580020B3 +:106BB000074A08B5536903F00803536123B1054A36 +:106BC00093690BB1D0699847BDE80840FDF70EBA4C +:106BD000003C014080580020074A08B5536903F083 +:106BE0001003536123B1054A136A0BB1506A9847E9 +:106BF000BDE80840FDF7FAB9003C0140805800208C +:106C0000164B10B55C6904F478725A61A30604D57A +:106C1000134A936A0BB1D06A9847600604D5104AAC +:106C2000136B0BB1506B9847210604D50C4A936B3C +:106C30000BB1D06B9847E20504D5094A136C0BB130 +:106C4000506C9847A30504D5054A936C0BB1D06CE2 +:106C50009847BDE81040FDF7C9B900BF003C0140AE +:106C600080580020194B10B55C6904F47C425A61CD +:106C7000620504D5164A136D0BB1506D9847230574 +:106C800004D5134A936D0BB1D06D9847E00404D539 +:106C90000F4A136E0BB1506E9847A10404D50C4AED +:106CA000936E0BB1D06E9847620404D5084A136FF7 +:106CB0000BB1506F9847230404D5054A936F0BB16D +:106CC000D06F9847BDE81040FDF790B9003C0140F7 +:106CD0008058002008B50348FDF724FABDE80840B5 +:106CE000FDF784B9884B002008B5FFF751FEBDE8D9 +:106CF0000840FDF77BB90000062108B50846FDF7FE +:106D000093FA06210720FDF78FFA06210820FDF7E8 +:106D10008BFA06210920FDF787FA06210A20FDF7E4 +:106D200083FA06211720FDF77FFA06212820FDF7B8 +:106D30007BFA07211C20FDF777FABDE808400C21FB +:106D40002620FDF771BA000008B5FFF735FE00F008 +:106D50000DF8FDF711FCFDF7F7FDFDF7CFFCFFF790 +:106D6000F1FDBDE80840FFF71BBD00000023054A08 +:106D700019460133102BC2E9001102F10802F8D1C3 +:106D8000704700BF805800200B460146184600F0AF +:106D90002DB8000000F040B8012838BF012010B520 +:106DA0000446204600F030F830B900F007F808B982 +:106DB00000F00CF88047F4E710BD0000024B1868A3 +:106DC000BFF35B8F704700BF0059002008B5062055 +:106DD00000F084F80120FEF7C5FA0000024B0A46D5 +:106DE00001461868FEF758BD5823002010B5054C21 +:106DF00013462CB10A4601460220AFF3008010BDB5 +:106E00002046FCE700000000024B01461868FEF730 +:106E100047BD00BF58230020024B01461868FEF70B +:106E200043BD00BF5823002010B5013902449042F1 +:106E300001D1002005E0037811F8014FA34201D0F1 +:106E4000181B10BD0130F2E72DE9F041A3B1C91ABA +:106E500017780144044603F1FF3C8C42204601D9D7 +:106E6000002009E00578BD4204F10104F5D10CEBE6 +:106E70000405D618A54201D1BDE8F08115F8018DB1 +:106E800016F801EDF045F5D0E7E700001F2938B509 +:106E900004460D4604D9162303604FF0FF3038BD79 +:106EA000426C12B152F821304BB9204600F030F854 +:106EB0002A4601462046BDE8384000F017B8012BAD +:106EC0000AD0591C03D1162303600120E7E70024F0 +:106ED00042F82540284698470020E0E7024B01464B +:106EE0001868FFF7D3BF00BF5823002038B5074DFF +:106EF00000230446084611462B60FEF737FA431C70 +:106F000002D12B6803B1236038BD00BF04590020B3 +:106F1000FEF726BA034611F8012B03F8012B002ACD +:106F2000F9D170476F72672E6172647570696C6F0A +:106F3000742E50697872616365722D706572697024 +:106F40006800000053544D3332463F3F3F005354D6 +:106F50004D3332463430780053544D333246343258 +:106F6000780053544D3332463434365858000000BC +:106F7000012033000010410001105A000310590095 +:106F80000710310000000000446F000813040000E7 +:106F90004E6F000819040000586F0008210400001B +:106FA000626F000840A2E4F1646891060041A3E525 +:106FB000F2656992070000004261642043414E4936 +:106FC0006661636520696E6465782E00800000004C +:106FD00000800000000080000000000000000000B1 +:106FE000F5240008DD2C00083D2C000805250008CC +:106FF000392500083527000809250008192500084B +:107000000D25000815250008112500085D2600083B +:107010001D250008A92F00082D250008312600088D +:1070200000960000000000000000000000000000CA +:107030000000000000000000394500082545000858 +:10704000614500084D4500085945000845450008C0 +:10705000314500081D4500086D450008000000008E +:107060007946000865460008A14600088D460008DC +:107070009946000885460008714600085D460008EC +:10708000AD46000800000000010000000000000004 +:107090006330000090700008504E002060500020C7 +:1070A0004172647550696C6F740025424F415244BF +:1070B000252D424C002553455249414C25000000E6 +:1070C0000200000000000000954800080149000887 +:1070D0004000400000550020105500200200000034 +:1070E0000000000003000000000000004549000807 +:1070F00000000000100000002055002000000000EB +:1071000001000000000000000858002001010200FA +:10711000655400087553000811540008F553000821 +:10712000430000002871000809024300020100C06A +:1071300032090400000102020100052400100105CB +:10714000240100010424020205240600010705822F +:10715000030800FF09040100020A000000070501FE +:1071600002400000070581024000000012000000FC +:107170007471000812011001020000400912415709 +:1071800000020102030100000403090425424F41EB +:1071900052442500303132333435363738394142A4 +:1071A000434445460000000000400000004000004D +:1071B000004000000040000000000100000002004C +:1071C00000000200000002000000020000000200B7 +:1071D000000002000000020000400000004000002B +:1071E000004000000040000000000100000002001C +:1071F0000000020000000200000002000000020087 +:10720000000002000000020000000000894A00089F +:10721000414D0008ED4D0008400040006858002036 +:10722000685800200100000078580020800000000D +:1072300040010000030000006D61696E0069646C2C +:10724000650000000000802A00000000AAAAAAAA87 +:1072500000000024FFFF00000000000000A00A0062 +:107260004400000000000000AAAAAAAA0000000032 +:10727000FFFF0000000000000000000010000040C0 +:1072800000000000AAAAAAAA10000040FFFF000008 +:1072900000000000000000000A681000000000006C +:1072A000AAAAAAAA00541000FFFF000099007007C4 +:1072B000000000000000004000000000AAAAAAAAE6 +:1072C00000000040FFFF0000000000000000000080 +:1072D0000000000000000000AAAAAAAA0000000006 +:1072E000FFFF0000000000000000000000000000A0 +:1072F00000000000AAAAAAAA00000000FFFF0000E8 +:10730000000000000000000000000000000000007D +:107310000A00000000000000030000000000000060 +:10732000000000000000000000000000000000005D +:10733000000000000000000000000000000000004D +:10734000E08EFF7F010000007A05000000000000D1 +:1073500000001F000000000040420F00FE2A010054 +:10736000D2040000FF00000068500020884B00207D +:1073700000960000000008009600000000080000D1 +:1073800004000000887100080000000000000000F8 +:1073900000000000000000000000000000000000ED +:1073A0005C2300200000000000000000000000003E +:1073B00000000000000000000000000000000000CD +:1073C00000000000000000000000000000000000BD +:1073D00000000000000000000000000000000000AD +:1073E000000000000000000000000000000000009D +:1073F000000000000000000000000000000000008D +:047400000000000088 :00000001FF diff --git a/Tools/bootloaders/QioTekAdeptF407_bl.bin b/Tools/bootloaders/QioTekAdeptF407_bl.bin new file mode 100755 index 00000000000000..4574e43539990c Binary files /dev/null and b/Tools/bootloaders/QioTekAdeptF407_bl.bin differ diff --git a/Tools/bootloaders/QioTekAdeptF407_bl.elf b/Tools/bootloaders/QioTekAdeptF407_bl.elf new file mode 100755 index 00000000000000..71df4265d656ed Binary files /dev/null and b/Tools/bootloaders/QioTekAdeptF407_bl.elf differ diff --git a/Tools/bootloaders/QioTekAdeptF407_bl.hex b/Tools/bootloaders/QioTekAdeptF407_bl.hex new file mode 100644 index 00000000000000..3141f862ed2efe --- /dev/null +++ b/Tools/bootloaders/QioTekAdeptF407_bl.hex @@ -0,0 +1,1009 @@ +:020000040800F2 +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E30100083536000899 +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E3010008E1380008093900085D +:10006000313900085939000881390008E3010008D6 +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E3010008A9390008B2 +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B000E3010008E3010008E3010008E301000890 +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E0000D3A0008E3010008E3010008E3010008FD +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008913A0008E301000858 +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E3010008DD2D0008D9 +:10015000E3010008E3010008E30100087D3A00081C +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F02F08EFAE7 +:1002500003F08EF94FF055301F491B4A91423CBFC5 +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE702F06CFA03F0BCF93A +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E702F054BA000600200022002017 +:1002D0000000000808ED00E00000002000060020FB +:1002E000A03E0008002200204C22002050220020C6 +:1002F000F0300020E0010008E0010008E001000803 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F0BAFDFEE701F041 +:1003300023FD00DFFEE7000038B500F061FB02F0AE +:10034000E5F9054602F008FA0446D8B90F4B9D427C +:100350001AD001339D4218BF044641F2883504BFCC +:1003600001240025002002F0DBF90CB100F076F842 +:1003700000F016FD00F0B0FB284600F0B7F800F0E2 +:100380006DF8F9E70025EDE70546EBE7010007B05A +:1003900008B500F06DFBA0F120035842584108BD9C +:1003A00007B541F21203022101A8ADF8043000F0B4 +:1003B0007DFB03B05DF804FB38B5302383F311886F +:1003C000174803680BB101F037FE164A14480023A2 +:1003D0004FF47A7101F026FE002383F31188124C4A +:1003E000236813B12368013B2360636813B163681A +:1003F000013B63600D4D2B7833B963687BB90220F4 +:1004000000F040FC322363602B78032B07D1636834 +:100410002BB9022000F036FC4FF47A73636038BDCC +:1004200050220020B9030008702300206822002019 +:10043000084B187003280CD8DFE800F00805020804 +:10044000022000F00FBC022000F0FCBB024B002297 +:100450005A60704768220020702300201F4B204AFA +:1004600010B51C461968013136D004339342F9D1D6 +:100470006268A24230D31B4B9B6803F1006303F513 +:1004800080439A4228D2002000F040FB0220FFF770 +:10049000CFFF154B1A6C00221A64196E1A66196E7A +:1004A000596C5A64596E5A665A6E1A6942F0005273 +:1004B0001A611A6922F000521A611B6972B64FF074 +:1004C000E0233021C3F8084DD4E9003281F31188CC +:1004D0009D4683F30888104710BD00BF0040000808 +:1004E0002040000800220020003802402DE9F04F93 +:1004F00093B0AA4B00902022FF210AA89D6800F02B +:10050000F9FBA74A1378A3B9A6480121036011702B +:10051000302383F3118803680BB101F08DFDA24AEB +:10052000A04800234FF47A7101F07CFD002383F38F +:100530001188009B13B19D4B009A1A609C4A009C45 +:100540001378032B1EBF00231370984A4FF0000A44 +:1005500018BF5360D3465646D146012000F082FBB7 +:1005600024B1924B1B68002B00F01182002000F098 +:100570007FFA0390039B002BF2DB012000F062FB6B +:10058000039B213B162BE8D801A252F823F000BFB1 +:10059000ED05000815060008A90600085B0500081F +:1005A0005B0500085B050008330700080309000825 +:1005B0001D0800087F080008A7080008CD080008EB +:1005C0005B050008DF0800085B050008510900080A +:1005D0008D0600085B05000895090008F90500086C +:1005E0008D0600085B0500087F0800080220FFF761 +:1005F000CFFE002840F0F581009B0221BAF1000FE8 +:1006000008BF1C4605A841F21233ADF8143000F0C3 +:100610004DFAA2E74FF47A7000F02AFA071EEBDBDE +:100620000220FFF7B5FE0028E6D0013F052F00F2BB +:10063000DA81DFE807F0030A0D101336052305936E +:10064000042105A800F032FA17E054480421F9E724 +:1006500058480421F6E758480421F3E74FF01C08F6 +:10066000404600F055FA08F104080590042105A859 +:1006700000F01CFAB8F12C0FF2D1012000FA07F7B4 +:1006800047EA0B0B5FFA8BFB4FF0000900F07EFB93 +:1006900026B10BF00B030B2B08BF0024FFF780FEE5 +:1006A0005BE746480421CDE7002EA5D00BF00B03F5 +:1006B0000B2BA1D10220FFF76BFE074600289BD031 +:1006C000012000F023FA0220FFF7B2FE00265FFAB5 +:1006D00086F8404600F02AFA044690B100214046D0 +:1006E00000F034FA01360028F1D1BA46044641F24E +:1006F0001213022105A8ADF814303E4600F0D6F9D9 +:100700002BE70120FFF794FE2546244B9B68AB4264 +:1007100007D9284600F0FCF9013040F06781043524 +:10072000F3E7234B00251D70204BBA465D603E4623 +:10073000ACE7002E3FF460AF0BF00B030B2B7FF404 +:100740005BAF0220FFF774FE322000F091F9B0F1A8 +:100750000008FFF651AF18F003077FF44DAF0F4AC2 +:10076000926808EB050393423FF646AFB8F5807FE9 +:100770003FF742AF124B0193B84523DD4FF47A7037 +:1007800000F076F90390039A002AFFF635AF019B3B +:10079000039A03F8012B0137EDE700BF0022002088 +:1007A0006C23002050220020B90300087023002091 +:1007B0006822002004220020082200200C220020B1 +:1007C0006C220020C820FFF7E3FD074600283FF415 +:1007D00013AF1F2D11D8C5F1200242450AAB25F0F9 +:1007E000030028BF424683490192184400F05CFA96 +:1007F000019A8048FF2100F07DFA4FEAA8037D4965 +:100800000193C8F38702284600F07CFA06460028C8 +:100810003FF46DAF019B05EB830537E70220FFF73F +:10082000B7FD00283FF4E8AE00F0BCF900283FF423 +:10083000E3AE0027B846704B9B68BB4218D91F2F08 +:1008400011D80A9B01330ED027F0030312AA1344D8 +:1008500053F8203C05934046042205A900F002FB12 +:1008600004378046E7E7384600F052F90590F2E792 +:10087000CDF81480042105A800F018F906E700233C +:10088000642104A8049300F007F900287FF4B4AEB3 +:100890000220FFF77DFD00283FF4AEAE049800F083 +:1008A00069F90590E6E70023642104A8049300F0A9 +:1008B000F3F800287FF4A0AE0220FFF769FD0028BE +:1008C0003FF49AAE049800F065F9EAE70220FFF7DA +:1008D0005FFD00283FF490AE00F074F9E1E70220DC +:1008E000FFF756FD00283FF487AE05A9142000F05D +:1008F0006FF904210746049004A800F0D7F83946A0 +:10090000B9E7322000F0B4F8071EFFF675AEBB075A +:100910007FF472AE384A926807EB090393423FF6C0 +:100920006BAE0220FFF734FD00283FF465AE27F0E0 +:1009300003074F44B9453FF4A9AE484600F0E8F834 +:100940000421059005A800F0B1F809F10409F1E7C8 +:100950004FF47A70FFF71CFD00283FF44DAE00F015 +:1009600021F9002844D00A9B01330BD008220AA9A0 +:10097000002000F0C7F900283AD02022FF210AA861 +:1009800000F0B8F9FFF70CFD1C4801F08FFA13B026 +:10099000BDE8F08F002E3FF42FAE0BF00B030B2BB6 +:1009A0007FF42AAE0023642105A8059300F074F8B3 +:1009B000074600287FF420AE0220FFF7E9FC8046BE +:1009C00000283FF419AEFFF7EBFC41F2883001F04C +:1009D0006DFA059800F024FA464600F0D7F93C4637 +:1009E000BBE5064652E64FF0000905E6BA467EE64C +:1009F00037467CE66C22002000220020A086010001 +:100A0000704700002DE9F84F4FF47A73DFF85880F3 +:100A1000DFF8589006460D4602FB03F7002498F9CC +:100A200000305A1C5FFA84FA01D0A34212D159F85F +:100A3000240003682A46D3F820B031463B46D84705 +:100A4000854207D1074B012083F800A0BDE8F88F4D +:100A50000124E4E7002CFBD04FF4FA7001F026FAF1 +:100A60000020F3E7B82300201022002014220020E9 +:100A700007B50023024601210DF107008DF807306C +:100A8000FFF7C0FF20B19DF8070003B05DF804FB3D +:100A90004FF0FF30F9E700000A4608B50421FFF7E0 +:100AA000B1FF80F00100C0B2404208BD30B4074B36 +:100AB0000A461978064B53F821402368DD69054B37 +:100AC0000146AC46204630BC604700BFB82300203A +:100AD00014220020A086010070B501F009FD094E26 +:100AE000094D3080002428683388834208D901F0FA +:100AF000F9FC2B6804440133B4F5804F2B60F2D32A +:100B000070BD00BFBA2300207823002001F0B2BDE1 +:100B100000F1006000F580400068704700F100605F +:100B2000920000F5804001F031BD0000054B1A68CD +:100B3000054B1B889B1A834202D9104401F0D2BC9A +:100B40000020704778230020BA23002038B5084DD4 +:100B5000044629B128682044BDE8384001F0E2BCD1 +:100B60002868204401F0C6FC0028F3D038BD00BF3F +:100B70007823002010F003030AD1B0F5047F05D2DA +:100B800000F10050A0F51040D0F80038184670472A +:100B90000023FBE700F10050A0F51040D0F8100A48 +:100BA00070470000064991F8243033B10023086AE9 +:100BB00081F824300822FFF7B1BF0120704700BF41 +:100BC0007C230020014B1868704700BF002004E020 +:100BD00070B5194B1D68194B0138C5F30B04084457 +:100BE0002D0C04221E88A6420BD15C680A46013CEB +:100BF000824213460FD214F9016F4EB102F8016B15 +:100C0000F6E7013A03F10803ECD181420B4602D228 +:100C10002C2203F8012B0A4A05241688AE4204D17F +:100C2000984284BF967803F8016B013C02F10402FC +:100C3000F3D1581A70BD00BF002004E0803B0008CB +:100C40006C3B0008022804D1054B4FF400429A6126 +:100C500070470128FCD1024B4FF48052F7E700BFE8 +:100C600000100240022804D1054B4FF000429A6167 +:100C700070470128FCD1024B4FF08052F7E700BFCC +:100C800000100240022805D1064A536983F400434C +:100C9000536170470128FCD1024A536983F48053A1 +:100CA000F6E700BF0010024010B50023934203D0C6 +:100CB000CC5CC4540133F9E710BD000010B5013815 +:100CC00010F9013F3BB191F900409C4203D11AB1A8 +:100CD0000131013AF4E71AB191F90020981A10BDD8 +:100CE0001046FCE703460246D01A12F9011B002900 +:100CF000FAD1704702440346934202D003F8011B25 +:100D0000FAE770472DE9F8431F4D144695F8242063 +:100D10000746884652BBDFF870909CB395F82430A4 +:100D20002BB92022FF2148462F62FFF7E3FF95F8F9 +:100D30002400C0F10802A24228BF2246D6B2414692 +:100D4000920005EB8000FFF7AFFF95F82430A41B5D +:100D50001E44F6B2082E17449044E4B285F824608D +:100D6000DBD1FFF71FFF0028D7D108E02B6A03EB88 +:100D700082038342CFD0FFF715FF0028CBD100209C +:100D8000BDE8F8830120FBE77C230020024B1A78A2 +:100D9000024B1A70704700BFB823002010220020B9 +:100DA00038B5194C194D204600F0C0FB29462046A5 +:100DB00000F0E8FB2D6816486A6DD2F8043843F05D +:100DC0000203C2F8043801F071F81249284600F015 +:100DD000DFFC6A6D104DD2F8043828680F4923F003 +:100DE0000203C2F80438A0424FF4E1330B6001D093 +:100DF00000F0FCFA6868A04204D0BDE8384007491A +:100E000000F0F4BA38BD00BF98280020883C0008E4 +:100E100040420F00903C000814220020A423002030 +:100E200070B50C4B0C4D1E780C4B55F826209A4291 +:100E300004460DD00A4B002114221846FFF75AFF32 +:100E40000460014655F82600BDE8704000F0CEBAB7 +:100E500070BD00BFB8230020142200209828002075 +:100E6000A423002030B5094D0A4491420DD011F859 +:100E7000013B5840082340F30004013B2C4013F091 +:100E8000FF0384EA5000F6D1EFE730BD2083B8EDD0 +:100E9000026843681143016003B1184770470000BE +:100EA000024AD36843F0C003D36070470014014086 +:100EB00010B5084C084A0021204600F075FA074B8F +:100EC000C4F85C3203F1454303F52943C4F86032AA +:100ED00010BD00BFBC230020A10E0008001401407B +:100EE000234A037C002918BF0A46012B30B5C0F8FD +:100EF00068220CD11F4B984209D11F4B596C41F00D +:100F000020015964596E41F0200159665B6EB2F9B7 +:100F100004501468D0F86032D0F85C12002D03EB56 +:100F20005403B3FBF4F3BEBF23F0070503F007033C +:100F300043EA450394888B60D38843F040030B61F8 +:100F4000138943F001034B6144F4045343F02C0331 +:100F5000CB6004F4A05400230B60B4F5806F0B68E1 +:100F60004B680CBF7F23FF2380F8643230BD00BF85 +:100F7000A03B0008BC230020003802402DE9F041CE +:100F8000D0F85C62F7683368DA0504469DB20DD587 +:100F9000302383F311884FF480610430FFF778FF2A +:100FA0006FF480733360002383F31188302383F35D +:100FB000118804F1040815F02F033AD183F3118846 +:100FC000380615D5290613D5302383F3118804F18B +:100FD000380000F065F900284EDA0821201DFFF7DF +:100FE00057FF4FF67F733B40F360002383F3118874 +:100FF0007A0616D56B0614D5302383F31188D4E90D +:1010000013239A420AD1236C43B127F040073F04CF +:101010001021201D3F0CFFF73BFFF760002383F3F7 +:101020001188D4F86822D36843B3BDE8F041106951 +:1010300018472B0714D015F0080F0CBF00214FF4F0 +:101040008071E80748BF41F02001AA0748BF41F07E +:1010500040016B0748BF41F080014046FFF718FF91 +:10106000AD06736805D594F864122046194000F067 +:10107000CBF93568ADB29EE77060B6E7BDE8F081A8 +:10108000F8B5154682680669AA420B46816938BFE1 +:101090008568761AB54204460BD218462A46FFF7F1 +:1010A00003FEA3692B44A361A3685B1BA3602846CE +:1010B000F8BD0CD918463246FFF7F6FDAF1BE168C4 +:1010C0003A463044FFF7F0FDE3683B44EBE718464F +:1010D0002A46FFF7E9FDE368E5E7000083689342ED +:1010E000F7B51546044638BF8568D0E90460361A5E +:1010F000B5420BD22A46FFF7D7FD63692B446361E3 +:10110000A36828465B1BA36003B0F0BD0DD932462F +:101110000191FFF7C9FD0199E068AF1B3A463144E0 +:10112000FFF7C2FDE3683B44E9E72A46FFF7BCFD51 +:10113000E368E4E710B50A440024C361029B8460BD +:10114000C0E90000C0E90511C1600261036210BD81 +:1011500008B5D0E90532934201D1826882B982682C +:10116000013282605A1C42611970D0E904329A42FD +:1011700024BFC3684361002100F0B4FE002008BD15 +:101180004FF0FF30FBE7000070B5302304460E46F9 +:1011900083F31188A568A5B1A368A269013BA36088 +:1011A000531CA36115782269934224BFE368A361AD +:1011B000E3690BB120469847002383F31188284642 +:1011C00007E03146204600F07DFE0028E2DA85F394 +:1011D000118870BD2DE9F74F04460E461746984614 +:1011E000D0F81C904FF0300A8AF311884FF0000BB2 +:1011F000154665B12A4631462046FFF741FF0346B2 +:1012000060B94146204600F05DFE0028F1D0002381 +:1012100083F31188781B03B0BDE8F08FB9F1000F9C +:1012200003D001902046C847019B8BF31188ED1A2B +:101230001E448AF31188DCE7C0E90511C160C3616F +:101240001144009B8260C0E90000016103627047A5 +:10125000F8B504460D461646302383F31188A76877 +:10126000A7B1A368013BA36063695A1C62611D704A +:10127000D4E904329A4224BFE3686361E3690BB1A5 +:1012800020469847002080F3118807E03146204629 +:1012900000F018FE0028E2DA87F31188F8BD00009C +:1012A000D0E905239A4210B501D182687AB98268E3 +:1012B000013282605A1C82611C7803699A4224BF01 +:1012C000C3688361002100F00DFE204610BD4FF081 +:1012D000FF30FBE72DE9F74F04460E4617469846C8 +:1012E000D0F81C904FF0300A8AF311884FF0000BB1 +:1012F000154665B12A4631462046FFF7EFFE034604 +:1013000060B94146204600F0DDFD0028F1D0002301 +:1013100083F31188781B03B0BDE8F08FB9F1000F9B +:1013200003D001902046C847019B8BF31188ED1A2A +:101330001E448AF31188DCE70268436811430160A8 +:1013400003B11847704700001430FFF743BF000097 +:101350004FF0FF331430FFF73DBF00003830FFF788 +:10136000B9BF00004FF0FF333830FFF7B3BF0000C4 +:101370001430FFF709BF00004FF0FF311430FFF7C2 +:1013800003BF00003830FFF763BF00004FF0FF32AB +:101390003830FFF75DBF0000012914BF6FF0130064 +:1013A00000207047FFF784BD37B515460E4A02602E +:1013B00000224260C0E902220122044602740B4668 +:1013C000009000F15C014FF480721430FFF7B2FE20 +:1013D00000942B464FF4807204F5AE7104F138008E +:1013E000FFF72AFF03B030BDB43B000810B530232F +:1013F000044683F31188FFF773FD02232374002052 +:1014000080F3118810BD000038B5C36904460D464D +:101410001BB904210844FFF78FFF294604F114008B +:10142000FFF796FE002806DA201D4FF40061BDE8A4 +:101430003840FFF781BF38BD02684368114301603F +:1014400003B118477047000013B5446BD4F89434C7 +:101450001A681178042915D1217C022912D1197931 +:10146000128901238B4013420CD101A904F14C00D5 +:1014700001F034FFD4F89444019B2179024620689E +:1014800000F0D0F902B010BD143001F0B7BE00007A +:101490004FF0FF33143001F0B1BE00004C3001F0CA +:1014A00089BF00004FF0FF334C3001F083BF0000D4 +:1014B000143001F085BE00004FF0FF31143001F010 +:1014C0007FBE00004C3001F055BF00004FF0FF32EE +:1014D0004C3001F04FBF00000020704710B5D0F82D +:1014E00094341A6811780429044617D1017C022922 +:1014F00014D15979528901238B4013420ED11430F3 +:1015000001F018FE024648B1D4F894444FF48073B9 +:1015100061792068BDE8104000F072B910BD00008C +:10152000406BFFF7DBBF0000704700007FB5124B38 +:10153000036000234360C0E90233012502260F4BFC +:10154000057404460290019300F184022946009636 +:101550004FF48073143001F0C9FD094B0294CDE9BA +:10156000006304F523724FF48073294604F14C00A4 +:1015700001F090FE04B070BDDC3B000821150008AE +:10158000491400080B68302282F311880A7903EBB2 +:10159000820290614A79093243F822008A7912B1B5 +:1015A00003EB820398610223C0F8941403740020B3 +:1015B00080F311887047000038B5037F044613B1EB +:1015C00090F85430ABB9201D01250221FFF734FFFC +:1015D00004F1140025776FF0010100F08FFC84F80E +:1015E000545004F14C006FF00101BDE8384000F0A8 +:1015F00085BC38BD10B5012104460430FFF71CFF3F +:101600000023237784F8543010BD000038B5044619 +:101610000025143001F082FD04F14C00257701F023 +:1016200051FE201D84F854500121FFF705FF20468C +:10163000BDE83840FFF752BF90F8443003F0600334 +:10164000202B07D190F84520212A4FF0000303D822 +:101650001F2A06D800207047222AFBD1C0E90E338A +:1016600003E0034A82630722C263036401207047D8 +:101670001C22002037B5D0F894341A681178042958 +:1016800004461AD1017C022917D119791289012344 +:101690008B40134211D100F14C05284601F0D2FED7 +:1016A00058B101A9284601F019FED4F89444019BD1 +:1016B00021790246206800F0B5F803B030BD000083 +:1016C000F0B500EB810385B09E6904460D46FEB17E +:1016D000302383F3118804EB8507301D0821FFF7C1 +:1016E000ABFEFB685B691B6806F14C001BB1019007 +:1016F00001F002FE019803A901F0F0FD024648B195 +:10170000039B2946204600F08DF8002383F31188BF +:1017100005B0F0BDFB685A691268002AF5D01B8A33 +:10172000013B1340F1D104F14402EAE7093138B535 +:1017300050F82140DCB1302383F31188D4F894248D +:101740001368527903EB8203DB689B695D6845B1DE +:1017500004216018FFF770FE294604F1140001F01F +:10176000F3FC2046FFF7BAFE002383F3118838BD4F +:101770007047000001F052B8012303700023C0E954 +:101780000133C36183620362C362436203637047D0 +:1017900038B50446302383F311880025C0E903558A +:1017A000C0E90555416001F049F80223237085F333 +:1017B0001188284638BD000070B500EB810305464E +:1017C0005069DA600E46144618B110220021FFF766 +:1017D00091FAA06918B110220021FFF78BFA314667 +:1017E0002846BDE8704001F0F3B80000826802F0BE +:1017F000011282600022C0E90422826101F074B902 +:10180000F0B400EB81044789E4680125A4698D40A8 +:101810003D43458123600023A2606360F0BC01F07A +:101820008FB90000F0B400EB81040789E46801255A +:1018300064698D403D43058123600023A26063609D +:10184000F0BC01F009BA000070B50223002504467F +:101850000370C0E90255C0E90455C564856180F88C +:10186000345001F051F863681B6823B129462046C3 +:10187000BDE87040184770BD0378052B10B50446CD +:101880000AD080F850300523037043681B680BB101 +:10189000042198470023A36010BD000001780529AA +:1018A00006D190F85020436802701B6803B11847B6 +:1018B0007047000070B590F83430044613B100232F +:1018C00080F8343004F14402204601F02FF96368B7 +:1018D0009B68B3B994F8443013F0600535D000210B +:1018E000204601F0CFFB0021204601F0C1FB6368D8 +:1018F0001B6813B1062120469847062384F834302C +:1019000070BD204698470028E4D0B4F84A30E26B16 +:101910009A4288BFE36394F94430E56B002B4FF0A3 +:10192000300380F20381002D00F0F280092284F858 +:10193000342083F311880021D4E90E232046FFF7D9 +:1019400071FF002383F31188DAE794F8452003F050 +:101950007F0343EA022340F20232934200F0C58043 +:1019600021D8B3F5807F48D00DD8012B3FD0022B72 +:1019700000F09380002BB2D104F14C02A26302224A +:10198000E2632364C1E7B3F5817F00F09B80B3F588 +:10199000407FA4D194F84630012BA0D1B4F84C304C +:1019A00043F0020332E0B3F5006F4DD017D8B3F522 +:1019B000A06F31D0A3F5C063012B90D8636894F871 +:1019C00046205E6894F84710B4F848302046B04787 +:1019D000002884D04368A3630368E3631AE0B3F587 +:1019E000106F36D040F6024293427FF478AF5C4BE2 +:1019F000A3630223E3630023C3E794F84630012B7B +:101A00007FF46DAFB4F84C3023F00203C4E90E55F7 +:101A1000A4F84C30256478E7B4F84430B3F5A06FEF +:101A20000ED194F8463084F84E30204600F0C4FFC2 +:101A300063681B6813B10121204698470323237074 +:101A40000023C4E90E339CE704F14F03A363012391 +:101A5000C3E72378042B10D1302383F31188204669 +:101A6000FFF7C4FE85F311880321636884F84F50A3 +:101A700021701B680BB12046984794F84630002B24 +:101A8000DED084F84F300423237063681B68002B7A +:101A9000D6D0022120469847D2E794F848301D0658 +:101AA00003F00F0120460AD501F032F8012804D0D6 +:101AB00002287FF414AF2B4B9AE72B4B98E701F0E9 +:101AC00019F8F3E794F84630002B7FF408AF94F848 +:101AD000483013F00F01B3D01A06204602D501F0AA +:101AE000E5FAADE701F0D8FAAAE794F84630002B02 +:101AF0007FF4F5AE94F8483013F00F01A0D01B0628 +:101B0000204602D501F0BEFA9AE701F0B1FA97E754 +:101B1000142284F8342083F311882B462A46294660 +:101B20002046FFF76DFE85F31188E9E65DB11522C9 +:101B300084F8342083F311880021D4E90E23204651 +:101B4000FFF75EFEFDE60B2284F8342083F3118854 +:101B50002B462A4629462046FFF764FEE3E700BFEE +:101B60000C3C0008043C0008083C000838B590F81C +:101B700034300446002B3ED0063BDAB20F2A34D86C +:101B80000F2B32D8DFE803F0373131082232313100 +:101B90003131313131313737C56BB0F84A309D4280 +:101BA00014D2C3681B8AB5FBF3F203FB12556DB95F +:101BB000302383F311882B462A462946FFF732FE4D +:101BC00085F311880A2384F834300EE0142384F856 +:101BD0003430302383F3118800231A4619462046F7 +:101BE000FFF70EFE002383F3118838BD036C03B1A9 +:101BF00098470023E7E70021204601F043FA00213F +:101C0000204601F035FA63681B6813B106212046AF +:101C100098470623D7E7000010B590F83430142B0E +:101C2000044629D017D8062B05D001D81BB110BD0A +:101C3000093B022BFBD80021204601F023FA0021AA +:101C4000204601F015FA63681B6813B1062120468F +:101C50009847062319E0152BE9D10B2380F834307F +:101C6000302383F3118800231A461946FFF7DAFD63 +:101C7000002383F31188DAE7C3689B695B68002B54 +:101C8000D5D1036C03B19847002384F83430CEE7F4 +:101C900000230375826803691B6899689142FBD22F +:101CA0005A680360426010605860704700230375F3 +:101CB000826803691B6899689142FBD85A6803607F +:101CC000426010605860704708B50846302383F3BF +:101CD00011880B7D032B05D0042B0DD02BB983F37A +:101CE000118808BD8B6900221A604FF0FF338361B1 +:101CF000FFF7CEFF0023F2E7D1E9003213605A600C +:101D0000F3E70000FFF7C4BF054BD96808751868F2 +:101D100002681A60536001220275D860FEF7F2BAB9 +:101D20002826002030B50C4BDD684B1C87B00446DC +:101D30000FD02B46094A684600F074F92046FFF799 +:101D4000E3FF009B13B1684600F076F9A86907B07D +:101D500030BDFFF7D9FFF9E728260020C91C00088D +:101D6000044B1A68DB6890689B68984294BF002017 +:101D70000120704728260020084B10B51C68D86841 +:101D800022681A60536001222275DC60FFF78EFF23 +:101D900001462046BDE81040FEF7B4BA28260020D0 +:101DA000044B1A68DB6892689B689A4201D9FFF776 +:101DB000E3BF70472826002038B5074C074908487C +:101DC000012300252370656001F07AFB0223237054 +:101DD00085F3118838BD00BF90280020143C00080E +:101DE0002826002000F05EB9EFF3118020B9EFF350 +:101DF0000583302282F311887047000010B530B996 +:101E0000EFF30584C4F3080414B180F3118810BD06 +:101E1000FFF7C6FF84F31188F9E70000034A516811 +:101E200053685B1A9842FBD8704700BF001000E06F +:101E30008B60022308618B82084670478368A3F198 +:101E4000840243F8142C026943F8442C426943F895 +:101E5000402C094A43F8242CC26843F8182C02226B +:101E600003F80C2C002203F80B2C044A43F8102C26 +:101E7000A3F12000704700BF1D03000828260020A2 +:101E800008B5FFF7DBFFBDE80840FFF73BBF0000E8 +:101E9000024BDB6898610F20FFF736BF2826002031 +:101EA000302383F31188FFF7F3BF000008B5014624 +:101EB000302383F311880820FFF734FF002383F3D6 +:101EC000118808BD064BDB6839B1426818605A605A +:101ED000136043600420FFF725BF4FF0FF307047C9 +:101EE000282600200368984206D01A6802605060D5 +:101EF00099611846FFF706BF7047000038B50446E1 +:101F00000D462068844200D138BD036823605C60C0 +:101F10008561FFF7F7FEF4E710B503689C68A242FD +:101F20000CD85C688A600B604C60216059609968CD +:101F30008A1A9A604FF0FF33836010BD1B68121B32 +:101F4000ECE700000A2938BF0A2170B504460D46A7 +:101F50000A26601901F0ACFA01F094FA041BA542BC +:101F600003D8751C2E460446F3E70A2E04D9BDE8B3 +:101F70007040012001F0E4BA70BD0000F8B5144BC8 +:101F80000D46D96103F1100141600A2A1969826086 +:101F900038BF0A22016048601861A818144601F091 +:101FA00077FA0A2701F06EFA431BA342064606D3CE +:101FB0007C1C281901F07CFA27463546F2E70A2FE7 +:101FC00004D9BDE8F840012001F0BABAF8BD00BF5D +:101FD00028260020F8B506460D4601F053FA0F4AB0 +:101FE000134653F8107F9F4206D12A4601463046D9 +:101FF000BDE8F840FFF7C2BFD169BB68441A2C198D +:1020000028BF2C46A34202D92946FFF79BFF224650 +:1020100031460348BDE8F840FFF77EBF2826002080 +:102020003826002010B4C0E9032300235DF8044BD8 +:102030004361FFF7CFBF000010B5194C23699842E8 +:102040000DD0D0E90032816813605A609A680A4462 +:102050009A60002303604FF0FF33A36110BD234655 +:10206000026843F8102F53600022026022699A42EE +:1020700003D1BDE8104001F015BA936881680B44A4 +:10208000936001F0FFF92269E1699268441AA24263 +:10209000E4D91144BDE81040091AFFF753BF00BF4F +:1020A000282600202DE9F047DFF8BC8008F1100752 +:1020B0002C4ED8F8105001F0E5F9D8F81C40AA6869 +:1020C000031B9A423ED81444D5E900324FF0000970 +:1020D000C8F81C4013605A60C5F80090D8F810305A +:1020E000B34201D101F0DEF989F31188D5E903315A +:1020F00028469847302383F311886B69002BD8D08A +:1021000001F0C0F96A69A0EB04094A4582460DD284 +:10211000022001F015FA0022D8F81030B34208D19D +:1021200051462846BDE8F047FFF728BF121A22445F +:10213000F2E712EB090938BF4A4629463846FFF74D +:10214000EBFEB5E7D8F81030B34208D01444211A9A +:10215000C8F81C00A960BDE8F047FFF7F3BEBDE872 +:10216000F08700BF38260020282600200020704776 +:10217000FEE70000704700004FF0FF30704700009E +:1021800002290CD0032904D00129074818BF0020D8 +:102190007047032A05D8054800EBC2007047044881 +:1021A00070470020704700BFEC3C00082C22002044 +:1021B000A03C000870B59AB00546084601A914462F +:1021C00000F0C2F801A8FEF78DFD431C5B00C5E9D5 +:1021D00000340022237003236370C6B201AB0234C3 +:1021E0001046D1B28E4204F1020401D81AB070BD7B +:1021F00013F8011B04F8021C04F8010C0132F0E78B +:1022000008B5302383F311880348FFF733FA00231E +:1022100083F3118808BD00BF9828002090F844304F +:1022200003F01F02012A07D190F845200B2A03D1A1 +:102230000023C0E90E3315E003F06003202B08D122 +:10224000B0F848302BB990F84520212A03D81F2A2E +:1022500004D8FFF7F1B9222AEBD0FAE7034A8263E8 +:102260000722C26303640120704700BF23220020BD +:1022700007B5052917D8DFE801F019160319192049 +:10228000302383F31188104A01900121FFF794FA5B +:1022900001980E4A0221FFF78FFA0D48FFF7B6F9B1 +:1022A000002383F3118803B05DF804FB302383F32C +:1022B00011880748FFF780F9F2E7302383F311888C +:1022C0000348FFF797F9EBE7403C0008643C00083F +:1022D0009828002038B50C4D0C4C0D492A4604F1C5 +:1022E0000800FFF767FF05F1CA0204F11000094971 +:1022F000FFF760FF05F5CA7204F118000649BDE852 +:102300003840FFF757BF00BF602D00202C2200206F +:10231000203C00082A3C0008353C000870B5044603 +:1023200008460D46FEF7DEFCC6B2204601340378AF +:102330000BB9184670BD32462946FEF7BFFC00288F +:10234000F3D10120F6E700002DE9F04705460C46E1 +:10235000FEF7C8FC2C49C6B22846FFF7DFFF08B1DC +:102360000836F6B229492846FFF7D8FF08B11036DB +:10237000F6B2632E0BD8DFF89080DFF89090244FF0 +:10238000DFF898A02E7846B92670BDE8F087294678 +:102390002046BDE8F04701F0CBBB252E30D1072207 +:1023A00041462846FEF78AFC80B91A4B224603F1C3 +:1023B0000C0153F8040B42F8040B8B42F9D1198835 +:1023C0009B781180937007350F34DBE7082249466C +:1023D0002846FEF773FC98B90F4BA21C197809091F +:1023E0000232C95D02F8041C13F8011B01F00F0151 +:1023F0005345C95D02F8031CF0D118340835C1E714 +:1024000004F8016B0135BDE70C3D0008353C0008C0 +:10241000243D0008143D0008107AFF1F1C7AFF1F9E +:10242000BFF34F8F024AD368DB03FCD4704700BF71 +:10243000003C024008B5094B1B7873B9FFF7F0FF69 +:10244000074B1A69002ABFBF064A5A6002F1883258 +:102450005A601A6822F480621A6008BDBE2F0020FC +:10246000003C02402301674508B50B4B1B7893B92C +:10247000FFF7D6FF094B1A6942F000421A611A6849 +:1024800042F480521A601A6822F480521A601A6864 +:1024900042F480621A6008BDBE2F0020003C02405A +:1024A0000B28F0B516D80C4C0C4923787BB90C4D91 +:1024B0000E460C234FF0006255F8047B46F8042BBF +:1024C000013B13F0FF033A44F6D10123237051F886 +:1024D0002000F0BD0020FCE7F02F0020C02F0020DE +:1024E000383D0008014B53F820007047383D000884 +:1024F0000C2070470B2810B5044601D9002010BDF0 +:10250000FFF7CEFF064B53F824301844C21A0BB91C +:102510000120F4E712680132F0D1043BF6E700BF76 +:10252000383D00080B2838B5044628D8FFF75CFC76 +:10253000FFF776FFFFF77EFF124AF323D360E30035 +:10254000DBB243F4007343F002031361136943F4F5 +:102550008033136105462046FFF762FFFFF7A0FFB7 +:10256000094B53F8241000F0E9F82846FFF77CFFE8 +:10257000FFF744FC2046BDE83840FFF7BBBF002012 +:1025800038BD00BF003C0240383D000812F0010396 +:102590002DE9F04105460E4614464BD18218B2F1A2 +:1025A000016F61D8314B1B6813F001035CD0304FD1 +:1025B000FFF71AFCFFF73EFFF323FB60FFF730FF46 +:1025C000314640F20128032C18D824F00104284E8B +:1025D0000C446D1A40F20118A142336905EB010762 +:1025E0002AD123F001033361FFF73EFFFFF706FC1A +:1025F0000120BDE8F081043C0435E4E7AB07E4D1F9 +:102600003B6923F440733B613B6943EA08033B6148 +:1026100051F8046B2E60BFF34F8FFFF701FF2B685B +:102620009E42E8D03B6923F001033B61FFF71CFFAA +:10263000FFF7E4FB0020DCE723F4407333613369E8 +:1026400043EA080333610B883B80BFF34F8FFFF7EA +:10265000E7FE3F8831F8023BBFB2BB42BCD03369D2 +:1026600023F001033361E1E71846C2E70038024076 +:10267000003C0240084908B50B7828B11BB9FFF7A8 +:10268000D9FE01230B7008BD002BFCD0BDE808402B +:102690000870FFF7E9BE00BFBE2F002010B502444E +:1026A000064BD2B2904200D110BD441C00B253F888 +:1026B000200041F8040BE0B2F4E700BF50280040CE +:1026C0000F4B30B51C6F240407D41C6F44F4007406 +:1026D0001C671C6F44F400441C670A4C236843F4D5 +:1026E000807323600244084BD2B2904200D130BDC7 +:1026F000441C00B251F8045B43F82050E0B2F4E708 +:1027000000380240007000405028004007B5012208 +:1027100001A90020FFF7C2FF019803B05DF804FB98 +:1027200013B50446FFF7F2FFA04205D0012201A92C +:1027300000200194FFF7C4FF02B010BD70470000F5 +:10274000034B1A681AB9034AD2F874281A60704702 +:10275000F42F00200030024008B5FFF7F1FF024BD4 +:102760001868C0F3407008BDF42F002070470000C7 +:10277000FEE700000A4B0B480B4A90420BD30B4B71 +:10278000DA1C121AC11E22F003028B4238BF00224B +:102790000021FEF7AFBA53F8041B40F8041BECE726 +:1027A000EC3E0008F0300020F0300020F030002037 +:1027B00070B5D0E915439E6800224FF0FF3504EB59 +:1027C00042135101D3F800090028BEBFD3F8000915 +:1027D00040F08040C3F80009D3F8000B0028BEBFCA +:1027E000D3F8000B40F08040C3F8000B01326318AF +:1027F0009642C3F80859C3F8085BE0D24FF00113C2 +:10280000C4F81C3870BD0000890141F0200101614D +:1028100003699B06FCD41220FFF700BB10B5054CE2 +:102820002046FEF7A9FF4FF0A0436365024BA36566 +:1028300010BD00BFF82F00208C3D000870B5037854 +:10284000012B054650D12A4B446D98421BD1294B90 +:102850005A6B42F080025A635A6D42F080025A6508 +:102860005A6D5A6942F080025A615A6922F0800218 +:102870005A610E2143205B6900F022FC1E4BE3608D +:102880001E4BC4F800380023C4F8003EC023236068 +:102890006E6D4FF40413A3633369002BFCDA01233C +:1028A00033610C20FFF7BAFA3369DB07FCD412203E +:1028B000FFF7B4FA3369002BFCDA0026A66028463D +:1028C000FFF776FF6B68C4F81068DB68C4F814681B +:1028D000C4F81C684BB90A4BA3614FF0FF33636126 +:1028E000A36843F00103A36070BD064BF4E700BF8B +:1028F000F82F00200038024040140040030020025E +:10290000003C30C0083C30C0F8B5446D054600219D +:102910002046FFF779FFA96D00234FF001128F6861 +:10292000C4F834384FF00066C4F81C284FF0FF306C +:1029300004EB431201339F42C2F80069C2F8006BF6 +:10294000C2F80809C2F8080BF2D20B686A6DEB6591 +:10295000636210231361166916F01006FBD1122072 +:10296000FFF75CFAD4F8003823F4FE63C4F80038AB +:10297000A36943F4402343F01003A3610923C4F87F +:102980001038C4F814380A4BEB604FF0C043C4F859 +:10299000103B084BC4F8003BC4F81069C4F8003978 +:1029A000EB6D03F1100243F48013EA65A362F8BDF6 +:1029B000683D000840800010426D90F84E10D2F83B +:1029C000003823F4FE6343EA0113C2F8003870476D +:1029D0002DE9F84300EB8103456DDA68166806F0CF +:1029E0000306731E022B05EB41130C4680460FFABB +:1029F00081F94FEA41104FF00001C3F8101B4FF06E +:102A0000010104F1100398BFB60401FA03F39169C0 +:102A10008EBF334E06F1805606F5004600293AD0A7 +:102A2000578A04F15801490137436F50D5F81C18F3 +:102A30000B43C5F81C382B180021C3F81019536933 +:102A40000127611EA7409BB3138A928B9B08012A22 +:102A500088BF5343D8F85C20981842EA034301F139 +:102A6000400205EB8202C8F85C002146536028460C +:102A7000FFF7CAFE08EB8900C3681B8A43EA845348 +:102A8000483464011E432E51D5F81C381F43C5F845 +:102A90001C78BDE8F88305EB4917D7F8001B21F433 +:102AA0000041C7F8001BD5F81C1821EA0303C0E752 +:102AB00004F13F0305EB83030A4A5A602846214686 +:102AC000FFF7A2FE05EB4910D0F8003923F40043CC +:102AD000C0F80039D5F81C3823EA0707D7E700BF4C +:102AE0000080001000040002826D1268C265FFF7CA +:102AF0005FBE00005831436D49015B5813F400403C +:102B000004D013F4001F0CBF022001207047000006 +:102B10004831436D49015B5813F4004004D013F46D +:102B2000001F0CBF022001207047000000EB810154 +:102B3000CB68196A0B6813604B68536070470000DC +:102B400000EB810330B5DD68AA691368D36019B959 +:102B5000402B84BF402313606B8A1468426D1C4471 +:102B6000013CB4FBF3F46343033323F0030302EBB0 +:102B7000411043EAC44343F0C043C0F8103B2B6804 +:102B800003F00303012B09B20ED1D2F8083802EB8F +:102B9000411013F4807FD0F8003B14BF43F0805302 +:102BA00043F00053C0F8003B02EB4112D2F8003B67 +:102BB00043F00443C2F8003B30BD00002DE9F04172 +:102BC000244D6E6D06EB40130446D3F8087BC3F822 +:102BD000087B38070AD5D6F81438190706D505EB4F +:102BE00084032146DB6828465B689847FA071FD5AF +:102BF000D6F81438DB071BD505EB8403D968CCB9AC +:102C00008B69488A5A68B2FBF0F600FB16228AB933 +:102C10001868DA6890420DD2121AC3E900243023F2 +:102C200083F311880B482146FFF78AFF84F311884C +:102C3000BDE8F081012303FA04F26B8923EA020361 +:102C40006B81CB68002BF3D021460248BDE8F041F0 +:102C5000184700BFF82F002000EB810370B5DD6836 +:102C6000436D6C692668E6604A0156BB1A444FF40E +:102C70000020C2F810092A6802F00302012A0AB2F1 +:102C80000ED1D3F8080803EB421410F4807FD4F877 +:102C9000000914BF40F0805040F00050C4F8000913 +:102CA00003EB4212D2F8000940F00440C2F80009D8 +:102CB000D3F83408012202FA01F10143C3F83418B1 +:102CC00070BD19B9402E84BF4020206020682E8A34 +:102CD0008419013CB4FBF6F440EAC44040F00050D3 +:102CE0001A44C6E72DE9F8433B4D6E6D06EB4013E1 +:102CF0000446D3F80889C3F8088918F0010F4FEA91 +:102D000040171AD0D6F81038DB0716D505EB80032C +:102D1000D9684B691868DA68904230D2121A4FF0BD +:102D200000091A60C3F80490302383F31188214608 +:102D30002846FFF791FF89F3118818F0800F1CD007 +:102D4000D6F834380126A640334216D005EB84036A +:102D50006D6DD3F80CC0DCF814200134E4B2D2F865 +:102D600000E005EB04342F445168714515D3D5F8C4 +:102D7000343823EA0606C5F83468BDE8F883012331 +:102D800003FA04F22B8923EA02032B818B68002BC0 +:102D9000D3D0214628469847CFE7BCF81000AEEBC9 +:102DA0000103834228BF0346D7F8180980B2B3EB6A +:102DB000800FE2D89068A0F1040959F8048FC4F894 +:102DC0000080A0EB09089844B8F1040FF5D8184426 +:102DD0000B4490605360C7E7F82F00202DE9F74FB0 +:102DE000A24C656D6E69AB691E4016F480586E6129 +:102DF00007D02046FEF728FD03B0BDE8F04F00F0F5 +:102E00004DBC002E12DAD5F8003E98489B071EBF35 +:102E1000D5F8003E23F00303C5F8003ED5F804388A +:102E200023F00103C5F80438FEF738FD370505D552 +:102E30008E48FFF7BDFC8D48FEF71EFDB0040CD593 +:102E4000D5F8083813F0060FEB6823F470530CBF65 +:102E500043F4105343F4A053EB6031071BD5636870 +:102E6000DB681BB9AB6923F00803AB612378052B42 +:102E70000CD1D5F8003E7D489A071EBFD5F8003E1C +:102E800023F00303C5F8003EFEF708FD6368DB6826 +:102E90000BB176489847F30274D4B70227D5D4F81B +:102EA0005490DFF8C8B100274FF0010A09EB471230 +:102EB000D2F8003B03F44023B3F5802F11D1D2F8B0 +:102EC000003B002B0DDA62890AFA07F322EA0303BA +:102ED000638104EB8703DB68DB6813B1394658462E +:102EE0009847A36D01379B68FFB29F42DED9F00679 +:102EF00017D5676D3A6AC2F30A1002F00F0302F4A5 +:102F0000F012B2F5802F00F08580B2F5402F08D185 +:102F100004EB83030022DB681B6A07F580579042AD +:102F20006AD13003D5F8184813D5E10302D5002043 +:102F3000FFF744FEA20302D50120FFF73FFE630323 +:102F400002D50220FFF73AFE270302D50320FFF740 +:102F500035FE75037FF550AFE00702D50020FFF77F +:102F6000C1FEA10702D50120FFF7BCFE620702D512 +:102F70000220FFF7B7FE23077FF53EAF0320FFF7E0 +:102F8000B1FE39E7636DDFF8E4A0019300274FF04D +:102F90000109A36D9B685FFA87FB9B453FF67DAFF8 +:102FA000019B03EB4B13D3F8001901F44021B1F559 +:102FB000802F1FD1D3F8001900291BDAD3F800198C +:102FC00041F09041C3F80019D3F800190029FBDB48 +:102FD0005946606DFFF718FC218909FA0BF321EAC5 +:102FE0000303238104EB8B03DB689B6813B1594611 +:102FF000504698470137CCE7910708BFD7F80080C3 +:10300000072A98BF03F8018B02F1010298BF4FEA2B +:10301000182884E7023304EB830207F580575268CF +:10302000D2F818C0DCF80820DCE9001CA1EB0C0C7D +:10303000002188420AD104EB830463689B699A6883 +:1030400002449A605A6802445A606AE711F0030F1A +:1030500008BFD7F800808C4588BF02F8018B01F1CA +:10306000010188BF4FEA1828E3E700BFF82F0020CE +:10307000436D03EB4111D1F8003B43F40013C1F859 +:10308000003B7047436D03EB4111D1F8003943F425 +:103090000013C1F800397047436D03EB4111D1F8BB +:1030A000003B23F40013C1F8003B7047436D03EB72 +:1030B0004111D1F8003923F40013C1F800397047E9 +:1030C00000F1604303F561430901C9B283F80013BD +:1030D000012200F01F039A4043099B0003F1604363 +:1030E00003F56143C3F880211A60704730B5039C33 +:1030F0000172043304FB0325C0E90653049B0363F8 +:103100000021059BC160C0E90000C0E90422C0E9BC +:103110000842C0E90A11436330BD0000416A002241 +:10312000C0E90411C0E90A22C2606FF00101FEF794 +:10313000E5BE0000D0E90432934201D1C2680AB969 +:10314000181D70470020704703691960C26801327A +:10315000C260C269134482690361934224BF436A17 +:1031600003610021FEF7BEBE38B504460D46E36894 +:103170003BB16269131D1268A3621344E36200202D +:1031800007E0237A33B929462046FEF79BFE002844 +:10319000EDDA38BD6FF00100FBE70000C368C269DB +:1031A000013BC3604369134482694361934224BF76 +:1031B000436A436100238362036B03B1184770477E +:1031C00070B53023044683F31188866A3EB9FFF751 +:1031D000CBFF054618B186F31188284670BDA36A57 +:1031E000E26A13F8015BA362934202D32046FFF721 +:1031F000D5FF002383F31188EFE700002DE9F84F96 +:1032000004460E46174698464FF0300989F3118858 +:103210000025AA46D4F828B0BBF1000F09D14146D9 +:103220002046FFF7A1FF20B18BF311882846BDE8A7 +:10323000F88FD4E90A12A7EB050B521A934528BF61 +:103240009346BBF1400F1BD9334601F1400251F8C0 +:10325000040B43F8040B9142F9D1A36A4033403682 +:10326000A3624035D4E90A239A4202D32046FFF7ED +:1032700095FF8AF31188BD42D8D289F31188C9E736 +:1032800030465A46FDF710FDA36A5B445E44A362D4 +:103290005D44E7E710B5029C0172043303FB04218F +:1032A000C0E906130023C0E90A33039B0363049BB0 +:1032B000C460C0E90000C0E90422C0E908424363D9 +:1032C00010BD0000026AC260426AC0E90422002206 +:1032D000C0E90A226FF00101FEF710BED0E9042315 +:1032E0009A4201D1C26822B9184650F8043B0B60DB +:1032F000704700231846FAE7C368C2690133C36008 +:103300004369134482694361934224BF436A436122 +:103310000021FEF7E7BD000038B504460D46E3681E +:103320003BB123691A1DA262E2691344E3620020E3 +:1033300007E0237A33B929462046FEF7C3FD00286B +:10334000EDDA38BD6FF00100FBE70000036919609A +:10335000C268013AC260C269134482690361934240 +:1033600024BF436A036100238362036B03B11847E0 +:103370007047000070B530230D460446114683F3B4 +:103380001188866A2EB9FFF7C7FF10B186F311883E +:1033900070BDA36A1D70A36AE26A01339342A362FF +:1033A00004D3E16920460439FFF7D0FF002080F301 +:1033B0001188EDE72DE9F84F04460D4690469946F1 +:1033C0004FF0300A8AF311880026B346A76A4FB936 +:1033D00049462046FFF7A0FF20B187F31188304609 +:1033E000BDE8F88FD4E90A073A1AA8EB0607974216 +:1033F00028BF1746402F1BD905F1400355F8042B71 +:1034000040F8042B9D42F9D1A36A4033A3624036B1 +:10341000D4E90A239A4204D3E16920460439FFF72C +:1034200095FF8BF311884645D9D28AF31188CDE7F1 +:1034300029463A46FDF738FCA36A3B443D44A36263 +:103440003E44E5E7D0E904239A4217D1C3689BB113 +:10345000836A8BB1043B9B1A0ED01360C368013B97 +:10346000C360C3691A44836902619A4224BF436AF4 +:103470000361002383620123184670470023FBE7A2 +:1034800000F036B9014B586A704700BF000C00408D +:10349000034B002258631A610222DA60704700BFB2 +:1034A000000C0040014B0022DA607047000C004025 +:1034B000014B5863704700BF000C0040FEE700005E +:1034C00070B51B4B01630025044686B058608562C9 +:1034D0000E4600F0BFF804F11003C4E904334FF0C6 +:1034E000FF33C4E90635C4E90044A560E562FFF78F +:1034F000C9FF2B460246C4E9082304F134010D4AF2 +:10350000256580232046FEF793FC0123E0600A4AEC +:103510000375009272680192B268CDE90223074BED +:103520006846CDE90435FEF7ABFC06B070BD00BFC0 +:1035300090280020983D00089D3D0008BD340008FB +:10354000024AD36A1843D062704700BF2826002081 +:103550004B6843608B688360CB68C3600B694361D1 +:103560004B6903628B6943620B680360704700001C +:1035700008B5264B26481A6940F2FF110A431A6122 +:103580001A6922F4FF7222F001021A611A691A6B99 +:103590000A431A631A6D0A431A651E4A1B6D1146C7 +:1035A000FFF7D6FF02F11C0100F58060FFF7D0FFA6 +:1035B00002F1380100F58060FFF7CAFF02F1540103 +:1035C00000F58060FFF7C4FF02F1700100F5806034 +:1035D000FFF7BEFF02F18C0100F58060FFF7B8FF36 +:1035E00002F1A80100F58060FFF7B2FF02F1C4010B +:1035F00000F58060FFF7ACFF02F1E00100F58060AC +:10360000FFF7A6FFBDE8084000F0F0B80038024020 +:1036100000000240A43D000808B500F069FAFEF77A +:10362000CBFBFFF78DF8BDE80840FEF753BE000066 +:1036300070470000EFF3098305494A6B22F001024D +:103640004A63683383F30988002383F31188704742 +:1036500000EF00E0302080F3118862B60C4B0D4A79 +:10366000D96821F4E0610904090C0A43DA60D3F84F +:10367000FC20094942F08072C3F8FC200A6842F03D +:1036800001020A602022DA7783F82200704700BF27 +:1036900000ED00E00003FA05001000E010B5302353 +:1036A00083F311880E4B5B6813F4006314D0F1EEC2 +:1036B000103AEFF30984683C4FF08073E361094BE3 +:1036C000DB6B236684F30988FEF74AFB10B1064BD7 +:1036D000A36110BD054BFBE783F31188F9E700BF39 +:1036E00000ED00E000EF00E02F03000832030008C7 +:1036F0000E4B1A6C42F008021A641A6E42F008026D +:103700001A660B4A1B6E936843F008039360094BDB +:1037100053229A624FF0FF32DA6200229A615A63B2 +:10372000DA605A6001225A611A607047003802401C +:10373000002004E0000C0040094A08B51169D36874 +:103740000B40D9B2C9439B07116107D5302383F3DE +:103750001188FEF747FB002383F3118808BD00BFE3 +:10376000000C00401F4B1A696FEAC2526FEAD25236 +:103770001A611A69C2F308021A614FF0FF301A6920 +:103780005A69586100215A6959615A691A6A62F086 +:1037900080521A621A6A02F080521A621A6A5A6ACF +:1037A00058625A6A59625A6A1A6C42F080521A6414 +:1037B0001A6E42F080521A661A6E0B4A106840F474 +:1037C00080701060186F00F44070B0F5007F1EBF6D +:1037D0004FF4803018671967536823F400735360FF +:1037E00000F05EB90038024000700040334B4FF0EB +:1037F00080521A64324A4FF4404111601A6842F014 +:1038000001021A601A689107FCD59A6822F0030237 +:103810009A602A4B9A6812F00C02FBD1196801F0E9 +:10382000F90119609A601A6842F480321A601A68C5 +:103830009203FCD55A6F42F001025A671F4B5A6F30 +:103840009007FCD51F4A5A601A6842F080721A60CD +:103850001B4A53685904FCD5184B1A689201FCD5D1 +:10386000194A9A60194B1A68194B9A42194B21D17F +:10387000194A1168194A91421CD140F205121A6086 +:10388000144A136803F00F03052BFAD10B4B9A6807 +:1038900042F002029A609A6802F00C02082AFAD1F9 +:1038A0005A6C42F480425A645A6E42F480425A661C +:1038B0005B6E704740F20572E1E700BF00380240DE +:1038C000007000400854400700948838002004E04D +:1038D00011640020003C024000ED00E041C20F41B5 +:1038E000074A08B5536903F00103536123B1054A40 +:1038F00013680BB150689847BDE80840FFF7CEBE8B +:10390000003C014070300020074A08B5536903F0BD +:103910000203536123B1054A93680BB1D0689847FD +:10392000BDE80840FFF7BABE003C014070300020FF +:10393000074A08B5536903F00403536123B1054AEC +:1039400013690BB150699847BDE80840FFF7A6BE60 +:10395000003C014070300020074A08B5536903F06D +:103960000803536123B1054A93690BB1D0699847A5 +:10397000BDE80840FFF792BE003C014070300020D7 +:10398000074A08B5536903F01003536123B1054A90 +:10399000136A0BB1506A9847BDE80840FFF77EBE36 +:1039A000003C014070300020164B10B55C6904F4F7 +:1039B00078725A61A30604D5134A936A0BB1D06A90 +:1039C0009847600604D5104A136B0BB1506B9847AB +:1039D000210604D50C4A936B0BB1D06B9847E205D6 +:1039E00004D5094A136C0BB1506C9847A30504D554 +:1039F000054A936C0BB1D06C9847BDE81040FFF7B7 +:103A00004DBE00BF003C014070300020194B10B586 +:103A10005C6904F47C425A61620504D5164A136D50 +:103A20000BB1506D9847230504D5134A936D0BB124 +:103A3000D06D9847E00404D50F4A136E0BB1506E59 +:103A40009847A10404D50C4A936E0BB1D06E9847E9 +:103A5000620404D5084A136F0BB1506F98472304D2 +:103A600004D5054A936F0BB1D06F9847BDE810405D +:103A7000FFF714BE003C01407030002008B5034839 +:103A8000FDF77CFABDE80840FFF708BEBC23002024 +:103A900008B5FFF751FEBDE80840FFF7FFBD000085 +:103AA000062108B50846FFF70BFB06210720FFF7A4 +:103AB00007FB06210820FFF703FB06210920FFF77B +:103AC000FFFA06210A20FFF7FBFA06211720FFF76D +:103AD000F7FA06212820FFF7F3FA07213220FFF733 +:103AE000EFFABDE808400C214720FFF7E9BA0000D3 +:103AF00008B5FFF737FE00F00DF8FDF753FCFDF7B2 +:103B000039FEFDF711FDFFF793FDBDE80840FFF713 +:103B1000B7BC00000023054A19460133102BC2E947 +:103B2000001102F10802F8D1704700BF7030002088 +:103B3000034611F8012B03F8012B002AF9D1704735 +:103B400053544D3332463F3F3F0053544D3332467A +:103B50003430780053544D33324634327800535465 +:103B60004D333246343436585800000001203300BB +:103B70000010410001105A000310590007103100D5 +:103B800000000000403B0008130400004A3B00080E +:103B900019040000543B0008210400005E3B0008AB +:103BA000009600000000000000000000000000007F +:103BB0000000000000000000651300085113000819 +:103BC0008D1300087913000885130008711300088D +:103BD0005D13000849130008991300080000000055 +:103BE000A514000891140008CD140008B9140008A9 +:103BF000C5140008B11400089D14000889140008B9 +:103C0000D9140008000000000100000000000000BE +:103C100063300000103C000880260020902800201F +:103C20004172647550696C6F740025424F41524473 +:103C3000252D424C002553455249414C250000009A +:103C40000200000000000000C11600082D17000847 +:103C500040004000302D0020402D002002000000D8 +:103C600000000000030000000000000071170008C1 +:103C70000000000010000000502D00200000000097 +:103C80000100000000000000F82F002001010200E8 +:103C900071220008812100081D220008012200086D +:103CA00043000000A83C000809024300020100C0D4 +:103CB0003209040000010202010005240010010580 +:103CC00024010001042402020524060001070582E4 +:103CD000030800FF09040100020A000000070501B3 +:103CE00002400000070581024000000012000000B1 +:103CF000F43C000812011001020000400912415773 +:103D000000020102030100000403090425424F419F +:103D10005244250051696F54656B41646570744667 +:103D20003430370030313233343536373839414268 +:103D300043444546000000000040000000400000F1 +:103D400000400000004000000000010000000200F0 +:103D5000000002000000020000000200000002005B +:103D6000000002000000020000000000B51800087A +:103D70006D1B0008191C000840004000583000204E +:103D80005830002001000000683000208000000052 +:103D900040010000030000006D61696E0069646C01 +:103DA000650000000000802A00000000AAAAAAAA5C +:103DB00000000024FFFF00000000000000A00A0037 +:103DC0004000000000000000AAAAAAAA40000000CB +:103DD000FFFF0000000000000000000000A0000441 +:103DE00000000000AAAAAAA200500004FFFF0000E1 +:103DF00000000088000000004041000000000000BA +:103E0000AAAAAAAA40410000FFFF0000000000008B +:103E1000000000000011004100000000AAAAAAAAA8 +:103E200000110000FFFF0000000000000000000083 +:103E30000000000000000000AAAAAAAA00000000DA +:103E4000FFFF000000000000000000000000000074 +:103E500000000000AAAAAAAA00000000FFFF0000BC +:103E60000000000000000000000000000000000052 +:103E70000A00000000000000030000000000000035 +:103E80000000000000000000000000000000000032 +:103E90000000000000000000000000000000000022 +:103EA000290400000000000000C00F000000000016 +:103EB000FF00000098280020BC230020009600008E +:103EC0000000080096000000000800000400000048 +:103ED000083D000800000000000000000000000095 +:0C3EE000000000000000000000000000D6 +:00000001FF diff --git a/Tools/bootloaders/SIYI_N7_bl.bin b/Tools/bootloaders/SIYI_N7_bl.bin new file mode 100755 index 00000000000000..c6b617881bf249 Binary files /dev/null and b/Tools/bootloaders/SIYI_N7_bl.bin differ diff --git a/Tools/bootloaders/Sierra-L431_bl.bin b/Tools/bootloaders/Sierra-L431_bl.bin index de216ad05d443f..64dfe430f880fb 100755 Binary files a/Tools/bootloaders/Sierra-L431_bl.bin and b/Tools/bootloaders/Sierra-L431_bl.bin differ diff --git a/Tools/bootloaders/Sierra-PrecisionPoint_bl.bin b/Tools/bootloaders/Sierra-PrecisionPoint_bl.bin new file mode 100644 index 00000000000000..fe14c80e861bcb Binary files /dev/null and b/Tools/bootloaders/Sierra-PrecisionPoint_bl.bin differ diff --git a/Tools/bootloaders/Sierra-PrecisionPoint_bl.hex b/Tools/bootloaders/Sierra-PrecisionPoint_bl.hex new file mode 100644 index 00000000000000..11826b369e91be --- /dev/null +++ b/Tools/bootloaders/Sierra-PrecisionPoint_bl.hex @@ -0,0 +1,1851 @@ +:020000040800F2 +:1000000000070020F5040008412F0008F92E000821 +:10001000212F0008F92E0008192F0008F704000806 +:10002000F7040008F7040008F7040008353F00084B +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008E56A00080D6B0008C3 +:10006000356B00085D6B0008856B0008F70400081D +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F7040008AD2E000884 +:10009000D92E0008E92E0008F7040008AD6B00080F +:1000A000F7040008F7040008F7040008F704000844 +:1000B000956C0008F7040008F7040008F70400082E +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008816C0008F7040008F704000822 +:1000E000116C0008F7040008F7040008F704000882 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F704000899600008A5 +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E0005D18000800000000000000000000000092 +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600005F062FA06F05AF94FF055301F491B4A60 +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE705F040FAC3 +:1005B00006F082F9144C154DAC4203DA54F8041BD2 +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E705F028BA0007002003 +:1005E000002300200000000808ED00E000010020CA +:1005F00000070020C872000800230020BC23002050 +:10060000C0230020E0580020E0010008E4010008B9 +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002004F00AFD18 +:10064000FEE704F063FC00DFFEE70000F8B501F010 +:1006500017F905F083F9074605F0D2F90546B8BB4E +:10066000204B9F4234D001339F4234D01E4B27F0A1 +:10067000FF029A4232D1F8B200F00EFF2E4642F24B +:10068000107400F00FFF08B10024264601F046FD6B +:1006900020B1032000F07CF80024264635B1134B2E +:1006A0009F4203D005F0A4F900242646002005F05F +:1006B0005FF90EB100F082F801F0AAFA00F05EFFD7 +:1006C00001F05AF9204600F0D5F800F077F8F9E784 +:1006D0002E460024D5E704460126D2E706464FF40D +:1006E0007A74CEE7010007B0000008B0263A09B0DE +:1006F00008B501F00DF9A0F120035842584108BD9A +:1007000007B541F21203022101A8ADF8043001F04F +:100710001DF903B05DF804FB38B5302383F311886D +:10072000174803680BB104F061FD164A1448002312 +:100730004FF47A7104F050FD002383F31188124CBA +:10074000236813B12368013B2360636813B16368B6 +:10075000013B63600D4D2B7833B963687BB9022090 +:1007600001F0D0F9322363602B78032B07D1636843 +:100770002BB9022001F0C6F94FF47A73636038BDDB +:10078000C023002019070008E0240020D8230020FF +:10079000084B187003280CD8DFE800F008050208A1 +:1007A000022001F0A5B9022001F098B9024B002205 +:1007B0005A607047D8230020E024002010B501F0D3 +:1007C000ADFC30B1244B03221A70244B00225A6036 +:1007D00010BD234B234A1C4619680131F8D004335D +:1007E0009342F9D16268204B9A42F1D91F4B9B6822 +:1007F00003F1006303F580339A42E9D205F0CCF8A7 +:1008000005F0DEF8002001F0D1F80220FFF7C0FF6C +:10081000174B1A6C00221A64196E1A66196E596CFD +:100820005A64596E5A665A6E1A6942F000521A6139 +:100830001A6922F000521A611B6972B64FF0E02368 +:100840003021C3F8084DD4E9003281F311889D4668 +:1008500083F308881047BBE7D8230020E02400205A +:100860000000010820000108FFFF0008002300200D +:10087000003802402DE9F04F93B0AC4B009020229D +:10088000FF210AA89D6801F06DF9A94A1378A3B960 +:10089000A848012103601170302383F31188036895 +:1008A0000BB104F0A3FCA44AA24800234FF47A71D0 +:1008B00004F092FC002383F31188009B13B19F4B3B +:1008C000009A1A609E4A009C1378032B1EBF0023D7 +:1008D00013709A4A4FF0000A18BF5360D346564629 +:1008E000D146012001F004F924B1944B1B68002B80 +:1008F00000F01582002001F00BF80390039B002B01 +:1009000001DA00F083FE039B002BEDDB012001F0F8 +:10091000E5F8039B213B162BE3D801A252F823F004 +:100920007D090008A5090008390A0008E308000845 +:10093000E3080008E3080008C30A0008930C000855 +:10094000AD0B00080F0C0008370C00085D0C000808 +:10095000E30800086F0C0008E3080008E10C000839 +:100960001D0A0008E3080008250D00088909000891 +:100970001D0A0008E30800080F0C00080220FFF71A +:10098000B7FE002840F0F581009B0221BAF1000F6C +:1009900008BF1C4605A841F21233ADF8143000F030 +:1009A000D5FF9EE74FF47A7000F0B2FF071EEBDB35 +:1009B0000220FFF79DFE0028E6D0013F052F00F240 +:1009C000DA81DFE807F0030A0D10133605230593DB +:1009D000042105A800F0BAFF17E054480421F9E704 +:1009E00058480421F6E758480421F3E74FF01C0863 +:1009F000404600F0DDFF08F104080590042105A839 +:100A000000F0A4FFB8F12C0FF2D1012000FA07F793 +:100A100047EA0B0B5FFA8BFB4FF0000901F0EEF891 +:100A200026B10BF00B030B2B08BF0024FFF768FE69 +:100A300057E746480421CDE7002EA5D00BF00B0365 +:100A40000B2BA1D10220FFF753FE074600289BD0B5 +:100A5000012000F0ABFF0220FFF79AFE00261FFAEC +:100A600086F8404600F0B2FF044690B100214046AF +:100A700000F0C4FF01360028F1D1BA46044641F225 +:100A80001213022105A8ADF814303E4600F05EFFB7 +:100A900027E70120FFF77CFE2546244B9B68AB42ED +:100AA00007D9284600F084FF013040F06781043503 +:100AB000F3E7234B00251D70204BBA465D603E4690 +:100AC000ACE7002E3FF460AF0BF00B030B2B7FF471 +:100AD0005BAF0220FFF75CFE322000F019FFB0F19F +:100AE0000008FFF651AF18F003077FF44DAF0F4A2F +:100AF000926808EB050393423FF646AFB8F5807F56 +:100B00003FF742AF124B0193B84523DD4FF47A70A3 +:100B100000F0FEFE0390039A002AFFF635AF019B1A +:100B2000039A03F8012B0137EDE700BF00230020F3 +:100B3000DC240020C023002019070008E024002046 +:100B4000D823002004230020082300200C230020A9 +:100B5000DC230020C820FFF7CBFD074600283FF428 +:100B600013AF1F2D11D8C5F1200242450AAB25F065 +:100B7000030028BF424683490192184400F0CCFF8D +:100B8000019A8048FF2100F0EDFF4FEAA8037D495C +:100B90000193C8F38702284600F0ECFF06460028C0 +:100BA0003FF46DAF019B05EB830537E70220FFF7AC +:100BB0009FFD00283FF4E8AE00F040FF00283FF41E +:100BC000E3AE0027B846704B9B68BB4218D91F2F75 +:100BD00011D80A9B01330ED027F0030312AA134445 +:100BE00053F8203C05934046042205A901F04EFA33 +:100BF00004378046E7E7384600F0DAFE0590F2E772 +:100C0000CDF81480042105A800F0A0FE06E700231B +:100C1000642104A8049300F08FFE00287FF4B4AE92 +:100C20000220FFF765FD00283FF4AEAE049800F007 +:100C3000EDFE0590E6E70023642104A8049300F08C +:100C40007BFE00287FF4A0AE0220FFF751FD0028B4 +:100C50003FF49AAE049800F0E9FEEAE70220FFF7BD +:100C600047FD00283FF490AE00F0F8FEE1E70220D7 +:100C7000FFF73EFD00283FF487AE05A9142000F0E1 +:100C8000F3FE04210746049004A800F05FFE3946F5 +:100C9000B9E7322000F03CFE071EFFF675AEBB0739 +:100CA0007FF472AE384A926807EB090393423FF62D +:100CB0006BAE0220FFF71CFD00283FF465AE27F065 +:100CC00003074F44B9453FF4A9AE484600F070FE13 +:100CD0000421059005A800F039FE09F10409F1E7A7 +:100CE0004FF47A70FFF704FD00283FF44DAE00F09A +:100CF000A5FE002844D00A9B01330BD008220AA984 +:100D0000002000F037FF00283AD02022FF210AA857 +:100D100000F028FFFFF7F4FC1C4804F0A1F913B021 +:100D2000BDE8F08F002E3FF42FAE0BF00B030B2B22 +:100D30007FF42AAE0023642105A8059300F0FCFD92 +:100D4000074600287FF420AE0220FFF7D1FC804642 +:100D500000283FF419AEFFF7D3FC41F2883004F0CD +:100D60007FF9059800F092FF464600F047FF3C46A9 +:100D7000B7E5064652E64FF0000905E6BA467EE6BC +:100D800037467CE6DC23002000230020A0860100FB +:100D9000094A136849F2690099B21B0C00FB013340 +:100DA0001360064B186844F2506182B2000C01FBDC +:100DB0000200186080B2704718230020142300201E +:100DC00010B500211022044600F0CCFE034B03CBEB +:100DD000206061601868A06010BD00BF107AFF1F1E +:100DE0002DE9F041ADF5507D0DF13C086EAC40F2BF +:100DF000751207460D4610A80021C8F8001000F033 +:100E0000B1FE4FF4C4720021204600F0ABFE02F0A8 +:100E10009FF8254B4FF47A72B0FBF2F0186093E81C +:100E20000700022384E807000DF5ED702382FFF729 +:100E3000C7FF44F204731D49238406A806F040F856 +:100E4000212384F832310DF2EB2206AB0DF1380C80 +:100E50001E4603CE664510605160334602F108021B +:100E6000F6D13378137041460122204600F030FF5E +:100E700000230393AB7E029305F11903019380B223 +:100E80000123CDE904800093E97E05A3D3E9002383 +:100E9000384602F025FC0DF5507DBDE8F08100BF1D +:100EA0009E6AC421818A46EEE8240020D06E0008A4 +:100EB0002DE9F0412C4C237ADAB080460D465BBB1D +:100EC00027A9284601F014F80746002842D19DF8CA +:100ED0009D60C82E3ED801464FF4A662204600F021 +:100EE00041FE4FF48073C4F8F8314FF40073C4F836 +:100EF0000C334FF44073C4F8203432460DF19E0198 +:100F000004F1090000F008FE26449DF89C30777239 +:100F100023720BB9EB7E23728122002106AC27A835 +:100F200000F020FE0122214627A801F01DF8002331 +:100F30000393AB7E029305F1190380B2019328233A +:100F4000CDE904400093E97E05A3D3E900234046A0 +:100F500002F0C6FB5AB0BDE8F08100BFAFF30080DD +:100F600026417272DF25D7B700460020F0B5254E26 +:100F70004FF48A7505FB0065F1B096F8D83085F816 +:100F8000DC300024D822214685F8E8403AA800F059 +:100F9000E9FD06F1090000F0DDFDD5F8E4308DF83B +:100FA000F000C2B206AF06F109010DF1F100CDE982 +:100FB0003A3400F0B1FD394601223AA801F000F8B8 +:100FC00080B2CDE9047008230127CDE9023706F18C +:100FD000D803019330230093317A0B4807A3D3E958 +:100FE000002302F07DFBA04206DD01F0B1FFC5F851 +:100FF000E000384671B0F0BD2046FBE778F6339F3D +:1010000093CACD8D00460020003500202DE9F04127 +:101010001D4D1E4E1E4F86B0284602F08DFB034626 +:1010200058B30024CDE90344ADF81440027B8DF899 +:10103000142099684068029403AA03C21B68DFF871 +:10104000548043F00043029301F084FF821941F180 +:101050000003009402A9384601F046FAA04205DDDB +:10106000284602F06DFB88F80040D5E798F800307C +:10107000072B05D8013388F8003006B0BDE8F081B1 +:10108000014802F05DFBF8E70035002040420F0008 +:1010900030350020354B002070B50D4614461E46F5 +:1010A00002F07AFA50B9022E10D1012C0ED112A3FF +:1010B000D3E90023C5E90023012007E0282C10D044 +:1010C00005D8012C09D0052C0FD0002070BD302C84 +:1010D000FBD10BA3D3E90023ECE70BA3D3E9002357 +:1010E000E8E70BA3D3E90023E4E70BA3D3E900234C +:1010F000E0E700BFAFF30080401DA12026812A0B4E +:1011000078F6339F93CACD8D9E6AC421818A46EEBC +:1011100026417272DF25D7B7F017304A39059E563F +:1011200038B505460E4C0021013500F067FCA4F8E7 +:101130002C55B4F82C0500F049FC78B1B4F82C0516 +:1011400000F054FC014648B9B4F82C0500F056FCF8 +:10115000B4F82C350133A4F82C35EAE738BD00BFCC +:101160000046002010B50A4B0A4A1A6003F5805366 +:1011700093F860203AB9DC6D2CB1204601F04CF8B0 +:10118000204605F0DDFDBDE81040034801F044B8FD +:1011900030350020906F0008784500202DE9F04F91 +:1011A0008FB000AF05460C4602F0F6F9002849D191 +:1011B000237E022B1BD1E38A012B18D101F0C8FE3C +:1011C0000646FFF7E5FD03464FF4C870DFF8C4821A +:1011D000B3FBF0F206F5167602FB103316FA83F332 +:1011E000C8F80030E37E33B9A34B00221A703C37B5 +:1011F000BD46BDE8F08F07F12401204600F036FE21 +:101200000028F4D107F11400FFF7DAFD97F8264023 +:1012100007F11401224607F1270005F0DBFD002845 +:10122000E2D10F2C08D8944B1C70D8F80030A3F5ED +:101230001673C8F80030DAE797F82410284602F051 +:10124000A3F9D4E7E38A282B2BD010D8012B23D085 +:10125000052BCCD1BFF34F8F8849894BCA6802F464 +:10126000E0621343CB60BFF34F8F00BFFDE7302B2D +:10127000BDD1844EE17E327A9142B8D1607E314652 +:10128000002291F8DC50854200F0A5800132042A4A +:1012900001F58A71F5D1AAE721462846FFF7A0FD9E +:1012A000A5E721462846FFF703FEA0E7B2F8EC5079 +:1012B0007B6005F103094FEA99094FEA8902D11DC4 +:1012C000C908A8EBC1039D46EB460021584600F033 +:1012D00049FC04F1EE012A463144584600F01CFC5A +:1012E0007B6813B9012000F061FB96F8D20000F092 +:1012F0006DFB044630B9307200F0A0FB204600F0D0 +:1013000055FBB1E0D6F8D4203AB996F8D200B6F839 +:101310002C25824201D8FFF703FFD6F8D4202A44B7 +:10132000944208D296F8D200B6F82C2501308242B9 +:1013300001D8FFF7F5FE70685FFA89F2594600F0B0 +:1013400019FC08B9C54679E0726896F8D2002A44BB +:101350007260D6F8D42005EB0209C6F8D49000F0EC +:1013600035FB814509D396F8D220D6F8D400013256 +:10137000001B86F8D220C6F8D400FF2D0FD8002419 +:10138000347200F05BFB204600F010FB00F0C6FE5C +:101390003D4B188108B9FFF711FAC54627E7BB682E +:1013A00096F8D9000AFB0362FB68D2F8E41082F8D1 +:1013B000E83001F58061C2F8E030C2F8E410FFF7D0 +:1013C000D5FDFFF723FE96F8D920013202F0030283 +:1013D00086F8D920B6E74FF48A7A0AFB02F505F1C0 +:1013E000EA013144204600F017FEF86000287FF43F +:1013F000FEAE3544012285F8E82001F0A9FDD5F8BC +:10140000E020D6ED007ADFED216A801A192838BF76 +:10141000192040F6B832904228BF1046B8EE677ADD +:1014200007EE900AF8EEE77A67EEA67ADFED186A23 +:10143000E7EE267AFCEEE77AC6ED007A96F8D93028 +:10144000BB60BA6873680AFB02F4321992F8E810BC +:1014500059B1D2F8E4108B42E8463FF427AF00219F +:1014600082F8E810C2F8E010C5467368064A9B0A85 +:1014700001331381BBE600BFF934002000ED00E02A +:101480000400FA0500460020E8240020CDCCCC3D25 +:101490006666663FFC340020014B1870704700BF41 +:1014A000F424002030B54FF000542B4B22689A42B0 +:1014B00085B007D004F0AEFA044620BB00242046D5 +:1014C00005B030BD254B627D25481A70237D03721F +:1014D0004FF48073C0F8F8314FF40073C0F80C3348 +:1014E00000254FF44073C0F820341E49C0F8E45082 +:1014F000C922093000F010FB2046E022294600F006 +:1015000031FB0124DBE7184A184D136C43F00073DC +:101510001364AA6D164B9A42D0D12B6E013B7E2BE1 +:10152000CCD8144A07CA01AB83E807001846032148 +:1015300000F0C2FD6B6D83424FF00003BED12A6DF7 +:101540008A4201BFAB65054B2A6E1A7003BF0A4B76 +:10155000EA6D1A601C46B2E79AAD44C5F424002037 +:1015600000460020160000200038024000660040BF +:101570005041A0B0586600401023002037B51A4DE6 +:1015800000F0CCFD02236B71184B288119681848B4 +:10159000012201F07BFB00230193164B16490093B7 +:1015A0001648174B4FF4805201F0C6FF154B1978BF +:1015B00011B1124801F0E8FF01F0CAFC0446FFF740 +:1015C000E7FB4FF4C873B0FBF3F202FB130304F51F +:1015D000167010FA83F00C4B186004F011FA08B181 +:1015E0000F232B8103B030BDE824002010230020FE +:1015F0003035002099100008F82400200035002024 +:101600009D110008F4240020FC3400202DE9F04F47 +:101610002DED028B0FF23829D9E90089834C93B064 +:101620000BAE9FED7E8BFFF7F1FC814FDFF828A218 +:1016300000230A93ADF834300B9373604FF0000B26 +:101640005B468DED008B01250DF11D0207A9384683 +:101650008DF81C508DF81DB001F0C8FA9DF81C30B3 +:10166000002B40F0A580204601F096FF064600289A +:1016700045D1704F01F06CFC3B6898423FD301F0BC +:1016800067FC8246FFF784FB4FF4C873B0FBF3F2AC +:1016900002FB13030AF5167010FA83F03860664FE8 +:1016A00097F800B0CBF1100ABBF1000F14BF33461E +:1016B0002B465FFA8AFA0EA88DF82830FFF780FBD8 +:1016C000BAF1060F28BF4FF0060A0EAB03EB0B0171 +:1016D00052460DF1290000F01FFA0AAB03931823BC +:1016E00002930AF10102554BD2B2CDE900530492A4 +:1016F00020464CA3D3E9002301F094FF3E7001F093 +:1017000027FC4F4A4F4D1368C31AB3F57A7F2ED387 +:10171000106001F01FFC02460B46204602F01AF84A +:10172000204601F039FF10B32B7A474E002B14BF2F +:1017300003230223737101F00BFC0EAF4FF47A7395 +:101740000122B0FBF3F039463060304600F066FB12 +:10175000182302933D4B019380B240F25513CDE91B +:101760000370009342464B46204601F05BFF2B7A04 +:1017700093B101F0EDFB002607464FF48A7A95F805 +:10178000D900304400F003000AFB005393F8E8202E +:1017900092B30136042EF2D1C82003F061FC2B7AFB +:1017A000002B7FF43DAF13B0BDEC028BBDE8F08F92 +:1017B000DAF8143083F48053CAF8143059461022F2 +:1017C0000EA800F0CFF90DF11E0308AA0AA93846A9 +:1017D00000F088FF96E803000FAB83E803009DF854 +:1017E00034308DF844300A9B0E930EA9DDE90823AE +:1017F000204602F083F921E7D3F8E02042B12B68BC +:10180000FA2B38BFFA23BA1A0533B2EB430FC0D311 +:10181000FFF7ACFB0028BCD1BEE700BF0000000012 +:1018200000000000401DA12026812A0B0035002069 +:1018300030350020FC340020F9340020F83400203A +:10184000304B002000460020E8240020344B0020CC +:10185000F1C6A7C1D068080F0004024008B50548CA +:1018600000F0DAFFBDE80840034A0449002005F013 +:1018700061BA00BF30350020844B0020651100089C +:10188000704700002DE9F84F4FF47A73DFF8588065 +:10189000DFF8589006460D4602FB03F7002498F93E +:1018A00000305A1C5FFA84FA01D0A34212D159F8D1 +:1018B000240003682A46D3F820B031463B46D84777 +:1018C000854207D1074B012083F800A0BDE8F88FBF +:1018D0000124E4E7002CFBD04FF4FA7003F0C0FBC6 +:1018E0000020F3E7784B00201C2300202023002059 +:1018F00070B504464FF47A76412C254628BF412521 +:1019000006FB05F003F0ACFB641BF5D170BD0000D5 +:1019100007B50023024601210DF107008DF80730BD +:10192000FFF7B0FF20B19DF8070003B05DF804FB9E +:101930004FF0FF30F9E700000A4608B50421FFF731 +:10194000A1FF80F00100C0B2404208BD30B4074B97 +:101950000A461978064B53F821402368DD69054B88 +:101960000146AC46204630BC604700BF784B0020A3 +:1019700020230020A086010070B503F091FE094EDF +:10198000094D3080002428683388834208D903F049 +:1019900081FE2B6804440133B4F5803F2B60F2D301 +:1019A00070BD00BF7A4B0020384B002003F028BFE9 +:1019B00000F1006000F580300068704700F10060C1 +:1019C000920000F5803003F0B1BE0000054B1A68AC +:1019D000054B1B889B1A834202D9104403F05ABE60 +:1019E00000207047384B00207A4B0020024B1B68C8 +:1019F000184403F057BE00BF384B0020024B1B6851 +:101A0000184403F067BE00BF384B002010F00303FA +:101A10000AD1B0F5047F05D200F10050A0F51040C6 +:101A2000D0F80038184670470023FBE700F100505B +:101A3000A0F51040D0F8100A70470000064991F850 +:101A4000243033B10023086A81F824300822FFF7DC +:101A5000B5BF0120704700BF3C4B0020014B186808 +:101A6000704700BF002004E070B5194B1D68194B8A +:101A70000138C5F30B0408442D0C04221E88A6422D +:101A80000BD15C680A46013C824213460FD214F91E +:101A9000016F4EB102F8016BF6E7013A03F108035A +:101AA000ECD181420B4602D22C2203F8012B0A4AC8 +:101AB00005241688AE4204D1984284BF967803F874 +:101AC000016B013C02F10402F3D1581A70BD00BF52 +:101AD000002004E0346F0008206F0008022802BFD5 +:101AE000024B4FF080529A61704700BF00040240E1 +:101AF000022802BF024B4FF480529A61704700BF28 +:101B000000040240022801BF024A536983F4805353 +:101B1000536170470004024010B50023934203D084 +:101B2000CC5CC4540133F9E710BD000010B5013896 +:101B300010F9013F3BB191F900409C4203D11AB129 +:101B40000131013AF4E71AB191F90020981A10BD59 +:101B50001046FCE703460246D01A12F9011B002981 +:101B6000FAD1704702440346934202D003F8011BA6 +:101B7000FAE770472DE9F8431F4D144695F82420E5 +:101B80000746884652BBDFF870909CB395F8243026 +:101B90002BB92022FF2148462F62FFF7E3FF95F87B +:101BA0002400C0F10802A24228BF2246D6B2414614 +:101BB000920005EB8000FFF7AFFF95F82430A41BDF +:101BC0001E44F6B2082E17449044E4B285F824600F +:101BD000DBD1FFF733FF0028D7D108E02B6A03EBF6 +:101BE00082038342CFD0FFF729FF0028CBD100200A +:101BF000BDE8F8830120FBE73C4B0020024B1A783C +:101C0000024B1A70704700BF784B00201C23002045 +:101C100038B5194C194D204602F04AFD2946204698 +:101C200002F072FD2D68EA6ED2F8043843F0020328 +:101C3000C2F804384FF47A70FFF75AFE104928466C +:101C400002F06AFEEA6E0F4DD2F8043828680E4999 +:101C500023F00203C2F80438A0424FF461430B6042 +:101C600001D002F085FC6868A04204D0BDE838408D +:101C7000054902F07DBC38BD68500020CC700008DA +:101C8000D470000820230020644B002070B50C4B5A +:101C90000C4D1E780C4B55F826209A4204460DD068 +:101CA0000A4B002114221846FFF75CFF046001462E +:101CB00055F82600BDE8704002F05ABC70BD00BF68 +:101CC000784B00202023002068500020644B002027 +:101CD0002DE9F0470D46044600219046284640F283 +:101CE0007912FFF73FFF234620220021284601F00A +:101CF000A7FE231D02222021284601F0A1FE631D1C +:101D000003222221284601F09BFEA31D0322252148 +:101D1000284601F095FE04F10803102228212846E8 +:101D200001F08EFE04F1100308223821284601F04C +:101D300087FE04F1110308224021284601F080FEAD +:101D400004F1120308224821284601F079FE04F12B +:101D5000140320225021284601F072FE04F11803DA +:101D600040227021284601F06BFE04F12003082276 +:101D7000B021284601F064FE04F121030822B821B5 +:101D8000284601F05DFE04F12207C0263B4631469D +:101D900008222846083601F053FEB6F5A07F07F169 +:101DA0000107F3D104F1320308223146284601F03D +:101DB00047FE002704F1330A94F832304FEAC7098E +:101DC0009F4209F5A47615D3B8F1000F08D131462A +:101DD00004F599730722284601F032FE09F24F16E6 +:101DE000274694F832213B1B93420CD3F01DC008C8 +:101DF000BDE8F0870AEB070308223146284601F0C8 +:101E00001FFE0137D8E707F2331331460822284670 +:101E100001F016FE08360137E3E7000013B504466B +:101E20000846002101602346C0F8031020220190DB +:101E300001F006FE0198231D0222202101F000FE80 +:101E40000198631D0322222101F0FAFD0198A31DD0 +:101E50000322252101F0F4FD019804F1080310226A +:101E6000282101F0EDFD072002B010BDF7B50023D9 +:101E7000047F00910E4607221946054601F0A4FC96 +:101E8000731C0093012200230721284601F09CFCCB +:101E9000C4B9B31C0093052223460821284601F04B +:101EA00093FC0D243746B278BB1B934211D32B7F92 +:101EB000A88A0734E408BBB9844294BF00200120FB +:101EC00003B0F0BDAB8ADB00083BDB08B37008242D +:101ED000E8E7FB1C0093214600230822284601F076 +:101EE00073FC08340137DEE7201A18BF0120E7E74A +:101EF000F7B50023047F00910E46082219460546D7 +:101F000001F062FC731CC4B90822009311462346F9 +:101F1000284601F059FC1024012372785F1C013B14 +:101F2000934211D32B7FA88A0734E408BBB98442BB +:101F300094BF0020012003B0F0BDAB8ADB00083B5A +:101F4000DB0873700824E7E7F319009321460023A8 +:101F50000822284601F038FC08343B46DDE7201A09 +:101F600018BF0120E7E70000F8B50E460546144605 +:101F7000002181223046FFF7F5FD2B460822002183 +:101F8000304601F05DFD7CB96B1C0722082130460C +:101F900001F056FD0F2401236A785F1C013B934238 +:101FA00004D3E01DC008F8BD0824F4E7EB1921466E +:101FB0000822304601F044FD08343B46ECE70000BF +:101FC000F8B50E46054614460021CE223046FFF7EE +:101FD000C9FD2B4628220021304601F031FD7CB995 +:101FE00005F1080308222821304601F029FD30249C +:101FF0002F462A7A7B1B934204D3E01DC008F8BD0C +:102000002824F5E707F1090321460822304601F0AC +:1020100017FD08340137ECE7F7B5047F00910E4651 +:10202000012310220021054601F0CEFBC4B9B31CE8 +:102030000093092223461021284601F0C5FB1924EC +:1020400037467288BB1B9A4211D82B7FA88A073467 +:10205000E408BBB9844294BF0020012003B0F0BD66 +:10206000AB8ADB00103BDB0873801024E8E73B1DE4 +:102070000093214600230822284601F0A5FB0834DE +:102080000137DEE7201A18BF0120E7E730B5094D18 +:102090000A4491420DD011F8013B5840082340F307 +:1020A0000004013B2C4013F0FF0384EA5000F6D1FA +:1020B000EFE730BD2083B8EDF7B54FF0FF33DFF821 +:1020C00054C0DFF854E000EB81011A4688421CD06E +:1020D00050F8044B019401AF042417F8015B82EA25 +:1020E00005620825DB18164605F1FF355241002E22 +:1020F000BCBF83EA0C0382EA0E0215F0FF05F1D1A2 +:10210000013C14F0FF04E8D1E0E7D843D14303B029 +:10211000F0BD00BF9336EAA9EBE1F042F7B5384ACB +:10212000106851686B4603C36A463649364808232F +:1021300004F060FE0446002833D10A25334A1068B3 +:1021400051686B4603C36A4631492F48082304F09F +:1021500051FE0446002849D00369B3F5E02F45D865 +:10216000B0F8661040F2474291423FD1294A0244FA +:1021700002F15C018B4239D35C3B234900209E1A5B +:10218000FFF784FF3246074604F164010020FFF7A1 +:102190007DFFA3689F4229D1E368984208BF0025CC +:1021A00024E00369B3F5E02F27D8418B40F2474282 +:1021B000914220D1174A024402F110018B4218D3F8 +:1021C000103B114900209D1AFFF760FF2A46064682 +:1021D00004F118010020FFF759FFA3689E4202D1C5 +:1021E000E368984201D00D25A8E70025284603B0F2 +:1021F000F0BD1025A2E70C25A0E70B259EE700BF48 +:10220000546F0008DCFF0600000001085D6F000845 +:1022100090FF06000800FFF710B5037C044613B9D1 +:10222000006804F0CFFD204610BD00000023BFF37E +:102230005B8FC360BFF35B8FBFF35B8F8360BFF3C4 +:102240005B8F7047BFF35B8F0068BFF35B8F704796 +:1022500070B505460C30FFF7F5FF05F1080604469A +:102260003046FFF7EFFFA04206D930466D68FFF712 +:10227000E9FF2544281A70BD3046FFF7E3FF201A16 +:10228000F9E7000070B50546406898B105F108000F +:10229000FFF7D8FF05F10C0604463046FFF7D2FFE2 +:1022A0008442304694BF6D680025FFF7CBFF013CA8 +:1022B0002C44201A70BD000038B50C460546FFF7C7 +:1022C000C7FFA04210D305F10800FFF7BBFF04448D +:1022D0006868B4FBF0F100FB1144BFF35B8F012091 +:1022E000AC60BFF35B8F38BD0020FCE72DE9F04107 +:1022F000144607460D46FFF7C5FF844228BF044633 +:10230000D4B1B84658F80C6B4046FFF79BFF3044F9 +:10231000286040467E68FFF795FF331A9C4203D839 +:102320006C600120BDE8F0816B60A41B3B68AB6072 +:102330002044E8600220F5E72046F3E738B50C4674 +:102340000546FFF79FFFA04210D305F10C00FFF7F1 +:1023500079FF04446868B4FBF0F100FB1144BFF35B +:102360005B8F0120EC60BFF35B8F38BD0020FCE782 +:102370002DE9FF41884669460746FFF7B7FF6C46DF +:1023800006B204EBC6060025B44209D06268206894 +:1023900008EB0501FFF7C0FB636808341D44F3E751 +:1023A00029463846FFF7CAFF284604B0BDE8F08149 +:1023B000F8B505460C300F46FFF744FF05F1080657 +:1023C00004463046FFF73EFFA042304688BF6C68A7 +:1023D000FFF738FF201A386020B130462C68FFF72D +:1023E00031FF2044F8BD000073B5144606460D4683 +:1023F000FFF72EFF844228BF04460190DCB101A9FB +:102400003046FFF7D5FF019B33B93268C5E9023387 +:10241000C5E9002401200CE09C4238BF01942860EB +:10242000019868608442F5D93368AB60241AEC6087 +:10243000022002B070BD2046FBE700002DE9FF41FD +:102440000F466946FFF7D0FF6C4600B204EBC005AB +:102450000026AC4209D0D4F8048054F8081BB819FF +:102460004246FFF759FB4644F3E7304604B0BDE867 +:10247000F081000038B50546FFF7E0FF044601464D +:102480002846FFF719FF204638BD0000302383F3AC +:10249000118862B670470000002383F3118862B68A +:1024A0007047000010B4026854681A4623465DF86D +:1024B000044B1847012070470020704700207047E8 +:1024C00070470000002070470E20704700F58050D4 +:1024D00090F8C800C0F340007047000000F580503D +:1024E00090F9C90070470000F7B50C68BDF820707E +:1024F00014F000541E466FD10B7B082B6CD8FFF7ED +:10250000C5FF4569AB685B010CD4AB681B0108D4FF +:10251000AC6814F080545DD1FFF7BEFF204603B0D5 +:10252000F0BD01240B6804F1180C002BB8BFDB00D0 +:102530004FEA0C1CB4BF43F004035B0545F80C30B4 +:102540000B680FFA84FC13F0804F18BF05EB0C1ECC +:1025500005EB0C1C1EBFDEF8803143F00203CEF801 +:1025600080310B7BCCF8843105EB04158B68C5F802 +:102570008C314B68C5F88831DCF8803143F00103B9 +:10258000CCF8803100EB441541F268031D4403EBA5 +:1025900044130344C5E9002608330D4601F10C0C31 +:1025A00055F804EB43F804EB6545F9D184342D88E4 +:1025B0001D8000EB441407F00303257925F00B057B +:1025C0002B432371FFF768FF0097334600F0E2FCCE +:1025D0000120A4E70224A5E74FF0FF309FE70000A9 +:1025E00013B500F580540191E06DFFF74BFE1F28F5 +:1025F0000AD90199E06D2022FFF7BAFEA0F120036D +:102600005842584102B010BD0020FBE708B500F564 +:102610008050FFF73BFFC06DFFF708FEBDE80840A4 +:10262000FFF73ABF002202608281426082607047F9 +:1026300010B500220023C0E90023002304460381D3 +:102640000C30FFF7EFFF204610BD0000F0B5054647 +:1026500000F580500C4690F8C83013F0040FC3F317 +:10266000800108BF114661F3820304F1840680F8FB +:10267000C83005EB461389B01B79D8072ED57AB33D +:1026800019072DD46846FFF7D3FF05EB441303F574 +:10269000835303F1180703AA1033186859681446C6 +:1026A00003C40833BB422246F7D1186820609B88D8 +:1026B000A380DDE90E23CDE900230123ADF8083026 +:1026C0002B686946DB6B2846984705EB46152B7946 +:1026D0001A075CBF43F008032B7101E0002AF4D114 +:1026E00009B0F0BD2DE9F047074688B007F58054E2 +:1026F00068469A468846FFF7C9FE9146FFF798FF5D +:10270000E06DFFF7A5FD1F2829D9E06D202269465D +:10271000FFF7B0FE202822D103AD444605AB2E467C +:1027200003CE9E4220606160354604F10804F6D174 +:1027300030682060B388A380DDE90023C9E9002365 +:10274000BDF80830AAF80030FFF7A6FE4A46534607 +:102750004146384608B0BDE8F04700F009BCFFF735 +:102760009BFE002008B0BDE8F08700002DE9F84F7F +:102770000023C0E90133254B044640F8183B0F46BF +:10278000FFF750FF04F12800FFF752FF04F148085B +:1027900004F582554646083530462036FFF748FF97 +:1027A000AE42F9D104F580554FF480534FF0000943 +:1027B000C5E91339C5F848800123EE6504F587584B +:1027C00004F58456C5F8549085F8583085F8603083 +:1027D000083608F108084FF0000A4FF0000B46E9F0 +:1027E00008ABA6F11800FFF71DFF203646F8289C1D +:1027F0004645F4D185F8C97017B1054800F0A2FB31 +:10280000044B63612046BDE8F88F00BF906F00085D +:10281000686F00080064004010B5044B1978044646 +:102820004A1C1A70FFF7A2FF204610BD804B002003 +:102830002DE9F047002950D0294B2A4FB7FBF1F57D +:1028400099428CBF0A231123581EB5FBF3FC03FBEE +:102850001C53C4B22BB102280346F5D80020BDE8B2 +:10286000F0870CF1FF36B6F5806FF7D2C4EBC40EDB +:102870000EF103034FEAE309C3F3C703A4EB030814 +:1028800009F1010A4FF47A755FFA88F009FB0555E2 +:102890005AFA88F8B5FBF8F5B5F5617FC1BF0EF1BE +:1028A000FF33C3F3C703E01AC0B25C1C50FA84F4D0 +:1028B0000CFB04F4B7FBF4F4A142CFD1013BDBB233 +:1028C0000F2BCBD80138C0B20728C7D80021107110 +:1028D00016809170D3700120C1E70846BFE700BFA2 +:1028E0003F420F0040787D0170B505460E464FF41B +:1028F0007A746B695B6803F00103B34207D04FF44D +:102900007A7002F0ADFB013CF3D1204670BD01208E +:10291000FCE7000030B54269936913F0700F16D0E0 +:1029200000230B4C936103F1840200EB42121179F6 +:102930004D0709D5890707D5416954F823508D60A3 +:10294000117941F0040111710133032BEBD130BD3A +:102950007C6F000873B51D46436916469A68D20716 +:10296000044609D59A6801219960C2F34002CDE975 +:1029700000650021FFF76AFE63699A68D1050BD5EF +:102980009A684FF480719960C2F34022CDE90065E6 +:1029900001212046FFF75AFE63699A68D2030BD5DE +:1029A0009A684FF480319960C2F34042CDE90065E6 +:1029B00002212046FFF74AFE204602B0BDE87040E3 +:1029C000FFF7A8BFF8B50446466900296CD106F1A7 +:1029D0000C07386880076AD006EB01153868D5F80F +:1029E000B00110F0040FD5F8B0011ABFC00840F0D4 +:1029F0000040400DA061D5F8B0C11CF0020F1CBF13 +:102A000040F08040A061D5F8B40106EB011100F060 +:102A10000F0084F82400D1F8B8012077D1F8B8016C +:102A2000000A6077D1F8B801000CA077D1F8B8019E +:102A3000000EE077D1F8BC0184F82000D1F8BC0189 +:102A4000000A84F82100D1F8BC01000C84F82200AF +:102A5000D1F8BC11090E84F823103821396004F133 +:102A6000340004F1180104F1240551F8046B40F816 +:102A7000046BA942F9D109880180C4E90A232146DF +:102A80000023238651F8283B2046DB6B984704F54A +:102A90008052204692F8C83043F0040382F8C830D0 +:102AA000BDE8F840FFF736BF06F1100791E7F8BD23 +:102AB00010B5044600F04EFA02460B4652EA0301F6 +:102AC00002D0013A63F100030449086820B12146AD +:102AD000BDE81040FFF776BF10BD00BF7C4B002063 +:102AE000F8B500F583511E46FFF7D0FCDFF844C06F +:102AF0000831002404F1840500EB45152B795F07AC +:102B00000ED4DB060CD5D1E900739742B34107D24E +:102B100043695CF824709F602B7943F004032B71A8 +:102B20000134032C01F12001E4D1BDE8F840FFF7A6 +:102B3000B3BC00BF7C6F000808B5FFF7A7FCFFF728 +:102B4000E9FEBDE80840FFF7A7BC0000F8B54369FF +:102B50000546986800F0E050B0F1E05F0F461FD0E6 +:102B6000E8B1FFF793FC05F583541034002606F115 +:102B7000840305EB43131B791A0706D50136032E90 +:102B800004F12004F3D1012007E05B07F6D42146CD +:102B9000384600F039FA0028F0D1FFF77DFCF8BD87 +:102BA0000120FCE700F5805008B5FFF76FFCC06D11 +:102BB000FFF74EFBFFF770FC43090CBF012000201C +:102BC00008BD0000F8B51D46002313700F460646E9 +:102BD0001446FFF7E7FF80F00100387025B1294661 +:102BE0003046FFF7B3FF2070F8BD00002DE9B84173 +:102BF0000C4615461F46804600F0ACF90B4621787E +:102C0000024609B9287850B14046FFF769FFFFF73F +:102C100093FF3B462A462146FFF7D4FF0120BDE83B +:102C2000B881000010B5FFF731FC174B1A6C42F069 +:102C300000721A641A6A42F000721A621A6A00F587 +:102C4000805422F000721A62FFF726FC94F8C83014 +:102C5000DB0718D4B9B103211320FFF717FC01F0EB +:102C6000BBFA0321142001F0B7FA0321152001F06B +:102C7000B3FA94F8C83043F0010384F8C830BDE8D3 +:102C80001040FFF709BC10BD003802402DE9F047A5 +:102C900000F5805588B095F8C930012B0446884668 +:102CA00016467FD8804F57F823200AB947F82300EB +:102CB000D7F800A0C4F80C802674BAF1000F63D0D6 +:102CC00095F8C930012B6FD001212046FFF7AAFFEC +:102CD000FFF7DCFB6269136823F00203136062698B +:102CE000136843F001031360636900275F610121EA +:102CF0002046FFF7D1FBFFF7F7FD002800F0958095 +:102D0000E86DFFF793FA04F58359BA4609F108090B +:102D1000202200216846FEF725FF02A8FFF782FC6B +:102D2000CDF818A06A4609EB07030DF1180E94467A +:102D3000BCE80300F44518605960624603F10803DB +:102D4000F5D1DCF80000186020379CF804201A71D7 +:102D5000602FDDD195F8C8306FF38203002785F826 +:102D6000C8306A4641462046ADF80070ADF80270A2 +:102D70008DF80470FFF75CFD636948BB4FF40042B7 +:102D80001A6008B0BDE8F08741F2D00003F0DAFF26 +:102D9000814610B15146FFF7E9FCC7F80090B9F140 +:102DA000000F8DD10020ECE7386803681B6B984753 +:102DB0000146002888D13868FFF734FF3868036877 +:102DC00032465B684146984700287FF47DAFE9E7CB +:102DD00061221A609DF802309DF803201B06120440 +:102DE00002F4702203F040731343BDF80020C2F3D5 +:102DF000090213439DF804201205022E02F4E0029A +:102E00000CBF4FF000410021134362690B43D361B3 +:102E1000636913225A616269136823F00103136026 +:102E200039462046FFF760FD08B96369A6E795F8C3 +:102E3000C93093BB6169D1F8002242F00102C1F8A8 +:102E400000226169D1F8002222F47C5222F00E02A5 +:102E5000C1F800226169D1F8002242F46062C1F831 +:102E600000226269C2F814326269C2F804326269EF +:102E700041F6FF71C2F80C126269C2F84032626911 +:102E8000C2F8443263690122C3F81C226269D2F895 +:102E9000003223F00103C2F8003295F8C83043F045 +:102EA000020385F8C8306CE77C4B002008B500F0C1 +:102EB00051F850EA0103024602D0421E61F10001BE +:102EC000044B186810B10B46FFF744FDBDE80840FD +:102ED00001F064B87C4B002008B50020FFF7E8FD46 +:102EE000BDE8084001F05AB808B50120FFF7E0FD41 +:102EF000BDE8084001F052B800B59BB0EFF309817E +:102F000068226846FEF708FEEFF30583014B9B6BD2 +:102F1000FEE700BF00ED00E008B5FFF7EDFF0000A1 +:102F200000B59BB0EFF3098168226846FEF7F4FD17 +:102F3000EFF30583014B5B6BFEE700BF00ED00E0A4 +:102F4000FEE700000FB408B5029802F015F8FEE79E +:102F500002F0A2BC02F07ABC13B56C4684E806000D +:102F6000031D94E8030083E80500012002B010BDB2 +:102F700073B58568019155B11B885B0707D4D0E90B +:102F800000369B6B9847019AC1B23046A847012092 +:102F900002B070BDF0B5866889B005460C465EB1DA +:102FA000BDF838305B070AD4D0E900379B6B9847EF +:102FB0002246C1B23846B047012009B0F0BD002218 +:102FC0000023CDE900230023ADF808300A4603AB07 +:102FD00001F10806106851681C4603C40832B24269 +:102FE0002346F7D1106820609288A280FFF7B2FFD5 +:102FF0000423ADF808302B68CDE90001DB6B69468E +:1030000028469847D8E7000030B503680968DD0F07 +:10301000B5EBD17F23F0604421F060424FEAD170DC +:103020000BD0002BB8BFA40C0029B8BF920C94425F +:1030300002D034BF0120002030BD944205D1C1F33D +:103040008070C3F380738342F6D194422CBF00207A +:103050000120F1E72DE9F041456A15B94162BDE86B +:10306000F0814B6823F06047C3F38A464FEAD37E72 +:10307000C3F3807816EA230638BF3E46AC462B469B +:103080005A68BEEBD27F22F060440AD0002A18DAD8 +:10309000A40CB44217D19D420FD10D60DEE7134658 +:1030A000EEE7A74207D102F08044C2F380724245A6 +:1030B0000BD054B1EFE708D2EDE7CCF800100B606D +:1030C000CDE7B44201D0B442E5D81A689C46002A44 +:1030D000E5D11960C3E700002DE9F047089D01F034 +:1030E00007044FEAD508224405F0070500EBD1009C +:1030F0004FF47F49944201D1BDE8F08704F00707FF +:1031000005F0070A57453E4638BF5646C6F1080641 +:10311000111B8E4228BF0E46E10808EBD50E415C1C +:1031200013F80EC0B94029FA06F721FA0AF1FFB2E6 +:103130008CEA010147FA0AF739408CEA010C03F8DE +:103140000EC034443544D5E780EA0120082341F21B +:10315000210201B24000002980B203F1FF33B8BF61 +:10316000504013F0FF03F4D17047000038B50C460F +:103170008D18A54200D138BD14F8011BFFF7E4FFFC +:10318000F7E7000042684AB11368436043898189C8 +:1031900001339BB29942438138BF83811046704707 +:1031A00070B588B0202204460D4668460021FEF71F +:1031B000D9FC20460495FFF7E5FF024658B16B465F +:1031C000054608AE1C4603CCB4422860696023461D +:1031D00005F10805F6D1104608B070BD082817D9CA +:1031E00009280CD00A280CD00B280CD00C280CD0A5 +:1031F0000D280CD00E2814BF4020302070470C2022 +:103200007047102070471420704718207047202006 +:1032100070470000082817D90C280CD910280CD9A1 +:1032200014280CD918280CD920280CD930288CBF88 +:103230000F200E207047092070470A2070470B208E +:1032400070470C2070470D20704700002DE9F843AF +:10325000078C072F04461ED9D0E9029800254FF6A7 +:10326000FF73C5F12006A5F1200029FA05F108FA3F +:1032700006F628FA00F031430143C9B21846FFF7B9 +:1032800063FF0835402D0346EBD1E1693A46BDE8BE +:10329000F843FFF76BBF4FF6FF70BDE8F8830000FF +:1032A00010B54B6823B9CA8A63F30902CA8210BDFC +:1032B00004691A681C600361C38A013BC3824A60C7 +:1032C000EFE700002DE9F84F1D46CB8A0F46C3F308 +:1032D00009010529814692460B4630D00020AAB24A +:1032E00007F11A049EB2042E1FFA80F80FD89045F9 +:1032F00003F1010306D3FB8A0A4462F30903FB824C +:1033000001201AE01AF80060E6540130EAE790451F +:10331000F1D2A1F1050B1C237C68BBFBF3F203FB8C +:1033200012BB1FFA8BF6002C45D14846FFF72AFF47 +:10333000044638B978606FF00200BDE8F88F4FF0AE +:103340000008E6E7002606607860ADB24FF0000B9B +:10335000454510D90AEB0803221D13F8011B9155AE +:10336000B1B208F101081B291FFA88F82BD0454596 +:1033700006F10106F1D8FB8AC3F30902154465F38F +:103380000903BCE7013292B21C462368002BF9D135 +:103390006B1F0B441C21B3FBF1F301339BB29A4228 +:1033A000D3D2BBF1000FD0D14846FFF7EBFE20B9D6 +:1033B000C4F800B0BFE70122E7E7C0F800B05E46FE +:1033C00020600446C1E74545D5D94846FFF7DAFEF7 +:1033D00008B92060AFE7C0F800B0002620600446BE +:1033E000B6E700002DE9F04F2DED028B1C4683B0AF +:1033F0005B69019207468846002B00F09A80238C77 +:103400002BB1E269002A00F09480072B35D807F130 +:103410000C00FFF7B7FE054638B96FF002052846E5 +:1034200003B0BDEC028BBDE8F08F14220021FEF743 +:1034300099FB228CE16905F10800FEF76DFB208CF9 +:10344000013080B2FFF7E6FEFFF7C8FE013880B218 +:103450002084013028746369228C1B782A4403F08D +:103460001F0363F03F0348F0004113723846696060 +:103470002946FFF7EFFD0125D1E700F10C034FF0DE +:10348000000908EE103A4FF0800A4E464D4618EEFD +:10349000100AFFF777FE83460028BED014220021D1 +:1034A000FEF760FB002E3AD1019BABF808300222F8 +:1034B0000BF1080E1FFA82FC0CF10100BCF1060FA3 +:1034C000218C80B201D88E422BD3FFF7A3FEFFF7E9 +:1034D00085FE62691278013802F01F028E4208BF31 +:1034E0004FF0400A42EA49121BFA80F14AEA020A06 +:1034F000013048F0004281F808A08BF81000CBF8AA +:10350000042059463846FFF7A5FD238C0135B34208 +:103510002DB289F001094FF0000AB8D17FE70022EF +:10352000C6E7E169895D0EF802100136B6B20132D4 +:10353000C0E76FF0010572E7F8B515460E46302278 +:10354000002104461F46FEF70DFB069B6360B5F5A0 +:10355000001F079BA76034BF6A094FF6FF72A36282 +:1035600097B2E66104F1100000239A4206D80023C6 +:103570000360A782E3822383E360F8BD0660013322 +:1035800030462036F1E7000003781BB94BB2002B20 +:10359000C8BF01707047000000787047F8B50C464E +:1035A000C969074611B9238C002B37D1257E1F2D01 +:1035B00034D8387828BB228C072A2CD8268A36F0B3 +:1035C00003032BD14FF6FF70FFF7D0FD20F0010071 +:1035D0003102400441EA0561400C41EA40254FF6C2 +:1035E000FF72234629463846FFF7FCFE002807DD18 +:1035F000626913780133DBB21F2B88BF002313707D +:10360000F8BD218A2D0645EA012505432046FFF72E +:103610001DFE0246E5E76FF00300F1E76FF00100E1 +:10362000EEE7000070B58AB0044616460021282255 +:1036300068461D46FEF796FABDF83830ADF81030F2 +:103640000F9B05939DF840308DF81830119B079320 +:103650006946BDF84830ADF820302046CDE9026516 +:10366000FFF79CFF0AB070BD2DE9F041D369054614 +:103670000C4616460BB9138C5BBB377E1F2F28D820 +:1036800095F80080B8F1000F26D03046FFF7DEFD38 +:103690003378210241EAC33141EA0801338A41EA21 +:1036A000076141EA03410246334641F08001284662 +:1036B000FFF798FE00280ADD3378012B07D17269E5 +:1036C00013780133DBB21F2B88BF00231370BDE8D2 +:1036D000F0816FF00100FAE76FF00300F7E70000F8 +:1036E000F0B58BB004460D461746002128226846E7 +:1036F0001E46FEF737FA9DF84C305A1E534253418E +:103700008DF800309DF84030ADF81030119B0593D6 +:103710009DF848308DF81830149B07936A46BDF821 +:103720005430ADF8203029462046CDE90276FFF727 +:103730009BFF0BB0F0BD0000406A00B10430704741 +:10374000436A1A68426202691A600361C38A013BD4 +:10375000C38270472DE9F041D0F82080194E1446FD +:103760001D464146002709B9BDE8F081D1E9022391 +:10377000A21A65EB0303964277EB03031ED2036A9A +:103780008B420DD1FFF78CFD036A1B68036203694E +:103790000B60C38A0161016A013BC3828846E2E78C +:1037A000FFF77EFD0B68C8F8003003690B60C38A21 +:1037B0000161013BC382D8F80010D4E7884609684C +:1037C000D1E700BF80841E002DE9F04F8BB00D467D +:1037D000DDF8509014469B468046002800F0198181 +:1037E000B9F1000F00F01581531E3F2B00F211813B +:1037F000012A03D1BBF1000F40F00B810023CDE97A +:103800000833B8F81430B5EBC30F4FEAC30703D33E +:1038100000200BB0BDE8F08F2B199F42D8F80C3078 +:103820003ABF7F1BFFB227461BB9D8F81030002BD8 +:103830007AD0272D4ED8C5F12806B7424FF00003A5 +:103840002CBFF6B23E4600932946D8F8080008ABD4 +:103850003246FFF741FCA7EB060A35445FFA8AFAC5 +:10386000B8F8143003F10053053BDB000493D8F89B +:103870000C3003932821039B13B1BAF1000F2CD114 +:10388000D8F8100040B1BAF1000F05D0009608AB8F +:103890005246691AFFF720FC38B2002FB8D06607ED +:1038A0000AD00AAB03EBD401624211F8083C02F0E3 +:1038B0000702134101F8083C082C3CD9102C40F2B7 +:1038C000B580202C40F2B780BBF1000F00F09C8047 +:1038D000082334E0BA460026C2E7049BE02B28BF49 +:1038E000E02306930B44AB42059314D95A1B03986B +:1038F0000096924534BF5246D2B2691A08AB0430E2 +:103900000792FFF7E9FB079A1644AAEB020A15444F +:10391000F6B25FFA8AFA049B069A05999B1A0493F9 +:10392000039B1B680393A6E70093D8F8080008AB35 +:103930003A462946AEE7BBF1000F13D00123B4EBA2 +:10394000C30F6CD0082C12D89DF82030621E23FAC9 +:1039500002F2D50706D54FF0FF3202FA04F42343F2 +:103960008DF820309DF8203089F8003051E7102C78 +:1039700012D8BDF82030621E23FA02F2D10706D514 +:103980004FF0FF3202FA04F42343ADF82030BDF8C3 +:103990002030A9F800303CE7202C0FD80899631E8E +:1039A00021FA03F3DA0705D54FF0FF3202FA04F4E7 +:1039B0000C430894089BC9F800302AE7402C2BD010 +:1039C000DDE90865611EC4F12102A4F1210326FA94 +:1039D00001F105FA02F225FA03F311431943CB076B +:1039E00012D50122A4F12003C4F1200102FA03F34D +:1039F00022FA01F1A240524243EA010363EB43037E +:103A000032432B43CDE90823DDE90823C9E900232C +:103A1000FFE66FF00100FCE66FF00800F9E6082C05 +:103A2000A0D9102CB3D9202CEED8C3E7BBF1000FDE +:103A3000ADD0022383E7BBF1000FBBD004237EE7A8 +:103A400030B5012A144638BF0124402C85B028BF68 +:103A500040240025012ACDE9025518D81B788DF89D +:103A6000083063070AD004AB03EBD405624215F8B3 +:103A7000083C02F00702934005F8083C0091034619 +:103A80002246002102A8FFF727FB05B030BD082A17 +:103A9000E4D9102A03D81B88ADF80830E1E7202AC2 +:103AA0008DBFD3E900231B680293CDE90223D8E739 +:103AB00010B5CB681BB98B600B618B8210BD04699C +:103AC0001A681C600361C38A013BC382CA60F0E7C5 +:103AD00003064CBFC0F3C0300220704708B5024651 +:103AE000FFF7F6FF022806D15306C2F30F2001D1DB +:103AF00000F0030008BDC2F30740FBE72DE9F04FDB +:103B000093B0CDE903230A6804461046FFF7E0FFAF +:103B1000022814BFC2F306260026002A0D4682465C +:103B200080F2F28112F0C04940F0EE81097B002959 +:103B300000F0EA81022803D02378B34240F0E78105 +:103B4000C2F304630693104602F07F030593FFF768 +:103B5000C5FF059B29444FEA834848EA0A4848EADA +:103B60004668CE7800230022CDE90823F309834676 +:103B700048EA0008029367D0059B009302466768F5 +:103B8000534608A92046B847002800F0C381276A99 +:103B90004FB9414604F10C00FFF702FB074690B90C +:103BA0006FF0020054E03B6998450DD03F68002F4C +:103BB000F9D1414604F10C00FFF7F2FA074600285C +:103BC000EED0236A3B60276297F817C006F01F0803 +:103BD000CCF3840CACEB08001FFA80FE0028B8BFC1 +:103BE0000EF12000A8EB0C031FFA83FED7E9022197 +:103BF000B8BF00B2002B0793BEBF0EF120031BB26B +:103C0000079352EA010338D0039BDFF824E39A1AA2 +:103C1000049B4FF0000C63EB010196457CEB010324 +:103C20002BD36B7B97F81AE0734519D1029B002BBD +:103C300078D0012821DC7868F8B9DFF8F0C2944523 +:103C400070EB010316D337E0276A27B96FF00C0039 +:103C500013B0BDE8F08F3B699845B5D03F68F4E7F5 +:103C6000B24890427CEB010301D30020F0E7029BB5 +:103C7000002BFAD0079B0F2B17DCFA7DB30002F064 +:103C8000030203F07C031343FB7539462046FFF71C +:103C900007FB6B7BBB76029B3BB9FB7DC3F38402C6 +:103CA000013262F38603FB75D0E76A7BBB7E9A42E2 +:103CB000DBD1029B002B35D0B309022B32D0039B02 +:103CC000BB60049BFB60142200210DA8FDF74AFF96 +:103CD000039B0A93049B0B932B1D0C932B7BADF83A +:103CE0003EB0013BDBB2ADF83C30069B8DF8423074 +:103CF000059B8DF8433094F82C308DF840A083F06C +:103D000001038DF844308DF84180A3680AA920464C +:103D10009847FB7DC3F38403013303F01F039B0229 +:103D2000FB82A2E7FB7DC6F34012B2EBD31F40F04B +:103D3000F480C3F38403434540F0F280029A2B7B66 +:103D4000B609002A4DD0F2075DD4032B40F2EB8078 +:103D5000039BBB60049BFB602B7BAE1D033BDBB274 +:103D60003246394604F10C00FFF7ACFA00280CDAB1 +:103D700039462046FFF794FAFB7DC3F384030133F1 +:103D800003F01F039B02FB820AE7DDE90884AB888E +:103D90003B834FF6FF73C9F12000A9F1200228FAF6 +:103DA00009F104FA00F0014324FA02F21143184623 +:103DB000C9B2FFF7C9F909F10809B9F1400F034683 +:103DC000E9D1B8822A7B033AD2B23146FFF7CEF965 +:103DD000FB7DB882DA43C2F3C01262F3C713FB75EE +:103DE00043E786B92E1D013BDBB23246394604F16A +:103DF0000C00FFF767FA0028BADB2A7BB88A013A81 +:103E0000D2B23146E2E7F98AC1F30901013B042944 +:103E1000DAB25BD8281D002307F11B069A4208D9A5 +:103E200010F801CB06F801C0013101330529DBB2DE +:103E3000F4D103990A9104990B91934207F11B0164 +:103E40000C9138BF043379680D9134BF55FA83F370 +:103E500000230E93FB8AADF83EB0C3F309031A4466 +:103E6000069B8DF84230059B8DF8433094F82C303A +:103E7000ADF83C2083F001038DF8443000238DF829 +:103E800040A08DF841807B602A7BB88A013A291DC9 +:103E9000FFF76CF93B8BB882834203D1A3680AA970 +:103EA0002046984720460AA9FFF702FEFB7DBA8A02 +:103EB000C3F38403013303F01F039B02FB823B8B9C +:103EC0009A420CBF00206FF01000C1E67B68002B07 +:103ED000AFD0052001E01C3033461E68002EFAD119 +:103EE000091A081D2E1D184401EB090CBCF11B0F0B +:103EF0005FFA89F39DD89A429BD916F8013B00F8E6 +:103F0000013B09F10109EFE76FF00900A0E66FF04E +:103F10000A009DE66FF00B009AE66FF00D0097E641 +:103F20006FF00E0094E66FF00F0091E640420F0034 +:103F300080841E00EFF3098305494A6B22F00102D9 +:103F40004A63683383F30988002383F31188704739 +:103F500000EF00E0302080F3118862B60C4B0D4A70 +:103F6000D96821F4E0610904090C0A43DA60D3F846 +:103F7000FC20094942F08072C3F8FC200A6842F034 +:103F800001020A602022DA7783F82200704700BF1E +:103F900000ED00E00003FA05001000E010B530234A +:103FA00083F311880E4B5B6813F4006314D0F1EEB9 +:103FB000103AEFF30984683C4FF08073E361094BDA +:103FC000DB6B236684F3098800F094FF10B1064B85 +:103FD000A36110BD054BFBE783F31188F9E700BF30 +:103FE00000ED00E000EF00E0430600084606000890 +:103FF000026843681143016003B11847704700002D +:10400000024AD36843F0C003D360704700100140F8 +:1040100010B5054C054A0021204600F087FA044AF5 +:10402000044BC4E9972310BD884B002001400008D1 +:104030000010014080F0FA02234A037C002918BFD7 +:104040000A46012B30B5C0F868220CD11F4B9842AC +:1040500009D11F4B596C41F010015964596E41F060 +:10406000100159665B6EB2F904501468D0F86032E2 +:10407000D0F85C12002D03EB5403B3FBF4F3BEBF86 +:1040800023F0070503F0070343EA450394888B6098 +:10409000D38843F040030B61138943F001034B6164 +:1040A00044F4045343F02C03CB6004F4A0540023E5 +:1040B0000B60B4F5806F0B684B680CBF7F23FF2348 +:1040C00080F8643230BD00BFD06F0008884B0020FC +:1040D000003802402DE9F041D0F85C62F76833689F +:1040E000DA0504469DB20DD5302383F311884FF4D1 +:1040F00080610430FFF77CFF6FF48073336000232E +:1041000083F31188302383F3118804F1040815F038 +:104110002F033AD183F31188380615D5290613D514 +:10412000302383F3118804F1380000F07BF9002874 +:104130004EDA0821201DFFF75BFF4FF67F733B40EF +:10414000F360002383F311887A0616D56B0614D525 +:10415000302383F31188D4E913239A420AD1236CC4 +:1041600043B127F040073F041021201D3F0CFFF70B +:104170003FFFF760002383F31188D4F86822D368E7 +:1041800043B3BDE8F041106918472B0714D015F070 +:10419000080F0CBF00214FF48071E80748BF41F0C1 +:1041A0002001AA0748BF41F040016B0748BF41F01A +:1041B00080014046FFF71CFFAD06736805D594F8F3 +:1041C00064122046194000F0E1F93568ADB29EE76F +:1041D0007060B6E7BDE8F08100F1604303F561432C +:1041E0000901C9B283F80013012200F01F039A40AD +:1041F00043099B0003F1604303F56143C3F8802149 +:104200001A607047F8B5154682680669AA420B46DF +:10421000816938BF8568761AB54204460BD21846C4 +:104220002A46FDF779FCA3692B44A361A3685B1BB5 +:10423000A3602846F8BD0CD918463246FDF76CFC41 +:10424000AF1BE1683A463044FDF766FCE3683B4447 +:10425000EBE718462A46FDF75FFCE368E5E7000058 +:1042600083689342F7B51546044638BF8568D0E9A0 +:104270000460361AB5420BD22A46FDF74DFC63693D +:104280002B446361A36828465B1BA36003B0F0BDA9 +:104290000DD932460191FDF73FFC0199E068AF1B53 +:1042A0003A463144FDF738FCE3683B44E9E72A46E7 +:1042B000FDF732FCE368E4E710B50A440024C3616B +:1042C000029B8460C0E90000C0E90511C160026181 +:1042D000036210BD08B5D0E90532934201D182686E +:1042E00082B98268013282605A1C42611970D0E939 +:1042F00004329A4224BFC3684361002100F0CCFE1F +:10430000002008BD4FF0FF30FBE7000070B5302300 +:1043100004460E4683F31188A568A5B1A368A26977 +:10432000013BA360531CA36115782269934224BF0B +:10433000E368A361E3690BB120469847002383F348 +:104340001188284607E03146204600F095FE0028F7 +:10435000E2DA85F3118870BD2DE9F74F04460E4669 +:1043600017469846D0F81C904FF0300A8AF311880F +:104370004FF0000B154665B12A4631462046FFF73F +:1043800041FF034660B94146204600F075FE002813 +:10439000F1D0002383F31188781B03B0BDE8F08FC0 +:1043A000B9F1000F03D001902046C847019B8BF361 +:1043B0001188ED1A1E448AF31188DCE7C0E9051163 +:1043C000C160C3611144009B8260C0E900000161CB +:1043D00003627047F8B504460D461646302383F352 +:1043E0001188A768A7B1A368013BA36063695A1C41 +:1043F00062611D70D4E904329A4224BFE3686361AC +:10440000E3690BB120469847002080F3118807E04C +:104410003146204600F030FE0028E2DA87F31188AA +:10442000F8BD0000D0E905239A4210B501D1826899 +:104430007AB98268013282605A1C82611C780369F1 +:104440009A4224BFC3688361002100F025FE204604 +:1044500010BD4FF0FF30FBE72DE9F74F04460E4645 +:1044600017469846D0F81C904FF0300A8AF311880E +:104470004FF0000B154665B12A4631462046FFF73E +:10448000EFFE034660B94146204600F0F5FD0028E6 +:10449000F1D0002383F31188781B03B0BDE8F08FBF +:1044A000B9F1000F03D001902046C847019B8BF360 +:1044B0001188ED1A1E448AF31188DCE7026843680C +:1044C0001143016003B11847704700001430FFF733 +:1044D00043BF00004FF0FF331430FFF73DBF000033 +:1044E0003830FFF7B9BF00004FF0FF333830FFF727 +:1044F000B3BF00001430FFF709BF00004FF0FF31D9 +:104500001430FFF703BF00003830FFF763BF00002F +:104510004FF0FF323830FFF75DBF0000012914BFB4 +:104520006FF0130000207047FFF772BD37B51546D6 +:104530000E4A026000224260C0E9022201220446C3 +:1045400002740B46009000F15C014FF4807214304D +:10455000FFF7B2FE00942B464FF4807204F5AE7163 +:1045600004F13800FFF72AFF03B030BDE46F000804 +:1045700010B53023044683F31188FFF75DFD022355 +:104580002374002080F3118810BD000038B5C36982 +:1045900004460D461BB904210844FFF78FFF294646 +:1045A00004F11400FFF796FE002806DA201D4FF4F0 +:1045B0000061BDE83840FFF781BF38BD026843683D +:1045C0001143016003B118477047000013B5446BF5 +:1045D000D4F894341A681178042915D1217C022961 +:1045E00012D11979128901238B4013420CD101A9F0 +:1045F00004F14C0001F0CEFFD4F89444019B2179E2 +:104600000246206800F0D6F902B010BD143001F067 +:1046100051BF00004FF0FF33143001F04BBF0000DA +:104620004C3002F023B800004FF0FF334C3002F062 +:104630001DB80000143001F01FBF00004FF0FF3123 +:10464000143001F019BF00004C3001F0EFBF000042 +:104650004FF0FF324C3001F0E9BF000000207047FE +:1046600010B5D0F894341A6811780429044617D18B +:10467000017C022914D15979528901238B401342BC +:104680000ED1143001F0B2FE024648B1D4F8944481 +:104690004FF4807361792068BDE8104000F078B96C +:1046A00010BD0000406BFFF7DBBF0000704700004B +:1046B0007FB5124B036000234360C0E9023301253C +:1046C00002260F4B057404460290019300F1840208 +:1046D000294600964FF48073143001F063FE094BB5 +:1046E0000294CDE9006304F523724FF480732946E8 +:1046F00004F14C0001F02AFF04B070BD0C700008FA +:10470000A5460008CD4500080B68302282F31188C9 +:104710000A7903EB820210624A790D3243F82200D3 +:104720008A7912B103EB820318620223C0F8941451 +:104730000374002080F311887047000038B5037FB0 +:10474000044613B190F85430ABB9201D0125022165 +:10475000FFF734FF04F1140025776FF0010100F03A +:10476000A7FC84F8545004F14C006FF00101BDE83F +:10477000384000F09DBC38BD10B50121044604301E +:10478000FFF71CFF0023237784F8543010BD00008E +:1047900038B504460025143001F01CFE04F14C002D +:1047A000257701F0EBFE201D84F854500121FFF71E +:1047B00005FF2046BDE83840FFF752BF90F85C3057 +:1047C00003F06003202B07D190F85D20212A4FF0E1 +:1047D000000303D81F2A06D800207047222AFBD1E5 +:1047E000C0E9143303E0034A02650722426583658A +:1047F000012070472823002037B5D0F894341A6878 +:104800001178042904461AD1017C022917D119799B +:10481000128901238B40134211D100F14C05284627 +:1048200001F06CFF58B101A9284601F0B3FED4F89D +:104830009444019B21790246206800F0BBF803B044 +:1048400030BD0000F0B500EB810385B01E6A044660 +:104850000D46FEB1302383F3118804EB8507301D2C +:104860000821FFF7ABFEFB685B691B6806F14C0093 +:104870001BB1019001F09CFE019803A901F08AFE92 +:10488000024648B1039B2946204600F093F80023D6 +:1048900083F3118805B0F0BDFB685A691268002ADD +:1048A000F5D01B8A013B1340F1D104F15C02EAE729 +:1048B0000D3138B550F82140DCB1302383F3118835 +:1048C000D4F894241368527903EB8203DB689B6964 +:1048D0005D6845B104216018FFF770FE294604F1B8 +:1048E000140001F08DFD2046FFF7BAFE002383F38C +:1048F000118838BD7047000001F0EEB810B50123F3 +:104900000446282200F8243B0021FDF72BF9002360 +:10491000C4E9013310BD000038B50446302383F3E9 +:1049200011880025C0E90355C0E90555C0E90755C0 +:10493000416001F0E1F80223237085F311882846D5 +:1049400038BD000070B500EB810305465069DA60A0 +:104950000E46144618B110220021FDF703F9A06994 +:1049600018B110220021FDF7FDF831462846BDE8B8 +:10497000704001F08BB90000826802F00112826081 +:104980000022C0E90422C0E90622026201F00ABA4C +:10499000F0B400EB81044789E4680125A4698D40E7 +:1049A0003D43458123600023A2606360F0BC01F0B9 +:1049B00025BA0000F0B400EB81040789E468012502 +:1049C00064698D403D43058123600023A2606360DC +:1049D000F0BC01F09FBA000070B502230025044628 +:1049E0000370C0E90255C0E90455C0E906554566A3 +:1049F000056280F84C5001F0E5F863681B6823B14C +:104A000029462046BDE87040184770BD0378052B45 +:104A100010B504460AD080F8683005230370436857 +:104A20001B680BB1042198470023A36010BD000050 +:104A30000178052906D190F86820436802701B6848 +:104A400003B118477047000070B590F84C30044629 +:104A500013B1002380F84C3004F15C02204601F0D1 +:104A6000C3F963689B68B3B994F85C3013F06005D0 +:104A700035D00021204601F077FC0021204601F0CE +:104A800069FC63681B6813B106212046984706231A +:104A900084F84C3070BD204698470028E4D0B4F824 +:104AA0006230626D9A4288BF636594F95C30656DCF +:104AB000002B4FF0300380F20381002D00F0F280D4 +:104AC000092284F84C2083F311880021D4E91423AF +:104AD0002046FFF76FFF002383F31188DAE794F88D +:104AE0005D2003F07F0343EA022340F20232934247 +:104AF00000F0C58021D8B3F5807F48D00DD8012BB8 +:104B00003FD0022B00F09380002BB2D104F164025D +:104B1000226502226265A365C1E7B3F5817F00F0DB +:104B20009B80B3F5407FA4D194F85E30012BA0D1D7 +:104B3000B4F8643043F0020332E0B3F5006F4DD0B7 +:104B400017D8B3F5A06F31D0A3F5C063012B90D86F +:104B5000636894F85E205E6894F85F10B4F8603083 +:104B60002046B047002884D0436823650368636506 +:104B70001AE0B3F5106F36D040F6024293427FF44C +:104B800078AF5C4B2365022363650023C3E794F889 +:104B90005E30012B7FF46DAFB4F8643023F0020374 +:104BA000C4E91455A4F86430A56578E7B4F85C301E +:104BB000B3F5A06F0ED194F85E3084F866302046CD +:104BC00001F058F863681B6813B10121204698472B +:104BD000032323700023C4E914339CE704F1670323 +:104BE00023650123C3E72378042B10D1302383F3FB +:104BF00011882046FFF7C0FE85F311880321636802 +:104C000084F8675021701B680BB12046984794F8D0 +:104C10005E30002BDED084F8673004232370636895 +:104C20001B68002BD6D0022120469847D2E794F883 +:104C300060301D0603F00F0120460AD501F0C6F8CA +:104C4000012804D002287FF414AF2B4B9AE72B4B9A +:104C500098E701F0ADF8F3E794F85E30002B7FF4AD +:104C600008AF94F8603013F00F01B3D01A06204655 +:104C700002D501F08DFBADE701F080FBAAE794F8C7 +:104C80005E30002B7FF4F5AE94F8603013F00F0126 +:104C9000A0D01B06204602D501F066FB9AE701F082 +:104CA00059FB97E7142284F84C2083F311882B4694 +:104CB0002A4629462046FFF76BFE85F31188E9E670 +:104CC0005DB1152284F84C2083F311880021D4E9CA +:104CD00014232046FFF75CFEFDE60B2284F84C20EF +:104CE00083F311882B462A4629462046FFF762FEA9 +:104CF000E3E700BF3C70000834700008387000081B +:104D000038B590F84C300446002B3ED0063BDAB262 +:104D10000F2A34D80F2B32D8DFE803F037313108AF +:104D2000223231313131313131313737456DB0F8DF +:104D300062309D4214D2C3681B8AB5FBF3F203FBB9 +:104D400012556DB9302383F311882B462A46294624 +:104D5000FFF730FE85F311880A2384F84C300EE00B +:104D6000142384F84C30302383F3118800231A462F +:104D700019462046FFF70CFE002383F3118838BD47 +:104D8000836D03B198470023E7E70021204601F037 +:104D9000EBFA0021204601F0DDFA63681B6813B1CD +:104DA0000621204698470623D7E7000010B590F863 +:104DB0004C30142B044629D017D8062B05D001D827 +:104DC0001BB110BD093B022BFBD80021204601F08E +:104DD000CBFA0021204601F0BDFA63681B6813B1CD +:104DE000062120469847062319E0152BE9D10B230D +:104DF00080F84C30302383F3118800231A4619467B +:104E0000FFF7D8FD002383F31188DAE7C3689B69B5 +:104E10005B68002BD5D1836D03B19847002384F8DC +:104E20004C30CEE700230375826803691B689968DC +:104E30009142FBD25A68036042601060586070472C +:104E400000230375826803691B6899689142FBD847 +:104E50005A680360426010605860704708B50846A1 +:104E6000302383F311880B7D032B05D0042B0DD049 +:104E70002BB983F3118808BD8B6900221A604FF0AB +:104E8000FF338361FFF7CEFF0023F2E7D1E9003261 +:104E900013605A60F3E70000FFF7C4BF054BD96801 +:104EA0000875186802681A60536001220275D8609C +:104EB000FBF7B2BBF84D002030B50C4BDD684B1C46 +:104EC00087B004460FD02B46094A684600F084F9A3 +:104ED0002046FFF7E3FF009B13B1684600F086F918 +:104EE000A86907B030BDFFF7D9FFF9E7F84D0020FA +:104EF0005D4E0008044B1A68DB6890689B68984216 +:104F000094BF002001207047F84D0020084B10B5D9 +:104F10001C68D86822681A60536001222275DC6020 +:104F2000FFF78EFF01462046BDE81040FBF774BB3B +:104F3000F84D0020044B1A68DB6892689B689A421F +:104F400001D9FFF7E3BF7047F84D002038B5074C93 +:104F500007490848012300252370656001F006FC1D +:104F60000223237085F3118838BD00BF60500020F4 +:104F700044700008F84D002008B572B6044B18655F +:104F800000F052FC00F006FD024B03221A70FEE70F +:104F9000F84D00206050002000F05EB9EFF3118062 +:104FA00020B9EFF30583302282F3118870470000A7 +:104FB00010B530B9EFF30584C4F3080414B180F3DD +:104FC000118810BDFFF7B6FF84F31188F9E70000E0 +:104FD000034A516853685B1A9842FBD8704700BF78 +:104FE000001000E08B60022308618B820846704746 +:104FF0008368A3F1840243F8142C026943F8442C1B +:10500000426943F8402C094A43F8242CC26843F80B +:10501000182C022203F80C2C002203F80B2C044A53 +:1050200043F8102CA3F12000704700BF31060008A0 +:10503000F84D002008B5FFF7DBFFBDE80840FFF79B +:105040002BBF0000024BDB6898610F20FFF726BFE3 +:10505000F84D0020302383F31188FFF7F3BF0000E1 +:1050600008B50146302383F311880820FFF724FF99 +:10507000002383F3118808BD064BDB6839B1426811 +:1050800018605A60136043600420FFF715BF4FF0AB +:10509000FF307047F84D00200368984206D01A6828 +:1050A0000260506099611846FFF7F6BE7047000035 +:1050B00038B504460D462068844200D138BD0368E7 +:1050C00023605C608561FFF7E7FEF4E710B50368D5 +:1050D0009C68A2420CD85C688A600B604C602160BE +:1050E000596099688A1A9A604FF0FF33836010BD47 +:1050F0001B68121BECE700000A2938BF0A2170B5B3 +:1051000004460D460A26601901F02AFB01F016FB41 +:10511000041BA54203D8751C2E460446F3E70A2E4D +:1051200004D9BDE87040012001F060BB70BD0000F3 +:10513000F8B5144B0D46D96103F1100141600A2AFC +:105140001969826038BF0A22016048601861A81896 +:10515000144601F0F7FA0A2701F0F0FA431BA342C4 +:10516000064606D37C1C281901F0FAFA2746354674 +:10517000F2E70A2F04D9BDE8F840012001F036BB60 +:10518000F8BD00BFF84D0020F8B506460D4601F009 +:10519000D5FA0F4A134653F8107F9F4206D12A468C +:1051A00001463046BDE8F840FFF7C2BFD169BB6891 +:1051B000441A2C1928BF2C46A34202D92946FFF7CE +:1051C0009BFF224631460348BDE8F840FFF77EBF0B +:1051D000F84D0020084E002010B4C0E9032300233E +:1051E0005DF8044B4361FFF7CFBF000010B5194CC9 +:1051F000236998420DD0D0E90032816813605A606B +:105200009A680A449A60002303604FF0FF33A36159 +:1052100010BD2346026843F8102F5360002202603D +:1052200022699A4203D1BDE8104001F093BA936815 +:1052300081680B44936001F081FA2269E169926808 +:10524000441AA242E4D91144BDE81040091AFFF7FC +:1052500053BF00BFF84D00202DE9F047DFF8BC80B8 +:1052600008F110072C4ED8F8105001F067FAD8F862 +:105270001C40AA68031B9A423ED81444D5E9003268 +:105280004FF00009C8F81C4013605A60C5F8009040 +:10529000D8F81030B34201D101F05CFA89F31188DB +:1052A000D5E9033128469847302383F311886B6989 +:1052B000002BD8D001F042FA6A69A0EB04094A45F4 +:1052C00082460DD2022001F091FA0022D8F8103067 +:1052D000B34208D151462846BDE8F047FFF728BF42 +:1052E000121A2244F2E712EB090938BF4A4629464E +:1052F0003846FFF7EBFEB5E7D8F81030B34208D0D8 +:105300001444211AC8F81C00A960BDE8F047FFF753 +:10531000F3BEBDE8F08700BF084E0020F84D002026 +:1053200000207047FEE70000704700004FF0FF309C +:105330007047000002290CD0032904D00129074836 +:1053400018BF00207047032A05D8054800EBC200AB +:105350007047044870470020704700BF3071000854 +:1053600038230020E470000870B59AB0054608465E +:1053700001A9144600F0C2F801A8FCF7EBFB431C9E +:105380005B00C5E900340022237003236370C6B2BA +:1053900001AB02341046D1B28E4204F1020401D8AE +:1053A0001AB070BD13F8011B04F8021C04F8010CBC +:1053B0000132F0E708B5302383F311880348FFF783 +:1053C0001BFA002383F3118808BD00BF685000203A +:1053D00090F85C3003F01F02012A07D190F85D209D +:1053E0000B2A03D10023C0E9143315E003F0600356 +:1053F000202B08D1B0F860302BB990F85D20212A1D +:1054000003D81F2A04D8FFF7D9B9222AEBD0FAE72C +:10541000034A02650722426583650120704700BF89 +:105420002F23002007B5052917D8DFE801F019164A +:1054300003191920302383F31188104A01900121A8 +:10544000FFF780FA01980E4A0221FFF77BFA0D4818 +:10545000FFF79EF9002383F3118803B05DF804FB86 +:10546000302383F311880748FFF768F9F2E7302308 +:1054700083F311880348FFF77FF9EBE78470000896 +:10548000A87000086850002038B50C4D0C4C0D4930 +:105490002A4604F10800FFF767FF05F1CA0204F18C +:1054A00010000949FFF760FF05F5CA7204F1180002 +:1054B0000649BDE83840FFF757BF00BF3055002010 +:1054C0003823002050700008617000087A700008CE +:1054D00070B5044608460D46FCF73CFBC6B22046B4 +:1054E000013403780BB9184670BD32462946FCF7E3 +:1054F0001DFB0028F3D10120F6E700002DE9F0475D +:1055000005460C46FCF726FB2B49C6B22846FFF79A +:10551000DFFF08B10E36F6B228492846FFF7D8FF5C +:1055200008B11036F6B2632E0BD8DFF88C80DFF8A6 +:105530008C90234FDFF894A02E7846B92670BDE8F2 +:10554000F08729462046BDE8F04701F0B9BC252E7A +:105550002ED1072241462846FCF7E8FA70B9194BCC +:10556000224603F1140153F8040B42F8040B8B425A +:10557000F9D11B78137007351534DDE70822494649 +:105580002846FCF7D3FA98B90F4BA21C19780909E1 +:105590000232C95D02F8041C13F8011B01F00F016F +:1055A0005345C95D02F8031CF0D118340835C3E730 +:1055B00004F8016B0135BFE7507100087A700008EC +:1055C0006E71000858710008107AFF1F1C7AFF1FC7 +:1055D000BFF34F8F024AD368DB03FCD4704700BF90 +:1055E000003C024008B5094B1B7873B9FFF7F0FF88 +:1055F000074B1A69002ABFBF064A5A6002F1883277 +:105600005A601A6822F480621A6008BD8E57002022 +:10561000003C02402301674508B50B4B1B7893B94A +:10562000FFF7D6FF094B1A6942F000421A611A6867 +:1056300042F480521A601A6822F480521A601A6882 +:1056400042F480621A6008BD8E570020003C024080 +:105650000728F0B516D80C4C0C4923787BB90C4DB3 +:105660000E4608234FF0006255F8047B46F8042BE1 +:10567000013B13F0FF033A44F6D10123237051F8A4 +:105680002000F0BD0020FCE7B0570020905700201C +:1056900080710008014B53F82000704780710008AA +:1056A00008207047072810B5044601D9002010BD16 +:1056B000FFF7CEFF064B53F824301844C21A0BB93B +:1056C0000120F4E712680132F0D1043BF6E700BF95 +:1056D00080710008072810B5044621D8FFF778FF2D +:1056E000FFF780FF0F4AF323D360C300DBB243F41C +:1056F000007343F002031361136943F480331361B1 +:10570000FFF766FFFFF7A4FF074B53F8241000F0E4 +:105710003DF9FFF781FF2046BDE81040FFF7C2BF0B +:10572000002010BD003C024080710008F8B512F066 +:105730000103144642D185182E4A954257D82E4B64 +:105740001B6813F0010352D02C4DFFF74BFFF323DE +:10575000EB60FFF73DFF40F20127032C15D824F042 +:1057600001046618254C401A40F20117B142236922 +:1057700000EB010524D123F001032361FFF74CFF67 +:105780000120F8BD043C0430E7E78307E7D12B692B +:1057900023F440732B612B693B432B6151F8046B5D +:1057A0000660BFF34F8FFFF713FF03689E42E9D0F7 +:1057B0002B6923F001032B61FFF72EFF0020E0E7A8 +:1057C00023F44073236123693B4323610B882B80BF +:1057D000BFF34F8FFFF7FCFE2D8831F8023BADB2CF +:1057E000AB42C3D0236923F001032361E4E71846E9 +:1057F000C7E700BF0000080800380240003C024034 +:10580000084908B50B7828B11BB9FFF7EBFE012357 +:105810000B7008BD002BFCD0BDE808400870FFF7F6 +:10582000FBBE00BF8E5700204FF480214FF0005088 +:1058300000F0AEB80846114601F0A6BA012001F00A +:10584000A3BA0000084601F0BDBA000070B582B0EE +:10585000FFF7A4FB0E4E054600F070FF3268904241 +:1058600037BF0C4A0B49516814682EBFD1E900417B +:10587000013151600419034641F1000128460191AC +:105880003360FFF795FB0199204602B070BD00BF61 +:10589000B4570020B857002070B582B0FFF77EFBE8 +:1058A000104E054600F04AFF3268904237BF0E4A5C +:1058B0000D49516814682EBFD1E900410131516092 +:1058C000041941F100010346284601913360FFF7B6 +:1058D0006FFB01994FF47A7200232046FAF788FC97 +:1058E00002B070BDB4570020B857002010B5024474 +:1058F000064BD2B2904200D110BD441C00B253F806 +:10590000200041F8040BE0B2F4E700BF502800404B +:105910000F4B30B51C6F240407D41C6F44F4007483 +:105920001C671C6F44F400441C670A4C236843F452 +:10593000807323600244084BD2B2904200D130BD44 +:10594000441C00B251F8045B43F82050E0B2F4E785 +:1059500000380240007000405028004007B5012286 +:1059600001A90020FFF7C2FF019803B05DF804FB16 +:1059700013B50446FFF7F2FFA04205D0012201A9AA +:1059800000200194FFF7C4FF02B010BD7047000073 +:105990007047000070470000074B45F255521A60EF +:1059A00002225A6040F6FF729A604CF6CC421A60AE +:1059B000024B01221A70704700300040C45700208B +:1059C000034B1B781BB1034B4AF6AA221A6070479F +:1059D000C457002000300040034B1A681AB9034A2C +:1059E000D2F874281A607047C05700200030024077 +:1059F000024B4FF08072C3F87428704700300240A9 +:105A000008B5FFF7E9FF024B1868C0F3407008BD06 +:105A1000C057002008B5FFF7DFFF024B1868C0F33E +:105A2000007008BDC057002070470000FEE700006E +:105A30000A4B0B480B4A90420BD30B4BDA1C121A41 +:105A4000C11E22F003028B4238BF00220021FCF766 +:105A500089B853F8041B40F8041BECE78473000872 +:105A6000E0580020E0580020E058002070B5D0E950 +:105A70001B439E6800224FF0FF3504EB4213510197 +:105A8000D3F800090028BEBFD3F8000940F08040D9 +:105A9000C3F80009D3F8000B0028BEBFD3F8000BF1 +:105AA00040F08040C3F8000B013263189642C3F8FF +:105AB0000859C3F8085BE0D24FF00113C4F81C3852 +:105AC00070BD0000890141F02001016103699B065E +:105AD000FCD41220FFF77CBA10B5054C2046FEF727 +:105AE0000DFF4FF0A043E366024B236710BD00BFDC +:105AF000C8570020C471000870B50378012B054613 +:105B000050D12A4BC46E98421BD1294B5A6B42F09C +:105B100080025A635A6D42F080025A655A6D5A6982 +:105B200042F080025A615A6922F080025A610E21C5 +:105B300043205B69FEF750FB1E4BE3601E4BC4F82D +:105B400000380023C4F8003EC0232360EE6E4FF4FB +:105B50000413A3633369002BFCDA012333610C20A7 +:105B6000FFF736FA3369DB07FCD41220FFF730FA6F +:105B70003369002BFCDA0026A6602846FFF776FF83 +:105B80006B68C4F81068DB68C4F81468C4F81C6853 +:105B90004BB90A4BA3614FF0FF336361A36843F035 +:105BA0000103A36070BD064BF4E700BFC857002097 +:105BB000003802404014004003002002003C30C086 +:105BC000083C30C0F8B5C46E054600212046FFF7FA +:105BD00079FF296F00234FF001128F68C4F8343821 +:105BE0004FF00066C4F81C284FF0FF3004EB43125E +:105BF00001339F42C2F80069C2F8006BC2F808097D +:105C0000C2F8080BF2D20B68EA6E6B67636210236E +:105C10001361166916F01006FBD11220FFF7D8F9B0 +:105C2000D4F8003823F4FE63C4F80038A36943F4C1 +:105C3000402343F01003A3610923C4F81038C4F8CB +:105C400014380A4BEB604FF0C043C4F8103B084BCC +:105C5000C4F8003BC4F81069C4F800396B6F03F155 +:105C6000100243F480136A67A362F8BDA0710008B4 +:105C700040800010C26E90F86610D2F8003823F40D +:105C8000FE6343EA0113C2F8003870472DE9F84378 +:105C900000EB8103C56EDA68166806F00306731E12 +:105CA000022B05EB41130C4680460FFA81F94FEAAF +:105CB00041104FF00001C3F8101B4FF0010104F137 +:105CC000100398BFB60401FA03F391698EBF334EF7 +:105CD00006F1805606F5004600293AD0578A04F1AD +:105CE0005801490137436F50D5F81C180B43C5F8CC +:105CF0001C382B180021C3F8101953690127611EA5 +:105D0000A7409BB3138A928B9B08012A88BF5343F9 +:105D1000D8F87420981842EA034301F1400205EBD9 +:105D20008202C8F87400214653602846FFF7CAFE75 +:105D300008EB8900C3681B8A43EA84534834640132 +:105D40001E432E51D5F81C381F43C5F81C78BDE8FA +:105D5000F88305EB4917D7F8001B21F40041C7F879 +:105D6000001BD5F81C1821EA0303C0E704F13F0328 +:105D700005EB83030A4A5A6028462146FFF7A2FE34 +:105D800005EB4910D0F8003923F40043C0F800397E +:105D9000D5F81C3823EA0707D7E700BF00800010BA +:105DA00000040002026F12684267FFF75FBE000046 +:105DB0005831C36E49015B5813F4004004D013F40A +:105DC000001F0CBF02200120704700004831C36E45 +:105DD00049015B5813F4004004D013F4001F0CBFBA +:105DE000022001207047000000EB8101CB68196A96 +:105DF0000B6813604B6853607047000000EB810331 +:105E000030B5DD68AA691368D36019B9402B84BF27 +:105E1000402313606B8A1468C26E1C44013CB4FBBF +:105E2000F3F46343033323F0030302EB411043EA2B +:105E3000C44343F0C043C0F8103B2B6803F0030396 +:105E4000012B09B20ED1D2F8083802EB411013F43D +:105E5000807FD0F8003B14BF43F0805343F00053E1 +:105E6000C0F8003B02EB4112D2F8003B43F0044380 +:105E7000C2F8003B30BD00002DE9F041244DEE6E2C +:105E800006EB40130446D3F8087BC3F8087B3807B9 +:105E90000AD5D6F81438190706D505EB8403214630 +:105EA000DB6828465B689847FA071FD5D6F8143890 +:105EB000DB071BD505EB8403D968CCB98B69488A0D +:105EC0005A68B2FBF0F600FB16228AB91868DA6845 +:105ED00090420DD2121AC3E90024302383F31188B3 +:105EE0000B482146FFF78AFF84F31188BDE8F08153 +:105EF000012303FA04F26B8923EA02036B81CB6866 +:105F0000002BF3D021460248BDE8F041184700BFFE +:105F1000C857002000EB810370B5DD68C36E6C6963 +:105F20002668E6604A0156BB1A444FF40020C2F8C6 +:105F300010092A6802F00302012A0AB20ED1D3F82E +:105F4000080803EB421410F4807FD4F8000914BF52 +:105F500040F0805040F00050C4F8000903EB4212BA +:105F6000D2F8000940F00440C2F80009D3F8340820 +:105F7000012202FA01F10143C3F8341870BD19B9C6 +:105F8000402E84BF4020206020682E8A8419013C66 +:105F9000B4FBF6F440EAC44040F000501A44C6E7AF +:105FA0002DE9F8433B4DEE6E06EB40130446D3F863 +:105FB0000889C3F8088918F0010F4FEA40171AD072 +:105FC000D6F81038DB0716D505EB8003D9684B6986 +:105FD0001868DA68904230D2121A4FF000091A603D +:105FE000C3F80490302383F3118821462846FFF735 +:105FF00091FF89F3118818F0800F1CD0D6F834383F +:106000000126A640334216D005EB8403ED6ED3F88B +:106010000CC0DCF814200134E4B2D2F800E005EB47 +:1060200004342F445168714515D3D5F8343823EA28 +:106030000606C5F83468BDE8F883012303FA04F2C4 +:106040002B8923EA02032B818B68002BD3D02146B6 +:1060500028469847CFE7BCF81000AEEB0103834217 +:1060600028BF0346D7F8180980B2B3EB800FE2D8F7 +:106070009068A0F1040959F8048FC4F80080A0EBDF +:1060800009089844B8F1040FF5D818440B449060FF +:106090005360C7E7C85700202DE9F74FAC4CE56EB9 +:1060A0006E69AB691E4016F480586E6107D02046B9 +:1060B000FEF792FC03B0BDE8F04FFDF76FBF002E76 +:1060C00012DAD5F8003EA2489B071EBFD5F8003E65 +:1060D00023F00303C5F8003ED5F8043823F001038C +:1060E000C5F80438FEF7A4FC370505D59848FFF736 +:1060F000BDFC9748FEF78AFCB0040CD5D5F80838EB +:1061000013F0060FEB6823F470530CBF43F41053E5 +:1061100043F4A053EB6031071BD56368DB681BB900 +:10612000AB6923F00803AB612378052B0CD1D5F8BC +:10613000003E87489A071EBFD5F8003E23F00303B0 +:10614000C5F8003EFEF774FC6368DB680BB180485D +:106150009847F30200F18980B70227D5D4F86C90F4 +:10616000DFF8ECB100274FF0010A09EB4712D2F833 +:10617000003B03F44023B3F5802F11D1D2F8003B4C +:10618000002B0DDA62890AFA07F322EA030363811E +:1061900004EB8703DB68DB6813B139465846984740 +:1061A000236F01379B68FFB29F42DED9F00617D5F7 +:1061B000E76E3A6AC2F30A1002F00F0302F4F0121B +:1061C000B2F5802F00F09980B2F5402F08D104EB92 +:1061D00083030022DB681B6A07F5805790427ED15B +:1061E0003303D5F818481DD5E70302D50020FFF783 +:1061F00043FEA50302D50120FFF73EFE600302D552 +:106200000220FFF739FE210302D50320FFF734FEF9 +:10621000E20202D50420FFF72FFEA30202D50520DB +:10622000FFF72AFE77037FF545AFE60702D500208A +:10623000FFF7B6FEA50702D50120FFF7B1FE600704 +:1062400002D50220FFF7ACFE210702D50320FFF79D +:10625000A7FEE20602D50420FFF7A2FEA3067FF503 +:1062600029AF0520FFF79CFE24E7E36EDFF8E0A0EE +:10627000019300274FF00109236F9B685FFA87FBAA +:106280009B453FF669AF019B03EB4B13D3F8001915 +:1062900001F44021B1F5802F1FD1D3F80019002956 +:1062A0001BDAD3F8001941F09041C3F80019D3F874 +:1062B00000190029FBDB5946E06EFFF703FC21893A +:1062C00009FA0BF321EA0303238104EB8B03DB6858 +:1062D0009B6813B15946504698470137CCE7910760 +:1062E00008BFD7F80080072A98BF03F8018B02F196 +:1062F000010298BF4FEA182870E7023304EB8302CB +:1063000007F580575268D2F818C0DCF80820DCE99D +:10631000001CA1EB0C0C002188420AD104EB830481 +:1063200063689B699A6802449A605A6802445A609A +:1063300056E711F0030F08BFD7F800808C4588BFDF +:1063400002F8018B01F1010188BF4FEA1828E3E749 +:10635000C8570020C36E03EB4111D1F8003B43F452 +:106360000013C1F8003B7047C36E03EB4111D1F835 +:10637000003943F40013C1F800397047C36E03EBD2 +:106380004111D1F8003B23F40013C1F8003B7047E2 +:10639000C36E03EB4111D1F8003923F40013C1F8A7 +:1063A0000039704730B5039C0172043304FB0325A8 +:1063B000C0E90653049B03630021059BC160C0E94B +:1063C0000000C0E90422C0E90842C0E90A114363A1 +:1063D00030BD0000416A0022C0E90411C0E90A2270 +:1063E000C2606FF00101FEF763BE0000D0E9043225 +:1063F000934201D1C2680AB9181D70470020704746 +:1064000003691960C2680132C260C26913448269BB +:106410000361934224BF436A03610021FEF73CBE3F +:1064200038B504460D46E3683BB16269131D126836 +:10643000A3621344E362002007E0237A33B92946BC +:106440002046FEF719FE0028EDDA38BD6FF0010096 +:10645000FBE70000C368C269013BC36043691344A2 +:1064600082694361934224BF436A4361002383628C +:10647000036B03B11847704770B53023044683F3AC +:106480001188866A3EB9FFF7CBFF054618B186F33F +:106490001188284670BDA36AE26A13F8015BA36203 +:1064A000934202D32046FFF7D5FF002383F31188E0 +:1064B000EFE700002DE9F84F04460E4617469846D0 +:1064C0004FF0300989F311880025AA46D4F828B086 +:1064D000BBF1000F09D141462046FFF7A1FF20B1D3 +:1064E0008BF311882846BDE8F88FD4E90A12A7EB90 +:1064F000050B521A934528BF9346BBF1400F1BD999 +:10650000334601F1400251F8040B43F8040B914269 +:10651000F9D1A36A40334036A3624035D4E90A2357 +:106520009A4202D32046FFF795FF8AF31188BD42B5 +:10653000D8D289F31188C9E730465A46FBF7ECFAFE +:10654000A36A5B445E44A3625D44E7E710B5029C26 +:106550000172043303FB0421C0E906130023C0E9E0 +:106560000A33039B0363049BC460C0E90000C0E9D5 +:106570000422C0E90842436310BD0000026AC26001 +:10658000426AC0E904220022C0E90A226FF0010138 +:10659000FEF78EBDD0E904239A4201D1C26822B928 +:1065A000184650F8043B0B60704700231846FAE782 +:1065B000C368C2690133C36043691344826943619C +:1065C000934224BF436A43610021FEF765BD00008A +:1065D00038B504460D46E3683BB123691A1DA26233 +:1065E000E2691344E362002007E0237A33B92946C5 +:1065F0002046FEF741FD0028EDDA38BD6FF00100BE +:10660000FBE7000003691960C268013AC260C26911 +:10661000134482690361934224BF436A03610023E8 +:106620008362036B03B118477047000070B53023D5 +:106630000D460446114683F31188866A2EB9FFF78A +:10664000C7FF10B186F3118870BDA36A1D70A36ADD +:10665000E26A01339342A36204D3E169204604391C +:10666000FFF7D0FF002080F31188EDE72DE9F84F08 +:1066700004460D46904699464FF0300A8AF3118839 +:106680000026B346A76A4FB949462046FFF7A0FF48 +:1066900020B187F311883046BDE8F88FD4E90A07A6 +:1066A0003A1AA8EB0607974228BF1746402F1BD976 +:1066B00005F1400355F8042B40F8042B9D42F9D115 +:1066C000A36A4033A3624036D4E90A239A4204D332 +:1066D000E16920460439FFF795FF8BF311884645A1 +:1066E000D9D28AF31188CDE729463A46FBF714FA46 +:1066F000A36A3B443D44A3623E44E5E7D0E904235A +:106700009A4217D1C3689BB1836A8BB1043B9B1A31 +:106710000ED01360C368013BC360C3691A44836928 +:1067200002619A4224BF436A03610023836201230A +:10673000184670470023FBE700F0CCB84FF08043C9 +:10674000586A70474FF08043002258631A61022252 +:10675000DA6070474FF080430022DA607047000033 +:106760004FF0804358637047FEE7000070B51B4B45 +:1067700001630025044686B0586085620E46FDF729 +:10678000E9FB04F11003C4E904334FF0FF33C4E91B +:106790000635C4E90044A560E562FFF7CFFF2B464C +:1067A0000246C4E9082304F134010D4A256580231B +:1067B0002046FEF717FC0123E0600A4A03750092A9 +:1067C00072680192B268CDE90223074B6846CDE9B1 +:1067D0000435FEF72FFC06B070BD00BF60500020EE +:1067E000D0710008D571000869670008024AD36AB1 +:1067F0001843D062704700BFF84D00204B684360DB +:106800008B688360CB68C3600B6943614B6903622B +:106810008B6943620B6803607047000008B5234B27 +:1068200023481A6942F0FF021A611A6922F0FF0236 +:106830001A611A691A6B42F0FF021A631A6D42F06C +:10684000FF021A651B4A1B6D1146FFF7D7FF02F1C5 +:106850001C0100F58060FFF7D1FF02F1380100F55F +:106860008060FFF7CBFF02F1540100F58060FFF775 +:10687000C5FF02F1700100F58060FFF7BFFF02F174 +:106880008C0100F58060FFF7B9FF02F1A80100F567 +:106890008060FFF7B3FF02F1C40100F58060FFF7ED +:1068A000ADFFBDE8084000F08FB800BF00380240DF +:1068B00000000240DC71000808B500F01BFAFEF78A +:1068C00045FBFFF789F8BDE80840FEF7DDBD000095 +:1068D000704700000F4B1A6C42F001021A641A6EE6 +:1068E00042F001021A660C4A1B6E936843F00103E2 +:1068F00093604FF0804331229A624FF0FF32DA62A8 +:1069000000229A615A63DA605A6001225A611A6061 +:10691000704700BF00380240002004E04FF0804282 +:1069200008B51169D3680B40D9B2C9439B071161FF +:1069300007D5302383F31188FEF72EFB002383F362 +:10694000118808BD1E4B1A6962F0FF021A611A69AC +:10695000D2B21A614FF0FF301A695A6958610021AA +:106960005A6959615A691A6A62F080521A621A6A3F +:1069700002F080521A621A6A5A6A58625A6A596256 +:106980005A6A1A6C42F080521A641A6E42F08052AF +:106990001A661A6E0B4A106840F480701060186F07 +:1069A00000F44070B0F5007F1EBF4FF480301867D0 +:1069B0001967536823F40073536000F073B900BF84 +:1069C00000380240007000403B4B3C4A1A643C4A8D +:1069D0004FF4404111601A6842F001021A601A68CF +:1069E0009007FCD59A6822F003029A60324B9A68AD +:1069F00012F00C02FBD1196801F0F90119609A60DC +:106A00001A6842F480321A601A689103FCD55A6FF2 +:106A100042F001025A67284B5A6F9207FCD5294A67 +:106A20005A601A6842F080721A60254A5368580406 +:106A3000FCD5214B1A689101FCD5234AC3F8842068 +:106A40001A6842F080621A601A681201FCD51F4A67 +:106A50009A600322C3F88C204FF00062C3F89420A0 +:106A60001B4B1A681B4B9A421B4B21D11B4A1168C6 +:106A70001B4A91421CD140F203121A60164A136855 +:106A800003F00F03032BFAD10B4B9A6842F002027A +:106A90009A609A6802F00C02082AFAD15A6C42F401 +:106AA00080425A645A6E42F480425A665B6E704766 +:106AB00040F20372E1E700BF00380240000400101A +:106AC00000700040081940021030002400948838FB +:106AD000002004E011640020003C024000ED00E0D2 +:106AE00041C20F41074A08B5536903F001035361DE +:106AF00023B1054A13680BB150689847BDE80840B8 +:106B0000FDF74CBA003C014058580020074A08B530 +:106B1000536903F00203536123B1054A93680BB133 +:106B2000D0689847BDE80840FDF738BA003C0140FE +:106B300058580020074A08B5536903F0040353610D +:106B400023B1054A13690BB150699847BDE8084065 +:106B5000FDF724BA003C014058580020074A08B508 +:106B6000536903F00803536123B1054A93690BB1DC +:106B7000D0699847BDE80840FDF710BA003C0140D5 +:106B800058580020074A08B5536903F010035361B1 +:106B900023B1054A136A0BB1506A9847BDE8084013 +:106BA000FDF7FCB9003C014058580020164B10B5C9 +:106BB0005C6904F478725A61A30604D5134A936A97 +:106BC0000BB1D06A9847600604D5104A136B0BB11D +:106BD000506B9847210604D50C4A936B0BB1D06BD0 +:106BE0009847E20504D5094A136C0BB1506C9847DD +:106BF000A30504D5054A936C0BB1D06C9847BDE84A +:106C00001040FDF7CBB900BF003C014058580020B0 +:106C1000194B10B55C6904F47C425A61620504D5D5 +:106C2000164A136D0BB1506D9847230504D5134ACE +:106C3000936D0BB1D06D9847E00404D50F4A136EE5 +:106C40000BB1506E9847A10404D50C4A936E0BB15A +:106C5000D06E9847620404D5084A136F0BB1506F89 +:106C60009847230404D5054A936F0BB1D06F98471A +:106C7000BDE81040FDF792B9003C01405858002093 +:106C800008B50348FDF726FABDE80840FDF786B9C8 +:106C9000884B002008B5FFF741FEBDE80840FDF72E +:106CA0007DB90000062108B50846FDF795FA0621D2 +:106CB0000720FDF791FA06210820FDF78DFA06213D +:106CC0000920FDF789FA06210A20FDF785FA062139 +:106CD0001720FDF781FA06212820FDF77DFA07210C +:106CE0001C20FDF779FABDE808400C212520FDF7AE +:106CF00073BA000008B5FFF725FE00F00DF8FDF7A8 +:106D000013FCFDF7F9FDFDF7D1FCFFF7E1FDBDE850 +:106D10000840FFF711BD00000023054A1946013362 +:106D2000102BC2E9001102F10802F8D1704700BF30 +:106D3000585800200B460146184600F02DB80000B8 +:106D400000F040B8012838BF012010B504462046A5 +:106D500000F030F830B900F007F808B900F00CF88E +:106D60008047F4E710BD0000024B1868BFF35B8F4B +:106D7000704700BFD858002008B5062000F084F8FE +:106D80000120FEF7CFFA0000024B0A4601461868C0 +:106D9000FEF750BD5823002010B5054C13462CB10A +:106DA0000A4601460220AFF3008010BD2046FCE7F2 +:106DB00000000000024B01461868FEF73FBD00BF0F +:106DC00058230020024B01461868FEF73BBD00BF68 +:106DD0005823002010B501390244904201D100200F +:106DE00005E0037811F8014FA34201D0181B10BD34 +:106DF0000130F2E72DE9F041A3B1C91A1778014437 +:106E0000044603F1FF3C8C42204601D9002009E0F2 +:106E10000578BD4204F10104F5D10CEB0405D61848 +:106E2000A54201D1BDE8F08115F8018D16F801EDFC +:106E3000F045F5D0E7E700001F2938B504460D46B8 +:106E400004D9162303604FF0FF3038BD426C12B1F5 +:106E500052F821304BB9204600F030F82A4601465E +:106E60002046BDE8384000F017B8012B0AD0591C65 +:106E700003D1162303600120E7E7002442F82540F0 +:106E8000284698470020E0E7024B01461868FFF7C4 +:106E9000D3BF00BF5823002038B5074D0023044658 +:106EA000084611462B60FEF741FA431C02D12B68BD +:106EB00003B1236038BD00BFDC580020FEF730BAB4 +:106EC000034611F8012B03F8012B002AF9D1704772 +:106ED000696E2E7369657272616165726F7370613C +:106EE00063652E507265636973696F6E506F696E6A +:106EF0007400000053544D3332463F3F3F0053541B +:106F00004D3332463430780053544D3332463432A8 +:106F1000780053544D33324634343658580000000C +:106F2000012033000010410001105A0003105900E5 +:106F30000710310000000000F46E00081304000088 +:106F4000FE6E000819040000086F0008210400000C +:106F5000126F000840A2E4F1646891060041A3E5C5 +:106F6000F2656992070000004261642043414E4986 +:106F70006661636520696E6465782E00800000009C +:106F80000080000000008000000000000000000001 +:106F9000A52400088D2C0008ED2B0008B52400085E +:106FA000E9240008E5260008B9240008C9240008DF +:106FB000BD240008C5240008C12400080D260008CF +:106FC000CD240008592F0008DD240008E125000821 +:106FD000009600000000000000000000000000001B +:106FE0000000000000000000E9440008D54400084B +:106FF00011450008FD44000809450008F544000853 +:10700000E1440008CD4400081D45000800000000D0 +:107010002946000815460008514600083D4600086C +:107020004946000835460008214600080D4600087C +:107030005D460008000000000100000000000000A4 +:107040006330000040700008504E00206050002067 +:10705000536965727261204165726F737061636517 +:10706000005369657272612D507265636973696F4F +:107070006E506F696E742D424C0025534552494144 +:107080004C250000020000000000000045480008F8 +:10709000B148000840004000005500201055002075 +:1070A00002000000000000000300000000000000DB +:1070B000F5480008000000001000000020550020E6 +:1070C000000000000100000000000000C857002080 +:1070D000010102002554000835530008D15300086F +:1070E000B553000843000000EC700008090243009B +:1070F000020100C03209040000010202010005245F +:1071000000100105240100010424020205240600E8 +:1071100001070582030800FF09040100020A0000BC +:107120000007050102400000070581024000000041 +:107130001200000038710008120110010200004026 +:10714000091241570002010203010000040309046F +:1071500025424F41524425005369657272612D509A +:107160007265636973696F6E506F696E7400303158 +:1071700032333435363738394142434445460000CE +:1071800000400000004000000040000000400000FF +:1071900000000100000002000000020000000200E8 +:1071A00000000000494A0008014D0008AD4D0008EC +:1071B00040004000405800204058002001000000DE +:1071C0005058002080000000400100000500000031 +:1071D0006D61696E0069646C650000000000002844 +:1071E00000020000AAAAAAAA00000024FFFF0000D3 +:1071F000000000000000000000A00A1500000000D0 +:10720000AAAAAA9600500000FF8F00000000007795 +:10721000880000000510000000000000AA9AAAAA39 +:1072200005000000FFFF000000000000000000005B +:107230000000000000000000AAAAAAAA00000000A6 +:10724000FFFF000000000000000000000000000040 +:1072500000000000AAAAAAAA00000000FFFF000088 +:10726000000000000000000000000000000000001E +:10727000AAAAAAAA00000000FFFF00000000000068 +:10728000000000000000000000000000AAAAAAAA56 +:1072900000000000FFFF00000000000000000000F0 +:1072A00000000000000000000A00000000000000D4 +:1072B000030000000000000000000000648FFF7F5A +:1072C0000100000000000000470400000000000072 +:1072D000000007000000000040420F00FE2A0100ED +:1072E000D2040000FF00000068500020884B0020FE +:1072F0000096000000000800960000000008000052 +:10730000040000004C7100080000000000000000B4 +:10731000000000000000000000000000000000006D +:107320005C230020000000000000000000000000BE +:10733000000000000000000000000000000000004D +:10734000000000000000000000000000000000003D +:10735000000000000000000000000000000000002D +:10736000000000000000000000000000000000001D +:10737000000000000000000000000000000000000D +:047380000000000009 +:00000001FF diff --git a/Tools/bootloaders/Sierra-TrueNavPro_bl.bin b/Tools/bootloaders/Sierra-TrueNavPro_bl.bin new file mode 100644 index 00000000000000..156c1b588eeede Binary files /dev/null and b/Tools/bootloaders/Sierra-TrueNavPro_bl.bin differ diff --git a/Tools/bootloaders/Sierra-TrueNorth_bl.bin b/Tools/bootloaders/Sierra-TrueNorth_bl.bin new file mode 100644 index 00000000000000..f03c94358947ac Binary files /dev/null and b/Tools/bootloaders/Sierra-TrueNorth_bl.bin differ diff --git a/Tools/bootloaders/Sierra-TrueSpeed_bl.bin b/Tools/bootloaders/Sierra-TrueSpeed_bl.bin new file mode 100644 index 00000000000000..216fbb887ca5ef Binary files /dev/null and b/Tools/bootloaders/Sierra-TrueSpeed_bl.bin differ diff --git a/Tools/bootloaders/SpeedyBeeF405Mini_bl.bin b/Tools/bootloaders/SpeedyBeeF405Mini_bl.bin new file mode 100644 index 00000000000000..d6e15918d0235c Binary files /dev/null and b/Tools/bootloaders/SpeedyBeeF405Mini_bl.bin differ diff --git a/Tools/bootloaders/SpeedyBeeF405Mini_bl.hex b/Tools/bootloaders/SpeedyBeeF405Mini_bl.hex new file mode 100644 index 00000000000000..6ef786304b0389 --- /dev/null +++ b/Tools/bootloaders/SpeedyBeeF405Mini_bl.hex @@ -0,0 +1,899 @@ +:020000040800F2 +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E3010008B92F00081C +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E301000861320008893200086A +:10006000B1320008D932000801330008E30100086A +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E30100082933000838 +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B000FD330008E3010008E3010008E301000844 +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E0008D330008E3010008E3010008E301000884 +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E30100086D2700084F +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F01F056FF1B +:1002500002F050FE4FF055301F491B4A91423CBFFF +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE701F034FF02F07EFEA8 +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E701F01CBF00060020002200204B +:1002D0000000000808ED00E00000002000060020FB +:1002E000C8370008002200204022002040220020C1 +:1002F000602E0020E0010008E0010008E001000895 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F084FAFEE701F07A +:10033000EDF900DFFEE7000038B500F061FB01F0E9 +:10034000ADFE054601F0D0FE0446D8B90F4B9D42E4 +:100350001AD001339D4218BF044641F2883504BFCC +:1003600001240025002001F0A3FE0CB100F076F876 +:1003700000F0ECFC00F09AFB284600F0B7F800F023 +:100380006DF8F9E70025EDE70546EBE7010007B05A +:1003900008B500F05DFBA0F120035842584108BDAC +:1003A00007B541F21203022101A8ADF8043000F0B4 +:1003B0006DFB03B05DF804FB38B5302383F311887F +:1003C000174803680BB101F001FB164A14480023DB +:1003D0004FF47A7101F0F0FA002383F31188124C84 +:1003E000236813B12368013B2360636813B163681A +:1003F000013B63600D4D2B7833B963687BB90220F4 +:1004000000F01EFC322363602B78032B07D1636856 +:100410002BB9022000F014FC4FF47A73636038BDEE +:1004200040220020B9030008602300205822002049 +:10043000084B187003280CD8DFE800F00805020804 +:10044000022000F0F3BB022000F0E6BB024B0022CA +:100450005A60704758220020602300201F4B204A1A +:1004600010B51C461968013136D004339342F9D1D6 +:100470006268A24230D31B4B9B6803F1006303F513 +:1004800040439A4228D2002000F02AFB0220FFF7C6 +:10049000CFFF154B1A6C00221A64196E1A66196E7A +:1004A000596C5A64596E5A665A6E1A6942F0005273 +:1004B0001A611A6922F000521A611B6972B64FF074 +:1004C000E0233021C3F8084DD4E9003281F31188CC +:1004D0009D4683F30888104710BD00BF00C0000888 +:1004E00020C0000800220020003802402DE9F04F13 +:1004F00093B0AA4B00902022FF210AA89D6800F02B +:10050000CFFBA74A1378A3B9A64801210360117055 +:10051000302383F3118803680BB101F057FAA24A24 +:10052000A04800234FF47A7101F046FA002383F3C8 +:100530001188009B13B19D4B009A1A609C4A009C45 +:100540001378032B1EBF00231370984A4FF0000A44 +:1005500018BF5360D3465646D146012000F066FBD3 +:1005600024B1924B1B68002B00F01182002000F098 +:100570006FFA0390039B002BF2DB012000F04CFB91 +:10058000039B213B162BE8D801A252F823F000BFB1 +:10059000ED05000815060008A90600085B0500081F +:1005A0005B0500085B050008330700080309000825 +:1005B0001D0800087F080008A7080008CD080008EB +:1005C0005B050008DF0800085B050008510900080A +:1005D0008D0600085B05000895090008F90500086C +:1005E0008D0600085B0500087F0800080220FFF761 +:1005F000CFFE002840F0F581009B0221BAF1000FE8 +:1006000008BF1C4605A841F21233ADF8143000F0C3 +:100610003DFAA2E74FF47A7000F01AFA071EEBDBFE +:100620000220FFF7B5FE0028E6D0013F052F00F2BB +:10063000DA81DFE807F0030A0D101336052305936E +:10064000042105A800F022FA17E054480421F9E734 +:1006500058480421F6E758480421F3E74FF01C08F6 +:10066000404600F03FFA08F104080590042105A86F +:1006700000F00CFAB8F12C0FF2D1012000FA07F7C4 +:1006800047EA0B0B5FFA8BFB4FF0000900F054FBBD +:1006900026B10BF00B030B2B08BF0024FFF780FEE5 +:1006A0005BE746480421CDE7002EA5D00BF00B03F5 +:1006B0000B2BA1D10220FFF76BFE074600289BD031 +:1006C000012000F00DFA0220FFF7B2FE00261FFA0B +:1006D00086F8404600F014FA044690B100214046E6 +:1006E00000F01EFA01360028F1D1BA46044641F264 +:1006F0001213022105A8ADF814303E4600F0C6F9E9 +:100700002BE70120FFF794FE2546244B9B68AB4264 +:1007100007D9284600F0E6F9013040F0678104353A +:10072000F3E7234B00251D70204BBA465D603E4623 +:10073000ACE7002E3FF460AF0BF00B030B2B7FF404 +:100740005BAF0220FFF774FE322000F081F9B0F1B8 +:100750000008FFF651AF18F003077FF44DAF0F4AC2 +:10076000926808EB050393423FF646AFB8F5807FE9 +:100770003FF742AF124B0193B84523DD4FF47A7037 +:1007800000F066F90390039A002AFFF635AF019B4B +:10079000039A03F8012B0137EDE700BF0022002088 +:1007A0005C23002040220020B903000860230020C1 +:1007B0005822002004220020082200200C220020C1 +:1007C0005C220020C820FFF7E3FD074600283FF425 +:1007D00013AF1F2D11D8C5F1200242450AAB25F0F9 +:1007E000030028BF424683490192184400F032FAC0 +:1007F000019A8048FF2100F053FA4FEAA8037D498F +:100800000193C8F38702284600F052FA06460028F2 +:100810003FF46DAF019B05EB830537E70220FFF73F +:10082000B7FD00283FF4E8AE00F0A6F900283FF439 +:10083000E3AE0027B846704B9B68BB4218D91F2F08 +:1008400011D80A9B01330ED027F0030312AA1344D8 +:1008500053F8203C05934046042205A900F0A0FA75 +:1008600004378046E7E7384600F03CF90590F2E7A8 +:10087000CDF81480042105A800F008F906E700234C +:10088000642104A8049300F0F7F800287FF4B4AEC4 +:100890000220FFF77DFD00283FF4AEAE049800F083 +:1008A00053F90590E6E70023642104A8049300F0BF +:1008B000E3F800287FF4A0AE0220FFF769FD0028CE +:1008C0003FF49AAE049800F04FF9EAE70220FFF7F0 +:1008D0005FFD00283FF490AE00F05EF9E1E70220F2 +:1008E000FFF756FD00283FF487AE05A9142000F05D +:1008F00059F904210746049004A800F0C7F83946C6 +:10090000B9E7322000F0A4F8071EFFF675AEBB076A +:100910007FF472AE384A926807EB090393423FF6C0 +:100920006BAE0220FFF734FD00283FF465AE27F0E0 +:1009300003074F44B9453FF4A9AE484600F0D2F84A +:100940000421059005A800F0A1F809F10409F1E7D8 +:100950004FF47A70FFF71CFD00283FF44DAE00F015 +:100960000BF9002844D00A9B01330BD008220AA9B6 +:10097000002000F09DF900283AD02022FF210AA88B +:1009800000F08EF9FFF70CFD1C4800F059FF13B082 +:10099000BDE8F08F002E3FF42FAE0BF00B030B2BB6 +:1009A0007FF42AAE0023642105A8059300F064F8C3 +:1009B000074600287FF420AE0220FFF7E9FC8046BE +:1009C00000283FF419AEFFF7EBFC41F2883000F04D +:1009D00037FF059800F0E2F9464600F0ADF93C46D5 +:1009E000BBE5064652E64FF0000905E6BA467EE64C +:1009F00037467CE65C22002000220020A086010011 +:100A00007047000070B50F4B1B780133DBB2012B30 +:100A10000C4611D80C4D29684FF47A730E6AA2FB6C +:100A20000332014622462846B047844204D1074B90 +:100A300000221A70012070BD4FF4FA7000F000FF20 +:100A40000020F8E710220020082600209423002030 +:100A500007B50023024601210DF107008DF807308C +:100A6000FFF7D0FF20B19DF8070003B05DF804FB4D +:100A70004FF0FF30F9E700000A4608B50421FFF700 +:100A8000C1FF80F00100C0B2404208BD30B4054C47 +:100A90002368DD69044B0A46AC460146204630BC5B +:100AA000604700BF08260020A086010070B501F055 +:100AB000E7F9094E094D30800024286833888342C5 +:100AC00008D901F0D7F92B6804440133B4F5404F3D +:100AD0002B60F2D370BD00BF962300206823002056 +:100AE00001F090BA00F1006000F5404000687047E6 +:100AF00000F10060920000F5404001F00FBA0000E4 +:100B0000054B1A68054B1B889B1A834202D9104477 +:100B100001F0B0B900207047682300209623002020 +:100B200038B5084D044629B128682044BDE838404E +:100B300001F0C0B92868204401F0A4F90028F3D0DE +:100B400038BD00BF6823002010F003030AD1B0F5C0 +:100B5000047F05D200F10050A0F51040D0F8003815 +:100B6000184670470023FBE700F10050A0F5104045 +:100B7000D0F8100A70470000064991F8243033B1CC +:100B80000023086A81F824300822FFF7B1BF012052 +:100B9000704700BF6C230020014B1868704700BFEE +:100BA000002004E070B5194B1D68194B0138C5F3DE +:100BB0000B0408442D0C04221E88A6420BD15C684D +:100BC0000A46013C824213460FD214F9016F4EB11E +:100BD00002F8016BF6E7013A03F10803ECD1814218 +:100BE0000B4602D22C2203F8012B0A4A0524168850 +:100BF000AE4204D1984284BF967803F8016B013C61 +:100C000002F10402F3D1581A70BD00BF002004E0C5 +:100C1000E0340008CC340008022802BF024B4FF039 +:100C200080729A61704700BF00000240022802BF34 +:100C3000024B4FF480729A61704700BF000002407F +:100C4000022801BF024A536983F4807353617047DD +:100C50000000024010B50023934203D0CC5CC45482 +:100C60000133F9E710BD000010B5013810F9013F5C +:100C70003BB191F900409C4203D11AB10131013AD4 +:100C8000F4E71AB191F90020981A10BD1046FCE75C +:100C900003460246D01A12F9011B0029FAD1704707 +:100CA00002440346934202D003F8011BFAE770475F +:100CB0002DE9F8431F4D144695F824200746884631 +:100CC00052BBDFF870909CB395F824302BB92022EA +:100CD000FF2148462F62FFF7E3FF95F82400C0F19B +:100CE0000802A24228BF2246D6B24146920005EB36 +:100CF0008000FFF7AFFF95F82430A41B1E44F6B226 +:100D0000082E17449044E4B285F82460DBD1FFF745 +:100D100033FF0028D7D108E02B6A03EB820383421C +:100D2000CFD0FFF729FF0028CBD10020BDE8F88302 +:100D30000120FBE76C230020024B1A78024B1A704B +:100D4000704700BF942300201022002010B50F4CE4 +:100D50000F4800F0B5F821460D4800F0DDF8246892 +:100D60000C48626DD2F8043843F00203C2F804382C +:100D700000F066FD0849204600F0D4F9626DD2F813 +:100D8000043823F00203C2F8043810BDAC35000863 +:100D90000826002040420F00B435000870470000CC +:100DA00030B5094D0A4491420DD011F8013B58402D +:100DB000082340F30004013B2C4013F0FF0384EAB6 +:100DC0005000F6D1EFE730BD2083B8ED02684368EC +:100DD0001143016003B118477047000013B5446B1D +:100DE000D4F894341A681178042915D1217C022989 +:100DF00012D11979128901238B4013420CD101A918 +:100E000004F14C0001F032FFD4F89444019B2179A5 +:100E10000246206800F0D0F902B010BD143001F095 +:100E2000B5BE00004FF0FF33143001F0AFBE00003C +:100E30004C3001F087BF00004FF0FF334C3001F021 +:100E400081BF0000143001F083BE00004FF0FF317D +:100E5000143001F07DBE00004C3001F053BF0000A3 +:100E60004FF0FF324C3001F04DBF000000207047C2 +:100E700010B5D0F894341A6811780429044617D1B3 +:100E8000017C022914D15979528901238B401342E4 +:100E90000ED1143001F016FE024648B1D4F8944445 +:100EA0004FF4807361792068BDE8104000F072B99A +:100EB00010BD0000406BFFF7DBBF00007047000073 +:100EC0007FB5124B036000234360C0E90233012564 +:100ED00002260F4B057404460290019300F1840230 +:100EE000294600964FF48073143001F0C7FD094B7A +:100EF0000294CDE9006304F523724FF48073294610 +:100F000004F14C0001F08EFE04B070BD0035000805 +:100F1000B50E0008DD0D00080B68302282F3118841 +:100F20000A7903EB820290614A79093243F8220080 +:100F30008A7912B103EB820398610223C0F89414FA +:100F40000374002080F311887047000038B5037FD8 +:100F5000044613B190F85430ABB9201D012502218D +:100F6000FFF734FF04F1140025776FF0010100F062 +:100F70008FFC84F8545004F14C006FF00101BDE87F +:100F8000384000F085BC38BD10B50121044604305E +:100F9000FFF71CFF0023237784F8543010BD0000B6 +:100FA00038B504460025143001F080FD04F14C00F2 +:100FB000257701F04FFE201D84F854500121FFF7E2 +:100FC00005FF2046BDE83840FFF752BF90F8443097 +:100FD00003F06003202B07D190F84520212A4FF021 +:100FE000000303D81F2A06D800207047222AFBD10D +:100FF000C0E90E3303E0034A82630722C26303643D +:10100000012070471122002037B5D0F894341A68B7 +:101010001178042904461AD1017C022917D11979C3 +:10102000128901238B40134211D100F14C0528464F +:1010300001F0D0FE58B101A9284601F017FED4F8FE +:101040009444019B21790246206800F0B5F803B072 +:1010500030BD0000F0B500EB810385B09E69044609 +:101060000D46FEB1302383F3118804EB8507301D54 +:101070000821FFF7ABFEFB685B691B6806F14C00BB +:101080001BB1019001F000FE019803A901F0EEFDF3 +:10109000024648B1039B2946204600F08DF8002304 +:1010A00083F3118805B0F0BDFB685A691268002A05 +:1010B000F5D01B8A013B1340F1D104F14402EAE769 +:1010C000093138B550F82140DCB1302383F3118861 +:1010D000D4F894241368527903EB8203DB689B698C +:1010E0005D6845B104216018FFF770FE294604F1E0 +:1010F000140001F0F1FC2046FFF7BAFE002383F351 +:10110000118838BD7047000001F050B8012303700A +:101110000023C0E90133C36183620362C362436297 +:101120000363704738B50446302383F311880025E4 +:10113000C0E90355C0E90555416001F047F80223B5 +:10114000237085F31188284638BD000070B500EB88 +:10115000810305465069DA600E46144618B1102224 +:101160000021FFF79DFDA06918B110220021FFF7B3 +:1011700097FD31462846BDE8704001F0F1B8000007 +:10118000826802F0011282600022C0E904228261BA +:1011900001F072B9F0B400EB81044789E4680125DD +:1011A000A4698D403D43458123600023A2606360B4 +:1011B000F0BC01F08DB90000F0B400EB81040789A8 +:1011C000E468012564698D403D4305812360002367 +:1011D000A2606360F0BC01F007BA000070B50223A2 +:1011E000002504460370C0E90255C0E90455C564F2 +:1011F000856180F8345001F04FF863681B6823B1B3 +:1012000029462046BDE87040184770BD0378052B7D +:1012100010B504460AD080F85030052303704368A7 +:101220001B680BB1042198470023A36010BD000088 +:101230000178052906D190F85020436802701B6898 +:1012400003B118477047000070B590F83430044679 +:1012500013B1002380F8343004F14402204601F039 +:101260002DF963689B68B3B994F8443013F06005B6 +:1012700035D00021204601F0CDFB0021204601F0B1 +:10128000BFFB63681B6813B10621204698470623FD +:1012900084F8343070BD204698470028E4D0B4F874 +:1012A0004A30E26B9A4288BFE36394F94430E56BBD +:1012B000002B4FF0300380F20381002D00F0F2800C +:1012C000092284F8342083F311880021D4E90E2305 +:1012D0002046FFF771FF002383F31188DAE794F8C3 +:1012E000452003F07F0343EA022340F20232934297 +:1012F00000F0C58021D8B3F5807F48D00DD8012BF0 +:101300003FD0022B00F09380002BB2D104F14C02AD +:10131000A2630222E2632364C1E7B3F5817F00F098 +:101320009B80B3F5407FA4D194F84630012BA0D127 +:10133000B4F84C3043F0020332E0B3F5006F4DD007 +:1013400017D8B3F5A06F31D0A3F5C063012B90D8A7 +:10135000636894F846205E6894F84710B4F8483003 +:101360002046B047002884D04368A3630368E36342 +:101370001AE0B3F5106F36D040F6024293427FF484 +:1013800078AF5C4BA3630223E3630023C3E794F8C5 +:101390004630012B7FF46DAFB4F84C3023F00203DC +:1013A000C4E90E55A4F84C30256478E7B4F844300D +:1013B000B3F5A06F0ED194F8463084F84E30204635 +:1013C00000F0C2FF63681B6813B1012120469847F3 +:1013D000032323700023C4E90E339CE704F14F0379 +:1013E000A3630123C3E72378042B10D1302383F3B5 +:1013F00011882046FFF7C4FE85F311880321636836 +:1014000084F84F5021701B680BB12046984794F820 +:101410004630002BDED084F84F30042323706368FD +:101420001B68002BD6D0022120469847D2E794F8BB +:1014300048301D0603F00F0120460AD501F030F8B0 +:10144000012804D002287FF414AF2B4B9AE72B4BD2 +:1014500098E701F017F8F3E794F84630002B7FF493 +:1014600008AF94F8483013F00F01B3D01A062046A5 +:1014700002D501F0E3FAADE701F0D6FAAAE794F855 +:101480004630002B7FF4F5AE94F8483013F00F018E +:10149000A0D01B06204602D501F0BCFA9AE701F065 +:1014A000AFFA97E7142284F8342083F311882B468F +:1014B0002A4629462046FFF76DFE85F31188E9E6A6 +:1014C0005DB1152284F8342083F311880021D4E91A +:1014D0000E232046FFF75EFEFDE60B2284F8342043 +:1014E00083F311882B462A4629462046FFF764FEDF +:1014F000E3E700BF30350008283500082C35000828 +:1015000038B590F834300446002B3ED0063BDAB2B2 +:101510000F2A34D80F2B32D8DFE803F037313108E7 +:10152000223231313131313131313737C56BB0F899 +:101530004A309D4214D2C3681B8AB5FBF3F203FB09 +:1015400012556DB9302383F311882B462A4629465C +:10155000FFF732FE85F311880A2384F834300EE059 +:10156000142384F83430302383F3118800231A467F +:1015700019462046FFF70EFE002383F3118838BD7D +:10158000036C03B198470023E7E70021204601F0F0 +:1015900041FA0021204601F033FA63681B6813B159 +:1015A0000621204698470623D7E7000010B590F89B +:1015B0003430142B044629D017D8062B05D001D877 +:1015C0001BB110BD093B022BFBD80021204601F0C6 +:1015D00021FA0021204601F013FA63681B6813B159 +:1015E000062120469847062319E0152BE9D10B2345 +:1015F00080F83430302383F3118800231A461946CB +:10160000FFF7DAFD002383F31188DAE7C3689B69EB +:101610005B68002BD5D1036C03B19847002384F895 +:101620003430CEE700230375826803691B6899682C +:101630009142FBD25A680360426010605860704764 +:1016400000230375826803691B6899689142FBD87F +:101650005A680360426010605860704708B50846D9 +:10166000302383F311880B7D032B05D0042B0DD081 +:101670002BB983F3118808BD8B6900221A604FF0E3 +:10168000FF338361FFF7CEFF0023F2E7D1E9003299 +:1016900013605A60F3E70000FFF7C4BF054BD96839 +:1016A0000875186802681A60536001220275D860D4 +:1016B000FEF728BE9823002030B50C4BDD684B1C8C +:1016C00087B004460FD02B46094A684600F074F9EB +:1016D0002046FFF7E3FF009B13B1684600F076F960 +:1016E000A86907B030BDFFF7D9FFF9E798230020BC +:1016F0005D160008044B1A68DB6890689B68984286 +:1017000094BF00200120704798230020084B10B59B +:101710001C68D86822681A60536001222275DC6058 +:10172000FFF78EFF01462046BDE81040FEF7EABDF8 +:1017300098230020044B1A68DB6892689B689A42E1 +:1017400001D9FFF7E3BF70479823002038B5074C55 +:1017500007490848012300252370656001F072FBEA +:101760000223237085F3118838BD00BF00260020B6 +:10177000383500089823002000F05EB9EFF311809F +:1017800020B9EFF30583302282F3118870470000FF +:1017900010B530B9EFF30584C4F3080414B180F335 +:1017A000118810BDFFF7C6FF84F31188F9E7000028 +:1017B000034A516853685B1A9842FBD8704700BFD0 +:1017C000001000E08B60022308618B82084670479E +:1017D0008368A3F1840243F8142C026943F8442C73 +:1017E000426943F8402C094A43F8242CC26843F864 +:1017F000182C022203F80C2C002203F80B2C044AAC +:1018000043F8102CA3F12000704700BF1D0300080F +:101810009823002008B5FFF7DBFFBDE80840FFF77D +:101820003BBF0000024BDB6898610F20FFF736BF1B +:1018300098230020302383F31188FFF7F3BF0000C3 +:1018400008B50146302383F311880820FFF734FFE1 +:10185000002383F3118808BD064BDB6839B1426869 +:1018600018605A60136043600420FFF725BF4FF0F3 +:10187000FF307047982300200368984206D01A680A +:101880000260506099611846FFF706BF704700007C +:1018900038B504460D462068844200D138BD03683F +:1018A00023605C608561FFF7F7FEF4E710B503681D +:1018B0009C68A2420CD85C688A600B604C60216016 +:1018C000596099688A1A9A604FF0FF33836010BD9F +:1018D0001B68121BECE700000A2938BF0A2170B50B +:1018E00004460D460A26601901F0A6FA01F092FAA4 +:1018F000041BA54203D8751C2E460446F3E70A2EA6 +:1019000004D9BDE87040012001F0DCBA70BD0000D0 +:10191000F8B5144B0D46D96103F1100141600A2A54 +:101920001969826038BF0A22016048601861A818EE +:10193000144601F073FA0A2701F06CFA431BA34224 +:10194000064606D37C1C281901F076FA2746354650 +:10195000F2E70A2F04D9BDE8F840012001F0B2BA3D +:10196000F8BD00BF98230020F8B506460D4601F0EB +:1019700051FA0F4A134653F8107F9F4206D12A4668 +:1019800001463046BDE8F840FFF7C2BFD169BB68E9 +:10199000441A2C1928BF2C46A34202D92946FFF726 +:1019A0009BFF224631460348BDE8F840FFF77EBF63 +:1019B00098230020A823002010B4C0E903230023AB +:1019C0005DF8044B4361FFF7CFBF000010B5194C21 +:1019D000236998420DD0D0E90032816813605A60C3 +:1019E0009A680A449A60002303604FF0FF33A361B2 +:1019F00010BD2346026843F8102F53600022026096 +:101A000022699A4203D1BDE8104001F00FBA9368F1 +:101A100081680B44936001F0FDF92269E1699268E5 +:101A2000441AA242E4D91144BDE81040091AFFF754 +:101A300053BF00BF982300202DE9F047DFF8BC809A +:101A400008F110072C4ED8F8105001F0E3F9D8F83F +:101A50001C40AA68031B9A423ED81444D5E90032C0 +:101A60004FF00009C8F81C4013605A60C5F8009098 +:101A7000D8F81030B34201D101F0D8F989F31188B8 +:101A8000D5E9033128469847302383F311886B69E1 +:101A9000002BD8D001F0BEF96A69A0EB04094A45D1 +:101AA00082460DD2022001F00DFA0022D8F8103043 +:101AB000B34208D151462846BDE8F047FFF728BF9A +:101AC000121A2244F2E712EB090938BF4A462946A6 +:101AD0003846FFF7EBFEB5E7D8F81030B34208D030 +:101AE0001444211AC8F81C00A960BDE8F047FFF7AC +:101AF000F3BEBDE8F08700BFA82300209823002094 +:101B000000207047FEE70000704700004FF0FF30F4 +:101B10007047000002290CD0032904D0012907488E +:101B200018BF00207047032A05D8054800EBC20003 +:101B30007047044870470020704700BF1036000807 +:101B400020220020C435000870B59AB0054608462A +:101B500001A9144600F0C2F801A8FFF799F8431C48 +:101B60005B00C5E900340022237003236370C6B212 +:101B700001AB02341046D1B28E4204F1020401D806 +:101B80001AB070BD13F8011B04F8021C04F8010C14 +:101B90000132F0E708B5302383F311880348FFF7DB +:101BA00033FA002383F3118808BD00BF0826002004 +:101BB00090F8443003F01F02012A07D190F8452025 +:101BC0000B2A03D10023C0E90E3315E003F06003B4 +:101BD000202B08D1B0F848302BB990F84520212AA5 +:101BE00003D81F2A04D8FFF7F1B9222AEBD0FAE76D +:101BF000034A82630722C26303640120704700BF67 +:101C00001822002007B5052917D8DFE801F01916BA +:101C100003191920302383F31188104A0190012100 +:101C2000FFF794FA01980E4A0221FFF78FFA0D4848 +:101C3000FFF7B6F9002383F3118803B05DF804FBC6 +:101C4000302383F311880748FFF780F9F2E7302348 +:101C500083F311880348FFF797F9EBE76435000831 +:101C6000883500080826002038B50C4D0C4C0D496D +:101C70002A4604F10800FFF767FF05F1CA0204F1E4 +:101C800010000949FFF760FF05F5CA7204F118005A +:101C90000649BDE83840FFF757BF00BFD02A0020F3 +:101CA00020220020443500084E3500085935000830 +:101CB00070B5044608460D46FEF7EAFFC6B2204658 +:101CC000013403780BB9184670BD32462946FEF739 +:101CD000CBFF0028F3D10120F6E700002DE9F04703 +:101CE00005460C46FEF7D4FF2B49C6B22846FFF73F +:101CF000DFFF08B10A36F6B228492846FFF7D8FFB9 +:101D000008B11036F6B2632E0BD8DFF88C80DFF8FE +:101D10008C90234FDFF894A02E7846B92670BDE84A +:101D2000F08729462046BDE8F04701F0B1BB252EDB +:101D30002ED1072241462846FEF796FF70B9194B6F +:101D4000224603F1100153F8040B42F8040B8B42B6 +:101D5000F9D11B78137007351134DDE708224946A5 +:101D60002846FEF781FF98B90F4BA21C1978090984 +:101D70000232C95D02F8041C13F8011B01F00F01C7 +:101D80005345C95D02F8031CF0D118340835C3E788 +:101D900004F8016B0135BFE73036000859350008FB +:101DA0004A36000838360008107AFF1F1C7AFF1FD9 +:101DB000BFF34F8F024AD368DB03FCD4704700BFE8 +:101DC000003C024008B5094B1B7873B9FFF7F0FFE0 +:101DD000074B1A69002ABFBF064A5A6002F18832CF +:101DE0005A601A6822F480621A6008BD2E2D002005 +:101DF000003C02402301674508B50B4B1B7893B9A3 +:101E0000FFF7D6FF094B1A6942F000421A611A68BF +:101E100042F480521A601A6822F480521A601A68DA +:101E200042F480621A6008BD2E2D0020003C024062 +:101E30000B28F0B516D80C4C0C4923787BB90C4D07 +:101E40000E460C234FF0006255F8047B46F8042B35 +:101E5000013B13F0FF033A44F6D10123237051F8FC +:101E60002000F0BD0020FCE7602D0020302D002078 +:101E70005C360008014B53F8200070475C360008C0 +:101E80000C2070470B2810B5044601D9002010BD66 +:101E9000FFF7CEFF064B53F824301844C21A0BB993 +:101EA0000120F4E712680132F0D1043BF6E700BFED +:101EB0005C3600080B2838B5044628D8FFF75EFCCE +:101EC000FFF776FFFFF77EFF124AF323D360E300AC +:101ED000DBB243F4007343F002031361136943F46C +:101EE0008033136105462046FFF762FFFFF7A0FF2E +:101EF000094B53F8241000F0E9F82846FFF77CFF5F +:101F0000FFF746FC2046BDE83840FFF7BBBF002086 +:101F100038BD00BF003C02405C36000812F00103EF +:101F20002DE9F04105460E4614464BD18218B2F118 +:101F3000016F61D8314B1B6813F001035CD0304F47 +:101F4000FFF71CFCFFF73EFFF323FB60FFF730FFBA +:101F5000314640F20128032C18D824F00104284E01 +:101F60000C446D1A40F20118A142336905EB0107D8 +:101F70002AD123F001033361FFF73EFFFFF708FC8E +:101F80000120BDE8F081043C0435E4E7AB07E4D16F +:101F90003B6923F440733B613B6943EA08033B61BF +:101FA00051F8046B2E60BFF34F8FFFF701FF2B68D2 +:101FB0009E42E8D03B6923F001033B61FFF71CFF21 +:101FC000FFF7E6FB0020DCE723F44073336133695D +:101FD00043EA080333610B883B80BFF34F8FFFF761 +:101FE000E7FE3F8831F8023BBFB2BB42BCD0336949 +:101FF00023F001033361E1E71846C2E700380240ED +:10200000003C0240084908B50B7828B11BB9FFF71E +:10201000D9FE01230B7008BD002BFCD0BDE80840A1 +:102020000870FFF7E9BE00BF2E2D002010B5024456 +:10203000064BD2B2904200D110BD441C00B253F8FE +:10204000200041F8040BE0B2F4E700BF5028004044 +:102050000F4B30B51C6F240407D41C6F44F400747C +:102060001C671C6F44F400441C670A4C236843F44B +:10207000807323600244084BD2B2904200D130BD3D +:10208000441C00B251F8045B43F82050E0B2F4E77E +:1020900000380240007000405028004007B501227F +:1020A00001A90020FFF7C2FF019803B05DF804FB0F +:1020B00013B50446FFF7F2FFA04205D0012201A9A3 +:1020C00000200194FFF7C4FF02B010BD704700006C +:1020D000034B1A681AB9034AD2F874281A60704779 +:1020E000642D00200030024008B5FFF7F1FF024BDD +:1020F0001868C0F3407008BD642D002070470000D0 +:10210000FEE700000A4B0B480B4A90420BD30B4BE7 +:10211000DA1C121AC11E22F003028B4238BF0022C1 +:102120000021FEF7BDBD53F8041B40F8041BECE78B +:1021300008380008602E0020602E0020602E00204D +:1021400070B5D0E915439E6800224FF0FF3504EBCF +:1021500042135101D3F800090028BEBFD3F800098B +:1021600040F08040C3F80009D3F8000B0028BEBF40 +:10217000D3F8000B40F08040C3F8000B0132631825 +:102180009642C3F80859C3F8085BE0D24FF0011338 +:10219000C4F81C3870BD0000890141F020010161C4 +:1021A00003699B06FCD41220FFF702BB10B5054C57 +:1021B0002046FEF7ABFF4FF0A0436365024BA365DB +:1021C00010BD00BF682D0020B036000870B5037840 +:1021D000012B054650D12A4B446D98421BD1294B07 +:1021E0005A6B42F080025A635A6D42F080025A657F +:1021F0005A6D5A6942F080025A615A6922F080028F +:102200005A610E2143205B6900F022FC1E4BE36003 +:102210001E4BC4F800380023C4F8003EC0232360DE +:102220006E6D4FF40413A3633369002BFCDA0123B2 +:1022300033610C20FFF7BCFA3369DB07FCD41220B2 +:10224000FFF7B6FA3369002BFCDA0026A6602846B1 +:10225000FFF776FF6B68C4F81068DB68C4F8146891 +:10226000C4F81C684BB90A4BA3614FF0FF3363619C +:10227000A36843F00103A36070BD064BF4E700BF01 +:10228000682D002000380240401400400300200266 +:10229000003C30C0083C30C0F8B5446D0546002114 +:1022A0002046FFF779FFA96D00234FF001128F68D8 +:1022B000C4F834384FF00066C4F81C284FF0FF30E3 +:1022C00004EB431201339F42C2F80069C2F8006B6D +:1022D000C2F80809C2F8080BF2D20B686A6DEB6508 +:1022E000636210231361166916F01006FBD11220E9 +:1022F000FFF75EFAD4F8003823F4FE63C4F8003820 +:10230000A36943F4402343F01003A3610923C4F8F5 +:102310001038C4F814380A4BEB604FF0C043C4F8CF +:10232000103B084BC4F8003BC4F81069C4F80039EE +:10233000EB6D03F1100243F48013EA65A362F8BD6C +:102340008C36000840800010426D90F84E10D2F894 +:10235000003823F4FE6343EA0113C2F800387047E3 +:102360002DE9F84300EB8103456DDA68166806F045 +:102370000306731E022B05EB41130C4680460FFA31 +:1023800081F94FEA41104FF00001C3F8101B4FF0E4 +:10239000010104F1100398BFB60401FA03F3916937 +:1023A0008EBF334E06F1805606F5004600293AD01E +:1023B000578A04F15801490137436F50D5F81C186A +:1023C0000B43C5F81C382B180021C3F810195369AA +:1023D0000127611EA7409BB3138A928B9B08012A99 +:1023E00088BF5343D8F85C20981842EA034301F1B0 +:1023F000400205EB8202C8F85C0021465360284683 +:10240000FFF7CAFE08EB8900C3681B8A43EA8453BE +:10241000483464011E432E51D5F81C381F43C5F8BB +:102420001C78BDE8F88305EB4917D7F8001B21F4A9 +:102430000041C7F8001BD5F81C1821EA0303C0E7C8 +:1024400004F13F0305EB83030A4A5A6028462146FC +:10245000FFF7A2FE05EB4910D0F8003923F4004342 +:10246000C0F80039D5F81C3823EA0707D7E700BFC2 +:102470000080001000040002826D1268C265FFF740 +:102480005FBE00005831436D49015B5813F40040B2 +:1024900004D013F4001F0CBF02200120704700007D +:1024A0004831436D49015B5813F4004004D013F4E4 +:1024B000001F0CBF022001207047000000EB8101CB +:1024C000CB68196A0B6813604B6853607047000053 +:1024D00000EB810330B5DD68AA691368D36019B9D0 +:1024E000402B84BF402313606B8A1468426D1C44E8 +:1024F000013CB4FBF3F46343033323F0030302EB27 +:10250000411043EAC44343F0C043C0F8103B2B687A +:1025100003F00303012B09B20ED1D2F8083802EB05 +:10252000411013F4807FD0F8003B14BF43F0805378 +:1025300043F00053C0F8003B02EB4112D2F8003BDD +:1025400043F00443C2F8003B30BD00002DE9F041E8 +:10255000244D6E6D06EB40130446D3F8087BC3F898 +:10256000087B38070AD5D6F81438190706D505EBC5 +:1025700084032146DB6828465B689847FA071FD525 +:10258000D6F81438DB071BD505EB8403D968CCB922 +:102590008B69488A5A68B2FBF0F600FB16228AB9AA +:1025A0001868DA6890420DD2121AC3E90024302369 +:1025B00083F311880B482146FFF78AFF84F31188C3 +:1025C000BDE8F081012303FA04F26B8923EA0203D8 +:1025D0006B81CB68002BF3D021460248BDE8F04167 +:1025E000184700BF682D002000EB810370B5DD683F +:1025F000436D6C692668E6604A0156BB1A444FF485 +:102600000020C2F810092A6802F00302012A0AB267 +:102610000ED1D3F8080803EB421410F4807FD4F8ED +:10262000000914BF40F0805040F00050C4F8000989 +:1026300003EB4212D2F8000940F00440C2F800094E +:10264000D3F83408012202FA01F10143C3F8341827 +:1026500070BD19B9402E84BF4020206020682E8AAA +:102660008419013CB4FBF6F440EAC44040F0005049 +:102670001A44C6E72DE9F8433B4D6E6D06EB401357 +:102680000446D3F80889C3F8088918F0010F4FEA07 +:1026900040171AD0D6F81038DB0716D505EB8003A3 +:1026A000D9684B691868DA68904230D2121A4FF034 +:1026B00000091A60C3F80490302383F3118821467F +:1026C0002846FFF791FF89F3118818F0800F1CD07E +:1026D000D6F834380126A640334216D005EB8403E1 +:1026E0006D6DD3F80CC0DCF814200134E4B2D2F8DC +:1026F00000E005EB04342F445168714515D3D5F83B +:10270000343823EA0606C5F83468BDE8F8830123A7 +:1027100003FA04F22B8923EA02032B818B68002B36 +:10272000D3D0214628469847CFE7BCF81000AEEB3F +:102730000103834228BF0346D7F8180980B2B3EBE0 +:10274000800FE2D89068A0F1040959F8048FC4F80A +:102750000080A0EB09089844B8F1040FF5D818449C +:102760000B4490605360C7E7682D00202DE9F74FB8 +:10277000A24C656D6E69AB691E4016F480586E619F +:1027800007D02046FEF72AFD03B0BDE8F04F00F069 +:1027900047BC002E12DAD5F8003E98489B071EBFB2 +:1027A000D5F8003E23F00303C5F8003ED5F8043801 +:1027B00023F00103C5F80438FEF73AFD370505D5C7 +:1027C0008E48FFF7BDFC8D48FEF720FDB0040CD508 +:1027D000D5F8083813F0060FEB6823F470530CBFDC +:1027E00043F4105343F4A053EB6031071BD56368E7 +:1027F000DB681BB9AB6923F00803AB612378052BB9 +:102800000CD1D5F8003E7D489A071EBFD5F8003E92 +:1028100023F00303C5F8003EFEF70AFD6368DB689A +:102820000BB176489847F30274D4B70227D5D4F891 +:102830005490DFF8C8B100274FF0010A09EB4712A6 +:10284000D2F8003B03F44023B3F5802F11D1D2F826 +:10285000003B002B0DDA62890AFA07F322EA030330 +:10286000638104EB8703DB68DB6813B139465846A4 +:102870009847A36D01379B68FFB29F42DED9F006EF +:1028800017D5676D3A6AC2F30A1002F00F0302F41B +:10289000F012B2F5802F00F08580B2F5402F08D1FC +:1028A00004EB83030022DB681B6A07F58057904224 +:1028B0006AD13003D5F8184813D5E10302D50020BA +:1028C000FFF744FEA20302D50120FFF73FFE63039A +:1028D00002D50220FFF73AFE270302D50320FFF7B7 +:1028E00035FE75037FF550AFE00702D50020FFF7F6 +:1028F000C1FEA10702D50120FFF7BCFE620702D589 +:102900000220FFF7B7FE23077FF53EAF0320FFF756 +:10291000B1FE39E7636DDFF8E4A0019300274FF0C3 +:102920000109A36D9B685FFA87FB9B453FF67DAF6E +:10293000019B03EB4B13D3F8001901F44021B1F5CF +:10294000802F1FD1D3F8001900291BDAD3F8001902 +:1029500041F09041C3F80019D3F800190029FBDBBE +:102960005946606DFFF718FC218909FA0BF321EA3B +:102970000303238104EB8B03DB689B6813B1594687 +:10298000504698470137CCE7910708BFD7F8008039 +:10299000072A98BF03F8018B02F1010298BF4FEAA2 +:1029A000182884E7023304EB830207F58057526846 +:1029B000D2F818C0DCF80820DCE9001CA1EB0C0CF4 +:1029C000002188420AD104EB830463689B699A68FA +:1029D00002449A605A6802445A606AE711F0030F91 +:1029E00008BFD7F800808C4588BF02F8018B01F141 +:1029F000010188BF4FEA1828E3E700BF682D0020D7 +:102A0000436D03EB4111D1F8003B43F40013C1F8CF +:102A1000003B7047436D03EB4111D1F8003943F49B +:102A20000013C1F800397047436D03EB4111D1F831 +:102A3000003B23F40013C1F8003B7047436D03EBE8 +:102A40004111D1F8003923F40013C1F8003970475F +:102A500000F1604303F561430901C9B283F8001333 +:102A6000012200F01F039A4043099B0003F16043D9 +:102A700003F56143C3F880211A60704730B5039CA9 +:102A80000172043304FB0325C0E90653049B03636E +:102A90000021059BC160C0E90000C0E90422C0E933 +:102AA0000842C0E90A11436330BD0000416A0022B8 +:102AB000C0E90411C0E90A22C2606FF00101FEF70B +:102AC000E7BE0000D0E90432934201D1C2680AB9DE +:102AD000181D70470020704703691960C2680132F1 +:102AE000C260C269134482690361934224BF436A8E +:102AF00003610021FEF7C0BE38B504460D46E36809 +:102B00003BB16269131D1268A3621344E3620020A3 +:102B100007E0237A33B929462046FEF79DFE0028B8 +:102B2000EDDA38BD6FF00100FBE70000C368C26951 +:102B3000013BC3604369134482694361934224BFEC +:102B4000436A436100238362036B03B118477047F4 +:102B500070B53023044683F31188866A3EB9FFF7C7 +:102B6000CBFF054618B186F31188284670BDA36ACD +:102B7000E26A13F8015BA362934202D32046FFF797 +:102B8000D5FF002383F31188EFE700002DE9F84F0C +:102B900004460E46174698464FF0300989F31188CF +:102BA0000025AA46D4F828B0BBF1000F09D1414650 +:102BB0002046FFF7A1FF20B18BF311882846BDE81E +:102BC000F88FD4E90A12A7EB050B521A934528BFD8 +:102BD0009346BBF1400F1BD9334601F1400251F837 +:102BE000040B43F8040B9142F9D1A36A40334036F9 +:102BF000A3624035D4E90A239A4202D32046FFF764 +:102C000095FF8AF31188BD42D8D289F31188C9E7AC +:102C100030465A46FEF71EF8A36A5B445E44A36240 +:102C20005D44E7E710B5029C0172043303FB042105 +:102C3000C0E906130023C0E90A33039B0363049B26 +:102C4000C460C0E90000C0E90422C0E9084243634F +:102C500010BD0000026AC260426AC0E9042200227C +:102C6000C0E90A226FF00101FEF712BED0E9042389 +:102C70009A4201D1C26822B9184650F8043B0B6051 +:102C8000704700231846FAE7C368C2690133C3607E +:102C90004369134482694361934224BF436A436199 +:102CA0000021FEF7E9BD000038B504460D46E36893 +:102CB0003BB123691A1DA262E2691344E36200205A +:102CC00007E0237A33B929462046FEF7C5FD0028E0 +:102CD000EDDA38BD6FF00100FBE700000369196011 +:102CE000C268013AC260C2691344826903619342B7 +:102CF00024BF436A036100238362036B03B1184757 +:102D00007047000070B530230D460446114683F32A +:102D10001188866A2EB9FFF7C7FF10B186F31188B4 +:102D200070BDA36A1D70A36AE26A01339342A36275 +:102D300004D3E16920460439FFF7D0FF002080F377 +:102D40001188EDE72DE9F84F04460D469046994667 +:102D50004FF0300A8AF311880026B346A76A4FB9AC +:102D600049462046FFF7A0FF20B187F3118830467F +:102D7000BDE8F88FD4E90A073A1AA8EB060797428C +:102D800028BF1746402F1BD905F1400355F8042BE7 +:102D900040F8042B9D42F9D1A36A4033A362403628 +:102DA000D4E90A239A4204D3E16920460439FFF7A3 +:102DB00095FF8BF311884645D9D28AF31188CDE768 +:102DC00029463A46FDF746FFA36A3B443D44A362C9 +:102DD0003E44E5E7D0E904239A4217D1C3689BB18A +:102DE000836A8BB1043B9B1A0ED01360C368013B0E +:102DF000C360C3691A44836902619A4224BF436A6B +:102E00000361002383620123184670470023FBE718 +:102E100000F030B94FF08043586A70474FF080435C +:102E2000002258631A610222DA6070474FF0804333 +:102E30000022DA60704700004FF08043586370470B +:102E4000FEE7000070B51B4B01630025044686B009 +:102E5000586085620E4600F0BFF804F11003C4E923 +:102E600004334FF0FF33C4E90635C4E90044A560DC +:102E7000E562FFF7CFFF2B460246C4E9082304F1C1 +:102E800034010D4A256580232046FEF79BFC012373 +:102E9000E0600A4A0375009272680192B268CDE957 +:102EA0000223074B6846CDE90435FEF7B3FC06B0B4 +:102EB00070BD00BF00260020BC360008C1360008E7 +:102EC000412E0008024AD36A1843D062704700BFFF +:102ED000982300204B6843608B688360CB68C36095 +:102EE0000B6943614B6903628B6943620B68036042 +:102EF0007047000008B5264B26481A6940F2FF11BA +:102F00000A431A611A6922F4FF7222F001021A615F +:102F10001A691A6B0A431A631A6D0A431A651E4A24 +:102F20001B6D1146FFF7D6FF02F11C0100F5806012 +:102F3000FFF7D0FF02F1380100F58060FFF7CAFF0C +:102F400002F1540100F58060FFF7C4FF02F1700147 +:102F500000F58060FFF7BEFF02F18C0100F5806094 +:102F6000FFF7B8FF02F1A80100F58060FFF7B2FF9C +:102F700002F1C40100F58060FFF7ACFF02F1E0014F +:102F800000F58060FFF7A6FFBDE8084000F0EEB84E +:102F90000038024000000240C836000808B500F0C2 +:102FA00059FAFEF7D3FBFFF793F8BDE80840FEF7A8 +:102FB0005BBE000070470000EFF3098305494A6BD0 +:102FC00022F001024A63683383F30988002383F304 +:102FD0001188704700EF00E0302080F3118862B65E +:102FE0000C4B0D4AD96821F4E0610904090C0A432D +:102FF000DA60D3F8FC20094942F08072C3F8FC2063 +:103000000A6842F001020A602022DA7783F822007F +:10301000704700BF00ED00E00003FA05001000E07B +:1030200010B5302383F311880E4B5B6813F40063F3 +:1030300014D0F1EE103AEFF30984683C4FF080733E +:10304000E361094BDB6B236684F30988FEF752FBCF +:1030500010B1064BA36110BD054BFBE783F311884C +:10306000F9E700BF00ED00E000EF00E02F030008EB +:10307000320300080F4B1A6C42F001021A641A6EF8 +:1030800042F001021A660C4A1B6E936843F001037A +:1030900093604FF0804353229A624FF0FF32DA621E +:1030A00000229A615A63DA605A6001225A611A60FA +:1030B000704700BF00380240002004E04FF080421B +:1030C00008B51169D3680B40D9B2C9439B07116198 +:1030D00007D5302383F31188FEF74EFB002383F3DB +:1030E000118808BD1F4B1A696FEAC2526FEAD252AB +:1030F0001A611A69C2F308021A614FF0FF301A69A7 +:103100005A69586100215A6959615A691A6A62F00C +:1031100080521A621A6A02F080521A621A6A5A6A55 +:1031200058625A6A59625A6A1A6C42F080521A649A +:103130001A6E42F080521A661A6E0B4A106840F4FA +:1031400080701060186F00F44070B0F5007F1EBFF3 +:103150004FF4803018671967536823F40073536085 +:1031600000F054B90038024000700040334B4FF07B +:1031700080521A64324A4FF4404111601A6842F09A +:1031800001021A601A689107FCD59A6822F00302BE +:103190009A602A4B9A6812F00C02FBD1196801F070 +:1031A000F90119609A601A6842F480321A601A684C +:1031B0009203FCD55A6F42F001025A671F4B5A6FB7 +:1031C0009007FCD51F4A5A601A6842F080721A6054 +:1031D0001B4A53685904FCD5184B1A689201FCD558 +:1031E000194A9A60194B1A68194B9A42194B21D106 +:1031F000194A1168194A91421CD140F205121A600D +:10320000144A136803F00F03052BFAD10B4B9A688D +:1032100042F002029A609A6802F00C02082AFAD17F +:103220005A6C42F480425A645A6E42F480425A66A2 +:103230005B6E704740F20572E1E700BF0038024064 +:10324000007000400854400700948838002004E0D3 +:1032500011640020003C024000ED00E041C20F413B +:10326000074A08B5536903F00103536123B1054AC6 +:1032700013680BB150689847BDE80840FFF7D0BE0F +:10328000003C0140E02D0020074A08B5536903F0D7 +:103290000203536123B1054A93680BB1D068984784 +:1032A000BDE80840FFF7BCBE003C0140E02D002017 +:1032B000074A08B5536903F00403536123B1054A73 +:1032C00013690BB150699847BDE80840FFF7A8BEE5 +:1032D000003C0140E02D0020074A08B5536903F087 +:1032E0000803536123B1054A93690BB1D06998472C +:1032F000BDE80840FFF794BE003C0140E02D0020EF +:10330000074A08B5536903F01003536123B1054A16 +:10331000136A0BB1506A9847BDE80840FFF780BEBA +:10332000003C0140E02D0020164B10B55C6904F410 +:1033300078725A61A30604D5134A936A0BB1D06A16 +:103340009847600604D5104A136B0BB1506B984731 +:10335000210604D50C4A936B0BB1D06B9847E2055C +:1033600004D5094A136C0BB1506C9847A30504D5DA +:10337000054A936C0BB1D06C9847BDE81040FFF73D +:103380004FBE00BF003C0140E02D0020194B10B59E +:103390005C6904F47C425A61620504D5164A136DD7 +:1033A0000BB1506D9847230504D5134A936D0BB1AB +:1033B000D06D9847E00404D50F4A136E0BB1506EE0 +:1033C0009847A10404D50C4A936E0BB1D06E984770 +:1033D000620404D5084A136F0BB1506F9847230459 +:1033E00004D5054A936F0BB1D06F9847BDE81040E4 +:1033F000FFF716BE003C0140E02D002008B5FFF7A6 +:103400005DFEBDE80840FFF70BBE0000062108B5D1 +:103410000846FFF71DFB06210720FFF719FB0621D1 +:103420000820FFF715FB06210920FFF711FB0621F5 +:103430000A20FFF70DFB06211720FFF709FB0621E5 +:103440002820FFF705FBBDE8084007211C20FFF7F7 +:10345000FFBA000008B5FFF745FE00F00BF8FDF7D6 +:1034600053FEFDF72BFDFFF7A5FDBDE80840FFF774 +:10347000CFBC00000023054A19460133102BC2E9D6 +:10348000001102F10802F8D1704700BFE02D0020C2 +:10349000034611F8012B03F8012B002AF9D17047DC +:1034A00053544D3332463F3F3F0053544D33324621 +:1034B0003430780053544D3332463432780053540C +:1034C0004D33324634343658580000000120330062 +:1034D0000010410001105A0003105900071031007C +:1034E00000000000A034000813040000AA34000803 +:1034F00019040000B434000821040000BE340008A0 +:1035000000000000390E0008250E0008610E0008BA +:103510004D0E0008590E0008450E0008310E000837 +:103520001D0E00086D0E00080000000001000000E4 +:10353000000000006330000034350008F023002054 +:10354000002600204172647550696C6F740025423A +:103550004F415244252D424C002553455249414C80 +:1035600025000000020000000000000055100008C7 +:10357000C110000840004000A02A0020B02A00200E +:103580000200000000000000030000000000000036 +:10359000051100080000000010000000C02A0020F3 +:1035A000000000000100000000000000682D002065 +:1035B00001010200051C0008151B0008B11B0008D2 +:1035C000951B000843000000CC35000809024300A9 +:1035D000020100C0320904000001020201000524BA +:1035E0000010010524010001042402020524060044 +:1035F00001070582030800FF09040100020A000018 +:10360000000705010240000007058102400000009C +:1036100012000000183600081201100102000040DC +:1036200009124157000201020301000004030904CA +:1036300025424F41524425005370656564794265C7 +:1036400065463430354D696E69003031323334357A +:1036500036373839414243444546000000400000B7 +:103660000040000000400000004000000000010099 +:103670000000020000000200000002000000020042 +:103680000000020000000200000002000000000034 +:103690004912000801150008AD150008400040005F +:1036A000C82D0020C82D002001000000D82D0020CA +:1036B0008000000040010000030000006D61696EA1 +:1036C0000069646C650000000001812A00000000B0 +:1036D000AAAAAAAA00010024FFFE00000000000020 +:1036E00000A00A000000000100000000AAAAAAAA87 +:1036F00000000001FFFF00000000000000000000CB +:103700000000001000000000AAAAAAAA00000010F1 +:10371000FFFF0000000000000000000000000000AB +:1037200000000000AAAAAAAA00000000FFFF0000F3 +:103730000000000000000000000000000000000089 +:10374000AAAAAAAA00000000FFFF000000000000D3 +:10375000000000000000000000000000AAAAAAAAC1 +:1037600000000000FFFF000000000000000000005B +:103770000000000000000000AAAAAAAA00000000A1 +:10378000FFFF00000000000000000000000000003B +:10379000000000000A00000000000000030000001C +:1037A0000000000000000000000000000000000019 +:1037B0000000000000000000000000000000000009 +:1037C00000000000000000006F0400000000000086 +:1037D00000400F0000000000FF00960000000008FD +:1037E0000096000000000800040000002C360008CD +:1037F00000000000000000000000000000000000C9 +:083800000000000000000000C0 +:00000001FF diff --git a/Tools/bootloaders/TMotorH743_bl.bin b/Tools/bootloaders/TMotorH743_bl.bin new file mode 100644 index 00000000000000..550f14faac3d6f Binary files /dev/null and b/Tools/bootloaders/TMotorH743_bl.bin differ diff --git a/Tools/bootloaders/TMotorH743_bl.hex b/Tools/bootloaders/TMotorH743_bl.hex new file mode 100644 index 00000000000000..7310b38e90ac1e --- /dev/null +++ b/Tools/bootloaders/TMotorH743_bl.hex @@ -0,0 +1,1005 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008DD340008F0 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008C5380008F138000890 +:100060001D3900084939000875390008E302000805 +:10007000E3020008E3020008E3020008E3020008CC +:10008000E3020008E3020008E3020008E3020008BC +:10009000E3020008E3020008E3020008A1390008B7 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E000053A0008E3020008E3020008E302000802 +:1000F000E3020008E3020008E3020008E30200084C +:10010000E3020008E3020008793A0008E30200086D +:10011000E3020008E3020008E3020008E30200082B +:10012000E3020008E3020008E3020008E30200081B +:10013000E3020008E3020008E3020008E30200080B +:10014000E3020008E3020008E3020008E3020008FB +:10015000E3020008E3020008E3020008E3020008EB +:10016000E3020008E3020008E3020008E3020008DB +:10017000E30200085D2E0008E3020008E302000825 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008492E0008E3020008E3020008D9 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F01F0F2FF7E +:1003500003F016F84FF055301F491B4A91423CBF3D +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F00AF803F074F8E6 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E701F0F2BF000600200022002074 +:1003D0000000000808ED00E00000002000060020FA +:1003E000503E0008002200205C22002060220020F5 +:1003F00034430020E0020008E0020008E0020008A8 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0F8FAFEE701F005 +:1004300061FA00DFFEE7000038B500F0CDFB01F007 +:1004400039FF054601F06CFF0446D0B90F4B9D42C1 +:1004500019D001339D4241F2883512BF0446002570 +:100460000124002001F030FF0CB100F077F800F01B +:100470004BFD00F007FC284600F010F900F06EF884 +:10048000F9E70025EDE70546EBE700BF010007B0FF +:1004900008B500F0C9FBA0F120035842584108BD3F +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000D9FB03B05DF804FB38B5302383F3118812 +:1004C000174803680BB101F075FB0023154A4FF480 +:1004D0007A71134801F064FB002383F31188124CF6 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F07CFC322363602B78032B07D16368F7 +:100510002BB9022000F072FC4FF47A73636038BD8F +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F051BC022000F044BC024B00220B +:100550005A6070477822002080230020F8B5494B6C +:10056000494A1C461968013100F08A8004339342DD +:10057000F8D16268454B9A4240F28280444B9B68B6 +:1005800003F1006303F5C0239A4279D2002000F002 +:1005900093FB0220FFF7CCFF3E4B0021D3F8E8206D +:1005A000C3F8E810D3F81021C3F81011D3F81021C4 +:1005B000D3F8EC20C3F8EC10D3F81421C3F81411CD +:1005C000D3F81421D3F8F020C3F8F010D3F8182191 +:1005D000C3F81811D3F81821D3F8802042F0007224 +:1005E000C3F88020D3F8802022F00072C3F8802066 +:1005F000D3F8803072B64FF0E023C3F8084DD4E949 +:100600000004BFF34F8FBFF36F8F234AC2F88410EB +:10061000BFF34F8F536923F480335361BFF34F8F80 +:10062000D2F8803043F6E076C3F3C905C3F34E3306 +:100630005B0103EA060C29464CEA81770139C2F8CE +:100640007472F9D2203B13F1200FF2D1BFF34F8F18 +:10065000BFF36F8FBFF34F8FBFF36F8F536923F4D7 +:10066000003353610023C2F85032BFF34F8FBFF302 +:100670006F8F302383F31188854680F308882047E5 +:10068000F8BD00BF0000060820000608FFFF0508AF +:10069000002200200044025800ED00E02DE9F04F58 +:1006A00093B0B44B2022FF2100900AA89D6800F06F +:1006B000D5FBB14A1378A3B90121B048117003608A +:1006C000302383F3118803680BB101F073FA002320 +:1006D000AB4A4FF47A71A94801F062FA002383F320 +:1006E0001188009B13B1A74B009A1A60A64A137891 +:1006F000032B03D000231370A24A53604FF0000A6B +:10070000009CD3465646D146012000F06DFB24B133 +:100710009C4B1B68002B00F02682002000F084FA1E +:100720000390039B002BF2DB012000F053FB039BA3 +:10073000213B1F2BE8D801A252F823F0BD07000887 +:10074000E5070008790800080907000809070008FC +:10075000090700080B090008DB0A0008F509000872 +:10076000570A00087F0A0008A50A000809070008C0 +:10077000B70A000809070008290B00085D080008EF +:10078000090700086D0B0008C90700085D0800088C +:1007900009070008570A00080907000809070008A8 +:1007A00009070008090700080907000809070008E9 +:1007B0000907000809070008790800080220FFF768 +:1007C00067FE002840F0F981009B022105A8BAF1DC +:1007D000000F08BF1C4641F21233ADF8143000F090 +:1007E00041FA91E74FF47A7000F01EFA071EEBDB36 +:1007F0000220FFF74DFE0028E6D0013F052F00F252 +:10080000DE81DFE807F0030A0D101336052304210B +:1008100005A8059300F026FA17E004215548F9E7EA +:1008200004215A48F6E704215948F3E74FF01C0821 +:10083000404608F1040800F041FA0421059005A89B +:1008400000F010FAB8F12C0FF2D101204FF000099E +:1008500000FA07F747EA0B0B5FFA8BFB00F04AFB45 +:1008600026B10BF00B030B2B08BF0024FFF718FE7B +:100870004AE704214748CDE7002EA5D00BF00B0333 +:100880000B2BA1D10220FFF703FE074600289BD0C7 +:100890000120002600F010FA0220FFF749FE1FFA9F +:1008A00086F8404600F018FA0446B0B10399404675 +:1008B0000136A1F140025142514100F01DFA0028D9 +:1008C000EDD1BA46044641F21213022105A83E4674 +:1008D000ADF8143000F0C6F916E725460120FFF701 +:1008E00027FE244B9B68AB4207D9284600F0E6F967 +:1008F000013040F067810435F3E70025224BBA460A +:100900003E461D701F4B5D60A8E7002E3FF45CAFB4 +:100910000BF00B030B2B7FF457AF0220FFF708FE01 +:10092000322000F081F9B0F10008FFF64DAF18F069 +:1009300003077FF449AF0F4A08EB0503926893421F +:100940003FF642AFB8F5807F3FF73EAF124BB84558 +:10095000019323DD4FF47A7000F066F90390039A57 +:10096000002AFFF631AF039A0137019B03F8012BF0 +:10097000EDE700BF002200207C2300206022002041 +:10098000B9040008802300207822002004220020DF +:10099000082200200C2200207C220020C820FFF723 +:1009A00077FD074600283FF40FAF1F2D11D8C5F182 +:1009B00020020AAB25F0030084494245184428BFB1 +:1009C0004246019200F024FA019AFF217F4800F08C +:1009D00045FA4FEAA803C8F387027C4928460193E9 +:1009E00000F044FA064600283FF46DAF019B05EB8A +:1009F000830533E70220FFF74BFD00283FF4E4AE08 +:100A000000F098F900283FF4DFAE0027B846704B9D +:100A10009B68BB4218D91F2F11D80A9B01330ED0F7 +:100A200027F0030312AA134453F8203C05934046D1 +:100A3000042205A9043700F093FA8046E7E7384618 +:100A400000F03CF90590F2E7CDF81480042105A8E8 +:100A500000F008F902E70023642104A8049300F0E1 +:100A6000F7F800287FF4B0AE0220FFF711FD002850 +:100A70003FF4AAAE049800F053F90590E6E700238E +:100A8000642104A8049300F0E3F800287FF49CAEEE +:100A90000220FFF7FDFC00283FF496AE049800F01A +:100AA00041F9EAE70220FFF7F3FC00283FF48CAE9F +:100AB00000F050F9E1E70220FFF7EAFC00283FF4DC +:100AC00083AE05A9142000F04BF9074604210490D9 +:100AD00004A800F0C7F83946B9E7322000F0A4F8BE +:100AE000071EFFF671AEBB077FF46EAE384A07EB08 +:100AF0000903926893423FF667AE0220FFF7C8FCF5 +:100B000000283FF461AE27F003074F44B9453FF496 +:100B1000A5AE484609F1040900F0D0F8042105907B +:100B200005A800F09FF8F1E74FF47A70FFF7B0FCEA +:100B300000283FF449AE00F0FDF8002844D00A9B9D +:100B400001330BD008220AA9002000F08FF90028F9 +:100B50003AD02022FF210AA800F080F9FFF7A0FC7C +:100B60001C4800F061FF13B0BDE8F08F002E3FF489 +:100B70002BAE0BF00B030B2B7FF426AE002364216E +:100B800005A8059300F064F8074600287FF41CAE22 +:100B90000220FFF77DFC804600283FF415AEFFF7EA +:100BA0007FFC41F2883000F03FFF059800F0D6F955 +:100BB00046463C4600F09EF9A6E506464EE64FF056 +:100BC000000901E6BA467EE637467CE67C22002034 +:100BD00000220020A0860100704700000F4B70B576 +:100BE0001B780C460133DBB2012B11D80C4D4FF4AE +:100BF0007A732968A2FB033222460E6A0146284610 +:100C0000B047844204D1074B002201201A7070BD06 +:100C10004FF4FA7000F008FF0020F8E710220020DF +:100C200028260020B4230020002307B50246012116 +:100C30000DF107008DF80730FFF7D0FF20B19DF8C8 +:100C4000070003B05DF804FB4FF0FF30F9E7000048 +:100C50000A46042108B5FFF7C1FF80F00100C0B2C9 +:100C6000404208BD30B4054C0A4601462368204680 +:100C7000DD69034BAC4630BC604700BF282600202E +:100C8000A086010070B50A4E00240A4D01F0EAF971 +:100C9000308028683388834208D901F0DFF92B6857 +:100CA00004440133B4F5C02F2B60F2D370BD00BFF4 +:100CB000B62300208823002001F0B2BA00F10060C2 +:100CC00000F5C0200068704700F10060920000F558 +:100CD000C02001F029BA0000054B1A68054B1B889B +:100CE0009B1A834202D9104401F0B8B90020704722 +:100CF00088230020B623002038B50446074D29B1CB +:100D000028682044BDE8384001F0C0B92868204474 +:100D100001F0AAF90028F3D038BD00BF88230020D5 +:100D20000020704700F1FF5000F58F10D0F8000848 +:100D300070470000064991F8243033B1002308229F +:100D4000086A81F82430FFF7BFBF0120704700BF59 +:100D50008C230020014B1868704700BF0010005C16 +:100D6000194B01380322084470B51D68174BC5F3B1 +:100D70000B042D0C1E88A6420BD15C680A46013C70 +:100D8000824213460FD214F9016F4EB102F8016B83 +:100D9000F6E7013A03F10803ECD181420B4602D297 +:100DA0002C2203F8012B0424094A1688AE4204D1F0 +:100DB000984284BF967803F8016B013C02F104026B +:100DC000F3D1581A70BD00BF0010005C142200203F +:100DD000703B0008022803D1024B4FF080729A61E9 +:100DE000704700BF00000258022803D1024B4FF4A5 +:100DF00080729A61704700BF00000258022804D137 +:100E0000024A536983F480735361704700000258AB +:100E1000002310B5934203D0CC5CC4540133F9E7EE +:100E200010BD0000013810B510F9013F3BB191F938 +:100E300000409C4203D11AB10131013AF4E71AB1E2 +:100E400091F90020981A10BD1046FCE703460246AF +:100E5000D01A12F9011B0029FAD170470244034647 +:100E6000934202D003F8011BFAE770472DE9F843DB +:100E70001F4D14460746884695F8242052BBDFF8DC +:100E800070909CB395F824302BB92022FF2148465E +:100E90002F62FFF7E3FF95F824004146C0F10802F6 +:100EA00005EB8000A24228BF2246D6B29200FFF78F +:100EB000AFFF95F82430A41B17441E449044E4B2BD +:100EC000F6B2082E85F82460DBD1FFF733FF002847 +:100ED000D7D108E02B6A03EB82038342CFD0FFF720 +:100EE00029FF0028CBD10020BDE8F8830120FBE7D3 +:100EF0008C230020024B1A78024B1A70704700BFF7 +:100F0000B42300201022002010B5104C104800F02F +:100F1000B9F821460E4800F0E1F824680D48D4F8ED +:100F20009020D2F8043843F00203C2F8043800F0ED +:100F30007BFD0949204600F0DFF9D4F89020D2F873 +:100F4000043823F00203C2F8043810BD2C3C00081A +:100F50002826002040420F00343C00087047000063 +:100F600030B50A44084D91420DD011F8013B58406C +:100F7000082340F30004013B2C4013F0FF0384EAF4 +:100F80005000F6D1EFE730BD2083B8ED026843682A +:100F90001143016003B118477047000013B5406B5F +:100FA00000F58054D4F8A4381A681178042914D1B3 +:100FB000017C022911D11979012312898B40134236 +:100FC0000BD101A94C3002F091F8D4F8A4480246A4 +:100FD000019B2179206800F0DFF902B010BD00000C +:100FE000143002F013B800004FF0FF33143002F059 +:100FF0000DB800004C3002F0E5B800004FF0FF33B0 +:101000004C3002F0DFB80000143001F0E1BF000006 +:101010004FF0FF31143001F0DBBF00004C3002F024 +:10102000B1B800004FF0FF324C3002F0ABB8000016 +:101030000020704710B500F58054D4F8A4381A6821 +:101040001178042917D1017C022914D1597901237F +:1010500052898B4013420ED1143001F073FF0246C7 +:1010600048B1D4F8A4484FF4407361792068BDE8D2 +:10107000104000F07FB910BD406BFFF7DBBF0000F0 +:10108000704700007FB5124B01250426044603601B +:101090000023057400F1840243602946C0E902334D +:1010A0000C4B0290143001934FF44073009601F002 +:1010B00025FF094B04F69442294604F14C000294A2 +:1010C000CDE900634FF4407301F0ECFF04B070BD54 +:1010D000803B0008791000089D0F00080A68302343 +:1010E00083F311880B790B3342F823004B791333C8 +:1010F00042F823008B7913B10B3342F8230000F53B +:101100008053C3F8A41802230374002080F31188CD +:101110007047000038B5037F044613B190F854308F +:10112000ABB90125201D0221FFF730FF04F11400A7 +:101130006FF00101257700F09FFC04F14C0084F86A +:1011400054506FF00101BDE8384000F095BC38BD47 +:1011500010B5012104460430FFF718FF0023237760 +:1011600084F8543010BD000038B504460025143012 +:1011700001F0DCFE04F14C00257701F0ABFF201DEF +:1011800084F854500121FFF701FF2046BDE83840A4 +:10119000FFF750BF90F8803003F06003202B06D19A +:1011A00090F881200023212A03D81F2A06D8002086 +:1011B0007047222AFBD1C0E91D3303E0034A42678E +:1011C00007228267C3670120704700BF2C220020DE +:1011D00037B500F58055D5F8A4381A681178042978 +:1011E0001AD1017C022917D11979012312898B4068 +:1011F000134211D100F14C04204602F02BF858B1F3 +:1012000001A9204601F072FFD5F8A4480246019BCF +:101210002179206800F0C0F803B030BD01F10B0364 +:10122000F0B550F8236085B004460D46FEB130237A +:1012300083F3118804EB8507301D0821FFF7A6FE14 +:10124000FB6806F14C005B691B681BB1019001F063 +:101250005BFF019803A901F049FF024648B1039BD7 +:101260002946204600F098F8002383F3118805B042 +:10127000F0BDFB685A691268002AF5D01B8A013B51 +:101280001340F1D104F18002EAE70000133138B5D0 +:1012900050F82140ECB1302383F3118804F58053DA +:1012A000D3F8A4281368527903EB8203DB689B69A7 +:1012B0005D6845B104216018FFF768FE294604F116 +:1012C000140001F049FE2046FFF7B4FE002383F32B +:1012D000118838BD7047000001F000B90123402299 +:1012E000002110B5044600F8303BFFF7B7FD00239E +:1012F000C4E9013310BD000010B53023044683F368 +:1013000011882422416000210C30FFF7A7FD204600 +:1013100001F006F902230020237080F3118810BD2C +:1013200070B500EB8103054650690E461446DA603D +:1013300018B110220021FFF791FDA06918B1102209 +:101340000021FFF78BFD31462846BDE8704001F0D3 +:10135000EDB9000083682022002103F0011310B5CD +:10136000044683601030FFF779FD2046BDE8104049 +:1013700001F068BAF0B4012500EB810447898D4083 +:10138000E4683D43A469458123600023A260636053 +:10139000F0BC01F085BA0000F0B4012500EB810437 +:1013A00007898D40E4683D4364690581236000231B +:1013B000A2606360F0BC01F0FBBA000070B50223CC +:1013C00000250446242203702946C0F888500C30BA +:1013D00040F8045CFFF742FD204684F8705001F0AD +:1013E00039F963681B6823B129462046BDE870407F +:1013F000184770BD0378052B10B504460AD080F855 +:101400008C300523037043681B680BB10421984797 +:101410000023A36010BD00000178052906D190F8D3 +:101420008C20436802701B6803B1184770470000A6 +:1014300070B590F87030044613B1002380F8703016 +:1014400004F18002204601F021FA63689B68B3B979 +:1014500094F8803013F0600535D00021204601F06B +:1014600013FD0021204601F003FD63681B6813B1E2 +:10147000062120469847062384F8703070BD204628 +:1014800098470028E4D0B4F88630A26F9A4288BF0B +:10149000A36794F98030A56F002B4FF0300380F2E2 +:1014A0000381002D00F0F280092284F8702083F37C +:1014B000118800212046D4E91D23FFF76DFF00238A +:1014C00083F31188DAE794F8812003F07F0343EA7D +:1014D000022340F20232934200F0C58021D8B3F5D6 +:1014E000807F48D00DD8012B3FD0022B00F0938095 +:1014F000002BB2D104F1880262670222A267E3677F +:10150000C1E7B3F5817F00F09B80B3F5407FA4D1A4 +:1015100094F88230012BA0D1B4F8883043F0020354 +:1015200032E0B3F5006F4DD017D8B3F5A06F31D0CE +:10153000A3F5C063012B90D86368204694F88220FD +:101540005E6894F88310B4F88430B047002884D0E3 +:10155000436863670368A3671AE0B3F5106F36D07A +:1015600040F6024293427FF478AF5C4B63670223FC +:10157000A3670023C3E794F88230012B7FF46DAF9B +:10158000B4F8883023F00203A4F88830C4E91D556C +:10159000E56778E7B4F88030B3F5A06F0ED194F822 +:1015A0008230204684F88A3001F0B2F863681B6804 +:1015B00013B1012120469847032323700023C4E977 +:1015C0001D339CE704F18B0363670123C3E7237892 +:1015D000042B10D1302383F311882046FFF7BAFE85 +:1015E00085F311880321636884F88B5021701B6890 +:1015F0000BB12046984794F88230002BDED084F857 +:101600008B300423237063681B68002BD6D0022123 +:1016100020469847D2E794F8843020461D0603F010 +:101620000F010AD501F024F9012804D002287FF423 +:1016300014AF2B4B9AE72B4B98E701F00BF9F3E72C +:1016400094F88230002B7FF408AF94F8843013F0C4 +:101650000F01B3D01A06204602D501F02DFCADE7EC +:1016600001F01EFCAAE794F88230002B7FF4F5AE5F +:1016700094F8843013F00F01A0D01B06204602D549 +:1016800001F002FC9AE701F0F3FB97E7142284F8DB +:10169000702083F311882B462A4629462046FFF7FF +:1016A00069FE85F31188E9E65DB1152284F87020A2 +:1016B00083F3118800212046D4E91D23FFF75AFE49 +:1016C000FDE60B2284F8702083F311882B462A460E +:1016D00029462046FFF760FEE3E700BFB03B000865 +:1016E000A83B0008AC3B000838B590F870300446C1 +:1016F000002B3ED0063BDAB20F2A34D80F2B32D85B +:10170000DFE803F037313108223231313131313104 +:1017100031313737856FB0F886309D4214D2C368B7 +:101720001B8AB5FBF3F203FB12556DB9302383F32B +:1017300011882B462A462946FFF72EFE85F311888D +:101740000A2384F870300EE0142384F870303023BC +:1017500083F31188002320461A461946FFF70AFE34 +:10176000002383F3118838BDC36F03B1984700236A +:10177000E7E70021204601F087FB0021204601F029 +:1017800077FB63681B6813B1062120469847062340 +:10179000D7E7000010B590F870300446142B29D01C +:1017A00017D8062B05D001D81BB110BD093B022B61 +:1017B000FBD80021204601F067FB0021204601F004 +:1017C00057FB63681B6813B1062120469847062320 +:1017D00019E0152BE9D10B2380F87030302383F307 +:1017E000118800231A461946FFF7D6FD002383F31C +:1017F0001188DAE7C3689B695B68002BD5D1C36F9A +:1018000003B19847002384F87030CEE70023826844 +:10181000037503691B6899689142FBD25A6803609B +:101820004260106058607047002382680375036946 +:101830001B6899689142FBD85A6803604260106047 +:101840005860704708B50846302383F311880B7D34 +:10185000032B05D0042B0DD02BB983F3118808BDC1 +:101860008B6900221A604FF0FF338361FFF7CEFFD0 +:101870000023F2E7D1E9003213605A60F3E7000079 +:10188000FFF7C4BF054BD968087518680268536034 +:101890001A600122D8600275FEF7B4BDB82300209B +:1018A0000C4B30B5DD684B1C87B004460FD02B467F +:1018B000094A684600F074F92046FFF7E3FF009BF1 +:1018C00013B1684600F076F9A86907B030BDFFF79C +:1018D000D9FFF9E7B823002045180008044B1A681F +:1018E000DB6890689B68984294BF00200120704795 +:1018F000B8230020084B10B51C68D86822685360D4 +:101900001A600122DC602275FFF78EFF0146204637 +:10191000BDE81040FEF776BDB8230020044B1A68DE +:10192000DB6892689B689A4201D9FFF7E3BF704772 +:10193000B823002038B5074C012300250649074885 +:101940002370656001F0C4FC0223237085F31188C5 +:1019500038BD00BF20260020B83B0008B823002077 +:1019600000F05EB9EFF3118020B9EFF30583302268 +:1019700082F311887047000010B530B9EFF3058489 +:10198000C4F3080414B180F3118810BDFFF7C6FF3B +:1019900084F31188F9E70000034A516853685B1A21 +:1019A0009842FBD8704700BF001000E08B60022314 +:1019B000086108468B8270478368A3F1840243F86C +:1019C000142C026943F8442C426943F8402C094A1C +:1019D00043F8242CC268A3F1200043F8182C0222FB +:1019E00003F80C2C002203F80B2C034A43F8102CAC +:1019F000704700BF1D040008B823002008B5FFF79A +:101A0000DBFFBDE80840FFF73BBF0000024BDB688F +:101A100098610F20FFF736BFB8230020302383F3EF +:101A20001188FFF7F3BF000008B50146302383F3A8 +:101A300011880820FFF734FF002383F3118808BDC5 +:101A4000064BDB6839B1426818605A601360436026 +:101A50000420FFF725BF4FF0FF307047B823002068 +:101A60000368984206D01A6802605060184699616F +:101A7000FFF706BF7047000038B504460D462068E2 +:101A8000844200D138BD036823605C608561FFF744 +:101A9000F7FEF4E7036810B59C68A2420CD85C68B6 +:101AA0008A600B604C602160596099688A1A9A605C +:101AB0004FF0FF33836010BD121B1B68ECE7000082 +:101AC0000A2938BF0A2170B504460D460A26601956 +:101AD00001F0F6FB01F0DEFB041BA54203D8751CE8 +:101AE00004462E46F3E70A2E04D90120BDE87040D3 +:101AF00001F02EBC70BD0000F8B5144B0D460A2A4B +:101B00004FF00A07D96103F11001826038BF0A2241 +:101B1000416019691446016048601861A81801F015 +:101B2000BFFB01F0B7FB431B0646A34206D37C1C58 +:101B300028192746354601F0C3FBF2E70A2F04D9DE +:101B40000120BDE8F84001F003BCF8BDB823002037 +:101B5000F8B506460D4601F09DFB0F4A134653F8B3 +:101B6000107F9F4206D12A4601463046BDE8F84024 +:101B7000FFF7C2BFD169BB68441A2C1928BF2C4695 +:101B8000A34202D92946FFF79BFF2246314603486C +:101B9000BDE8F840FFF77EBFB8230020C82300202F +:101BA000C0E90323002310B45DF8044B4361FFF741 +:101BB000CFBF000010B5194C236998420DD0816841 +:101BC000D0E9003213605A609A680A449A60002390 +:101BD00003604FF0FF33A36110BD0268234643F852 +:101BE000102F53600022026022699A4203D1BDE89F +:101BF000104001F05FBB936881680B44936001F073 +:101C000049FB2269E1699268441AA242E4D911446D +:101C1000BDE81040091AFFF753BF00BFB8230020EA +:101C20002DE9F047DFF8BC8008F110072C4ED8F8FA +:101C3000105001F02FFBD8F81C40AA68031B9A42F1 +:101C40003ED814444FF00009D5E90032C8F81C40D2 +:101C500013605A60C5F80090D8F81030B34201D133 +:101C600001F028FB89F31188D5E90331284698470C +:101C7000302383F311886B69002BD8D001F00AFB65 +:101C80006A69A0EB040982464A450DD2022001F0A0 +:101C90005FFB0022D8F81030B34208D151462846E5 +:101CA000BDE8F047FFF728BF121A2244F2E712EB13 +:101CB00009092946384638BF4A46FFF7EBFEB5E723 +:101CC000D8F81030B34208D01444C8F81C00211AC8 +:101CD000A960BDE8F047FFF7F3BEBDE8F08700BF9D +:101CE000C8230020B823002000207047FEE7000032 +:101CF000704700004FF0FF307047000002290CD001 +:101D0000032904D00129074818BF00207047032A7F +:101D100005D8054800EBC200704704487047002012 +:101D2000704700BF903C00083C220020443C000863 +:101D300070B59AB005460846144601A900F0C2F8ED +:101D400001A8FFF783F8431C0022C6B25B001046CF +:101D5000C5E9003423700323023404F8013C01ABCD +:101D6000D1B202348E4201D81AB070BD13F8011BF3 +:101D7000013204F8010C04F8021CF1E708B5302325 +:101D800083F311880348FFF723FA002383F31188B4 +:101D900008BD00BF2826002090F8803003F01F0205 +:101DA000012A07D190F881200B2A03D10023C0E932 +:101DB0001D3315E003F06003202B08D1B0F8843008 +:101DC0002BB990F88120212A03D81F2A04D8FFF7C5 +:101DD000E1B9222AEBD0FAE7034A42670722826779 +:101DE000C3670120704700BF3322002007B50529D3 +:101DF00017D8DFE801F0191603191920302383F3EF +:101E00001188104A01210190FFF78AFA01980221F6 +:101E10000D4AFFF785FA0D48FFF7A6F9002383F373 +:101E2000118803B05DF804FB302383F31188074861 +:101E3000FFF770F9F2E7302383F311880348FFF7C7 +:101E400087F9EBE7E43B0008083C0008282600205F +:101E500038B50C4D0C4C2A460C4904F10800FFF72C +:101E600067FF05F1CA0204F110000949FFF760FF9E +:101E700005F5CA7204F118000649BDE83840FFF7BD +:101E800057BF00BF003F00203C220020C43B000899 +:101E9000CE3B0008D93B000870B5044608460D4605 +:101EA000FEF7D4FFC6B22046013403780BB91846BA +:101EB00070BD32462946FEF7B5FF0028F3D1012058 +:101EC000F6E700002DE9F84F05460C46FEF7BEFF89 +:101ED0002C49C6B22846FFF7DFFF08B10336F6B239 +:101EE00029492846FFF7D8FF08B11036F6B2632E0D +:101EF0000DD8DFF89080DFF89090244FDFF894A0A1 +:101F0000DFF894B02E7846B92670BDE8F88F2946E0 +:101F10002046BDE8F84F01F00DBE252E2ED1072238 +:101F200041462846FEF77EFF70B9DBF800300735E2 +:101F30000A3444F80A3CDBF8043044F8063CBBF8A9 +:101F4000083024F8023CDDE7082249462846FEF71F +:101F500069FF98B9A21C0E4B197802320909C95DB4 +:101F600002F8041C13F8011B01F00F015345C95D71 +:101F700002F8031CF0D118340835C3E7013504F822 +:101F8000016BBFE7B03C0008D93B0008C33C000828 +:101F900000E8F11F0CE8F11FB83C0008BFF34F8FB9 +:101FA000044B1A695107FCD1D3F810215207F8D11C +:101FB000704700BF0020005208B50D4B1B78ABB92D +:101FC000FFF7ECFF0B4BDA68D10704D50A4A5A60D9 +:101FD00002F188325A60D3F80C21D20706D5064A9E +:101FE000C3F8042102F18832C3F8042108BD00BF00 +:101FF0005E410020002000522301674508B5114BC7 +:102000001B78F3B9104B1A69510703D5DA6842F00F +:102010004002DA60D3F81021520705D5D3F80C211D +:1020200042F04002C3F80C21FFF7B8FF064BDA6814 +:1020300042F00102DA60D3F80C2142F00102C3F849 +:102040000C2108BD5E410020002000520F289ABFDD +:1020500000F5806040040020704700004FF400301D +:1020600070470000102070470F2808B50BD8FFF705 +:10207000EDFF00F500330268013204D104308342E1 +:10208000F9D1012008BD0020FCE700000F2870B541 +:10209000054645D8FFF766FC224CFFF77FFF064652 +:1020A000FFF78AFF4FF0FF33072D6361C4F8143147 +:1020B00020D82361FFF772FF2B0243F02403E36073 +:1020C000E36843F08003E36023695A07FCD42846A1 +:1020D000FFF764FF4FF40031FFF7B8FF00F002F99B +:1020E0003046FFF78BFFFFF747FC2846BDE87040FE +:1020F000FFF7BABFC4F81031FFF750FFA5F108038E +:102100001B0243F02403C4F80C31D4F80C3143F023 +:102110008003C4F80C31D4F810315B07FBD4D6E748 +:10212000002070BD002000522DE9F84F40EA020364 +:1021300005460C461746D80602D00020BDE8F88FA9 +:1021400027F01F07DFF8D4B0FFF736FF2744BC4263 +:1021500003D10120FFF752FFF0E720222946204655 +:1021600001F0D8FC10B920352034F0E72B4605F1FA +:1021700020021E68711CE0D104339A42F9D1FFF7A6 +:10218000F1FB05F17843234AB3F5801F224B28BFAA +:102190009A4603F1040338BF9046A2F1080228BF13 +:1021A0009846A3F108033ABF9146DA469946FFF7ED +:1021B000F5FEC8F80060A5EB040CD9F8002004F186 +:1021C0001C0142F00202C9F80020221FDAF8006068 +:1021D00016F00506FAD152F8043F8A424CF8023054 +:1021E000F4D1BFF34F8FFFF7D9FE4FF0FF32C8F89D +:1021F0000020D9F8002022F00202C9F80020FFF7E1 +:10220000BBFB20222146284601F084FC0028AAD0EE +:1022100030469FE714200052102100521020005237 +:1022200010B5084C237828B11BB9FFF7C5FE012370 +:10223000237010BD002BFCD02070BDE81040FFF7CC +:10224000DDBE00BF5E4100200244074BD2B210B594 +:10225000904200D110BD441C00B253F8200041F858 +:10226000040BE0B2F4E700BF504000580E4B30B50D +:102270001C6F240405D41C6F1C671C6F44F40044BD +:102280001C670A4C02442368D2B243F48073236073 +:10229000074B904200D130BD441C51F8045B00B2A2 +:1022A00043F82050E0B2F4E70044025800480258D6 +:1022B0005040005807B5012201A90020FFF7C4FFD4 +:1022C000019803B05DF804FB13B50446FFF7F2FF75 +:1022D000A04205D0012201A900200194FFF7C6FF0A +:1022E00002B010BD0144BFF34F8F064B884204D3A8 +:1022F000BFF34F8FBFF36F8F7047C3F85C0220307E +:10230000F4E700BF00ED00E0034B1A681AB9034A76 +:10231000D2F8D0241A607047604100200040025873 +:1023200008B5FFF7F1FF024B1868C0F3806008BDE5 +:102330006041002070B5BFF34F8FBFF36F8F1A4A13 +:102340000021C2F85012BFF34F8FBFF36F8F536954 +:1023500043F400335361BFF34F8FBFF36F8FC2F865 +:102360008410BFF34F8FD2F8803043F6E074C3F38C +:10237000C900C3F34E335B0103EA0406014646EA93 +:1023800081750139C2F86052F9D2203B13F1200F58 +:10239000F2D1BFF34F8F536943F480335361BFF3DE +:1023A0004F8FBFF36F8F70BD00ED00E0FEE70000C0 +:1023B000214B2248224A70B5904237D3214BC11E8F +:1023C000DA1C121A22F003028B4238BF00220021CD +:1023D000FEF744FD1C4A0023C2F88430BFF34F8F40 +:1023E000D2F8803043F6E074C3F3C900C3F34E3330 +:1023F0005B0103EA0406014646EA81750139C2F829 +:102400006C52F9D2203B13F1200FF2D1BFF34F8F62 +:10241000BFF36F8FBFF34F8FBFF36F8F0023C2F8EF +:102420005032BFF34F8FBFF36F8F70BD53F8041B53 +:1024300040F8041BC0E700BFAC3E00083443002056 +:10244000344300203443002000ED00E0074BD3F874 +:10245000D81021EA0001C3F8D810D3F8002122EAED +:102460000002C3F80021D3F800317047004402583D +:1024700070B5D0E9244300224FF0FF359E6804EB8D +:1024800042135101D3F80009002805DAD3F80009F6 +:1024900040F08040C3F80009D3F8000B002805DAAB +:1024A000D3F8000B40F08040C3F8000B01326318F2 +:1024B0009642C3F80859C3F8085BE0D24FF0011305 +:1024C000C4F81C3870BD0000890141F02001016191 +:1024D00003699B06FCD41220FFF75EBA10B50A4CC4 +:1024E0002046FEF7FBFE094BC4F89030084BC4F8B9 +:1024F0009430084C2046FEF7F1FE074BC4F89030AC +:10250000064BC4F8943010BD644100200000084020 +:10251000F83C00080042002000000440043D000890 +:1025200070B503780546012B5CD1434BD0F8904041 +:10253000984258D1414B0E216520D3F8D82042F063 +:102540000062C3F8D820D3F8002142F00062C3F83B +:102550000021D3F80021D3F8802042F00062C3F8B4 +:102560008020D3F8802022F00062C3F88020D3F8C6 +:10257000803000F0ADFC324BE360324BC4F80038E1 +:102580000023D5F89060C4F8003EC02323604FF4C8 +:102590000413A3633369002BFCDA01230C2033619D +:1025A000FFF7FAF93369DB07FCD41220FFF7F4F9DF +:1025B0003369002BFCDA00262846A660FFF758FF97 +:1025C0006B68C4F81068DB68C4F81468C4F81C6849 +:1025D00083BB1D4BA3614FF0FF336361A36843F0DE +:1025E0000103A36070BD194B9842C9D1134B4FF042 +:1025F0008060D3F8D82042F00072C3F8D820D3F816 +:10260000002142F00072C3F80021D3F80021D3F872 +:10261000802042F00072C3F88020D3F8802022F09E +:102620000072C3F88020D3F88030FFF70FFF0E212F +:102630004D209EE7064BCDE7644100200044025840 +:102640004014004003002002003C30C00042002043 +:10265000083C30C0F8B5D0F89040054600214FF056 +:1026600000662046FFF730FFD5F8941000234FF0A6 +:1026700001128F684FF0FF30C4F83438C4F81C28BA +:1026800004EB431201339F42C2F80069C2F8006BA9 +:10269000C2F80809C2F8080BF2D20B68D5F89020EE +:1026A000C5F89830636210231361166916F010069E +:1026B000FBD11220FFF770F9D4F8003823F4FE6341 +:1026C000C4F80038A36943F4402343F01003A36126 +:1026D0000923C4F81038C4F814380B4BEB604FF0E2 +:1026E000C043C4F8103B094BC4F8003BC4F8106960 +:1026F000C4F80039D5F8983003F1100243F4801380 +:10270000C5F89820A362F8BDD43C000840800010B2 +:10271000D0F8902090F88A10D2F8003823F4FE63A5 +:1027200043EA0113C2F80038704700002DE9F8436E +:1027300000EB8103D0F890500C468046DA680FFA1F +:1027400081F94801166806F00306731E022B05EB9B +:1027500041134FF0000194BFB604384EC3F8101B6C +:102760004FF0010104F1100398BF06F1805601FA01 +:1027700003F3916998BF06F5004600293AD0578ABD +:1027800004F15801374349016F50D5F81C180B4329 +:102790000021C5F81C382B180127C3F81019A740D1 +:1027A0005369611E9BB3138A928B9B08012A88BFD1 +:1027B0005343D8F89820981842EA034301F14002A5 +:1027C0002146C8F89800284605EB82025360FFF7BF +:1027D0007BFE08EB8900C3681B8A43EA84534834B4 +:1027E0001E4364012E51D5F81C381F43C5F81C78D0 +:1027F000BDE8F88305EB4917D7F8001B21F4004129 +:10280000C7F8001BD5F81C1821EA0303C0E704F140 +:102810003F030B4A2846214605EB83035A60FFF726 +:1028200053FE05EB4910D0F8003923F40043C0F8FB +:102830000039D5F81C3823EA0707D7E700800010D5 +:1028400000040002D0F894201268C0F89820FFF726 +:102850000FBE00005831D0F8903049015B5813F496 +:10286000004004D013F4001F0CBF02200120704769 +:102870004831D0F8903049015B5813F4004004D03F +:1028800013F4001F0CBF02200120704700EB8101F0 +:10289000CB68196A0B6813604B685360704700007F +:1028A00000EB810330B5DD68AA691368D36019B9FC +:1028B000402B84BF402313606B8A1468D0F89020AB +:1028C0001C4402EB4110013C09B2B4FBF3F4634336 +:1028D000033323F0030343EAC44343F0C043C0F887 +:1028E000103B2B6803F00303012B0ED1D2F80838FC +:1028F00002EB411013F4807FD0F8003B14BF43F08B +:10290000805343F00053C0F8003B02EB4112D2F871 +:10291000003B43F00443C2F8003B30BD2DE9F041D9 +:10292000D0F8906005460C4606EB4113D3F8087BBF +:102930003A07C3F8087B08D5D6F814381B0704D526 +:1029400000EB8103DB685B689847FA071FD5D6F870 +:102950001438DB071BD505EB8403D968CCB98B6928 +:10296000488A5A68B2FBF0F600FB16228AB918684A +:10297000DA6890420DD2121AC3E90024302383F39F +:10298000118821462846FFF78BFF84F31188BDE8A4 +:10299000F081012303FA04F26B8923EA02036B81BD +:1029A000CB68002BF3D021462846BDE8F0411847FC +:1029B00000EB81034A0170B5DD68D0F890306C6996 +:1029C0002668E66056BB1A444FF40020C2F810098E +:1029D0002A6802F00302012A0AB20ED1D3F80808CD +:1029E00003EB421410F4807FD4F8000914BF40F0C8 +:1029F000805040F00050C4F8000903EB4212D2F8B6 +:102A0000000940F00440C2F800090122D3F834085C +:102A100002FA01F10143C3F8341870BD19B9402E10 +:102A200084BF4020206020681A442E8A8419013C0B +:102A3000B4FBF6F440EAC44040F00050C6E70000A2 +:102A40002DE9F843D0F8906005460C464F0106EB9F +:102A50004113D3F8088918F0010FC3F808891CD076 +:102A6000D6F81038DB0718D500EB8103D3F80CC07B +:102A7000DCF81430D3F800E0DA68964530D2A2EBE7 +:102A80000E024FF000091A60C3F80490302383F35C +:102A90001188FFF78DFF89F3118818F0800F1DD082 +:102AA000D6F834380126A640334217D005EB84030C +:102AB0000134D5F89050D3F80CC0E4B22F44DCF8C0 +:102AC000142005EB0434D2F800E05168714514D3AA +:102AD000D5F8343823EA0606C5F83468BDE8F8832B +:102AE000012303FA01F2038923EA02030381DCF8DC +:102AF0000830002BD1D09847CFE7AEEB0103BCF8EC +:102B00001000834228BF0346D7F8180980B2B3EB00 +:102B1000800FE3D89068A0F1040959F8048FC4F835 +:102B20000080A0EB09089844B8F1040FF5D81844C8 +:102B30000B4490605360C8E72DE9F84FD0F89050EF +:102B400004466E69AB691E4016F480586E6103D06E +:102B5000BDE8F84FFEF732BC002E12DAD5F8003E81 +:102B60009B0705D0D5F8003E23F00303C5F8003ECF +:102B7000D5F80438204623F00103C5F80438FEF7E1 +:102B80004BFC370505D52046FFF772FC2046FEF7C3 +:102B900031FCB0040CD5D5F8083813F0060FEB68FB +:102BA00023F470530CBF43F4105343F4A053EB6071 +:102BB00031071BD56368DB681BB9AB6923F00803D9 +:102BC000AB612378052B0CD1D5F8003E9A0705D0D0 +:102BD000D5F8003E23F00303C5F8003E2046FEF77B +:102BE0001BFC6368DB680BB120469847F30200F1D9 +:102BF000BA80B70226D5D4F8909000274FF0010A8A +:102C000009EB4712D2F8003B03F44023B3F5802FC1 +:102C100011D1D2F8003B002B0DDA62890AFA07F3D2 +:102C200022EA0303638104EB8703DB68DB6813B1EB +:102C30003946204698470137D4F89430FFB29B6854 +:102C40009F42DDD9F00619D5D4F89000026AC2F38C +:102C50000A1702F00F0302F4F012B2F5802F00F011 +:102C6000CA80B2F5402F09D104EB8303002200F59E +:102C70008050DB681B6A974240F0B0803003D5F883 +:102C8000185835D5E90303D500212046FFF746FE45 +:102C9000AA0303D501212046FFF740FE6B0303D5AD +:102CA00002212046FFF73AFE2F0303D503212046D9 +:102CB000FFF734FEE80203D504212046FFF72EFE7D +:102CC000A90203D505212046FFF728FE6A0203D595 +:102CD00006212046FFF722FE2B0203D507212046BE +:102CE000FFF71CFEEF0103D508212046FFF716FE73 +:102CF000700340F1A780E90703D500212046FFF7C4 +:102D00009FFEAA0703D501212046FFF799FE6B0716 +:102D100003D502212046FFF793FE2F0703D5032199 +:102D20002046FFF78DFEEE0603D504212046FFF76F +:102D300087FEA80603D505212046FFF781FE690618 +:102D400003D506212046FFF77BFE2A0603D507217F +:102D50002046FFF775FEEB0574D520460821BDE837 +:102D6000F84FFFF76DBED4F890904FF0000B4FF086 +:102D7000010AD4F894305FFA8BF79B689F423FF6C4 +:102D800038AF09EB4713D3F8002902F44022B2F51B +:102D9000802F20D1D3F80029002A1CDAD3F800298B +:102DA00042F09042C3F80029D3F80029002AFBDB47 +:102DB0003946D4F89000FFF787FB22890AFA07F317 +:102DC00022EA0303238104EB8703DB689B6813B1CA +:102DD0003946204698470BF1010BCAE7910701D10C +:102DE000D0F80080072A02F101029CBF03F8018B92 +:102DF0004FEA18283FE704EB830300F58050DA68B8 +:102E0000D2F818C0DCF80820DCE9001CA1EB0C0C9F +:102E100000218F4208D1DB689B699A683A449A6026 +:102E20005A683A445A6029E711F0030F01D1D0F8EB +:102E300000808C4501F1010184BF02F8018B4FEA4B +:102E40001828E6E7BDE8F88F08B50348FFF774FED9 +:102E5000BDE8084000F07ABB6441002008B5034893 +:102E6000FFF76AFEBDE8084000F070BB004200209A +:102E7000D0F8903003EB4111D1F8003B43F400133C +:102E8000C1F8003B70470000D0F8903003EB4111CF +:102E9000D1F8003943F40013C1F80039704700003D +:102EA000D0F8903003EB4111D1F8003B23F400132C +:102EB000C1F8003B70470000D0F8903003EB41119F +:102EC000D1F8003923F40013C1F80039704700002D +:102ED000090100F16043012203F56143C9B283F89F +:102EE000001300F01F039A4043099B0003F1604365 +:102EF00003F56143C3F880211A60704730B504338D +:102F0000039C0172002104FB0325C160C0E9065344 +:102F1000049B0363059BC0E90000C0E90422C0E9EB +:102F20000842C0E90A11436330BD00000022416A33 +:102F3000C260C0E90411C0E90A226FF00101FEF786 +:102F40009BBD0000D0E90432934201D1C2680AB9A6 +:102F5000181D704700207047036919600021C2687E +:102F60000132C260C269134482699342036124BF83 +:102F7000436A0361FEF774BD38B504460D46E36845 +:102F80003BB162690020131D1268A3621344E3621F +:102F900007E0237A33B929462046FEF751FD002881 +:102FA000EDDA38BD6FF00100FBE70000C368C269CD +:102FB000013BC3604369134482699342436124BF68 +:102FC000436A436100238362036B03B11847704770 +:102FD00070B53023044683F31188866A3EB9FFF743 +:102FE000CBFF054618B186F31188284670BDA36A49 +:102FF000E26A13F8015B9342A36202D32046FFF713 +:10300000D5FF002383F31188EFE700002DE9F84F87 +:1030100004460E46174698464FF0300989F311884A +:103020000025AA46D4F828B0BBF1000F09D14146CB +:103030002046FFF7A1FF20B18BF311882846BDE899 +:10304000F88FD4E90A12A7EB050B521A934528BF53 +:103050009346BBF1400F1BD9334601F1400251F8B2 +:10306000040B914243F8040BF9D1A36A4036403572 +:103070004033A362D4E90A239A4202D32046FFF7E1 +:1030800095FF8AF31188BD42D8D289F31188C9E728 +:1030900030465A46FDF7BCFEA36A5E445D445B447D +:1030A000A362E7E710B5029C0433017203FB04211D +:1030B000C460C0E906130023C0E90A33039B03631D +:1030C000049BC0E90000C0E90422C0E90842436350 +:1030D00010BD0000026A6FF00101C260426AC0E9DF +:1030E00004220022C0E90A22FEF7C6BCD0E904236C +:1030F0009A4201D1C26822B9184650F8043B0B60CD +:10310000704700231846FAE7C3680021C2690133FB +:10311000C3604369134482699342436124BF436A95 +:103120004361FEF79DBC000038B504460D46E368D8 +:103130003BB1236900201A1DA262E2691344E362D5 +:1031400007E0237A33B929462046FEF779FC0028A8 +:10315000EDDA38BD6FF00100FBE70000036919608C +:10316000C268013AC260C269134482699342036132 +:1031700024BF436A036100238362036B03B11847D2 +:103180007047000070B530230D460446114683F3A6 +:103190001188866A2EB9FFF7C7FF10B186F3118830 +:1031A00070BDA36A1D70A36AE26A01339342A362F1 +:1031B00004D3E16920460439FFF7D0FF002080F3F3 +:1031C0001188EDE72DE9F84F04460D4690469946E3 +:1031D0004FF0300A8AF311880026B346A76A4FB928 +:1031E00049462046FFF7A0FF20B187F311883046FB +:1031F000BDE8F88FD4E90A073A1AA8EB0607974208 +:1032000028BF1746402F1BD905F1400355F8042B62 +:103210009D4240F8042BF9D1A36A40364033A362A3 +:10322000D4E90A239A4204D3E16920460439FFF71E +:1032300095FF8BF311884645D9D28AF31188CDE7E3 +:1032400029463A46FDF7E4FDA36A3D443E443B442B +:10325000A362E5E7D0E904239A4217D1C3689BB182 +:10326000836A8BB1043B9B1A0ED01360C368013B89 +:10327000C360C3691A4483699A42026124BF436AE6 +:103280000361002383620123184670470023FBE794 +:1032900000F086B9014B586A704700BF000C00402F +:1032A000034B002258631A610222DA60704700BFA4 +:1032B000000C0040014B0022DA607047000C004017 +:1032C000014B5863704700BF000C0040FEE7000050 +:1032D00070B51B4B0025044686B058600E468562CB +:1032E000016300F00BF904F11003A560E562C4E985 +:1032F00004334FF0FF33C4E90044C4E90635FFF757 +:10330000C9FF2B46024604F134012046C4E90823D4 +:1033100080230C4A2565FEF749FB01230A4AE06039 +:1033200000920375684672680192B268CDE9022383 +:10333000064BCDE90435FEF761FB06B070BD00BF5A +:1033400020260020103D0008153D0008CD32000861 +:10335000024AD36A1843D062704700BFB8230020E6 +:103360004B6843608B688360CB68C3600B694361C3 +:103370004B6903628B6943620B680360704700000E +:1033800008B53C4B40F2FF713B48D3F888200A4314 +:10339000C3F88820D3F8882022F4FF6222F00702C5 +:1033A000C3F88820D3F88820D3F8E0200A43C3F874 +:1033B000E020D3F808210A43C3F808212F4AD3F8A4 +:1033C00008311146FFF7CCFF00F5806002F11C01C7 +:1033D000FFF7C6FF00F5806002F13801FFF7C0FF7C +:1033E00000F5806002F15401FFF7BAFF00F580603C +:1033F00002F17001FFF7B4FF00F5806002F18C016B +:10340000FFF7AEFF00F5806002F1A801FFF7A8FF0B +:1034100000F5806002F1C401FFF7A2FF00F58060B3 +:1034200002F1E001FFF79CFF00F5806002F1FC0172 +:10343000FFF796FF02F58C7100F58060FFF790FFB3 +:1034400000F076F90E4BD3F8902242F00102C3F857 +:103450009022D3F8942242F00102C3F8942205226C +:10346000C3F898204FF06052C3F89C20054AC3F877 +:10347000A02008BD00440258000002581C3D00086E +:1034800000ED00E01F00080308B500F025FBFEF783 +:1034900051FA0F4BD3F8DC2042F04002C3F8DC2095 +:1034A000D3F8042122F04002C3F80421D3F80431F8 +:1034B000084B1A6842F008021A601A6842F00402C7 +:1034C0001A60FEF721FFBDE80840FEF7C1BC00BF4F +:1034D000004402580018024870470000EFF30983C7 +:1034E000054968334A6B22F001024A6383F3098875 +:1034F000002383F31188704700EF00E0302080F351 +:10350000118862B60D4B0E4AD96821F4E0610904B6 +:10351000090C0A430B49DA60D3F8FC2042F08072B0 +:10352000C3F8FC20084AC2F8B01F116841F001013D +:1035300011602022DA7783F82200704700ED00E066 +:103540000003FA0555CEACC5001000E0302310B5DD +:1035500083F311880E4B5B6813F4006314D0F1EE13 +:10356000103AEFF309844FF08073683CE361094B34 +:10357000DB6B236684F30988FEF7B0F910B1064BC4 +:10358000A36110BD054BFBE783F31188F9E700BF8A +:1035900000ED00E000EF00E02F0400083204000816 +:1035A000114BD3F8E82042F00802C3F8E820D3F822 +:1035B000102142F00802C3F810210C4AD3F8103150 +:1035C000D36B43F00803D363C722094B9A624FF0D1 +:1035D000FF32DA6200229A615A63DA605A6001228D +:1035E0005A611A60704700BF004402580010005C26 +:1035F000000C0040094A08B51169D3680B40D9B2E4 +:103600009B076FEA0101116107D5302383F311880D +:10361000FEF7A6F9002383F3118808BD000C0040D3 +:10362000064BD3F8DC200243C3F8DC20D3F8042196 +:103630001043C3F80401D3F8043170470044025822 +:103640003A4B4FF0FF31D3F8802062F00042C3F8CC +:103650008020D3F8802002F00042C3F88020D3F805 +:103660008020D3F88420C3F88410D3F8842000226B +:10367000C3F88420D3F88400D86F40F0FF4040F4B2 +:10368000FF0040F4DF4040F07F00D867D86F20F0A3 +:10369000FF4020F4FF0020F4DF4020F07F00D867D7 +:1036A000D86FD3F888006FEA40506FEA5050C3F8E3 +:1036B0008800D3F88800C0F30A00C3F88800D3F864 +:1036C0008800D3F89000C3F89010D3F89000C3F8A6 +:1036D0009020D3F89000D3F89400C3F89410D3F856 +:1036E0009400C3F89420D3F89400D3F89800C3F85A +:1036F0009810D3F89800C3F89820D3F89800D3F81E +:103700008C00C3F88C10D3F88C00C3F88C20D3F84D +:103710008C00D3F89C00C3F89C10D3F89C10C3F81D +:103720009C20D3F89C3000F0AFB900BF0044025891 +:1037300008B50122534BC3F80821534BD3F8F420AA +:1037400042F00202C3F8F420D3F81C2142F0020236 +:10375000C3F81C210222D3F81C314C4BDA605A68A2 +:103760009104FCD54A4A1A6001229A60494ADA60FB +:1037700000221A614FF440429A61444B9A699204C4 +:10378000FCD51A6842F480721A603F4B1A6F12F42B +:10379000407F04D04FF480321A6700221A671A68FB +:1037A00042F001021A60384B1A685007FCD500221B +:1037B0001A611A6912F03802FBD1012119604FF029 +:1037C000804159605A67344ADA62344A1A611A6889 +:1037D00042F480321A602C4B1A689103FCD51A68A7 +:1037E00042F480521A601A689204FCD52C4A2D4982 +:1037F0009A6200225A63196301F57C01DA6301F2CF +:10380000E71199635A64284A1A64284ADA621A68E6 +:1038100042F0A8521A601C4B1A6802F02852B2F10A +:10382000285FF9D148229A614FF48862DA61402218 +:103830001A621F4ADA641F4A1A651F4A5A651F4AEC +:103840009A6532231E4A1360136803F00F03022B9C +:10385000FAD10D4A136943F003031361136903F0AE +:103860003803182BFAD14FF00050FFF7D9FE4FF074 +:103870008040FFF7D5FE4FF00040BDE80840FFF75D +:10388000CFBE00BF008000510044025800480258DB +:1038900000C000F0020000010000FF010088900855 +:1038A0001210200063020901470E0508DD0BBF015D +:1038B00020000020000001100910E00000010110AC +:1038C000002000524FF0B04208B5D2F8883003F023 +:1038D0000103C2F8883023B1044A13680BB1506861 +:1038E0009847BDE80840FFF731BE00BFB442002052 +:1038F0004FF0B04208B5D2F8883003F00203C2F8A6 +:10390000883023B1044A93680BB1D0689847BDE86A +:103910000840FFF71BBE00BFB44200204FF0B0428A +:1039200008B5D2F8883003F00403C2F8883023B118 +:10393000044A13690BB150699847BDE80840FFF786 +:1039400005BE00BFB44200204FF0B04208B5D2F827 +:10395000883003F00803C2F8883023B1044A936921 +:103960000BB1D0699847BDE80840FFF7EFBD00BF35 +:10397000B44200204FF0B04208B5D2F8883003F0CE +:103980001003C2F8883023B1044A136A0BB1506A9D +:103990009847BDE80840FFF7D9BD00BFB4420020FA +:1039A0004FF0B04310B5D3F8884004F47872C3F8F0 +:1039B0008820A30604D5124A936A0BB1D06A9847AF +:1039C000600604D50E4A136B0BB1506B9847210665 +:1039D00004D50B4A936B0BB1D06B9847E20504D525 +:1039E000074A136C0BB1506C9847A30504D5044AE1 +:1039F000936C0BB1D06C9847BDE81040FFF7A6BDA3 +:103A0000B44200204FF0B04310B5D3F8884004F41E +:103A10007C42C3F88820620504D5164A136D0BB1A9 +:103A2000506D9847230504D5124A936D0BB1D06DA4 +:103A30009847E00404D50F4A136E0BB1506E9847B7 +:103A4000A10404D50B4A936E0BB1D06E9847620463 +:103A500004D5084A136F0BB1506F9847230404D55F +:103A6000044A936F0BB1D06F9847BDE81040FFF741 +:103A70006DBD00BFB442002008B5FFF7BBFDBDE837 +:103A80000840FFF763BD0000062108B50846FFF7B0 +:103A90001FFA06210720FFF71BFA06210820FFF76F +:103AA00017FA06210920FFF713FA06210A20FFF76B +:103AB0000FFA06211720FFF70BFA06212820FFF73F +:103AC00007FA09217A20FFF703FA07213220BDE81F +:103AD0000840FFF7FDB9000008B5FFF7B1FD00F0A1 +:103AE0000BF8FDF7F9FBFDF7CBFAFFF7F5FCBDE8A6 +:103AF0000840FFF7CDBB00000023054A19460133FB +:103B0000102BC2E9001102F10802F8D1704700BF82 +:103B1000B442002010B501390244904201D1002086 +:103B200005E0037811F8014FA34201D0181B10BD26 +:103B30000130F2E7034611F8012B03F8012B002AAC +:103B4000F9D1704753544D333248373F3F3F00530C +:103B5000544D3332483733782F3732780053544D31 +:103B60003332483734332F3735332F373530000071 +:103B700001105A000310590001205800032056007C +:103B800000000000FD0F0008E90F000825100008E4 +:103B9000111000081D10000809100008F50F00089A +:103BA000E10F0008311000080000000001000000D3 +:103BB0000000000063300000B43B00081024002027 +:103BC000202600204172647550696C6F7400254294 +:103BD0004F415244252D424C002553455249414CFA +:103BE0002500000002000000000000001D12000877 +:103BF0008D12000840004000D03E0020E03E002032 +:103C000002000000000000000300000000000000AF +:103C1000D51200080000000010000000F03E002057 +:103C200000000000010000000000000064410020CE +:103C300001010200ED1D0008FD1C0008991D00088F +:103C40007D1D0008430000004C3C000809024300B1 +:103C5000020100C032090400000102020100052433 +:103C600000100105240100010424020205240600BD +:103C700001070582030800FF09040100020A000091 +:103C80000007050102400000070581024000000016 +:103C900012000000983C00081201100102000040D0 +:103CA0000912415700020102030100000403090444 +:103CB00025424F4152442500544D6F746F7248376E +:103CC00034330030313233343536373839414243BA +:103CD000444546000000000031140008E9160008C1 +:103CE00095170008400040009C4200209C420020A4 +:103CF00001000000AC4200208000000040010000F4 +:103D00000800000000010000001000000800000092 +:103D10006D61696E0069646C650000000001816A74 +:103D200000000000AAAAAAAA00010064FFFE000089 +:103D30000000000000A00A000000000100000000D8 +:103D4000AAAAAAAA00000001FFFF000000000000CC +:103D5000000000000000000000000000AAAAAAAABB +:103D600000000000FFFF0000000000000000000055 +:103D70000000000000000000AAAAAAAA000000009B +:103D8000FFFF0000000000000000000000004000F5 +:103D900000000000AAAAAAAA00004000FFFF00003D +:103DA0000000000000000000000000000000000013 +:103DB000AAAAAAAA00000000FFFF0000000000005D +:103DC000000000000000000000000000AAAAAAAA4B +:103DD00000000000FFFF00000000000000000000E5 +:103DE0000000000000000000AAAAAAAA000000002B +:103DF000FFFF0000000000000000000000000000C5 +:103E000000000000AAAAAAAA00000000FFFF00000C +:103E100000000000000000000000000000000000A2 +:103E2000AAAAAAAA00000000FFFF000000000000EC +:103E3000000000000000000000000000AAAAAAAADA +:103E400000000000FFFF0000000000000000000074 +:103E5000720400000000000000001A0000000000D2 +:103E6000FF00000000000000443B00088304000045 +:103E70004F3B0008500400005D3B00080096000026 +:103E80000000080096000000000800000400000088 +:103E9000AC3C000800000000000000000000000032 +:0C3EA00000000000000000000000000016 +:00000001FF diff --git a/Tools/bootloaders/YJUAV_A6SE_bl.bin b/Tools/bootloaders/YJUAV_A6SE_bl.bin new file mode 100644 index 00000000000000..2d733311ae2fe7 Binary files /dev/null and b/Tools/bootloaders/YJUAV_A6SE_bl.bin differ diff --git a/Tools/bootloaders/YJUAV_A6_bl.bin b/Tools/bootloaders/YJUAV_A6_bl.bin new file mode 100755 index 00000000000000..dac704dd9eb8ad Binary files /dev/null and b/Tools/bootloaders/YJUAV_A6_bl.bin differ diff --git a/Tools/bootloaders/ZubaxGNSS_bl.bin b/Tools/bootloaders/ZubaxGNSS_bl.bin index d391822244c4da..a3eaf5eb2ec827 100755 Binary files a/Tools/bootloaders/ZubaxGNSS_bl.bin and b/Tools/bootloaders/ZubaxGNSS_bl.bin differ diff --git a/Tools/bootloaders/ZubaxGNSS_bl.elf b/Tools/bootloaders/ZubaxGNSS_bl.elf index 9cdd2287d2abe2..aaf300ca07199c 100755 Binary files a/Tools/bootloaders/ZubaxGNSS_bl.elf and b/Tools/bootloaders/ZubaxGNSS_bl.elf differ diff --git a/Tools/bootloaders/ZubaxGNSS_bl.hex b/Tools/bootloaders/ZubaxGNSS_bl.hex index 7f9eb818e3bb24..48dccd0022483e 100644 --- a/Tools/bootloaders/ZubaxGNSS_bl.hex +++ b/Tools/bootloaders/ZubaxGNSS_bl.hex @@ -1,1057 +1,1163 @@ :020000040800F2 -:10000000000200207904000809220008AD21000840 -:10001000ED210008AD210008CD2100087B04000877 -:100020007B0400087B0400087B040008BD30000846 -:100030007B0400087B0400087B040008B13C000836 -:100040007B0400087B0400087B0400087B04000894 -:100050007B0400087B040008E5390008113A000819 -:100060003D3A0008693A0008953A00087B04000808 -:100070007B0400087B0400087B0400087B04000864 -:100080007B0400087B0400087B040008F51D0008C1 -:10009000211E0008311E00087B040008C13A000838 -:1000A0007B0400087B0400087B0400087B04000834 -:1000B0007B0400087B0400087B0400087B04000824 -:1000C0007B0400087B0400087B0400087B04000814 -:1000D0007B0400087B0400087B0400087B04000804 -:1000E000293B00087B0400087B0400087B0400080F -:1000F0007B0400087B0400087B0400087B040008E4 -:100100007B0400087B0400087B0400087B040008D3 -:100110007B0400087B0400087B0400087B040008C3 -:100120007B0400087B0400087B0400087B040008B3 -:100130007B0400087B0400087B0400087B040008A3 -:100140007B0400087B0400087B0400087B04000893 -:100150007B0400087B0400087B0400087B04000883 -:100160006112000800000000000000000000000014 -:1001700053B94AB9002908BF00281CBF4FF0FF310E -:100180004FF0FF3000F076B9ADF1080C6DE904CE08 -:1001900000F006F8DDF804E0DDE9022304B0704762 -:1001A0002DE9F047089E0D4604468846002B4DD1A8 -:1001B0008A42944668D9B2FA82F252B101FA02F345 -:1001C000C2F1200120FA01F10CFA02FC41EA030815 -:1001D00094404FEA1C41B8FBF1F71FFA8CFE01FB7B -:1001E000178807FB0EF0230C43EA084398420AD90C -:1001F0001CEB030307F1FF3580F01E81984240F2AB -:100200001B81023F63441B1AB3FBF1F001FB103367 -:1002100000FB0EFEA4B244EA0344A6450AD91CEB37 -:10022000040400F1FF3380F00981A64540F2068105 -:10023000644402380021A4EB0E0440EA07401EB1DA -:100240000023D440C6E90043BDE8F0878B4208D9BB -:10025000002E00F0EE800021C6E900050846BDE84A -:10026000F087B3FA83F100294AD1AB4202D382422C -:1002700000F2FC80841A65EB030301209846002EEF -:10028000E2D0C6E90048DFE702B9FFDEB2FA82F247 -:10029000002A40F09180A1EB0C0001214FEA1C479D -:1002A0001FFA8CFEB0FBF7F307FB1300250C45EAA1 -:1002B00000450EFB03F0A84208D91CEB050503F12D -:1002C000FF3802D2A84200F2CE8043462D1AB5FB79 -:1002D000F7F007FB10550EFB00FEA4B244EA0544FC -:1002E000A64508D91CEB040400F1FF3502D2A6454F -:1002F00000F2B6802846A4EB0E0440EA03409EE7D5 -:10030000C1F120078B4022FA07FC4CEA030C25FAC6 -:1003100007FA4FEA1C49BAFBF9F820FA07F309FB80 -:1003200018AA8D401FFA8CFE1D4300FA01F308FB4A -:100330000EF02C0C44EA0A44A04202FA01F20BD956 -:100340001CEB040408F1FF3A80F08880A04240F2E0 -:100350008580A8F102086444241AB4FBF9F009FB73 -:10036000104400FB0EFEADB245EA0444A64508D990 -:100370001CEB040400F1FF356CD2A6456AD90238A3 -:10038000644440EA0840A0FB0295A4EB0E04AC4292 -:10039000C846AE4656D353D0002E69D0B3EB080200 -:1003A00064EB0E0422FA01F304FA07F71F43CC4072 -:1003B000C6E90074002147E70CFA02FCC2F12001F3 -:1003C00025FA01F34FEA1C4720FA01F195400D434D -:1003D000B3FBF7F107FB11331FFA8CFE280C40EA40 -:1003E000034001FB0EF3834204FA02F408D91CEB2C -:1003F000000001F1FF382FD283422DD90239604429 -:10040000C01AB0FBF7F307FB1300ADB245EA004595 -:1004100003FB0EF0A84208D91CEB050503F1FF38D9 -:1004200016D2A84214D9023B6544281A43EA014176 -:1004300038E73146304607E72F46E4E61846F9E646 -:100440004B45A9D2B9EB020865EB0C0E0138A3E7C6 -:100450004346EAE7284694E74146D1E7D0467BE7A2 -:100460006444023847E7023B65442FE7084606E745 -:100470003146E9E6704700BF02E000F000F8FEE711 -:1004800072B6284880F30888274880F309882748EF -:100490004EF60851CEF200010860022080F3148865 -:1004A000BFF36F8F03F026FA03F002FA03F024FA89 -:1004B0004FF055301E491B4A91423CBF41F8040B96 -:1004C000FAE71C49184A91423CBF41F8040BFAE78D -:1004D00019491A4A1A4B9A423EBF51F8040B42F886 -:1004E000040BF8E700201749174A91423CBF41F836 -:1004F000040BFAE703F0E0F903F000FA134C144D93 -:10050000AC4203DA54F8041B8847F9E700F03CF8E2 -:10051000104C114DAC4203DA54F8041B8847F9E73C -:1005200003F0C8B900020020000800200000000805 -:10053000000100200002002068410008000800209F -:1005400080080020800800206C2000206001000846 -:100550006401000864010008640100082DE9F04FFF -:10056000C1F80CD0C3689D46BDE8F08F002383F32B -:1005700011882846A047002002F048FFFEE702F05D -:10058000C1FE00DFFEE700002DE9F0412F4A53686D -:1005900023F0E06343F0905343F48043536003F04F -:1005A00021F9074603F070F90546B8BB284B9F4276 -:1005B00034D001339F4234D0264B27F0FF029A42B9 -:1005C00033D1F8B200F066FAA84642F2107400F097 -:1005D0006BFC08B10024A04600F062FA064640B366 -:1005E0004CBB464635B11C4B9F4203D0002403F060 -:1005F00043F92646002003F0FFF80EB100F02EF874 -:1006000000F0B0FC00F03EFE01F006FE0546ACB97D -:1006100000F0EEFC012002F0FFFEF8E7A8460024FF -:10062000D5E704464FF00108D1E7804641F288340F -:10063000CDE70446D6E74FF47A74D3E701F0ECFD3A -:10064000431BA342E4D900F009F8DDE700000140B4 -:10065000010007B0000008B0263A09B038B51D4ABD -:100660001D4B1968013134D004339342F9D11B4C2E -:10067000194DD4F80428AA422BD3194B9B6803F1D7 -:10068000006303F508439A4223D203F0C9F803F04C -:10069000DBF8002000F01CFE0220124B187000F066 -:1006A00053FE114BDA690022DA61D96999699A61BE -:1006B0009B6972B64FF0E023C3F8085DD4F80038A8 -:1006C000D4F80428202181F311889D4683F30888FB -:1006D000104738BD20880008008800080080000806 -:1006E00000080020800800200010024049F2690044 -:1006F000084A136899B21B0C00FB013344F25061A5 -:100700001360054B186882B2000C01FB02001860F0 -:1007100080B27047180800201408002010B5044665 -:100720000021102200F02CFE034B03CB20606160FF -:100730001868A06010BD00BFE8F7FF1F2DE9F04367 -:10074000BBB001F069FD40F2ED22204DAB68C31A49 -:10075000934232D906AF2B4628220021A8603846A2 -:1007600002F066FA05F10E0000F002FE00260446D3 -:100770005FFA80F905F10E08F3B2F100994501F135 -:10078000280107D908EB06030822384602F050FA80 -:100790000136F1E708230122CDE902320C4B053482 -:1007A00001933023A4B20093CDE9047405A3D3E9E7 -:1007B0000023297B074802F051F83BB0BDE8F083E5 -:1007C000AFF3008078F6339F93CACD8D981D00203B -:1007D000A51D00209C18002070B50D4614461E462D -:1007E00001F0D2FF50B9022E10D1012C0ED112A36C -:1007F000D3E900230120C5E9002307E0282C10D00D -:1008000005D8012C09D0052C0FD0002070BD302C4C -:10081000FBD10BA3D3E90023ECE70BA3D3E900231F -:10082000E8E70BA3D3E90023E4E70BA3D3E9002314 -:10083000E0E700BFAFF30080401DA12026812A0B16 -:1008400078F6339F93CACD8D9E6AC421818A46EE85 -:1008500026417272DF25D7B7F017304A39059E5608 -:1008600038B50D460446034620222846002102F0F2 -:10087000DFF922792346032A28BF0322284603F8FA -:10088000042F2021022202F0D3F962792346072A9D -:1008900028BF0722284603F8052F2221032202F051 -:1008A000C7F9A2792346072A28BF0722284603F85A -:1008B000062F2521032202F0BBF928461022282109 -:1008C00004F1080302F0B4F9382038BD2DE9F04FE7 -:1008D0000024ADF5037D10AE40F2751280460F4640 -:1008E00024A82146239400F04BFD2146482230469F -:1008F00000F046FD01F090FC4FF47A72B0FBF2F08C -:10090000544B23AD186093E80700012386E80700E5 -:100910000DF162003382FFF701FF4EF6035333847B -:1009200007AB18464C4903F039FB212229463064B5 -:10093000304686F83C20FFF793FF08220446014624 -:1009400014AB284602F074F908222846A1180DF1CC -:10095000510302F06DF9082228460DF1520304F10B -:10096000100102F065F92022284615AB04F11801A8 -:1009700002F05EF94022284616AB04F1380102F07D -:1009800057F90822284618AB04F1780102F050F913 -:10099000082228460DF1610304F1800102F048F9B4 -:1009A00004F1880A0DF1620904F5847B4B46514637 -:1009B000082228460AF1080A02F03AF9D34509F15B -:1009C0000109F3D10822594628461DAB02F030F93F -:1009D0004FF0000904F5887496F834304B450AD975 -:1009E000B36B21464B440822284602F021F9083413 -:1009F00009F10109F0E74FF0000996F83C3004EBEB -:100A0000C9014B4508D9336C08224B44284602F0F3 -:100A10000FF909F10109F0E700230393BB7E0731C9 -:100A2000029307F1190301930123C1F3CF01CDE92B -:100A300004510093404605A3D3E90023F97E01F059 -:100A40000DFF0DF5037DBDE8F08F00BF9E6AC42148 -:100A5000818A46EE84080020CC3F000810B50A4B7E -:100A60000A4A1A6093F8602442B9D3F85C442CB166 -:100A7000204601F067FA204603F028F9BDE810404F -:100A8000034801F05FBA00BFC8180020B440000856 -:100A9000101D0020014B1870704700BF9008002007 -:100AA000F0B5334B85B01C7B34B10E22314B1A812B -:100AB0000024204605B0F0BD2F4A02AB10685168F3 -:100AC00003C308232D492E480DEB030203F050F910 -:100AD000054630B90A22274B2A481A8101F0B0F99D -:100AE000E6E70169B1F55E3F06D90B22214B2648A6 -:100AF0001A8101F0A5F9DCE740F2ED32438B934215 -:100B000007D00C201B4908811946204801F098F9AC -:100B1000CFE71F4A024402F11003994204D2102287 -:100B2000144B1C481A81E4E710398E1A20461449E8 -:100B300001F078FB07463246204605F1180101F026 -:100B400071FBAB689F4202D1EB6898420AD00D223C -:100B5000084B1A8100903B46D5E902120E4801F07D -:100B60006FF9A5E70D4801F06BF90124A1E700BF7B -:100B7000981D00208408002081400008DC770300D5 -:100B800000880008F03F0008FC3F00080E40000805 -:100B90000878FFF72C400008494000087240000820 -:100BA0002DE9F04FADB006AF80460C4601F0ECFDEC -:100BB0000546002859D1237E022B1AD1E38A012B46 -:100BC00017D101F029FB0646FFF790FD4FF4C873DB -:100BD000B0FBF3F202FB1300DFF8B49206F51676D1 -:100BE00080B2E37E0644C9F8006033B90022A94B05 -:100BF0001A709C37BD46BDE8F08FA38AEEB2013B68 -:100C0000B34205F101050BD93B1D1E44E900002349 -:100C100008222046009601F0F80101F0CBFEECE737 -:100C200007F11400FFF77AFD324607F11401381D71 -:100C300003F08EF803460028D8D10F2E08D8954B24 -:100C40001E70D9F80030A3F51673C9F80030D0E74C -:100C5000FA1CF870014600922046072201F0AAFE15 -:100C60004046F97801F088FDC3E7E38A282B26D0B7 -:100C700010D8012B1ED0052BBBD1BFF34F8F864957 -:100C8000864BCA6802F4E0621343CB60BFF34F8F18 -:100C900000BFFDE7302BACD1637E814D01336A7B11 -:100CA000DBB29342E94603D1E27E2B7B9A4265D0C8 -:100CB000CD469EE721464046FFF708FE99E7A38A06 -:100CC000013B9BB2C92B94D8754D2E7B26BB05F1F9 -:100CD0000C030093082233463146204601F06AFE99 -:100CE000731CF2B2D9001E46A38A013B9A4205DA70 -:100CF0000E322A44009200230822EEE7002300224D -:100D0000C5E900230023AB6085F8D730C5F8D8309B -:100D10002B7B0BB9E37E2B73002507F11406082209 -:100D2000294630463B1DC7E90155FD6001F080FFB3 -:100D30003B7A05F10109AB424FEAC90107D9FB68CB -:100D400008222B44304601F073FF4D46F0E70023A4 -:100D5000C1F3CF01E07ECDE904610393A37E193492 -:100D60000293282301460093404647A3D3E900237A -:100D7000019401F073FDFFF7E1FC3AE74FF0000842 -:100D800007F11403A7F814801022009341460123B1 -:100D9000204601F00FFEA68A023EB6B2F31C9B105D -:100DA0009B000733DB08A9EBC3039D460DF1180A2E -:100DB0001FFA88F34FEAC801B34201F110010AD2C9 -:100DC0000AEB0803009308220023204601F0F2FDFD -:100DD00008F10108ECE795F8D70000F083FAD5F8A0 -:100DE000D83004461BB995F8D70000F08BFAD5F837 -:100DF000D83033449C4204D295F8D700013000F03B -:100E000081FA4FF000084FEA960B1FFA88F18B45E4 -:100E1000D5E9003209D90AEB880103EB88000122E9 -:100E200000F0B6FA08F10108EFE7F31842F100020A -:100E3000C5E90032D5F8D83095F8D70006EB03089D -:100E4000C5F8D88000F04EFA804509D395F8D73020 -:100E5000D5F8D8000133001B85F8D730C5F8D80085 -:100E6000FF2E08D800232B7300F05EFAFFF718FE60 -:100E700008B1FFF7F3FB2B680A4A9B0A0133138181 -:100E80000023AB6014E700BF26417272DF25D7B79D -:100E9000981800209518002000ED00E00400FA05E5 -:100EA000981D00208408002030B54FF00054244BDA -:100EB000226885B09A4207D002F0F0FC0446A8B937 -:100EC0000024204605B030BD627D1E4B1E481A70BE -:100ED000237DC92203731D490E3000F03FFA2046DE -:100EE000E022002100F04CFA0124EAE7184A194DEB -:100EF000D36943F00073D361AA6D174B9A42DFD1D7 -:100F00002B6E013B7E2BDBD8144A01AB07CA83E86A -:100F100007001846032101F09BF96B6D83424FF0E7 -:100F20000003CDD12A6D8A4203BFAB652A6E054B03 -:100F30001C4601BF1A70EA6D094B1A60C1E700BF79 -:100F40009AAD44C590080020981D0020160000208E -:100F500000100240006600405041A0B058660040BA -:100F600010080020022337B5184D01226B71184B71 -:100F70001848196800F036FE00230193164B1749F4 -:100F800000934FF48052164B164801F0CDFB164BE0 -:100F9000197811B1134801F0EFFB01F03DF9044657 -:100FA000FFF7A4FB4FF4C873B0FBF3F202FB13038B -:100FB00004F516709BB218440C4B186002F064FCE8 -:100FC00008B10F232B8103B030BD00BF840800207F -:100FD00010080020C8180020D90700089408002035 -:100FE000A10B00089C1800209008002098180020F1 -:100FF0002DE9F04F0FF26029D9E900898A4C93B0AE -:101000008A4E8B4F204601F08DFC034660B30025CD -:10101000CDE90F550E95ADF84450027BDFF814A2D0 -:101020008DF84420996840680FAA03C21B6843F0FA -:1010300000430E9301F0F2F8821941F100033846A3 -:1010400000950EA900F014FAA84205DD204601F033 -:101050006DFC8AF80050D5E79AF80030072B00F2B3 -:10106000B78001338AF8003000230BAE704FDFF8F1 -:10107000C8A10A93ADF834300B9373604FF0000BA6 -:10108000002200230125CDE9002338465B460DF1FF -:101090001D0207A98DF81C508DF81DB000F054FDFD -:1010A0009DF81C30002B40F09780204601F06CFB2F -:1010B0000646002848D101F0AFF8DFF880A1DAF841 -:1010C0000030984240D301F0A7F80746FFF70EFB27 -:1010D0004FF4C873B0FBF3F202FB130007F5167769 -:1010E00080B20744CAF80070554F0EA897F800B0B8 -:1010F000BBF1000F14BF33462B46CBF1100A5FFA49 -:101100008AFA8DF82830FFF709FBBAF1060F28BFDD -:101110004FF0060A0EAB03EB0B0152460DF129000E -:1011200000F01CF90AAB039318230AF101020293A1 -:10113000444BD2B2CDE900530492204638A3D3E900 -:10114000002301F023FB3E7001F066F83E4A3F4D5C -:101150001368C31AB3F57A7F2FD3106001F05EF8DD -:1011600002460B46204601F0EBFB204601F00CFB4B -:1011700018B32B7B364E002B14BF0323022373714D -:1011800001F04AF84FF47A73B0FBF3F00EAF306021 -:1011900039463046FFF764FB182302932D4B073086 -:1011A000019340F25513C0F3CF00CDE903700093D3 -:1011B00042464B46204601F0E9FA2B7B2BB1FFF764 -:1011C000BDFA2B7B002B7FF41BAF13B0BDE8F08F73 -:1011D000204601F0ABFB47E7DAF80C30594683F0C4 -:1011E0000803CAF80C3010220EA800F0C9F80DF15F -:1011F0001E0308AA0AA9384600F032FA96E803004E -:101200000FAB83E803009DF8343020468DF844305E -:101210000A9B0EA90E93DDE9082301F051FD2DE78D -:10122000401DA12026812A0B9C18002040420F005F -:10123000C81800207D1E0020000C014098180020D6 -:101240009518002094180020781E0020981D00207A -:10125000840800207C1E0020F1C6A7C1D068080FBA -:1012600008B5054800F092FABDE808400020034A9E -:10127000034902F025BD00BFC8180020B81E002099 -:101280005D0A000870B502F07DF900250E4C0F4E86 -:1012900020803068238883420CD8002520880138BC -:1012A00002F06CF923880544013BB5F5805F23808B -:1012B000F4D370BD02F062F9336805440133B5F52B -:1012C000084F3360E5D3E8E7AC1E0020801E002005 -:1012D00002F0F6B900F10060920000F5084002F05B -:1012E00091B90000054B1A68054B1B889B1A834275 -:1012F00002D9104402F042B900207047801E00203D -:10130000AC1E002038B50446064D2868204402F083 -:101310003BF928B928682044BDE8384002F046B9B6 -:1013200038BD00BF801E0020064991F8243033B13B -:1013300000230822086A81F82430FFF7CBBF012080 -:10134000704700BF841E0020022802BF4FF4002215 -:10135000014B1A61704700BF000C0140002310B51B -:10136000934203D0CC5CC4540133F9E710BD0000B4 -:1013700003460246D01A12F9011B0029FAD1704720 -:1013800003460244934202D003F8011BFAE7704778 -:101390002DE9F8431F4D144695F82420074688464A -:1013A00052BBDFF870909CB395F824302BB9202203 -:1013B000FF2148462F62FFF7E3FF95F824004146DE -:1013C000C0F10802A24228BF224605EB8000D6B237 -:1013D0009200FFF7C3FF95F82430A41B1E44F6B219 -:1013E000082E17449044E4B285F82460DBD1FFF75F -:1013F0009BFF0028D7D108E02B6A03EB82038342CE -:10140000CFD0FFF791FF0028CBD10020BDE8F883B3 -:101410000120FBE7841E0020202383F3118862B69D -:1014200070470000002383F3118862B67047000004 -:1014300010B4026854681A46234610BC18470000CE -:10144000012070470020704700207047704700005F -:1014500070470000002070470E20704790F8C804C5 -:10146000C0F340007047000090F9C90470470000C5 -:101470002DE9F0410C681E4614F00054BDF81870B8 -:101480006AD10B7B082B67D8FFF7C6FF4569AB68AD -:101490005B010CD4AB681B0108D4AC6814F0805419 -:1014A00058D1FFF7BFFF2046BDE8F08101240B684B -:1014B00004F1180C002BBABFDB0043F004035B05FA -:1014C0004FEA0C1C45F80C300B684FEA041C13F073 -:1014D000804F1CBF05EB0C0EDEF88031AC441CBF06 -:1014E00043F00203CEF880310B7B05EB0415CCF8FA -:1014F00084318B68C5F88C314B68C5F888310D464E -:10150000DCF8803143F00103CCF8803100EB441368 -:10151000C3F86824C3F86C6401F10C0C03F58E6306 -:1015200055F804EB654543F804EBF9D12D882434D4 -:101530001D8000EB4414257907F0030325F00B050B -:101540002B432371FFF76EFF33460697BDE8F0414A -:1015500000F098BC0224AAE74FF0FF30A4E7000097 -:1015600038B50446D0F85C040D4600F01FFD1F2876 -:101570000AD920222946D4F85C0400F08DFDA0F1A0 -:1015800020035842584138BD0020FCE708B5FFF75A -:1015900043FFD0F85C0400F0DFFCBDE80840FFF733 -:1015A00041BF000000220260828142608260704779 -:1015B0000022002310B5C0E9002300230446038164 -:1015C0000C30FFF7EFFF204610BD0000F0B590F89B -:1015D000C8340D4613F0040FC3F3800108BF114651 -:1015E00005F1240661F3820380F8C83400EB46134A -:1015F0001B790446D80789B02DD572B319072CD4AE -:1016000004EB45156846FFF7D3FF05F58E6303AA83 -:1016100005F58F65174618685968083303C7AB424C -:101620003A46F7D11868694638609B882046BB80E7 -:10163000DDE90E23CDE900230123ADF8083023684E -:101640001B6C984704EB461423791A075CBF43F0E0 -:101650000803237101E0002AF4D109B0F0BD0000B5 -:101660002DE9F047054688B068469A468846914677 -:10167000FFF7D2FEFFF79CFFD5F85C0400F07EFC7C -:101680001F282AD920226946D5F85C0400F082FD83 -:10169000202822D1444603AE05AB374603CF9F42F4 -:1016A000206061603E4604F10804F6D13868414686 -:1016B0002060BB882846A380DDE90023C9E9002318 -:1016C000BDF808304A46AAF80030FFF7ABFE534693 -:1016D00008B0BDE8F04700F0C3BB0020FFF7A2FE52 -:1016E00008B0BDE8F087000000232DE9F04704466C -:1016F000C0E90133224B0E4640F8183BFFF752FF7A -:1017000004F1480704F12800FFF752FF3D4604F5B5 -:10171000896828462035FFF74BFF4545F9D14FF43E -:101720008063C4F84874C4F84C34002701234FF098 -:1017300000084FF00009C4F85C54C4F85074C4F8B1 -:10174000547484F8583484F8603404F5916504F5D1 -:101750009D6A45E90889A5F11800FFF723FF2035A8 -:1017600045F8287C5545F4D184F8C96416B105487C -:1017700000F04CFD044B20466361BDE8F08700BFDC -:10178000B44000088C4000080064004010B50446D6 -:10179000034B19784A1C1A70FFF7A6FF204610BDAC -:1017A000B41E00202DE9F04300294FD0284F294BCB -:1017B000B7FBF1F499428CBF0A231123B4FBF3FC6D -:1017C000581E03FB1C43C5B22BB102280346F5D8B3 -:1017D0000020BDE8F0830CF1FF36B6F5806FF7D23C -:1017E0004FF47A74C5EBC50E0EF103034FEAE3091B -:1017F00009FB0444C3F3C703E81AC0B209F10108A6 -:101800008044B4FBF8F4B4F5617FC2BF0EF1FF333E -:10181000C3F3C703E81A03F10104C8BFC0B2E4B2BE -:1018200004440CFB04F4B7FBF4F4A142D0D1013B17 -:10183000DBB20F2BCCD80138C0B20728C8D80021A2 -:101840001071168001209170D370C2E70846C0E77E -:10185000005125023F420F0070B505460E464FF479 -:101860007A746B6901205B6803F00103B34204D012 -:1018700001F0D2FD013CF4D1204670BD30B5426983 -:10188000936913F0700F16D000230B4C936103F192 -:10189000240200EB421211794D0709D5890707D5BB -:1018A000416954F823508D60117941F004011171A0 -:1018B0000133032BEBD130BDA040000873B51D46AA -:1018C000436916469A680446D20709D501219A68E9 -:1018D0009960C2F340020021CDE90065FFF776FE72 -:1018E00063699A68D1050BD54FF480719A682046D8 -:1018F0009960C2F340220121CDE90065FFF766FE41 -:1019000063699A68D2030BD54FF480319A682046F8 -:101910009960C2F340420221CDE90065FFF756FE0F -:10192000204602B0BDE87040FFF7A8BFF8B50446F6 -:10193000466900296AD106F10C073868800768D02B -:10194000386806EB01104FEA011CD0F8B011D0F84E -:10195000B051490746BFED0845F000456D0DA56142 -:10196000D0F8B011890744BF45F08045A561D0F893 -:10197000B40106EB0C0100F00F0084F82400D1F84C -:10198000B80104F124052077D1F8B801000A607786 -:10199000D1F8B801000CA077D1F8B801000EE077BB -:1019A000D1F8BC0184F82000D1F8BC01000A84F809 -:1019B0002100D1F8BC01000C84F82200D1F8BC1140 -:1019C00004F13400090E84F823103821396004F141 -:1019D000180151F8046BA94240F8046BF9D1098849 -:1019E0000180C4E90A2300232146238651F8283BBD -:1019F00020461B6C984794F8C834204643F00403F3 -:101A000084F8C834BDE8F840FFF738BF06F1100786 -:101A100093E7F8BD10B5044600F000FC02460B4603 -:101A200052EA030102D0013A63F100030449086855 -:101A300020B12146BDE81040FFF778BF10BD00BFC0 -:101A4000B01E0020F8B500211E46FFF7E5FC124F3E -:101A500000F58D6501F1240400EB4414237913F0A3 -:101A6000040F0FD1DB060DD5D5E900C39445B34172 -:101A700008D2436957F821C0C3F808C0237943F05E -:101A8000040323710131032905F12005E2D1BDE8EA -:101A9000F840FFF7C7BC00BFA040000808B5FFF73B -:101AA000BBFCFFF7EBFEBDE80840FFF7BBBC000046 -:101AB000F8B54369044698680E4600F0E050B0F16E -:101AC000E05F1DD0D8B1FFF7A7FC002504F58E67B5 -:101AD00004EB451393F884341A0706D50135032D1A -:101AE00007F12007F4D1012007E05B07F6D439465F -:101AF000304600F001FA0028F0D1FFF793FCF8BD62 -:101B00000120FCE708B5FFF787FCD0F85C0400F083 -:101B100035FAFFF787FC43090CBF0120002008BD00 -:101B2000F8B51D46002313700F4606461446FFF70E -:101B3000E9FF80F00100387025B129463046FFF7F3 -:101B4000B7FF2070F8BD0000F8B50C4615461E46DC -:101B5000074600F063FB0B462178024609B9287856 -:101B600050B13846FFF76EFFFFF798FF33462A461D -:101B70002146FFF7D5FF0120F8BD000010B5FFF7A3 -:101B80004BFC174B0446DA6942F00072DA611A69BD -:101B900042F000721A611A6922F000721A61FFF7AE -:101BA00041FC90F8C834DB0718D4B9B102211320E6 -:101BB000FFF732FC01F0D2FA0221142001F0CEFA34 -:101BC0000221152001F0CAFA94F8C83443F0010349 -:101BD00084F8C834BDE81040FFF724BC10BD00BF36 -:101BE000001002402DE9F04790F8C9340446012B5B -:101BF0000F46154688B000F2F9807D4E56F8232036 -:101C00000AB946F82300D6F80090E7602574B9F1C8 -:101C1000000F09D14FF49A6002F05AF88046494605 -:101C2000FFF762FDC6F8008094F8C934012B5CD040 -:101C30004FF0000801212046FFF7A0FFFFF7ECFB63 -:101C4000626901211368204623F002031360626970 -:101C5000136843F0010313606369C3F81480FFF74E -:101C6000E1FBFFF7F9FD002800F08180D4F85C0467 -:101C700000F072F9A14604F1600A202200216846B2 -:101C8000FFF77EFB02A8FFF78DFC6A46CDF81880AF -:101C900009F58D630DF1180C164603CE66451860E4 -:101CA0005960324603F10803F6D1306809F1200982 -:101CB00018603279CA451A71DFD1002694F8C83409 -:101CC0006A466FF3820384F8C83439462046ADF87B -:101CD0000060ADF802608DF80460FFF763FD636992 -:101CE000C0B94FF400421A6011E0306803685B6BC2 -:101CF0009847014600289BD13068FFF73FFF3068C6 -:101D00002A46036839465B689847002890D108B096 -:101D1000BDE8F0876122022D0CBF4FF00041002189 -:101D20001A609DF802309DF803201B06120402F48D -:101D3000702203F040731343BDF800202046C2F325 -:101D4000090213439DF80420120502F4E002134334 -:101D500062690B43D3611322636931465A61626938 -:101D6000136823F001031360FFF776FD08B9636978 -:101D7000B7E794F8C93493BB6169D1F8002242F007 -:101D80000102C1F800226169D1F8002222F47C52DC -:101D900022F00E02C1F800226169D1F8002242F45B -:101DA0006062C1F8002241F6FF716269C2F8143224 -:101DB0006269C2F804326269C2F80C126269C2F840 -:101DC00040326269C2F8443201226369C3F81C22BE -:101DD0006269D2F8003223F00103C2F8003294F8AD -:101DE000C83443F0020384F8C83490E700208EE73B -:101DF000B01E002008B500F011FA02460B4652EA68 -:101E0000030102D0013A63F100030449086808B1F4 -:101E1000FFF754FDBDE8084001F07EB9B01E002078 -:101E200008B50020FFF7F6FDBDE8084001F074B9E1 -:101E300008B50120FFF7EEFDBDE8084001F06CB9E0 -:101E40000FB4002004B0704713B56C4684E8060058 -:101E5000031D94E8030083E80500012002B010BDD3 -:101E6000F8B586680D4656B11B885B0707D4D0E9E4 -:101E70000037DB6B98472A46C1B23846B04701208D -:101E8000F8BD0000F0B5866805460C4689B05EB125 -:101E9000BDF838305B070AD4D0E90037DB6B9847D0 -:101EA0002246C1B23846B047012009B0F0BD002239 -:101EB0000023CDE9002300230A46ADF8083001F1E4 -:101EC000080603AB1C4610685168083203C4B242CE -:101ED0002346F7D1106820609288A28000F0A0F914 -:101EE0000423ADF808302B68CDE900011B6C69466E -:101EF00028469847D8E7000030B503680968DD0F29 -:101F0000B5EBD17F23F0604421F060424FEAD170FD -:101F10000BD0002BB8BFA40C0029B8BF920C944280 -:101F200002D034BF0120002030BD944205D1C1F35E -:101F30008070C3F380738342F6D194422CBF00209B -:101F40000120F1E710B5037C044613B9006801F0E5 -:101F5000F7FE204610BD00000023BFF35B8FC36077 -:101F6000BFF35B8FBFF35B8F8360BFF35B8F704703 -:101F7000BFF35B8F0068BFF35B8F704770B505469A -:101F80000C30FFF7F5FF05F1080604463046FFF771 -:101F9000EFFFA04206D930466D68FFF7E9FF2C44F9 -:101FA000201A70BD3046FFF7E3FFF9E770B505462C -:101FB0004068A0B105F10800FFF7DAFF05F10C0653 -:101FC00004463046FFF7D4FF844288BF00253046E0 -:101FD00098BF6D68FFF7CCFF013C2C44201A70BD00 -:101FE00038B50C460546FFF7C9FFA04210D305F1EE -:101FF0000800FFF7BDFF04446868BFF35B8FB4FBC4 -:10200000F0F100FB1144AC60BFF35B8F012038BDE1 -:102010000020FCE72DE9F041144607460D46FFF786 -:10202000C5FF844228BF0446D4B1B84658F80C6BAB -:102030004046FFF79DFF06442E6040467E68FFF74E -:1020400097FF331A9C4203D801206C60BDE8F081F1 -:102050006B603B68A61B0644AB600220EE60F5E7B0 -:102060002046F3E738B50C460546FFF79FFFA04230 -:1020700010D305F10C00FFF77BFF04446868BFF341 -:102080005B8FB4FBF0F100FB1144EC60BFF35B8F9E -:10209000012038BD0020FCE72DE9FF410F466946CD -:1020A00006466C46FFF7B6FF002504EBC008444522 -:1020B00008D0626820687919FFF750F9636808341E -:1020C0001D44F4E729463046FFF7CCFF284604B00C -:1020D000BDE8F081F8B505460C300F46FFF748FF24 -:1020E00005F1080604463046FFF742FFA04230469D -:1020F00088BF6C68FFF73CFF201A386020B130467B -:102100002C68FFF735FF2044F8BD0000F7B51746EF -:1021100006460D46FFF732FFB842044628BF3C464C -:102120000190DCB1304601A9FFF7D4FF019B33B920 -:102130003268C5E90233C5E9002401200CE09C4265 -:1021400038BF01942860019884426860F5D9241A48 -:1021500002203368EC60AB6003B0F0BD2046FBE7C3 -:102160002DE9FF410E466946FFF7D0FF6C4600257A -:1021700004EBC007BC4209D0D4F804807019424671 -:1021800054F8081BFFF7EAF84544F3E7284604B083 -:10219000BDE8F08138B50546FFF7E2FF0446014689 -:1021A0002846FFF71DFF204638BD0000EFF30983E6 -:1021B000EFF30583044B9A6BDA6A9A6A9A6A9A6A11 -:1021C0009A6A9A6A9B6AFEE700ED00E0EFF30983E2 -:1021D000EFF30583044B9A6B9A6A9A6A9A6A9A6A31 -:1021E0009A6A9B6AFEE700BF00ED00E0EFF3098307 -:1021F000EFF30583034B5A6B9A6A9A6A9A6A9A6A52 -:102200009B6AFEE700ED00E0FEE700000FB408B5B2 -:10221000029801F09BF8FEE701F092BA01F06ABA69 -:1022200001F068BA30B5094D0A4491420DD011F859 -:10223000013B5840082340F30004013B2C4013F0BD -:10224000FF0384EA5000F6D1EFE730BD2083B8EDFC -:102250004FF0FF33F7B500EB81061946DFF848C0B1 -:10226000DFF848E0B0421BD050F8042B01AF0192D8 -:10227000042217F8014B81EA046108240D46DB189B -:102280004941013C002DBCBF83EA0C0381EA0E01E9 -:1022900014F0FF04F2D1013A12F0FF02E9D1E1E7B4 -:1022A000D843C94303B0F0BD9336EAA9EBE1F0424D -:1022B0002DE9F041C56915B9C161BDE8F0814B68F0 -:1022C000AC4623F06047C3F38A4616EA230638BFBC -:1022D0003E464FEAD37EC3F380782B465A68BEEB66 -:1022E000D27F22F060440AD0002A18DAA40CB4424B -:1022F00017D19D420FD10D60DEE71346EEE7A742EE -:1023000007D102F08044C2F3807242450BD054B131 -:10231000EFE708D2EDE7CCF800100B60CDE7B44250 -:1023200001D0B442E5D81A689C46002AE5D119606C -:10233000C3E700002DE9F0474FF47F49089D01F005 -:1023400007044FEAD508224405F0070500EBD10049 -:10235000944201D1BDE8F08704F0070705F0070AB1 -:1023600057453E4638BF5646111BC6F108068E42F9 -:1023700028BF0E46E108415C08EBD50E13F80EC0ED -:10238000B94029FA06F721FA0AF1FFB28CEA0101F5 -:1023900047FA0AF739408CEA010C03F80EC03444BE -:1023A0003544D5E7082341F2210280EA012001B239 -:1023B0004000002980B203F1FF33B8BF504013F052 -:1023C000FF03F4D17047000038B50C468D18A542C4 -:1023D00000D138BD14F8011BFFF7E4FFF7E7000058 -:1023E0000346006848B1026819891A60DA88013228 -:1023F00092B29142DA8038BF1A81704770B50446B4 -:102400000D4688B0202200216846FEF7B9FF20461D -:102410000495FFF7E5FF024658B16B46054608AE46 -:102420001C4603CCB44228606960234605F10805C8 -:10243000F6D1104608B070BD082817D909280CD06D -:102440000A280CD00B280CD00C280CD00D280CD04E -:102450000E2814BF4020302070470C2070471020F9 -:1024600070471420704718207047202070470000E4 -:10247000082817D90C280CD910280CD914280CD9E5 -:1024800018280CD920280CD930288CBF0F200E20FA -:102490007047092070470A2070470B2070470C20B6 -:1024A00070470D207047000010B54B6823B9CA8AE9 -:1024B00063F30902CA8210BDC4681A681C60C36055 -:1024C000438A013B43824A60EFE700002DE9F84F61 -:1024D0001D46CB8A0F46C3F3090106298146924661 -:1024E0000B4630D00020AAB207F119049EB2052E87 -:1024F0001FFA80F80FD8904503F1010306D3FB8A39 -:102500000A4462F309030120FB821AE01AF8006012 -:102510000130E654EAE79045F1D21C23A1F1060B05 -:10252000BBFBF3F203FB12BB7C681FFA8BF6002C9B -:1025300045D14846FFF754FF044638B978606FF03C -:102540000200BDE8F88F4FF00008E6E700260660BD -:1025500078604FF0000BADB2454510D90AEB080387 -:10256000221D13F8011B08F101089155B1B21B2976 -:102570001FFA88F82BD0454506F10106F1D8FB8AF1 -:10258000C3F30902154465F30903BCE71C46013295 -:1025900092B22368002BF9D1AB1F0B441C21B3FB73 -:1025A000F1F301339BB29A42D3D2BBF1000FD0D1E9 -:1025B0004846FFF715FF20B9C4F800B0BFE7012275 -:1025C000E7E7C0F800B05E4620600446C1E7454535 -:1025D000D5D94846FFF704FF08B92060AFE7C0F837 -:1025E00000B0002620600446B6E700002DE9F04F59 -:1025F00085B007469146CDE90113BDF83C50002A4D -:1026000000F08F802DB10E9B002B00F08A80072DEB -:1026100030D807F10C00FFF7E3FE044628B96FF04D -:102620000204204605B0BDE8F08F14220021FEF719 -:10263000A7FE2A460E9904F10800FEF78FFE681CDB -:10264000C0B2FFF715FFFFF7F7FE207499F80020DE -:10265000431E9BB202F01F02234462F03F021A7233 -:10266000019B384643F0004161602146FFF720FEA0 -:102670000124D6E74FF000084FF0800A4646444652 -:1026800000F10C0303930398FFF7AAFE834600288A -:10269000C5D014220021FEF773FE002E38D102208F -:1026A000029BABF808300E9B00F10802D2B29919D8 -:1026B0005A440130C0B2082801D0AE422AD3FFF7F5 -:1026C000D7FEFFF7B9FEAE4208BF4FF0400A99F8B7 -:1026D0000020019B411E02F01F0242EA4812C9B2CB -:1026E0004AEA020A594443F0004281F808A08BF8F4 -:1026F000100059463846CBF80420FFF7D9FD0134C5 -:10270000AE424FF0000A24B288F00108BBD188E73E -:102710000020C8E711F801CB013602F801CBB6B2B0 -:10272000C7E76FF001047CE7F8B5044615460E468E -:10273000282200211F46FEF723FE069BB5F5001F49 -:102740006360079B28BF4FF6FF7223624FF00003C0 -:1027500038BF6A09A76004F10C0097B29A4205D805 -:102760000023036027826382A382F8BD06600133E1 -:1027700030462036F2E7000003781BB94BB2002B3D -:10278000C8BF017070470000007870472DE9F74F0F -:10279000DDF83C90804692469B46BDF830500D9E39 -:1027A0009DF83840BDF84070B9F1000F01D1002FFD -:1027B00051D11F2C4FD898F80000B0B9072F47D837 -:1027C00035F0030347D13A4649464FF6FF70FFF70D -:1027D000FBFD20F001002D02400445EA0464400C9A -:1027E00044EA40244FF6FF7321E040EA0520072F1A -:1027F00040EA0464F6D900254FF6FF73C5F12000C6 -:10280000A5F120022AFA05F10BFA00F001432BFA98 -:1028100002F211431846C9B2FFF7C4FD0835402D36 -:102820000346EBD13A464946FFF7CEFD0346324612 -:1028300021464046CDE90097FFF7D8FE33780133B3 -:10284000DBB21F2B88BF0023337003B0BDE8F08FCD -:102850006FF00300F9E76FF00100F6E72DE9F04FA4 -:1028600085B0DDF84880924606469B460F9D9DF850 -:1028700040209DF84490BDF84C70B8F1000F01D194 -:10288000002F48D11F2A46D83378002B46D00C029F -:1028900044EA02649DF8381044EAC93444EA014429 -:1028A0001C43072F44F0800432D900234FF6FF72F7 -:1028B000C3F1200CA3F120002AFA03F10BFA0CFC5F -:1028C00041EA0C012BFA00F00143C9B21046039310 -:1028D000FFF768FD039B02460833402BE8D13A46D8 -:1028E0004146FFF771FD03462A4621463046CDE9B1 -:1028F0000087FFF77BFEB9F1010F06D12B7801337A -:10290000DBB21F2B88BF00232B7005B0BDE8F08F12 -:102910004FF6FF73E8E76FF00100F6E76FF0030092 -:10292000F3E70000C06900B104307047C3691A685A -:10293000C261C2681A60C360438A013B4382704728 -:102940002DE9F041D0F8188014461D464146002775 -:10295000174E09B9BDE8F081D1E90223A21A65EB4F -:102960000303964277EB03031ED283698B420DD19A -:10297000FFF79AFD83691B688361C3680B60438A14 -:10298000C1608169013B88464382E2E7FFF78CFD25 -:102990000B68C8F80030C3680B60438AC160013B14 -:1029A0004382D8F80010D4E788460968D1E700BF11 -:1029B00080841E002DE9F04F8BB00D4614469B46D7 -:1029C0008046DDF85090002800F01A81B9F1000F20 -:1029D00000F01681531E3F2B00F21281012A03D111 -:1029E000BBF1000F40F00C810023CDE90833B8F8AB -:1029F0001430B5EBC30F4FEAC30703D300200BB06D -:102A0000BDE8F08F2B199F42D8F80C3036BF7F1BE2 -:102A10002746FFB21BB9D8F81030002B7BD02F2DE2 -:102A20004ED8C5F13006B7424FF0000334BF3E46E2 -:102A3000F6B2009329463246D8F8080008ABFFF7F3 -:102A400079FCA7EB060A35445FFA8AFA3021B8F818 -:102A5000143003F10053063BDB000493D8F80C302C -:102A60000393039B13B1BAF1000F2CD1D8F81000D7 -:102A700040B1BAF1000F05D05246009608AB691A72 -:102A8000FFF758FC38B2002FB8D066070AD00AAB5F -:102A900003EBD40111F8083C624202F00702134133 -:102AA00001F8083C082C3DD9102C40F2B680202CAF -:102AB00040F2B880BBF1000F00F09D80082335E0A4 -:102AC000BA460026C2E7049BE02B28BFE02306930A -:102AD0000B44AB42059315D95A1B924538BF524659 -:102AE000039828BFD2B20096691A08AB0430079247 -:102AF000FFF720FC079A1644AAEB020A1544F6B227 -:102B00005FFA8AFA049B069A05999B1A0493039B21 -:102B10001B680393A5E700933A462946D8F80800B6 -:102B200008ABADE7BBF1000F13D00123B4EBC30F2B -:102B30006CD0082C12D89DF82030621E23FA02F2C5 -:102B4000D50706D54FF0FF3202FA04F423438DF87F -:102B500020309DF8203089F8003050E7102C12D832 -:102B6000BDF82030621E23FA02F2D10706D54FF0DD -:102B7000FF3202FA04F42343ADF82030BDF82030D0 -:102B8000A9F800303BE7202C0FD80899631E21FAE2 -:102B900003F3DA0705D54FF0FF3202FA04F40C43D1 -:102BA0000894089BC9F8003029E7402C2BD0DDE9B8 -:102BB0000865611EC4F12102A4F1210326FA01F186 -:102BC00005FA02F225FA03F311431943CB0712D594 -:102BD0000122A4F12003C4F1200102FA03F322FA36 -:102BE00001F1A240524243EA010363EB4303324343 -:102BF0002B43CDE90823DDE90823C9E90023FEE6DC -:102C00006FF00100FBE66FF00800F8E6082CA0D991 -:102C1000102CB3D9202CEED8C3E7BBF1000FADD0F8 -:102C2000022383E7BBF1000FBBD004237EE7000043 -:102C3000012A30B5144638BF01220025402A28BF9A -:102C4000402285B0012CCDE9025517D81B788DF8AC -:102C5000083053070AD004AB03EBD20515F8083C43 -:102C6000544204F00704A34005F8083C03460091D1 -:102C700002A80021FFF75EFB05B030BD082CE5D9A6 -:102C8000102C03D81B88ADF80830E2E7202C02D8BE -:102C90001B680293DDE7D3E90045CDE90245D8E79B -:102CA00010B5CB681BB98B600B618B8210BDC468FB -:102CB0001A681C60C360438A013B4382CA60F0E724 -:102CC0002DE9F04FD1F8008093B018F0800FCDE9D6 -:102CD0000323C8F3C01207BF4FF0020B1646C8F318 -:102CE000C03BC8F30626B8F1000F04460D4680F23B -:102CF000D48118F0C043059340F0CF810B7B002BAB -:102D000000F0CB81BBF1020F03D00178B14240F05B -:102D1000C78108F07F0107917AB3C8F3074A2B44B3 -:102D200093F80390760646EA0B4608F07F0246EADF -:102D300082465FEAD91346EA0A06069300F09180BC -:102D400000220023CDE90A2308F07F0300935246B6 -:102D50005B46204667680AA9B84700287ED0A76965 -:102D60009FB9314604F10C00FFF748FB0746E0B974 -:102D70006FF0020013B0BDE8F08FC8F30F2A18F00F -:102D80007F0F08BF0AF0030AC9E73B699E420DD0D6 -:102D90003F68002FF9D1314604F10C00FFF72EFBFC -:102DA00007460028E4D0A3693B60A7610026DDE95F -:102DB0000A234FF6FF70C6F1200E22FA06F103FA3D -:102DC0000EFEA6F1200C23FA0CFC41EA0E0141EAAA -:102DD0000C01C9B2083609920893FFF7E3FADDE95E -:102DE0000832402EE7D1B882FB7D09F01F06C3F3FD -:102DF00084039B1B98B2002BBCBF00F120031BB2C5 -:102E0000D7E9022152EA0100C8F304680FD0039801 -:102E1000821A049860EB0101A74890424FF000022B -:102E20008A4104D3069A002A5BD0012B23DDFA7D68 -:102E30004FEA890302F0030203F07C031343FB759E -:102E400039462046FFF730FB069BA3B9FB7DC3F351 -:102E50008402013262F38603FB7504E06FF00B001D -:102E600088E7A76917B96FF00C0083E73B699E42BA -:102E7000BAD03F68F6E719F0400F32D0039B142216 -:102E8000BB60049B0021FB600DA8FEF779FA039B51 -:102E900020460A93049BADF83EA00B932B1D0C9388 -:102EA0002B7B8DF840B0013BDBB2ADF83C30079B8B -:102EB0008DF841608DF8433094F824308DF84280CD -:102EC00083F001038DF844300AA9A3689847FB7D7D -:102ED000C3F38403013303F01F039B02FB82002032 -:102EE00048E7FB7DC9F34012B2EBD31F40F0DB8013 -:102EF000C3F38403B34240F0D98006992B7B4FEA99 -:102F00009912002934D0D20741D4032B40F2D1804A -:102F1000039BAE1DBB60049B3246FB602B7B394696 -:102F2000033BDBB204F10C00FFF7D0FA00280DDA06 -:102F300020463946FFF7B8FAFB7D0320C3F384032C -:102F4000013303F01F039B02FB8213E7AB883B8333 -:102F50002A7B033AB88AD2B23146FFF735FAFB7DB5 -:102F6000B882DA43C2F3C01262F3C713FB75B6E747 -:102F70006AB92E1D013B32463946DBB204F10C0022 -:102F8000FFF7A4FA0028D3DB2A7B013AE2E7F98AAB -:102F9000013BC1F309010529DAB25BD80023281DE2 -:102FA00007F11A0C9A4208D910F801EB01330CF81A -:102FB00001E001310629DBB2F4D1934228BF00239E -:102FC000039938BF04330A91049938BFDBB20B91DF -:102FD00007F11A010C91796838BF5B190D910E93B6 -:102FE000FB8AADF83EA0C3F309031A44079BADF872 -:102FF0003C208DF8433094F824308DF840B083F0B5 -:1030000001038DF8443000238DF841608DF8428033 -:103010007B602A7BB88A013A291DFFF7D5F93B8BE3 -:10302000B882834203D12046A3680AA99847204664 -:103030000AA9FFF735FEFB7DB88AC3F38403013389 -:1030400003F01F039B02FB823B8B984214BF1120AD -:1030500000208FE67B68002BAFD0062001E063469E -:103060001C30D3F800C0BCF1000FF8D1091A081DBC -:1030700005F1040C1844DDF814E09DF814308E447A -:10308000BEF11B0F99D89A4297D91CF8013B00F862 -:10309000013B059B01330593EDE76FF0090069E6FD -:1030A0006FF00A0066E66FF00D0063E66FF00E0049 -:1030B00060E66FF00F005DE680841E00EFF3098389 -:1030C000203383F30988002383F3118870470000BD -:1030D000202080F3118862B60C4B0D4AD96821F488 -:1030E000E0610904090C0A43DA60D3F8FC200949BD -:1030F00042F08072C3F8FC200A6842F001020A60C4 -:103100001022DA7783F82200704700BF00ED00E05C -:103110000003FA05001000E0202310B583F31188A6 -:103120000B4B5B6813F400630FD0EFF309844FF08F -:103130008073203CE36184F3098800F0B9F810B192 -:10314000044BA36110BD044BFBE783F31188F9E73F -:1031500000ED00E07F05000882050008012209015A -:1031600000F1604303F56143C9B283F8001300F036 -:103170001F039A4043099B0003F1604303F5614339 -:10318000C3F880211A607047090100F16040C9B29C -:1031900000F56D40017670470022024BC3E9003311 -:1031A0009A607047BC1E0020002382680374054BA0 -:1031B0001B6899689142FBD25A68036042601060B4 -:1031C00058607047BC1E002008B5202383F3118887 -:1031D000037C032B05D0042B0DD02BB983F311886E -:1031E00008BD002243691A604FF0FF334361FFF7C7 -:1031F000DBFF0023F2E7D0E9003213605A60F3E707 -:10320000002382680374054B1B6899689142FBD8C0 -:103210005A6803604260106058607047BC1E00200E -:10322000054B196908741868026853601A601861C0 -:1032300001230374FDF792B9BC1E002030B54B1C6E -:1032400004460B4D87B010D02B690A4A01A800F044 -:10325000FDF82046FFF7E4FF049B13B101A800F03E -:1032600011F92B69586907B030BDFFF7D9FFF8E7AE -:10327000BC1E0020C931000838B50C4D41612B69D6 -:1032800081689A680446914203D8BDE83840FFF748 -:103290008BBF1846FFF7B4FF01232C61014623744E -:1032A0002046BDE83840FDF759B900BFBC1E0020DC -:1032B000044B1A681B6990689B68984294BF002071 -:1032C00001207047BC1E002010B5084C23682069FF -:1032D0001A6854602260012223611A74FFF790FF7C -:1032E00001462069BDE81040FDF738B9BC1E00203A -:1032F00008B5FFF7DDFF18B1BDE80840FFF7E4BFF0 -:1033000008BD0000FFF7E0BFFEE7000010B50C4C61 -:10331000FFF742FF00F08CF880220A49204600F0B7 -:103320003DF8012344F8180C0374FFF7D1FE002385 -:1033300083F3118862B6BDE81040034800F04EB830 -:10334000E41E0020F84000080841000808B572B6E5 -:10335000034B586200F0C8F900F060FAFEE700BFC6 -:10336000BC1E002000F0A0B8EFF3118020B9EFF3ED -:103370000583202282F311887047000010B530B910 -:10338000EFF30584C4F3080414B180F3118810BD71 -:10339000FFF7AEFF84F31188F9E700008260022294 -:1033A000028270478368A3F13C0243F80C2C026947 -:1033B00043F83C2C426943F8382C074A43F81C2C4C -:1033C000C268A3F1180043F8102C022203F8082C5D -:1033D000002203F8072C70476D05000810B5202364 -:1033E00083F31188FFF7DEFF00210446FFF744FF57 -:1033F000002383F31188204610BD0000024B1B6997 -:1034000058610F20FFF70CBFBC1E0020202383F360 -:103410001188FFF7F3BF000008B50146202383F3AE -:1034200011880820FFF70AFF002383F3118808BDE5 -:10343000054B03F11402C3E905224FF0FF32DA61B4 -:1034400000221A62704700BFBC1E002010B5C0E900 -:1034500003230B4A136A53699C68A1420CD85C6829 -:10346000816003604460206058609868411A9960E8 -:103470004FF0FF33D36110BD1B68091BECE700BFA1 -:10348000BC1E0020036881689A680A449A604268FA -:1034900013605A6000234FF0FF32C360014BDA61C2 -:1034A000704700BFBC1E002038B50F4C2246236A6F -:1034B0000133236252F8143F934206D020259A68C4 -:1034C000013A9A6063699A6802B138BDD3E9001085 -:1034D00001604860D968DA6082F31188186988470A -:1034E00085F31188EEE700BFBC1E00200C230360AB -:1034F0004FF0FF307047000000207047FEE70000EB -:10350000704700004FF0FF3070470000BFF34F8F4F -:10351000024AD368DB07FCD4704700BF002002409A -:1035200008B5074B1B7853B9FFF7F0FF054B1A6935 -:10353000120641BF044A5A6002F188325A6008BD3F -:10354000C01F0020002002402301674508B5054B3D -:103550001B7833B9FFF7DAFF034A136943F080039E -:10356000136108BDC01F0020002002407F289ABFC1 -:1035700000F58030C0020020704700004FF400606A -:1035800070470000802070477F2808B50BD8FFF7F0 -:10359000EDFF00F500630268013204D1043083427C -:1035A000F9D1012008BD0020FCE700007F2838B5D4 -:1035B000044623D8FFF7D8FEFFF7A8FFFFF7B0FFB8 -:1035C000F3220F4B0546DA60022220461A61FFF70C -:1035D000CDFF58611A694FF4006142F040021A6150 -:1035E000FFF794FF00F016F92846FFF7AFFFFFF74B -:1035F000C5FE2046BDE83840FFF7C6BF002038BDF5 -:10360000002002402DE9F047044612F001000E466A -:10361000154606D040F2BD22234B1A600020BDE8BB -:10362000F087224BA2189A4204D940F2C2221E4BC4 -:103630001A60F4E7FFF798FE4FF0010AFFF770FFFA -:10364000FFF764FFDFF868903146A61B012D88461E -:1036500006EB010705D8FFF779FFFFF78FFE012082 -:10366000DDE7B8F80030C9F810A03B800024FFF770 -:103670004DFFC9F810403B8831F8022B9BB29A42AB -:103680000FD040F2D922084B1A600A4B1F600A4B38 -:103690001D600A4BC3F80080FFF758FFFFF76EFE6E -:1036A000BCE7023DD2E700BFBC1F002000000408B9 -:1036B00000200240B01F0020B81F0020B41F0020CF -:1036C000084908B50B7828B11BB9FFF729FF01237A -:1036D0000B7008BD002BFCD0BDE808400870FFF758 -:1036E00035BF00BFC01F00204FF480314FF00050A5 -:1036F00000F092B870B5FFF737FE4FF47A710D4BBA -:103700000D4E1B6A326801FB03F3934237BF0B4A2D -:103710000A495168156836BF4C1CD1E90054546001 -:103720005D1944F100043360FFF728FE2846214666 -:1037300070BD00BFBC1E0020C41F0020C81F002099 -:1037400070B5FFF711FE4FF47A710F4B0F4E1B6AE5 -:10375000326801FB03F3934237BF0D4A0C495168AD -:1037600015683ABF4C1C5460D1E900545D1944F10E -:1037700000043360FFF702FE4FF47A7200232846FC -:103780002146FCF7F5FC70BDBC1E0020C41F0020C4 -:10379000C81F002010B5094C013AD2B2FF2A00D14F -:1037A00010BD500854F82030013054F820009BB26E -:1037B00043EA004341F8043BEEE700BF046C0040DD -:1037C00010B50748013AD2B2FF2A00D110BD0C88CB -:1037D000530840F823404C88013340F82340F1E778 -:1037E000046C004007B50122002001A9FFF7D2FFB9 -:1037F000019803B05DF804FB13B50446FFF7F2FF30 -:10380000A04205D00122002001A90194FFF7D8FFB2 -:1038100002B010BD70470000704700007047000004 -:1038200045F25552064B1A6002225A6040F6FF726A -:103830009A604CF6CC421A600122024B1A70704713 -:1038400000300040D41F0020034B1B781BB14AF608 -:10385000AA22024B1A607047D41F0020003000409B -:10386000044B1A682AB902F1804202F50432526A06 -:103870001A607047D01F00204FF08072014B5A62CF -:10388000704700BF0010024008B5FFF7E9FF024B88 -:103890001868C0F3407008BDD01F002008B5FFF7BE -:1038A000DFFF024B1868C0F3007008BDD01F002076 -:1038B00070470000FEE700000A4B0B480B4A90429D -:1038C0000BD30B4BC11EDA1C121A22F003028B42DF -:1038D00038BF00220021FDF753BD53F8041B40F808 -:1038E000041BECE7E84100086C2000206C2000205D -:1038F0006C2000207047000000F030B808B500F0E0 -:103900006DF9FFF703FDBDE80840FFF7A9BF000010 -:10391000704700004FF0FF310E4B1A6919611A69A8 -:1039200000221A611869D868D960D968DA60DA6843 -:10393000DA6942F08052DA61DA69DA6942F00062EB -:10394000DA61054ADB69136843F48073136000F0A1 -:1039500025B900BF00100240007000401E4B1A68DD -:1039600042F001021A601A689007FCD55A6822F0EA -:1039700003025A605A6812F00C02FBD1196801F078 -:10398000F90119605A601A6842F480321A601A68A4 -:103990009103FCD54EF63162DA625A6842F4E812BD -:1039A0005A601A6842F080721A601A689201FCD557 -:1039B0000A4A0B495A6012220A600A6802F007029A -:1039C000022AFAD15A6842F002025A605A6802F09A -:1039D0000C02082AFAD170470010024000641D0052 -:1039E00000200240084A08B5516913680B4003F0F3 -:1039F0000103536123B1054A13680BB1506898471E -:103A0000BDE80840FFF788BB00040140D81F002034 -:103A1000084A08B5516913680B4003F0020353616B -:103A200023B1054A93680BB1D0689847BDE80840B8 -:103A3000FFF772BB00040140D81F0020084A08B5F8 -:103A4000516913680B4003F00403536123B1054A25 -:103A500013690BB150699847BDE80840FFF75CBB9C -:103A600000040140D81F0020084A08B551691368B6 -:103A70000B4003F00803536123B1054A93690BB16E -:103A8000D0699847BDE80840FFF746BB00040140F5 -:103A9000D81F0020084A08B5516913680B4003F08D -:103AA0001003536123B1054A136A0BB1506A98475A -:103AB000BDE80840FFF730BB00040140D81F0020DC -:103AC000174B10B55A691C68144004F478725A6197 -:103AD000A30604D5134A936A0BB1D06A98476006CF -:103AE00004D5104A136B0BB1506B9847210604D5CF -:103AF0000C4A936B0BB1D06B9847E20504D5094A89 -:103B0000136C0BB1506C9847A30504D5054A936C10 -:103B10000BB1D06C9847BDE81040FFF7FDBA00BF6D -:103B200000040140D81F00201A4B10B55A691C68C8 -:103B3000144004F47C425A61620504D5164A136DA0 -:103B40000BB1506D9847230504D5134A936D0BB103 -:103B5000D06D9847E00404D50F4A136E0BB1506E38 -:103B60009847A10404D50C4A936E0BB1D06E9847C8 -:103B7000620404D5084A136F0BB1506F98472304B1 -:103B800004D5054A936F0BB1D06F9847BDE810403C -:103B9000FFF7C2BA00040140D81F0020062108B573 -:103BA0000846FFF7DBFA06210720FFF7D7FA0621C0 -:103BB0000820FFF7D3FA06210920FFF7CFFA0621E4 -:103BC0000A20FFF7CBFA06211720FFF7C7FABDE856 -:103BD000084006212820FFF7C1BA000008B5FFF70A -:103BE00099FE044800F00AF8FFF792FEBDE808408D -:103BF00000F002B82041000800F042B80023194646 -:103C00001C4A0133102BC2E9001102F10802F8D15D -:103C1000194B9A6942F07D029A619B690268174BC1 -:103C2000DA6082685A6042681A60C26803F580638D -:103C3000DA6042695A6002691A608269C3F80C242A -:103C4000026AC3F80424C269C3F80024426AC3F8B4 -:103C50000C28C26AC3F80428826AC3F80028026BE1 -:103C6000C3F80C2C826BC3F8042C426BC3F8002CF5 -:103C7000704700BFD81F002000100240000801401C -:103C80004FF0E023044A08215A6100229A6107227A -:103C90000B201A61FFF778BA3F19010008B52023FD -:103CA00083F31188FFF75EFB002383F3118808BDBF -:103CB00008B5FFF7F3FFBDE80840FFF72DBA000095 -:103CC0000B460146184600F025B8000000F038B851 -:103CD000012838BF012010B50446204600F028F81E -:103CE00030B900F007F808B900F00CF88047F4E7A5 -:103CF00010BD0000024B1868BFF35B8F704700BF18 -:103D000058200020062008B500F02CF90120FFF70C -:103D1000F5FB000010B504460448134620B10A46DE -:103D200002202146AFF3008010BD00BF000000005C -:103D3000024B0146186800F083B800BF1C08002041 -:103D4000024B0146186800F033B800BF1C08002081 -:103D500010B501390244904201D1002005E00378FA -:103D600011F8014FA34201D0181B10BD0130F2E73A -:103D70002DE9F0419BB10446C91A1778014403F1BB -:103D8000FF3C8C42204601D9002008E00578013430 -:103D9000BD42F6D10CEB0405D618A54201D1BDE811 -:103DA000F08115F8018D16F801EDF045F5D0E8E742 -:103DB00038B50546002940D051F8043C0C1F002BB3 -:103DC000B8BFE41800F0F2F81C4A136833B9636016 -:103DD00014602846BDE8384000F0EEB8A34208D988 -:103DE000206821188B4201BF19685B68091821609F -:103DF000EDE71A465B680BB1A342FAD91168501877 -:103E0000A0420BD120680144501883421160E0D1D8 -:103E100018685B68014411605360DAE702D90C232B -:103E20002B60D6E7206821188B4201BF19685B68B8 -:103E30000918216063605460CBE738BD5C20002026 -:103E4000F8B5CD1C25F0030508350C2D38BF0C2521 -:103E5000002D064601DBA94203D90C233360002064 -:103E6000F8BD00F0A3F821490A6814469CB9204F18 -:103E70003B6823B92146304600F03CF838602946BB -:103E8000304600F037F8431C23D10C233046336012 -:103E900000F092F8E3E723685B1B17D40B2B03D9E0 -:103EA00023601C44256004E06368A2420CBF0B60E1 -:103EB0005360304600F080F804F10B00231D20F021 -:103EC0000700C21ACCD01B1AA350C9E72246646867 -:103ED000CCE7C41C24F00304A042E3D0211A3046EE -:103EE00000F008F80130DDD1CFE700BF5C200020F2 -:103EF0006020002038B50023054D044608462B609D -:103F0000FFF7F4FA431C02D12B6803B1236038BDDC -:103F1000642000201F2938B504460D4604D9162315 -:103F200003604FF0FF3038BD426C12B152F82130BF -:103F30004BB9204600F030F82A4601462046BDE83D -:103F4000384000F017B8012B0AD0591C03D11623B2 -:103F500003600120E7E70024284642F825409847FF -:103F60000020E0E7024B01461868FFF7D3BF00BF0F -:103F70001C08002038B50023064D044608461146AB -:103F80002B60FFF7BFFA431C02D12B6803B12360FB -:103F900038BD00BF64200020FFF7AEBA034611F819 -:103FA000012B03F8012B002AF9D17047014800F0DA -:103FB00009B800BF68200020014800F005B800BF24 -:103FC0006820002070470000704700006F72672E65 -:103FD0006172647570696C6F742E61705F70657268 -:103FE0006970685F5A75626178474E5353000000EC -:103FF0004E6F20617070207369670A00426164200F -:104000006677206C656E6774682025750A004261CA -:104010006420626F6172645F696420257520736833 -:104020006F756C642062652025750A00426164200A -:1040300066772064657363726970746F72206C6553 -:104040006E6774682025750A004261642061707093 -:1040500020435243203078253038783A3078253064 -:104060003878203078253038783A307825303878EC -:104070000A00476F6F64206669726D776172650A26 -:104080000040A2E4F16468910600000042616420EF -:1040900043414E496661636520696E6465782E0010 -:1040A0008000000000800000000080000000000090 -:1040B0000000000031140008E51B0008491B00083F -:1040C0004114000871140008611600084514000826 -:1040D00059140008491400084D140008551400082C -:1040E000511400088D1500085D140008491E0008D1 -:1040F00069140008611500086D61696E0000000018 -:1041000069646C650000000000410008001F002089 -:10411000B01F00200100000009330008000000006B -:104120000C880000447B444444544424800E000026 -:1041300044141114947B444400000000444444445B -:10414000444444440400000044424444444444443D -:1041500000000000444444444444444444C0FF7FBD -:104160000100000000000000ED030000000000005E -:10417000006803000000000040420F00FE2A01001A -:10418000D204000020080020000000000000000011 -:10419000000000000000000000000000000000001F -:1041A000000000000000000000000000000000000F -:1041B00000000000000000000000000000000000FF -:1041C00000000000000000000000000000000000EF -:1041D00000000000000000000000000000000000DF -:0841E0000000000000000000D7 +:10000000000200203D08000879290008492900085D +:1000100065290008492900085D2900083F080008F3 +:100020003F0800083F0800083F0800087139000831 +:100030003F0800083F0800083F0800087545000811 +:100040003F0800083F0800083F0800083F08000874 +:100050003F0800083F080008A9420008D5420008F0 +:10006000014300082D430008594300083F080008D9 +:100070003F0800083F0800083F0800083F08000844 +:100080003F0800083F0800083F080008FD28000856 +:1000900029290008392900083F080008854300087D +:1000A0003F0800083F0800083F0800083F08000814 +:1000B0003F0800083F0800083F0800083F08000804 +:1000C0003F0800083F0800083F0800083F080008F4 +:1000D0003F0800083F0800083F0800083F080008E4 +:1000E000ED4300083F0800083F0800083F080008EB +:1000F0003F0800083F0800083F0800083F080008C4 +:100100003F0800083F0800083F0800083F080008B3 +:100110003F0800083F0800083F0800083F080008A3 +:100120003F0800083F0800083F0800083F08000893 +:100130003F0800083F0800083F0800083F08000883 +:100140003F0800083F0800083F0800083F08000873 +:100150003F0800083F0800083F0800083F08000863 +:10016000AD150008000000000000000000000000C5 +:100170004FF0FF0C1CEAD0521EBF1CEAD15392EA8A +:100180000C0F93EA0C0F6FD01A4480EA010C400266 +:1001900018BF5FEA41211ED04FF0006343EA5010C0 +:1001A00043EA5111A0FB01310CF00040B1F5000F02 +:1001B0003EBF490041EAD3715B0040EA010062F1B1 +:1001C0007F02FD2A1DD8B3F1004F40EBC25008BF9B +:1001D00020F00100704790F0000F0CF0004C08BFB9 +:1001E00049024CEA502040EA51207F3AC2BFD2F186 +:1001F000FF0340EAC250704740F400004FF0000394 +:10020000013A5DDC12F1190FDCBF00F000407047CD +:10021000C2F10002410021FA02F1C2F1200200FA0B +:1002200002FC5FEA310040F1000053EA4C0308BFD2 +:1002300020EADC70704792F0000F00F0004C02BF23 +:10024000400010F4000F013AF9D040EA0C0093F09E +:10025000000F01F0004C02BF490011F4000F013BF8 +:10026000F9D041EA0C018FE70CEAD15392EA0C0F66 +:1002700018BF93EA0C0F0AD030F0004C18BF31F0D1 +:10028000004CD8D180EA010000F00040704790F0A7 +:10029000000F17BF90F0004F084691F0000F91F04B +:1002A000004F14D092EA0C0F01D142020FD193EA11 +:1002B0000C0F03D14B0218BF084608D180EA010099 +:1002C00000F0004040F0FE4040F40000704740F075 +:1002D000FE4040F44000704780F0004002E000BF64 +:1002E00081F0004142001FBF5FEA410392EA030F21 +:1002F0007FEA226C7FEA236C6AD04FEA1262D2EB6B +:100300001363C1BFD218414048404140B8BF5B426F +:10031000192B88BF704710F0004F40F4000020F008 +:100320007F4018BF404211F0004F41F4000121F01E +:100330007F4118BF494292EA030F3FD0A2F1010268 +:1003400041FA03FC10EB0C00C3F1200301FA03F1A6 +:1003500000F0004302D5494260EB4000B0F5000FC9 +:1003600013D3B0F1807F06D340084FEA310102F188 +:100370000102FE2A51D2B1F1004F40EBC25008BF3A +:1003800020F0010040EA03007047490040EB000004 +:10039000013A28BFB0F5000FEDD2B0FA80FCACF105 +:1003A000080CB2EB0C0200FA0CF0AABF00EBC25032 +:1003B00052421843BCBFD0401843704792F0000F20 +:1003C00081F4000106BF80F400000132013BB5E773 +:1003D0004FEA41037FEA226C18BF7FEA236C21D0E9 +:1003E00092EA030F04D092F0000F08BF084670474E +:1003F00090EA010F1CBF0020704712F07F4F04D11C +:10040000400028BF40F00040704712F100723CBF2E +:1004100000F50000704700F0004343F0FE4040F458 +:10042000000070477FEA226216BF08467FEA236316 +:100430000146420206BF5FEA412390EA010F40F401 +:10044000800070474FF0000304E000BF10F000434D +:1004500048BF40425FEA000C08BF704743F0964334 +:1004600001464FF000001CE050EA010208BF70474F +:100470004FF000030AE000BF50EA010208BF7047D6 +:1004800011F0004302D5404261EB41015FEA010CEB +:1004900002BF84460146002043F0B64308BFA3F1E3 +:1004A0008053A3F50003BCFA8CF2083AA3EBC253C5 +:1004B00010DB01FA02FC634400FA02FCC2F12002E4 +:1004C000BCF1004F20FA02F243EB020008BF20F01B +:1004D0000100704702F1200201FA02FCC2F1200281 +:1004E00050EA4C0021FA02F243EB020008BF20EA76 +:1004F000DC70704742000ED2B2F1FE4F0BD34FF0CA +:100500009E03B3EB126209D44FEA002343F0004389 +:1005100023FA02F070474FF00000704712F1610FAC +:1005200001D1420202D14FF0FF3070474FF000007E +:10053000704700BF53B94AB9002908BF00281CBF43 +:100540004FF0FF314FF0FF3000F076B9ADF1080CFD +:100550006DE904CE00F006F8DDF804E0DDE90223E1 +:1005600004B070472DE9F047089E0D4604468846C2 +:10057000002B4DD18A42944668D9B2FA82F252B128 +:1005800001FA02F3C2F1200120FA01F10CFA02FC97 +:1005900041EA030894404FEA1C41B8FBF1F71FFA07 +:1005A0008CFE01FB178807FB0EF0230C43EA08437F +:1005B00098420AD91CEB030307F1FF3580F01E8136 +:1005C000984240F21B81023F63441B1AB3FBF1F0D7 +:1005D00001FB103300FB0EFEA4B244EA0344A6451F +:1005E0000AD91CEB040400F1FF3380F00981A64511 +:1005F00040F20681644402380021A4EB0E0440EA74 +:1006000007401EB10023D440C6E90043BDE8F0878F +:100610008B4208D9002E00F0EE800021C6E90005CB +:100620000846BDE8F087B3FA83F100294AD1AB420E +:1006300002D3824200F2FC80841A65EB030301209E +:100640009846002EE2D0C6E90048DFE702B9FFDE97 +:10065000B2FA82F2002A40F09180A1EB0C00012155 +:100660004FEA1C471FFA8CFEB0FBF7F307FB1300A1 +:10067000250C45EA00450EFB03F0A84208D91CEB07 +:10068000050503F1FF3802D2A84200F2CE804346AE +:100690002D1AB5FBF7F007FB10550EFB00FEA4B2B8 +:1006A00044EA0544A64508D91CEB040400F1FF35D3 +:1006B00002D2A64500F2B6802846A4EB0E0440EA1A +:1006C00003409EE7C1F120078B4022FA07FC4CEA69 +:1006D000030C25FA07FA4FEA1C49BAFBF9F820FA8D +:1006E00007F309FB18AA8D401FFA8CFE1D4300FA80 +:1006F00001F308FB0EF02C0C44EA0A44A04202FA73 +:1007000001F20BD91CEB040408F1FF3A80F0888059 +:10071000A04240F28580A8F102086444241AB4FB88 +:10072000F9F009FB104400FB0EFEADB245EA0444AB +:10073000A64508D91CEB040400F1FF356CD2A64590 +:100740006AD90238644440EA0840A0FB0295A4EB51 +:100750000E04AC42C846AE4656D353D0002E69D0E4 +:10076000B3EB080264EB0E0422FA01F304FA07F774 +:100770001F43CC40C6E90074002147E70CFA02FC95 +:10078000C2F1200125FA01F34FEA1C4720FA01F1DA +:1007900095400D43B3FBF7F107FB11331FFA8CFEB5 +:1007A000280C40EA034001FB0EF3834204FA02F4F2 +:1007B00008D91CEB000001F1FF382FD283422DD95C +:1007C00002396044C01AB0FBF7F307FB1300ADB267 +:1007D00045EA004503FB0EF0A84208D91CEB0505CD +:1007E00003F1FF3816D2A84214D9023B6544281AF7 +:1007F00043EA014138E73146304607E72F46E4E651 +:100800001846F9E64B45A9D2B9EB020865EB0C0E88 +:100810000138A3E74346EAE7284694E74146D1E793 +:10082000D0467BE76444023847E7023B65442FE744 +:10083000084606E73146E9E6704700BF02E000F0EF +:1008400000F8FEE772B6264880F30888254880F352 +:100850000988254825490860022080F31488BFF3E1 +:100860006F8F03F045FC03F0A9FC4FF05530204991 +:100870001B4A91423CBF41F8040BFAE71D49194A53 +:1008800091423CBF41F8040BFAE71B491B4A1C4B41 +:100890009A423EBF51F8040B42F8040BF8E70020DF +:1008A0001849194A91423CBF41F8040BFAE703F09A +:1008B00023FC03F085FC154C154DAC4203DA54F8CB +:1008C000041B8847F9E700F03FF8124C124DAC4288 +:1008D00003DA54F8041B8847F9E703F00BBC000067 +:1008E00000020020000800200000000808ED00E0E1 +:1008F000000100200002002010480008000800202D +:1009000080080020800800203025002060010008B9 +:100910006401000864010008640100082DE9F04F3B +:10092000C1F80CD0C3689D46BDE8F08F002383F367 +:1009300011882846A047002003F096F9FEE703F04F +:10094000F9F800DFFEE70000F8B500F041FE314A9B +:10095000536823F0E06343F0905343F480435360C3 +:1009600003F060FB074603F0AFFB0546C8BB2A4B0C +:100970009F4236D001339F4236D0284B27F0FF02EA +:100980009A4234D1F8B200F03BFC2E4642F2107489 +:1009900000F03CFC08B10024264601F00FF950B3EA +:1009A0000024032000F03EF8264635B11C4B9F4240 +:1009B00003D0002403F080FB2646002003F03CFB1C +:1009C0000EB100F045F800F08DFC00F003FE01F0E0 +:1009D000DBFF0546ACB900F0CDFC012003F04AF97D +:1009E000F8E72E460024D3E704460126D0E7064662 +:1009F00041F28834CCE7002CD7D04FF47A7401262A +:100A0000D3E701F0C1FF431BA342E4D900F020F873 +:100A1000DDE700BF00000140010007B0000008B0A2 +:100A2000263A09B0084B187003280CD8DFE800F00C +:100A300008050208022000F035BE022000F02ABEA0 +:100A40000022024B5A607047800800208408002072 +:100A500038B501F0B3F830B103221F4B1A700022F1 +:100A60001E4B5A6038BD1E4B1E4A19680131F9D021 +:100A700004339342F9D11C4C194DD4F80428AA42EE +:100A8000F0D31A4B9B6803F1006303F508439A42C5 +:100A9000E8D203F0E5FA03F0F7FA002000F0C0FD19 +:100AA0000220FFF7BFFF124BDA690022DA61D96931 +:100AB00099699A619B6972B64FF0E023C3F8085DAB +:100AC0003021D4F80038D4F8042881F311889D46E9 +:100AD00083F308881047C5E78008002084080020B9 +:100AE0000088000820880008008000080008002016 +:100AF0000010024049F26900084A136899B21B0CC1 +:100B000000FB013344F250611360054B186882B258 +:100B1000000C01FB0200186080B27047180800202A +:100B20001408002010B504460021102200F0D6FD64 +:100B3000034B03CB206061601868A06010BD00BF4C +:100B4000E8F7FF1F2DE9F0410026ADF54E7D6CACB6 +:100B500040F2751207460D460EA831460D9600F07C +:100B6000BDFD4FF4C4723146204600F0B7FD01F0E0 +:100B70000BFF4FF47A72B0FBF2F0264B0DF1340804 +:100B8000186093E80700022384E807000DF5E97078 +:100B90002382FFF7C7FF4EF603531F4907A823849C +:100BA00003F0B4FD17230DF2E32284F832310DF186 +:100BB0002C0C07AB1E4603CE6645106051603346D1 +:100BC00002F10802F6D130681060B188B37920468E +:100BD000918093714146012200F0CCFD00230393E4 +:100BE000AB7E80B2029305F1190301930123CDE995 +:100BF00004800093384605A3D3E90023E97E02F080 +:100C000087FA0DF54E7DBDE8F08100BF9E6AC421D4 +:100C1000818A46EE8C0800201C4700082DE9F0412F +:100C20002C4C8046237A0D46DAB05BBB284627A9B8 +:100C300000F0B0FE0746002842D19DF89D60C82E06 +:100C40003ED801464FF4A662204600F047FD4FF41F +:100C50008073C4F8F8314FF40073C4F80C334FF4C8 +:100C600040733246C4F820340DF19E0104F10900AE +:100C700000F022FD9DF89C302644777223720BB958 +:100C8000EB7E23728122002106AC27A800F026FD0E +:100C90000122214627A800F0B9FE00230393AB7E72 +:100CA00080B2029305F1190301932823CDE9044092 +:100CB0000093404605A3D3E90023E97E02F028FA19 +:100CC0005AB0BDE8F08100BFAFF3008026417272D8 +:100CD000DF25D7B7A81D0020F0B54FF48A75002492 +:100CE000234EF1B005FB006596F8D830D822214696 +:100CF00085F8DC3085F8E8403AA800F0EFFC06F112 +:100D0000090000F0E3FCD5F8E430C2B206AF8DF87C +:100D1000F00006F109010DF1F100CDE93A3400F0DF +:100D2000CBFC394601223AA800F09CFE80B2CDE906 +:100D3000047008230127CDE9023706F1D803019397 +:100D40003023317A00930B4807A3D3E9002302F044 +:100D5000DFF9A04206DD01F017FEC5F8E0003846D5 +:100D600071B0F0BD2046FBE778F6339F93CACD8D76 +:100D7000A81D0020A41800202DE9F0411D4D1E4E95 +:100D80001E4F86B0284602F0EFF9034658B3002400 +:100D9000CDE90344ADF81440027B02948DF8142091 +:100DA0009968406803AA03C21B68DFF8548043F0C7 +:100DB0000043029301F0EAFD821941F10003384635 +:100DC000009402A901F0D6F8A04205DD284602F001 +:100DD000CFF988F80040D5E798F80030072B05D800 +:100DE000013388F8003006B0BDE8F081014802F018 +:100DF000BFF9F8E7A418002040420F00D8180020DF +:100E0000DD22002070B50D4614461E4602F0DCF8C7 +:100E100050B9022E10D1012C0ED112A3D3E9002318 +:100E20000120C5E9002307E0282C10D005D8012CAB +:100E300009D0052C0FD0002070BD302CFBD10BA3A6 +:100E4000D3E90023ECE70BA3D3E90023E8E70BA3E6 +:100E5000D3E90023E4E70BA3D3E90023E0E700BFD5 +:100E6000AFF30080401DA12026812A0B78F6339F26 +:100E700093CACD8D9E6AC421818A46EE2641727244 +:100E8000DF25D7B7F017304A39059E5638B50546E5 +:100E90000E4C0021013500F0E5FBA4F82C55B4F808 +:100EA0002C0500F0C7FB78B1B4F82C0500F0D2FB9C +:100EB000014648B9B4F82C0500F0D4FBB4F82C3541 +:100EC0000133A4F82C35EAE738BD00BFA81D002087 +:100ED00010B50A4B0A4A1A6093F8602442B9D3F855 +:100EE0005C442CB1204600F0E7FE204603F050FBA6 +:100EF000BDE81040034800F0DFBE00BFD818002056 +:100F000070470008201D00202DE9F04F8FB000AF82 +:100F100005460C4602F058F8002848D1237E022BE3 +:100F20001AD1E38A012B17D101F02EFD0646FFF7F7 +:100F3000E1FD4FF4C873B0FBF3F202FB1303DFF8DB +:100F4000A0829BB206F516763344C8F80030E37EE3 +:100F500033B90022A34B1A703C37BD46BDE8F08F71 +:100F6000204607F1240100F0D3FC0028F4D107F15A +:100F70001400FFF7D7FD97F8264007F11401224629 +:100F800007F1270003F04EFB0028E2D10F2C08D810 +:100F9000944B1C70D8F80030A3F51673C8F80030D5 +:100FA000DAE7284697F8241002F006F8D4E7E38A37 +:100FB000282B2BD010D8012B23D0052BCCD1BFF35D +:100FC0004F8F8949894BCA6802F4E0621343CB60B2 +:100FD000BFF34F8F00BFFDE7302BBDD1844EE17EC4 +:100FE000327A9142B8D131460022607E91F8DC50CD +:100FF000854200F0A5800132042A01F58A71F5D1FD +:10100000AAE721462846FFF79DFDA5E72146284689 +:10101000FFF704FEA0E7B2F8EC507B6005F103098E +:101020004FEA99094FEA8902D11DC908A8EBC1030B +:101030009D46EB460021584600F050FB04F1EE01BE +:101040002A465846314400F037FB7B6813B901202B +:1010500000F0E6FA96F8D20000F0ECFA044630B957 +:10106000307200F007FB204600F0DAFAB0E0D6F864 +:10107000D4203AB996F8D200B6F82C25824201D88D +:10108000FFF704FFD6F8D4202A44944208D296F8F9 +:10109000D200B6F82C250130824201D8FFF7F6FEC7 +:1010A000594670685FFA89F200F020FB08B9C5461E +:1010B00078E0726896F8D2002A447260D6F8D4209C +:1010C00005EB0209C6F8D49000F0B4FA814509D3C3 +:1010D00096F8D220D6F8D4000132001B86F8D22030 +:1010E000C6F8D400FF2D0FD80024347200F0C2FAE5 +:1010F000204600F095FA00F061FD3E4B188108B9DA +:10110000FFF7A6FCC54627E7BB6896F8D9000AFB9F +:101110000362D2F8E410FB6801F5806182F8E830E0 +:10112000C2F8E030C2F8E410FFF7D6FDFFF724FE66 +:1011300096F8D920013202F0030286F8D920B6E7EA +:101140004FF48A7A0AFB02F505F1EA0120463144A0 +:1011500000F0B4FCF86000287FF4FEAE01223544B4 +:1011600085F8E82001F010FCD5F8E020801A192855 +:1011700040F6B83238BF1920904228BF1046FFF71A +:1011800061F91D49FEF7F4FF04463068FFF75AF98C +:101190001A49FEF7EDFF01462046FFF7A3F8FFF7D7 +:1011A000A9F9306096F8D930BB60BA6873680AFB59 +:1011B00002F4321992F8E81059B1D2F8E410E84676 +:1011C0008B423FF428AF002182F8E810C2F8E0100B +:1011D000C5467368074A9B0A01331381BCE600BF0A +:1011E000A01800209D18002000ED00E00400FA0582 +:1011F000A81D00208C080020CDCCCC3D6666663F43 +:10120000014B1870704700BF9808002030B54FF0B0 +:1012100000542B4B226885B09A4207D002F05EFF43 +:10122000044620BB0024204605B030BD627D254B1E +:1012300025481A70237D002503724FF48073C0F88F +:10124000F8314FF40073C0F80C334FF44073C922E7 +:10125000C0F820341D49C0F8E450093000F02CFAE1 +:101260002046E022294600F039FA0124DBE7184A3B +:10127000184DD36943F00073D361AA6D164B9A429F +:10128000D0D12B6E013B7E2BCCD8144A01AB07CAC0 +:1012900083E807001846032100F060FC6B6D834271 +:1012A0004FF00003BED12A6D8A4203BFAB652A6EA0 +:1012B000044B1C4601BF1A70EA6D094B1A60B2E775 +:1012C0009AAD44C598080020A81D002016000020F3 +:1012D00000100240006600405041A0B05866004037 +:1012E0001008002037B500F069FC0223184D0122D8 +:1012F0006B71184B28811968174801F0F3F9002326 +:101300000193164B164900934FF48052154B164823 +:1013100001F028FE154B197811B1134801F04CFE6D +:1013200001F032FB0446FFF7E5FB4FF4C873B0FB56 +:10133000F3F202FB130304F516709BB218440C4B36 +:10134000186002F0C1FE08B10F232B8103B030BD3D +:101350008C08002010080020D8180020050E000876 +:101360009C080020090F0008A418002098080020FD +:10137000A01800202DE9F04F0FF22829D9E90089A3 +:101380007E4C93B0FFF7F8FC00230BAE7C4FDFF8E8 +:10139000F4A10A93ADF834300B9373604FF0000B57 +:1013A000002200230125CDE9002338465B460DF1DC +:1013B0001D0207A98DF81C508DF81DB001F044F9ED +:1013C0009DF81C30002B40F0A080204601F0FCFD71 +:1013D0000646002845D101F0D7FA6B4F3B6898428A +:1013E0003FD301F0D1FA8246FFF784FB4FF4C87374 +:1013F000B0FBF3F202FB130083B20AF51670184437 +:101400003860624F0EA897F800B0BBF1000F14BF10 +:1014100033462B46CBF1100A5FFA8AFA8DF8283052 +:10142000FFF780FBBAF1060F28BF4FF0060A0EAB9C +:1014300003EB0B0152460DF1290000F03DF90AAB18 +:10144000039318230AF101020293514BD2B2CDE962 +:1014500000530492204647A3D3E9002301F0FAFD8C +:101460003E7001F091FA4B4A4B4D1368C31AB3F525 +:101470007A7F2ED3106001F089FA02460B4620468F +:1014800001F080FE204601F09FFD10B32B7A434E01 +:10149000002B14BF03230223737101F075FA4FF47C +:1014A0007A73B0FBF3F00EAF01223060394630465C +:1014B00000F006FA18230293394B80B2019340F2F0 +:1014C0005513CDE90370009342464B46204601F088 +:1014D000C1FD2B7AB3B101F057FA002607464FF44D +:1014E0008A7A95F8D900304400F003000AFB0053D3 +:1014F00093F8E8206AB30136042EF2D12B7A002B40 +:101500007FF440AF13B0BDE8F08FDAF80C305946E5 +:1015100083F00803CAF80C3010220EA800F0DEF8A1 +:101520000DF11E0308AA0AA9384600F019FE96E834 +:1015300003000FAB83E803009DF8343020468DF89C +:1015400044300A9B0EA90E93DDE9082301F0F0FF59 +:1015500024E7D3F8E02042B12B68BA1AFA2B38BF3F +:10156000FA230533B2EB430FC5D3FFF7B5FB0028D1 +:10157000C1D1C3E7401DA12026812A0BA418002059 +:10158000D8180020000C0140A01800209D18002051 +:101590009C180020D8220020A81D00208C080020C4 +:1015A000DC220020F1C6A7C1D068080F08B50548A5 +:1015B00000F06CFEBDE808400020034A034902F039 +:1015C000E1BF00BFD818002018230020D10E00086A +:1015D0007047000070B502F0F9FB00250E4C0F4E6D +:1015E00020803068238883420CD800252088013869 +:1015F00002F0E8FB23880544013BB5F5805F2380BA +:10160000F4D370BD02F0DEFB336805440133B5F559 +:10161000084F3360E5D3E8E70C230020E0220020E8 +:1016200002F062BC00F10060920000F5084002F098 +:1016300007BC0000054B1A68054B1B889B1A8342A8 +:1016400002D9104402F0BEBB00207047E022002007 +:101650000C230020024B1B68184402F0B9BB00BFEA +:10166000E0220020024B1B68184402F0C3BB00BFFD +:10167000E0220020064991F8243033B100230822EB +:10168000086A81F82430FFF7CDBF0120704700BF02 +:10169000E4220020022802BF0822014B1A61704791 +:1016A000000C0140022802BF4FF40022014B1A61D6 +:1016B000704700BF000C0140002310B5934203D0D7 +:1016C000CC5CC4540133F9E710BD00000346024668 +:1016D000D01A12F9011B0029FAD1704703460244BF +:1016E000934202D003F8011BFAE770472DE9F84353 +:1016F0001F4D144695F824200746884652BBDFF854 +:1017000070909CB395F824302BB92022FF214846D5 +:101710002F62FFF7E3FF95F824004146C0F108026D +:10172000A24228BF224605EB8000D6B29200FFF706 +:10173000C3FF95F82430A41B1E44F6B2082E1744AC +:101740009044E4B285F82460DBD1FFF793FF0028D2 +:10175000D7D108E02B6A03EB82038342CFD0FFF797 +:1017600089FF0028CBD10020BDE8F8830120FBE7EA +:10177000E42200202DE9F0470D4604460021904662 +:10178000284640F27912FFF7A9FF234620220021C4 +:10179000284601F06FFE022220212846231D01F079 +:1017A00069FE032222212846631D01F063FE032205 +:1017B00025212846A31D01F05DFE10222821284680 +:1017C00004F1080301F056FE08223821284604F1EE +:1017D000100301F04FFE08224021284604F11103B6 +:1017E00001F048FE08224821284604F1120301F0C6 +:1017F00041FE20225021284604F1140301F03AFE54 +:1018000040227021284604F1180301F033FE08221B +:10181000B021284604F1200301F02CFE0822B82153 +:10182000284604F1210301F025FEC02604F1220719 +:101830003B46314608222846083601F01BFEB6F525 +:10184000A07F07F10107F3D108223146284604F1B1 +:10185000320301F00FFE002704F1330A94F832300E +:101860004FEAC7099F4209F5A47615D3B8F1000FD6 +:1018700008D131460722284604F5997301F0FAFD94 +:1018800009F24F16274694F832213B1B93420CD3A2 +:10189000F01DC008BDE8F0870AEB070308223146B7 +:1018A000284601F0E7FD0137D8E7314607F2331348 +:1018B0000822284601F0DEFD08360137E3E7000084 +:1018C00038B50C460021054621600346C4F80310D4 +:1018D0002046202201F0CEFD20462B1D0222202191 +:1018E00001F0C8FD20466B1D0322222101F0C2FD3C +:1018F0002046AB1D0322252101F0BCFD204610220D +:10190000282105F1080301F0B5FD072038BD0000CE +:101910000023F7B50E460546047F072200911946BD +:1019200001F06AFC731C0093012200230721284662 +:1019300001F062FCC4B9B31C0093052223460821C0 +:10194000284601F059FC0D243746B278BB1B934260 +:1019500011D32B7FE01DC008AC8ABBB9A04294BF55 +:101960000020012003B0F0BDAB8A0824DB00083B57 +:10197000DB08B370E8E7FB1C214600930822002334 +:10198000284601F039FC08340137DEE7001B18BF98 +:101990000120E7E70023F7B50E46047F08220091F7 +:1019A0001946054601F028FC731CC4B908220093AF +:1019B00011462346284601F01FFC102401237278AB +:1019C0005F1C013B934211D32B7FE01DC008AC8A02 +:1019D000BBB9A04294BF0020012003B0F0BDAB8A88 +:1019E0000824DB00083BDB087370E7E7F3192146A6 +:1019F000009308220023284601F0FEFB08343B46F2 +:101A0000DDE7001B18BF0120E7E70000F8B50E4630 +:101A100005461446002181223046FFF75FFE2B4623 +:101A200008220021304601F025FD7CB9072208215B +:101A300030466B1C01F01EFD0F2401236A785F1CE9 +:101A4000013B934204D3E01DC008F8BD0824F4E72D +:101A50002146EB190822304601F00CFD08343B46C4 +:101A6000ECE70000F8B50E46054614460021CE22EC +:101A70003046FFF733FE2B4628220021304601F086 +:101A8000F9FC7CB908222821304605F1080301F051 +:101A9000F1FC30242F462A7A7B1B934204D3E01DAD +:101AA000C008F8BD2824F5E7214607F109030822FC +:101AB000304601F0DFFC08340137ECE7F7B5047F6E +:101AC0000E460091012310220021054601F094FBEF +:101AD000C4B9B31C0093092223461021284601F003 +:101AE0008BFB192437467288BB1B9A4211D82B7F77 +:101AF000E01DC008AC8ABBB9A04294BF0020012001 +:101B000003B0F0BDAB8A1024DB00103BDB08738010 +:101B1000E8E73B1D2146009308220023284601F0F8 +:101B20006BFB08340137DEE7001B18BF0120E7E735 +:101B300030B5094D0A4491420DD011F8013B58408F +:101B4000082340F30004013B2C4013F0FF0384EA18 +:101B50005000F6D1EFE730BD2083B8ED4FF0FF33F2 +:101B6000F7B500EB81061946DFF848C0DFF848E01A +:101B7000B0421BD050F8042B01AF0192042217F899 +:101B8000014B81EA046108240D46DB184941013C00 +:101B9000002DBCBF83EA0C0381EA0E0114F0FF04A0 +:101BA000F2D1013A12F0FF02E9D1E1E7D843C9438B +:101BB00003B0F0BD9336EAA9EBE1F042F7B56B460E +:101BC000374A106851686A4603C3082335493648C6 +:101BD00002F038FD0446002833D10A256B46334A0B +:101BE000106851686A4603C3082331492E4802F041 +:101BF00029FD0446002849D00369B3F55E3F45D866 +:101C000040F2ED32B0F8661091423FD1294A0244C9 +:101C100002F15C018B4239D35C3B234900209E1AC0 +:101C2000FFF786FF07463246002004F16401FFF704 +:101C30007FFFA3689F4229D1E368984208BF00252F +:101C400024E00369B3F55E3F27D840F2ED32418BC3 +:101C5000914220D1174A024402F110018B4218D35D +:101C6000103B114900209D1AFFF762FF06462A46E5 +:101C7000002004F11801FFF75BFFA3689E4202D128 +:101C8000E368984201D00D25A8E70025284603B057 +:101C9000F0BD1025A2E70C25A0E70B259EE700BFAD +:101CA00034470008DC770300008800083D4700083F +:101CB000907703000878FFF710B5037C044613B94A +:101CC000006802F0A7FC204610BD00000023BFF30F +:101CD0005B8FC360BFF35B8FBFF35B8F8360BFF32A +:101CE0005B8F7047BFF35B8F0068BFF35B8F7047FC +:101CF00070B505460C30FFF7F5FF05F10806044600 +:101D00003046FFF7EFFFA04206D930466D68FFF777 +:101D1000E9FF2C44201A70BD3046FFF7E3FFF9E7D6 +:101D200070B505464068A0B105F10800FFF7DAFF7D +:101D300005F10C0604463046FFF7D4FF844288BF05 +:101D40000025304698BF6D68FFF7CCFF013C2C445E +:101D5000201A70BD38B50C460546FFF7C9FFA042F2 +:101D600010D305F10800FFF7BDFF04446868BFF316 +:101D70005B8FB4FBF0F100FB1144AC60BFF35B8FF1 +:101D8000012038BD0020FCE72DE9F041144607464C +:101D90000D46FFF7C5FF844228BF0446D4B1B846BC +:101DA00058F80C6B4046FFF79DFF06442E604046F6 +:101DB0007E68FFF797FF331A9C4203D801206C60BE +:101DC000BDE8F0816B603B68A61B0644AB60022057 +:101DD000EE60F5E72046F3E738B50C460546FFF719 +:101DE0009FFFA04210D305F10C00FFF77BFF0444D6 +:101DF0006868BFF35B8FB4FBF0F100FB1144EC604B +:101E0000BFF35B8F012038BD0020FCE72DE9FF41C7 +:101E10000F46694606466C46FFF7B6FF002504EB01 +:101E2000C008444508D0626820687919FFF744FC6F +:101E3000636808341D44F4E729463046FFF7CCFFB9 +:101E4000284604B0BDE8F081F8B505460C300F46D1 +:101E5000FFF748FF05F1080604463046FFF742FF4A +:101E6000A042304688BF6C68FFF73CFF201A3860FC +:101E700020B130462C68FFF735FF2044F8BD000044 +:101E8000F7B5174606460D46FFF732FFB84204463F +:101E900028BF3C460190DCB1304601A9FFF7D4FFD2 +:101EA000019B33B93268C5E90233C5E9002401203A +:101EB0000CE09C4238BF019428600198844268601D +:101EC000F5D9241A02203368EC60AB6003B0F0BD92 +:101ED0002046FBE72DE9FF410E466946FFF7D0FF9C +:101EE0006C46002504EBC007BC4209D0D4F804803E +:101EF0007019424654F8081BFFF7DEFB4544F3E730 +:101F0000284604B0BDE8F08138B50546FFF7E2FF8A +:101F1000044601462846FFF71DFF204638BD000055 +:101F2000302383F3118862B670470000002383F3E7 +:101F3000118862B67047000010B4026854681A46EF +:101F4000234610BC1847000001207047002070474E +:101F50000020704770470000002070470E20704737 +:101F600090F8C804C0F340007047000090F9C9041D +:101F700070470000F7B50C681E4614F00054BDF819 +:101F800020706AD10B7B082B67D8FFF7C9FF456922 +:101F9000AB685B010CD4AB681B0108D4AC6814F0CF +:101FA000805458D1FFF7C2FF204603B0F0BD012492 +:101FB0000B6804F1180C002BBABFDB0043F00403DC +:101FC0005B054FEA0C1C45F80C300B684FEA041C0B +:101FD00013F0804F1CBF05EB0C0EDEF88031AC44D3 +:101FE0001CBF43F00203CEF880310B7B05EB0415D8 +:101FF000CCF884318B68C5F88C314B68C5F88831D2 +:102000000D46DCF8803143F00103CCF8803100EB61 +:102010004413C3F86824C3F86C6401F10C0C03F595 +:102020008E6355F804EB654543F804EBF9D12D8830 +:1020300024341D8000EB4414257907F0030325F0B8 +:102040000B052B432371FFF771FF3346009700F018 +:10205000BDFC0120A9E70224AAE74FF0FF30A4E766 +:1020600038B50446D0F85C040D46FFF759FE1F282A +:102070000AD920222946D4F85C04FFF7C7FEA0F154 +:1020800020035842584138BD0020FCE708B5FFF74F +:1020900047FFD0F85C04FFF719FEBDE80840FFF7E2 +:1020A00045BF00000022026082814260826070476A +:1020B0000022002310B5C0E9002300230446038159 +:1020C0000C30FFF7EFFF204610BD0000F0B590F890 +:1020D000C8340D4613F0040FC3F3800108BF114646 +:1020E00005F1240661F3820380F8C83400EB46133F +:1020F0001B790446D80789B02DD572B319072CD4A3 +:1021000004EB45156846FFF7D3FF05F58E6303AA78 +:1021100005F58F65174618685968083303C7AB4241 +:102120003A46F7D11868694638609B882046BB80DC +:10213000DDE90E23CDE900230123ADF80830236843 +:10214000DB6B984704EB461423791A075CBF43F016 +:102150000803237101E0002AF4D109B0F0BD0000AA +:102160002DE9F047054688B068469A46884691466C +:10217000FFF7D6FEFFF79CFFD5F85C04FFF7B8FD2C +:102180001F282AD920226946D5F85C04FFF7BCFE37 +:10219000202822D1444603AE05AB374603CF9F42E9 +:1021A000206061603E4604F10804F6D1386841467B +:1021B0002060BB882846A380DDE90023C9E900230D +:1021C000BDF808304A46AAF80030FFF7AFFE534684 +:1021D00008B0BDE8F04700F0E7BB0020FFF7A6FE1F +:1021E00008B0BDE8F087000000232DE9F047044661 +:1021F000C0E90133224B0E4640F8183BFFF752FF6F +:1022000004F1480704F12800FFF752FF3D4604F5AA +:10221000896828462035FFF74BFF4545F9D14FF433 +:102220008063C4F84874C4F84C34002701234FF08D +:1022300000084FF00009C4F85C54C4F85074C4F8A6 +:10224000547484F8583484F8603404F5916504F5C6 +:102250009D6A45E90889A5F11800FFF723FF20359D +:1022600045F8287C5545F4D184F8C96416B1054871 +:1022700000F084FB044B20466361BDE8F08700BF9B +:1022800070470008484700080064004010B5044645 +:10229000034B19784A1C1A70FFF7A6FF204610BDA1 +:1022A000142300202DE9F04300294FD0284F294B5B +:1022B000B7FBF1F499428CBF0A231123B4FBF3FC62 +:1022C000581E03FB1C43C5B22BB102280346F5D8A8 +:1022D0000020BDE8F0830CF1FF36B6F5806FF7D231 +:1022E0004FF47A74C5EBC50E0EF103034FEAE30910 +:1022F00009FB0444C3F3C703E81AC0B209F101089B +:102300008044B4FBF8F4B4F5617FC2BF0EF1FF3333 +:10231000C3F3C703E81A03F10104C8BFC0B2E4B2B3 +:1023200004440CFB04F4B7FBF4F4A142D0D1013B0C +:10233000DBB20F2BCCD80138C0B20728C8D8002197 +:102340001071168001209170D370C2E70846C0E773 +:10235000005125023F420F0070B505460E464FF46E +:102360007A746B6901205B6803F00103B34204D007 +:1023700001F080FC013CF4D1204670BD30B54269CB +:10238000936913F0700F16D000230B4C936103F187 +:10239000240200EB421211794D0709D5890707D5B0 +:1023A000416954F823508D60117941F00401117195 +:1023B0000133032BEBD130BD5C47000873B51D46DC +:1023C000436916469A680446D20709D501219A68DE +:1023D0009960C2F340020021CDE90065FFF776FE67 +:1023E00063699A68D1050BD54FF480719A682046CD +:1023F0009960C2F340220121CDE90065FFF766FE36 +:1024000063699A68D2030BD54FF480319A682046ED +:102410009960C2F340420221CDE90065FFF756FE04 +:10242000204602B0BDE87040FFF7A8BFF8B50446EB +:10243000466900296AD106F10C073868800768D020 +:10244000386806EB01104FEA011CD0F8B011D0F843 +:10245000B051490746BFED0845F000456D0DA56137 +:10246000D0F8B011890744BF45F08045A561D0F888 +:10247000B40106EB0C0100F00F0084F82400D1F841 +:10248000B80104F124052077D1F8B801000A60777B +:10249000D1F8B801000CA077D1F8B801000EE077B0 +:1024A000D1F8BC0184F82000D1F8BC01000A84F8FE +:1024B0002100D1F8BC01000C84F82200D1F8BC1135 +:1024C00004F13400090E84F823103821396004F136 +:1024D000180151F8046BA94240F8046BF9D109883E +:1024E0000180C4E90A2300232146238651F8283BB2 +:1024F0002046DB6B984794F8C834204643F0040329 +:1025000084F8C834BDE8F840FFF738BF06F110077B +:1025100093E7F8BD10B5044600F038FA02460B46C2 +:1025200052EA030102D0013A63F10003044908684A +:1025300020B12146BDE81040FFF778BF10BD00BFB5 +:1025400010230020F8B500211E46FFF7E9FC124FCA +:1025500000F58D6501F1240400EB4414237913F098 +:10256000040F0FD1DB060DD5D5E900C39445B34167 +:1025700008D2436957F821C0C3F808C0237943F053 +:10258000040323710131032905F12005E2D1BDE8DF +:10259000F840FFF7CBBC00BF5C47000808B5FFF769 +:1025A000BFFCFFF7EBFEBDE80840FFF7BFBC000033 +:1025B000F8B54369044698680E4600F0E050B0F163 +:1025C000E05F1DD0D8B1FFF7ABFC002504F58E67A6 +:1025D00004EB451393F884341A0706D50135032D0F +:1025E00007F12007F4D1012007E05B07F6D4394654 +:1025F000304600F025FA0028F0D1FFF797FCF8BD2F +:102600000120FCE708B5FFF78BFCD0F85C04FFF76E +:102610006FFBFFF78BFC43090CBF0120002008BDB6 +:10262000F8B51D46002313700F4606461446FFF703 +:10263000E9FF80F00100387025B129463046FFF7E8 +:10264000B7FF2070F8BD0000F8B50C4615461E46D1 +:10265000074600F09BF90B462178024609B9287815 +:1026600050B13846FFF76EFFFFF798FF33462A4612 +:102670002146FFF7D5FF0120F8BD000010B5FFF798 +:102680004FFC174B0446DA6942F00072DA611A69AE +:1026900042F000721A611A6922F000721A61FFF7A3 +:1026A00045FC90F8C834DB0718D4B9B103211320D6 +:1026B000FFF736FC01F0ACF90321142001F0A8F972 +:1026C0000321152001F0A4F994F8C83443F0010364 +:1026D00084F8C834BDE81040FFF728BC10BD00BF27 +:1026E000001002402DE9F04790F8C9340446012B50 +:1026F0000F46154688B07DD87F4E56F823200AB97C +:1027000046F82300D6F80090E7602574B9F1000F71 +:1027100062D094F8C934012B6ED04FF0000801212B +:102720002046FFF7ABFFFFF7FBFB6269012113684F +:10273000204623F0020313606269136843F001032B +:1027400013606369C3F81480FFF7F0FBFFF704FE22 +:10275000002800F09280D4F85C04FFF7B7FAA14695 +:1027600004F1600A202200216846FEF7B7FF02A8A4 +:10277000FFF798FC6A46CDF8188009F58D630DF1D6 +:10278000180C164603CE664518605960324603F1B0 +:102790000803F6D1306809F1200918603279CA457A +:1027A0001A71DFD1002694F8C8346A466FF38203A9 +:1027B00084F8C83439462046ADF80060ADF80260B0 +:1027C0008DF80460FFF76EFD636948BB4FF400426B +:1027D0001A6008B0BDE8F0874FF49A6001F0DAFEA5 +:1027E000804610B14946FFF7FFFCC6F80080B8F1FB +:1027F000000F8ED10020ECE7306803681B6B984710 +:102800000146002889D13068FFF738FF30682A4632 +:10281000036839465B68984700287FF47EAFE9E794 +:102820006122022D0CBF4FF0004100211A609DF87B +:1028300002309DF803201B06120402F4702203F0FC +:1028400040731343BDF800202046C2F3090213432E +:102850009DF80420120502F4E002134362690B4361 +:10286000D3611322636931465A616269136823F0A8 +:1028700001031360FFF770FD08B96369A6E794F8D8 +:10288000C93493BB6169D1F8002242F00102C1F85A +:1028900000226169D1F8002222F47C5222F00E025B +:1028A000C1F800226169D1F8002242F46062C1F8E7 +:1028B000002241F6FF716269C2F814326269C2F8FF +:1028C00004326269C2F80C126269C2F8403262696D +:1028D000C2F8443201226369C3F81C226269D2F84B +:1028E000003223F00103C2F8003294F8C83443F0F8 +:1028F000020384F8C8346CE71023002008B500F008 +:1029000045F802460B4652EA030102D0013A63F150 +:1029100000030449086808B1FFF750FDBDE808400E +:1029200001F054B81023002008B50020FFF7F2FD95 +:10293000BDE8084001F04AB808B50120FFF7EAFDFC +:10294000BDE8084001F042B8EFF30983EFF30583D7 +:10295000014B9B6BFEE700BF00ED00E008B5FFF701 +:10296000F3FF0000EFF30983EFF30583014B5B6B8B +:10297000FEE700BF00ED00E0FEE700000FB408B581 +:10298000029801F00DF9FEE701F0FABA01F0D2BAAF +:1029900013B56C4684E80600031D94E8030083E841 +:1029A0000500012002B010BDF8B586680D4656B18D +:1029B0001B885B0707D4D0E900379B6B98472A46F2 +:1029C000C1B23846B0470120F8BD0000F0B58668B6 +:1029D00005460C4689B05EB1BDF838305B070AD4B5 +:1029E000D0E900379B6B98472246C1B23846B047C2 +:1029F000012009B0F0BD00220023CDE9002300230F +:102A00000A46ADF8083001F1080603AB1C46106811 +:102A10005168083203C4B2422346F7D110682060DF +:102A20009288A280FFF7B2FF0423ADF808302B682C +:102A3000CDE90001DB6B694628469847D8E70000DE +:102A400030B503680968DD0FB5EBD17F23F0604432 +:102A500021F060424FEAD1700BD0002BB8BFA40C1C +:102A60000029B8BF920C944202D034BF012000204C +:102A700030BD944205D1C1F38070C3F380738342AB +:102A8000F6D194422CBF00200120F1E72DE9F0415E +:102A9000456A15B94162BDE8F0814B68AC4623F048 +:102AA0006047C3F38A4616EA230638BF3E464FEA1C +:102AB000D37EC3F380782B465A68BEEBD27F22F0D8 +:102AC00060440AD0002A18DAA40CB44217D19D42FF +:102AD0000FD10D60DEE71346EEE7A74207D102F003 +:102AE0008044C2F3807242450BD054B1EFE708D264 +:102AF000EDE7CCF800100B60CDE7B44201D0B44252 +:102B0000E5D81A689C46002AE5D11960C3E70000A1 +:102B10002DE9F0474FF47F49089D01F007044FEA83 +:102B2000D508224405F0070500EBD100944201D1FD +:102B3000BDE8F08704F0070705F0070A57453E4651 +:102B400038BF5646111BC6F108068E4228BF0E46F6 +:102B5000E108415C08EBD50E13F80EC0B94029FA24 +:102B600006F721FA0AF1FFB28CEA010147FA0AF7E7 +:102B700039408CEA010C03F80EC034443544D5E7E3 +:102B8000082341F2210280EA012001B2400000291D +:102B900080B203F1FF33B8BF504013F0FF03F4D10C +:102BA0007047000038B50C468D18A54200D138BDDD +:102BB00014F8011BFFF7E4FFF7E700000346406845 +:102BC00048B1026899895A605A89013292B2914299 +:102BD0005A8138BF9A81704770B504460D4688B057 +:102BE000202200216846FEF779FD20460495FFF774 +:102BF000E5FF024658B16B46054608AE1C4603CCBD +:102C0000B44228606960234605F10805F6D11046F4 +:102C100008B070BD082817D909280CD00A280CD094 +:102C20000B280CD00C280CD00D280CD00E2814BF6B +:102C30004020302070470C2070471020704714202F +:102C4000704718207047202070470000082817D9C7 +:102C50000C280CD910280CD914280CD918280CD9F8 +:102C600020280CD930288CBF0F200E207047092057 +:102C700070470A2070470B2070470C2070470D20CA +:102C8000704700002DE9F843078C0446072F1ED932 +:102C9000D0E9029800254FF6FF73C5F12006A5F193 +:102CA000200029FA05F108FA06F628FA00F0314367 +:102CB0000143C9B21846FFF763FF0835402D0346AC +:102CC000EBD13A46E169BDE8F843FFF76BBF4FF639 +:102CD000FF70BDE8F883000010B54B6823B9CA8ABD +:102CE00063F30902CA8210BD04691A681C6003619B +:102CF000C38A013BC3824A60EFE700002DE9F84F29 +:102D00001D46CB8A0F46C3F3090105298146924629 +:102D10000B4630D00020AAB207F11A049EB2042E4E +:102D20001FFA80F80FD8904503F1010306D3FB8A00 +:102D30000A4462F309030120FB821AE01AF80060DA +:102D40000130E654EAE79045F1D21C23A1F1050BCE +:102D5000BBFBF3F203FB12BB7C681FFA8BF6002C63 +:102D600045D14846FFF72AFF044638B978606FF02E +:102D70000200BDE8F88F4FF00008E6E70026066085 +:102D800078604FF0000BADB2454510D90AEB08034F +:102D9000221D13F8011B08F101089155B1B21B293E +:102DA0001FFA88F82BD0454506F10106F1D8FB8AB9 +:102DB000C3F30902154465F30903BCE71C4601325D +:102DC00092B22368002BF9D16B1F0B441C21B3FB7B +:102DD000F1F301339BB29A42D3D2BBF1000FD0D1B1 +:102DE0004846FFF7EBFE20B9C4F800B0BFE7012268 +:102DF000E7E7C0F800B05E4620600446C1E74545FD +:102E0000D5D94846FFF7DAFE08B92060AFE7C0F829 +:102E100000B0002620600446B6E700002DE9F74F19 +:102E20001C465B69074688460092002B00F097809D +:102E3000238C2BB1E269002A00F09180072B33D854 +:102E400007F10C00FFF7BAFE054628B96FF002053E +:102E5000284603B0BDE8F08F14220021FEF73EFCA7 +:102E6000228CE16905F10800FEF726FC208C48F071 +:102E70000041013080B2FFF7E9FEFFF7CBFE0138D9 +:102E800080B22084013028746369228C1B782A4424 +:102E900003F01F0363F03F0313723846696029464D +:102EA000FFF7F4FD0125D3E74FF000094FF0800A4A +:102EB0004E464D4600F10C0301930198FFF77EFE4C +:102EC00083460028C2D014220021FEF707FC002E02 +:102ED0003BD10222009BABF808300BF1080E1FFA21 +:102EE00082FC0CF10100BCF1060F218C80B201D8EC +:102EF0008E422CD3FFF7AAFEFFF78CFE8E4208BF4E +:102F00004FF0400A62690138127880B202F01F0265 +:102F100042EA49120BEB00014AEA020A013048F08A +:102F2000004281F808A08BF8100059463846CBF8CB +:102F30000420FFF7ABFD238C0135B3424FF0000AAC +:102F40002DB289F00109B8D182E70022C5E7E16915 +:102F5000895D01360EF80210B6B20132BFE76FF09C +:102F6000010575E7F8B5044615460E4630220021E6 +:102F70001F46FEF7B3FB069BB5F5001F6360079B7A +:102F800028BF4FF6FF72A3624FF0000338BF6A09F3 +:102F9000A760E66197B204F110009A4206D80023B8 +:102FA0000360A782E3822383E360F8BD06600133F8 +:102FB00030462036F1E7000003781BB94BB2002BF6 +:102FC000C8BF01707047000000787047F8B50C4624 +:102FD000C969074611B9238C002B37D1257E1F2DD7 +:102FE00034D8387828BB228C072A2CD8268A36F089 +:102FF00003032BD14FF6FF70FFF7D4FD4FF6FF729E +:1030000020F001003602400446EA0565400C45EA1E +:103010004025234629463846FFF700FF002807DDF4 +:10302000626913780133DBB21F2B88BF0023137052 +:10303000F8BD218A2D0645EA012505432046FFF704 +:1030400021FE0246E5E76FF00300F1E76FF00100B3 +:10305000EEE7000070B504461D4616468AB02822E9 +:1030600000216846FEF73AFBBDF838306946ADF8F6 +:1030700010300F9B204605939DF84030CDE9026546 +:103080008DF81830119B0793BDF84830ADF820300B +:10309000FFF79CFF0AB070BD2DE9F041D3690546EA +:1030A0000C4616460BB9138C5BBB377E1F2F28D8F6 +:1030B00095F80080B8F1000F26D03046FFF7E2FD0A +:1030C0003378210241EAC33141EA0801338A41EAF7 +:1030D000076141EA034102463346284641F0800138 +:1030E000FFF79CFE00280ADD3378012B07D17269B7 +:1030F00013780133DBB21F2B88BF00231370BDE8A8 +:10310000F0816FF00100FAE76FF00300F7E70000CD +:10311000F0B504460D461E4617468BB02822002106 +:103120006846FEF7DBFA9DF84C3029465A1E53429A +:1031300053418DF800309DF840306A46ADF81030AC +:10314000119B204605939DF84830CDE902768DF815 +:103150001830149B0793BDF85430ADF82030FFF7BA +:103160009BFF0BB0F0BD0000406A00B10430704717 +:10317000436A1A68426202691A600361C38A013BAA +:10318000C38270472DE9F041D0F8208014461D46D7 +:1031900041460027174E09B9BDE8F081D1E9022365 +:1031A000A21A65EB0303964277EB03031ED2036A70 +:1031B0008B420DD1FFF790FD036A1B680362036920 +:1031C0000B60C38A0161016A013B8846C382E2E762 +:1031D000FFF782FD0B68C8F8003003690B60C38AF3 +:1031E0000161013BC382D8F80010D4E78846096822 +:1031F000D1E700BF80841E002DE9F04F8BB00D4653 +:1032000014469B468046DDF85090002800F01A8155 +:10321000B9F1000F00F01681531E3F2B00F212810E +:10322000012A03D1BBF1000F40F00C810023CDE94E +:103230000833B8F81430B5EBC30F4FEAC30703D314 +:1032400000200BB0BDE8F08F2B199F42D8F80C304E +:1032500036BF7F1B2746FFB21BB9D8F81030002BB2 +:103260007BD0272D4ED8C5F12806B7424FF000037A +:1032700034BF3E46F6B2009329463246D8F80800DD +:1032800008ABFFF745FCA7EB060A35445FFA8AFA5C +:103290002821B8F8143003F10053053BDB000493F8 +:1032A000D8F80C300393039B13B1BAF1000F2CD163 +:1032B000D8F8100040B1BAF1000F05D05246009680 +:1032C00008AB691AFFF724FC38B2002FB8D06607A4 +:1032D0000AD00AAB03EBD40111F8083C624202F0B9 +:1032E0000702134101F8083C082C3DD9102C40F28C +:1032F000B680202C40F2B880BBF1000F00F09D801A +:10330000082335E0BA460026C2E7049BE02B28BF1D +:10331000E02306930B44AB42059315D95A1B924503 +:1033200038BF5246039828BFD2B20096691A08AB3C +:1033300004300792FFF7ECFB079A1644AAEB020A47 +:103340001544F6B25FFA8AFA049B069A05999B1A0D +:103350000493039B1B680393A5E700933A46294611 +:10336000D8F8080008ABADE7BBF1000F13D001237C +:10337000B4EBC30F6CD0082C12D89DF82030621E1D +:1033800023FA02F2D50706D54FF0FF3202FA04F411 +:1033900023438DF820309DF8203089F8003050E725 +:1033A000102C12D8BDF82030621E23FA02F2D10789 +:1033B00006D54FF0FF3202FA04F42343ADF8203073 +:1033C000BDF82030A9F800303BE7202C0FD8089931 +:1033D000631E21FA03F3DA0705D54FF0FF3202FA34 +:1033E00004F40C430894089BC9F8003029E7402CEA +:1033F0002BD0DDE90865611EC4F12102A4F121038F +:1034000026FA01F105FA02F225FA03F311431943F2 +:10341000CB0712D50122A4F12003C4F1200102FA46 +:1034200003F322FA01F1A240524243EA010363EBA3 +:10343000430332432B43CDE90823DDE90823C9E9DF +:103440000023FEE66FF00100FBE66FF00800F8E6EF +:10345000082CA0D9102CB3D9202CEED8C3E7BBF18F +:10346000000FADD0022383E7BBF1000FBBD00423D4 +:103470007EE70000012A30B5144638BF012200253E +:10348000402A28BF402285B0012CCDE9025517D82B +:103490001B788DF8083053070AD004AB03EBD20534 +:1034A00015F8083C544204F00704A34005F8083C12 +:1034B0000346009102A80021FFF72AFB05B030BDAA +:1034C000082CE5D9102C03D81B88ADF80830E2E7AA +:1034D000202C02D81B680293DDE7D3E90045CDE933 +:1034E0000245D8E710B5CB681BB98B600B618B82A6 +:1034F00010BD04691A681C600361C38A013BC38262 +:10350000CA60F0E703064CBFC0F3C030022070472A +:1035100008B50246FFF7F6FF022806D15306C2F3AC +:103520000F2001D100F0030008BDC2F30740FBE704 +:103530002DE9F04F93B0CDE903230A680446104605 +:10354000FFF7E0FF02280CBF0026C2F30626002A80 +:103550000D46824680F2F98112F0C04940F0F581B3 +:10356000097B002900F0F181022803D02378B342BF +:1035700040F0EE81C2F304631046069302F07F032D +:103580000593FFF7C5FF059B00224FEA8348002300 +:1035900048EA0A48294448EA4668CE78CDE9082333 +:1035A000F309834648EA0008029367D0059B024668 +:1035B000009320465346676808A9B847002800F0E2 +:1035C000CA81276A4FB9414604F10C00FFF704FB9A +:1035D000074690B96FF0020054E03B6998450DD062 +:1035E0003F68002FF9D1414604F10C00FFF7F4FACF +:1035F00007460028EED0236A3B60276297F817C081 +:1036000006F01F08CCF3840CACEB08001FFA80FE18 +:103610000028B8BF0EF12000A8EB0C031FFA83FEB0 +:10362000B8BF00B2002B0793BEBF0EF120031BB240 +:103630000793D7E9022152EA010338D04FF0000C7A +:10364000039BDFF8F8E19A1A049B63EB01019645AE +:103650007CEB01032BD36B7B97F81AE0734519D1F0 +:10366000029B002B78D0012821DC7868F8B9DFF8BC +:10367000D0C1944570EB010316D337E0276A27B910 +:103680006FF00C0013B0BDE8F08F3B699845B5D0E2 +:103690003F68F4E76A4890427CEB010301D30020C5 +:1036A000F0E7029B002BFAD0079B0F2B17DCFA7D6B +:1036B000B30002F0030203F07C031343FB753946A9 +:1036C0002046FFF709FB6B7BBB76029B3BB9FB7D7A +:1036D000C3F38402013262F38603FB75D0E76A7B91 +:1036E000BB7E9A42DBD1029B002B35D0B309022B63 +:1036F00032D0039B1422BB60049B0021FB600DA809 +:10370000FDF7ECFF039B20460A93049BADF83EB007 +:103710000B932B1D0C932B7B8DF840A0013BDBB250 +:10372000ADF83C30069B8DF841808DF84230059B0A +:103730000AA98DF8433094F82C3083F001038DF8FA +:103740004430A3689847FB7DC3F38403013303F03F +:103750001F039B02FB82A2E7FB7DC6F34012B2EB84 +:10376000D31F40F0FB80C3F38403434540F0F9804E +:10377000029A2B7BB609002A4DD0F20762D4032BA4 +:1037800040F2F280039BAE1DBB60049B3246FB609F +:103790002B7B3946033BDBB204F10C00FFF7AEFA9A +:1037A00000280CDA39462046FFF796FAFB7DC3F372 +:1037B0008403013303F01F039B02FB820AE7AB88FB +:1037C000DDE908843B834FF6FF73C9F12000A9F1BE +:1037D000200228FA09F104FA00F0014324FA02F267 +:1037E00011431846C9B2FFF7CBF909F10809B9F13D +:1037F000400F0346E9D13146B8822A7B033AD2B260 +:10380000FFF7D0F9FB7DB882DA43C2F3C01262F34E +:10381000C713FB7543E7AEB92E1D013B324639464F +:10382000DBB204F10C00FFF769FA0028BADB2A7B4F +:103830003146013AB88AD2B2E2E700BF80841E0066 +:1038400040420F00F98A013BC1F309010429DAB2B1 +:103850005DD80023281D07F11B069A4208D910F8ED +:1038600001CB013306F801C001310529DBB2F4D1E7 +:10387000934228BF0023039938BF04330A91049967 +:1038800038BFDBB20B9107F11B010C91796838BF8F +:103890005B190D910E93FB8AADF83EB0C3F309039B +:1038A0001A44069BADF83C208DF84230059B8DF8FC +:1038B00040A08DF8433094F82C308DF8418083F08F +:1038C00001038DF8443000237B602A7BB88A013ADB +:1038D000291DFFF767F93B8BB882834203D120464D +:1038E000A3680AA9984720460AA9FFF7FBFDFB7DBC +:1038F000BA8AC3F38403013303F01F039B02FB82E4 +:103900003B8B9A420CBF00206FF01000BAE67B6838 +:10391000002BADD0052001E033461C301E68002E80 +:10392000FAD1091A081D2E1D184401EB090CBCF12F +:103930001B0F5FFA89F39BD89A4299D916F8013B7D +:1039400009F1010900F8013BEFE76FF0090099E682 +:103950006FF00A0096E66FF00B0093E66FF00D0033 +:1039600090E66FF00E008DE66FF00F008AE600BF64 +:10397000EFF30983203383F30988002383F311884D +:1039800070470000302080F3118862B60C4B0D4A5E +:10399000D96821F4E0610904090C0A43DA60D3F81C +:1039A000FC20094942F08072C3F8FC200A6842F00A +:1039B00001020A602022DA7783F82200704700BFF4 +:1039C00000ED00E00003FA05001000E0302310B520 +:1039D00083F311880B4B5B6813F400630FD0EFF394 +:1039E00009844FF08073203CE36184F3098800F080 +:1039F00095F810B1044BA36110BD044BFBE783F3B2 +:103A00001188F9E700ED00E03F09000842090008CD +:103A10000122090100F1604303F56143C9B283F853 +:103A2000001300F01F039A4043099B0003F1604319 +:103A300003F56143C3F880211A607047090100F162 +:103A40006040C9B200F56D4001767047002382687E +:103A5000037503691B6899689142FBD25A68036039 +:103A600042601060586070470023826803750369E4 +:103A70001B6899689142FBD85A68036042601060E5 +:103A80005860704708B50846302383F311880B7DD2 +:103A9000032B05D0042B0DD02BB983F3118808BD5F +:103AA00000228B691A604FF0FF338361FFF7CEFF6E +:103AB0000023F2E7D1E9003213605A60F3E7000017 +:103AC000FFF7C4BF054BD9680875186802685360D2 +:103AD0001A6001220275D860FCF720BF2023002065 +:103AE00030B50C4B0446DD684B1C87B00FD02B461D +:103AF0006846094A00F0E2F82046FFF7E3FF009B22 +:103B000013B1684600F0E2F8A86907B030BDFFF7CE +:103B1000D9FFF9E720230020853A0008044B1A68F2 +:103B2000DB6890689B68984294BF00200120704732 +:103B300020230020084B10B51C68D8682268536009 +:103B40001A6001222275DC60FFF78EFF01462046D5 +:103B5000BDE81040FCF7E2BE20230020044B1A68A9 +:103B6000DB6892689B689A4201D9FFF7E3BF704710 +:103B70002023002038B501230025064C06490748BC +:103B80002370656000F0D8FA0223237085F3118852 +:103B900038BD00BF78240020B4470008202300204F +:103BA00008B572B6044B186500F0B2F900F056FA89 +:103BB0000322024B1A70FEE7202300207824002005 +:103BC00000F096B8EFF3118020B9EFF305833022AF +:103BD00082F311887047000010B530B9EFF3058407 +:103BE000C4F3080414B180F3118810BDFFF7B6FFC9 +:103BF00084F31188F9E700008B60022308618B824F +:103C0000084670478368A3F1440243F8142C026904 +:103C100043F8442C426943F8402C094A43F8242CC9 +:103C2000C268A3F1200043F8182C022203F80C2CE0 +:103C3000002203F80B2C034A43F8102C704700BFF6 +:103C40002D0900082023002008B5FFF7DBFFBDE8A1 +:103C50000840FFF735BF0000024BDB6898610F207A +:103C6000FFF730BF20230020302383F31188FFF7B4 +:103C7000F3BF000008B50146302383F31188082004 +:103C8000FFF72EFF002383F3118808BD10B50A4CFF +:103C900023699A6891420CD85A6881600360426037 +:103CA00010609A685860511A99604FF0FF33A36111 +:103CB00010BD1B68891AECE720230020C0E903230C +:103CC000002310B410BC4361FFF7E0BF03688168B4 +:103CD0009A680A449A60426813605A6000234FF061 +:103CE000FF320360014B9A61704700BF2023002020 +:103CF00070B5124D2A46EB690133EB6152F8103F63 +:103D0000934206D030269A68013A9A602C69A368DB +:103D100003B170BDD4E900210A605160236083F3D0 +:103D200011882046D4E90331984786F311886169E8 +:103D30000029EBD02046FFF7A9FFE7E7202300206A +:103D400000207047FEE70000704700004FF0FF3092 +:103D500070470000BFF34F8F024AD368DB07FCD4E3 +:103D6000704700BF0020024008B5074B1B7853B9CD +:103D7000FFF7F0FF054B1A69120641BF044A5A606B +:103D800002F188325A6008BD9024002000200240D1 +:103D90002301674508B5054B1B7833B9FFF7DAFFF8 +:103DA000034A136943F08003136108BD9024002087 +:103DB000002002407F289ABF00F58030C00200201A +:103DC000704700004FF4006070470000802070478B +:103DD0007F2808B50BD8FFF7EDFF00F500630268F8 +:103DE000013204D104308342F9D1012008BD002002 +:103DF000FCE700007F2810B504461CD8FFF7AAFF97 +:103E0000FFF7B2FFF3220D4B4FF40061DA6002229C +:103E10001A61FFF7CFFF58611A6942F040021A6138 +:103E2000FFF798FF00F016F9FFF7B4FF2046BDE852 +:103E30001040FFF7CDBF002010BD00BF00200240A2 +:103E40002DE9F843054612F00100144606D040F271 +:103E5000F32200201E4B1A60BDE8F8831D4BAA1800 +:103E60009A4204D94FF43E72194B1A60F4E7FFF7F7 +:103E70007BFF4FF00109FFF76DFFDFF85C806D1AE3 +:103E8000012C0F4605EB010603D8FFF783FF012045 +:103E9000E2E73B88C8F8109033800020FFF75AFF14 +:103EA000C8F81000338831F8022B9BB29A420CD02C +:103EB00040F20F32064B1A60084B1E60084B1C6024 +:103EC000084B1F60FFF766FFC6E7023CD8E700BF5C +:103ED0008C240020000004080020024080240020E0 +:103EE0008824002084240020084908B50B7828B1D4 +:103EF0001BB9FFF739FF01230B7008BD002BFCD065 +:103F0000BDE808400870FFF745BF00BF90240020BF +:103F10004FF480314FF0005000F09EB80846114633 +:103F200000F05ABB012000F057BB0000084600F02B +:103F300071BB000070B5FFF745FE4FF47A710D4B71 +:103F40000D4EDB69326801FB03F3934237BF0B4A26 +:103F50000A495168156836BF4C1CD1E900545460B9 +:103F60005D1944F100043360FFF736FE2846214610 +:103F700070BD00BF2023002094240020982400203E +:103F800070B5FFF71FFE4FF47A710F4B0F4EDB69D0 +:103F9000326801FB03F3934237BF0D4A0C49516865 +:103FA00015683ABF4C1C5460D1E900545D1944F1C6 +:103FB00000043360FFF710FE4FF47A7200232846A6 +:103FC0002146FCF7B7FA70BD20230020942400207E +:103FD0009824002010B5094C013AD2B2FF2A00D132 +:103FE00010BD500854F82030013054F820009BB226 +:103FF00043EA004341F8043BEEE700BF046C004095 +:1040000010B50748013AD2B2FF2A00D110BD0C8882 +:10401000530840F823404C88013340F82340F1E72F +:10402000046C004007B50122002001A9FFF7D2FF70 +:10403000019803B05DF804FB13B50446FFF7F2FFE7 +:10404000A04205D00122002001A90194FFF7D8FF6A +:1040500002B010BD704700007047000070470000BC +:1040600045F25552064B1A6002225A6040F6FF7222 +:104070009A604CF6CC421A600122024B1A707047CB +:1040800000300040A4240020034B1B781BB14AF6EB +:10409000AA22024B1A607047A4240020003000407E +:1040A000044B1A682AB902F1804202F50432526ABE +:1040B0001A607047A02400204FF08072014B5A62B2 +:1040C000704700BF0010024008B5FFF7E9FF024B40 +:1040D0001868C0F3407008BDA024002008B5FFF7A1 +:1040E000DFFF024B1868C0F3007008BDA024002059 +:1040F00070470000FEE700000A4B0B480B4A904255 +:104100000BD30B4BC11EDA1C121A22F003028B4296 +:1041100038BF00220021FDF7E1BA53F8041B40F834 +:10412000041BECE7904800083025002030250020D3 +:1041300030250020FEE7000070B5002504461A4B2C +:1041400086B05860856201630E46FFF71BFC04F1E0 +:104150001003C4E904334FF0FF33A361134BE5614F +:10416000D9692B460A462046C4E9082304F13401E4 +:104170008023C4E900440E4AA560E5622565FFF787 +:104180003BFD01230B4AE0600375009272686846AC +:104190000192B268CDE90223074BCDE90435FFF760 +:1041A00053FD06B070BD00BF7824002020230020FE +:1041B000C0470008C54700083541000800F030B886 +:1041C00008B500F06DF9FFF7D5FCBDE80840FFF732 +:1041D00067BF0000704700004FF0FF310E4B1A69B7 +:1041E00019611A6900221A611869D868D960D968FA +:1041F000DA60DA68DA6942F08052DA61DA69DA693B +:1042000042F00062DA61054ADB69136843F48073A7 +:10421000136000F025B900BF00100240007000409C +:104220001E4B1A6842F001021A601A689007FCD50A +:104230005A6822F003025A605A6812F00C02FBD14D +:10424000196801F0F90119605A601A6842F4803265 +:104250001A601A689103FCD54EF63162DA625A6828 +:1042600042F4E8125A601A6842F080721A601A68C2 +:104270009201FCD50A4A0B495A6012220A600A6868 +:1042800002F00702022AFAD15A6842F002025A608A +:104290005A6802F00C02082AFAD170470010024056 +:1042A00000641D0000200240084A08B551691368E7 +:1042B0000B4003F00103536123B1054A13680BB1AE +:1042C00050689847BDE80840FFF780BB00040140F4 +:1042D000A8240020084A08B5516913680B4003F070 +:1042E0000203536123B1054A93680BB1D068984724 +:1042F000BDE80840FFF76ABB00040140A824002085 +:10430000084A08B5516913680B4003F00403536170 +:1043100023B1054A13690BB150699847BDE80840BD +:10432000FFF754BB00040140A8240020084A08B548 +:10433000516913680B4003F00803536123B1054A28 +:1043400093690BB1D0699847BDE80840FFF73EBBC1 +:1043500000040140A8240020084A08B551691368E8 +:104360000B4003F01003536123B1054A136A0BB1EC +:10437000506A9847BDE80840FFF728BB0004014099 +:10438000A8240020174B10B55A691C68144004F487 +:1043900078725A61A30604D5134A936A0BB1D06AA6 +:1043A0009847600604D5104A136B0BB1506B9847C1 +:1043B000210604D50C4A936B0BB1D06B9847E205EC +:1043C00004D5094A136C0BB1506C9847A30504D56A +:1043D000054A936C0BB1D06C9847BDE81040FFF7CD +:1043E000F5BA00BF00040140A82400201A4B10B504 +:1043F0005A691C68144004F47C425A61620504D571 +:10440000164A136D0BB1506D9847230504D5134A16 +:10441000936D0BB1D06D9847E00404D50F4A136E2D +:104420000BB1506E9847A10404D50C4A936E0BB1A2 +:10443000D06E9847620404D5084A136F0BB1506FD1 +:104440009847230404D5054A936F0BB1D06F984762 +:10445000BDE81040FFF7BABA00040140A8240020CC +:10446000062108B50846FFF7D3FA06210720FFF713 +:10447000CFFA06210820FFF7CBFA06210920FFF723 +:10448000C7FA06210A20FFF7C3FA06211720FFF713 +:10449000BFFABDE8084006212820FFF7B9BA00009E +:1044A00008B5FFF799FE044800F00AF8FFF792FEFE +:1044B000BDE8084000F002B8CC47000800F042B860 +:1044C000002319461C4A0133102BC2E9001102F1E6 +:1044D0000802F8D1194B9A6942F07D029A619B69F2 +:1044E0000268174BDA6082685A6042681A60C268D4 +:1044F00003F58063DA6042695A6002691A60826972 +:10450000C3F80C24026AC3F80424C269C3F8002467 +:10451000426AC3F80C28C26AC3F80428826AC3F846 +:104520000028026BC3F80C2C826BC3F8042C426B7E +:10453000C3F8002C704700BFA824002000100240E0 +:10454000000801404FF0E023044A08215A6100228C +:104550009A6107220B201A61FFF770BA3F19010018 +:1045600008B5302383F31188FFF72AFB002383F378 +:10457000118808BD08B5FFF7F3FFBDE80840FFF755 +:1045800025BA00000B460146184600F02DB8000081 +:1045900000F040B8012838BF012010B5044620467D +:1045A00000F030F830B900F007F808B900F00CF866 +:1045B0008047F4E710BD0000024B1868BFF35B8F23 +:1045C000704700BF28250020062008B500F082F8BB +:1045D0000120FFF7B7FB0000024B0A4601461868AE +:1045E000FFF79CBC1C08002010B504460448134685 +:1045F00020B10A4602202146AFF3008010BD00BF63 +:1046000000000000024B01461868FFF78BBC00BF9A +:104610001C080020024B01461868FFF787BC00BF4A +:104620001C08002010B501390244904201D100203D +:1046300005E0037811F8014FA34201D0181B10BD0B +:104640000130F2E72DE9F0419BB10446C91A177811 +:10465000014403F1FF3C8C42204601D9002008E0D0 +:1046600005780134BD42F6D10CEB0405D618A542FD +:1046700001D1BDE8F08115F8018D16F801EDF04586 +:10468000F5D0E8E71F2938B504460D4604D91623AE +:1046900003604FF0FF3038BD426C12B152F8213048 +:1046A0004BB9204600F030F82A4601462046BDE8C6 +:1046B000384000F017B8012B0AD0591C03D116233B +:1046C00003600120E7E70024284642F82540984788 +:1046D0000020E0E7024B01461868FFF7D3BF00BF98 +:1046E0001C08002038B50023064D04460846114634 +:1046F0002B60FFF72BFB431C02D12B6803B1236017 +:1047000038BD00BF2C250020FFF71ABB034611F867 +:10471000012B03F8012B002AF9D170476F72672E25 +:104720006172647570696C6F742E5A756261784736 +:104730004E53530040A2E4F1646891060041A3E5A2 +:10474000F2656992070000004261642043414E49CE +:104750006661636520696E6465782E0080000000E4 +:104760000080000000008000000000000000000049 +:10477000391F0008E526000849260008491F0008DF +:10478000751F0008612100084D1F00085D1F00080B +:10479000511F0008591F0008551F00088D200008F0 +:1047A000611F0008912900086D1F000861200008A2 +:1047B00063300000B04700087823002078240020F0 +:1047C0006D61696E0069646C650000000C88000012 +:1047D000447B444444544424800E00004414111487 +:1047E000947B444400000000444444444444444412 +:1047F0000400000044424444444444440000000097 +:1048000044444444444444445CBDFF7F01000000F0 +:10481000ED0300000000000000680300000000003D +:1048200040420F00FE2A0100D204000020080020B0 +:104830000000000000000000000000000000000078 +:104840000000000000000000000000000000000068 +:104850000000000000000000000000000000000058 +:104860000000000000000000000000000000000048 +:104870000000000000000000000000000000000038 +:104880000000000000000000000000000000000028 :00000001FF diff --git a/Tools/bootloaders/f103-ADSB_bl.bin b/Tools/bootloaders/f103-ADSB_bl.bin index b6351b5e50a9f3..7e698ca14ea11f 100755 Binary files a/Tools/bootloaders/f103-ADSB_bl.bin and b/Tools/bootloaders/f103-ADSB_bl.bin differ diff --git a/Tools/bootloaders/f103-ADSB_bl.elf b/Tools/bootloaders/f103-ADSB_bl.elf index a3677f545ea2e2..9776e83a7c9680 100755 Binary files a/Tools/bootloaders/f103-ADSB_bl.elf and b/Tools/bootloaders/f103-ADSB_bl.elf differ diff --git a/Tools/bootloaders/f103-ADSB_bl.hex b/Tools/bootloaders/f103-ADSB_bl.hex index d5ce6dc807249f..1cd83a81d0fc07 100644 --- a/Tools/bootloaders/f103-ADSB_bl.hex +++ b/Tools/bootloaders/f103-ADSB_bl.hex @@ -1,963 +1,997 @@ :020000040800F2 -:100000000009002069040008C114000865140008F4 -:10001000A514000865140008851400086B04000886 -:100020006B0400086B0400086B0400087D350008B1 -:100030006B0400086B0400086B040008113A000808 -:100040006B0400086B0400086B0400086B040008D4 -:100050006B0400086B0400083D370008693700088E -:1000600095370008C1370008ED3700086B04000819 -:100070006B0400086B0400086B0400086B040008A4 -:100080006B0400086B0400086B040008712400086E -:10009000DD240008312500088525000819380008EE -:1000A0006B0400086B0400086B0400086B04000874 -:1000B0006B0400086B0400086B0400086B04000864 -:1000C0006B0400086B0400086B0400086B04000854 -:1000D0006B04000825290008392900086B04000872 -:1000E000813800086B0400086B0400086B040008EA -:1000F0006B0400086B0400086B0400086B04000824 -:100100006B0400086B0400086B0400086B04000813 -:100110006B0400086B0400086B0400086B04000803 -:100120006B0400086B0400086B0400086B040008F3 -:100130006B0400086B0400086B0400086B040008E3 -:100140006B0400086B0400086B0400086B040008D3 -:100150006B0400086B0400086B0400086B040008C3 -:1001600053B94AB9002908BF00281CBF4FF0FF311E -:100170004FF0FF3000F076B9ADF1080C6DE904CE18 -:1001800000F006F8DDF804E0DDE9022304B0704772 -:100190002DE9F047089E0D4604468846002B4DD1B8 -:1001A0008A42944668D9B2FA82F252B101FA02F355 -:1001B000C2F1200120FA01F10CFA02FC41EA030825 -:1001C00094404FEA1C41B8FBF1F71FFA8CFE01FB8B -:1001D000178807FB0EF0230C43EA084398420AD91C -:1001E0001CEB030307F1FF3580F01E81984240F2BB -:1001F0001B81023F63441B1AB3FBF1F001FB103378 -:1002000000FB0EFEA4B244EA0344A6450AD91CEB47 -:10021000040400F1FF3380F00981A64540F2068115 -:10022000644402380021A4EB0E0440EA07401EB1EA -:100230000023D440C6E90043BDE8F0878B4208D9CB -:10024000002E00F0EE800021C6E900050846BDE85A -:10025000F087B3FA83F100294AD1AB4202D382423C -:1002600000F2FC80841A65EB030301209846002EFF -:10027000E2D0C6E90048DFE702B9FFDEB2FA82F257 -:10028000002A40F09180A1EB0C0001214FEA1C47AD -:100290001FFA8CFEB0FBF7F307FB1300250C45EAB1 -:1002A00000450EFB03F0A84208D91CEB050503F13D -:1002B000FF3802D2A84200F2CE8043462D1AB5FB89 -:1002C000F7F007FB10550EFB00FEA4B244EA05440C -:1002D000A64508D91CEB040400F1FF3502D2A6455F -:1002E00000F2B6802846A4EB0E0440EA03409EE7E5 -:1002F000C1F120078B4022FA07FC4CEA030C25FAD7 -:1003000007FA4FEA1C49BAFBF9F820FA07F309FB90 -:1003100018AA8D401FFA8CFE1D4300FA01F308FB5A -:100320000EF02C0C44EA0A44A04202FA01F20BD966 -:100330001CEB040408F1FF3A80F08880A04240F2F0 -:100340008580A8F102086444241AB4FBF9F009FB83 -:10035000104400FB0EFEADB245EA0444A64508D9A0 -:100360001CEB040400F1FF356CD2A6456AD90238B3 -:10037000644440EA0840A0FB0295A4EB0E04AC42A2 -:10038000C846AE4656D353D0002E69D0B3EB080210 -:1003900064EB0E0422FA01F304FA07F71F43CC4082 -:1003A000C6E90074002147E70CFA02FCC2F1200103 -:1003B00025FA01F34FEA1C4720FA01F195400D435D -:1003C000B3FBF7F107FB11331FFA8CFE280C40EA50 -:1003D000034001FB0EF3834204FA02F408D91CEB3C -:1003E000000001F1FF382FD283422DD90239604439 -:1003F000C01AB0FBF7F307FB1300ADB245EA0045A6 -:1004000003FB0EF0A84208D91CEB050503F1FF38E9 -:1004100016D2A84214D9023B6544281A43EA014186 -:1004200038E73146304607E72F46E4E61846F9E656 -:100430004B45A9D2B9EB020865EB0C0E0138A3E7D6 -:100440004346EAE7284694E74146D1E7D0467BE7B2 -:100450006444023847E7023B65442FE7084606E755 -:100460003146E9E6704700BF02E000F000F8FEE721 -:1004700072B6284880F30888274880F309882748FF -:100480004EF60851CEF200010860022080F3148875 -:10049000BFF36F8F03F0E4F803F0C0F803F0E2F865 -:1004A0004FF055301E491B4A91423CBF41F8040BA6 -:1004B000FAE71C49184A91423CBF41F8040BFAE79D -:1004C00019491A4A1A4B9A423EBF51F8040B42F896 -:1004D000040BF8E700201749174A91423CBF41F846 -:1004E000040BFAE703F09EF803F0BEF8134C144D2A -:1004F000AC4203DA54F8041B8847F9E700F03CF8F3 -:10050000104C114DAC4203DA54F8041B8847F9E74C -:1005100003F086B800090020001100200000000848 -:100520000001002000090020E03B0008001100202D -:100530002411002028110020A025002060010008BF -:100540006001000860010008600100082DE9F04F1B -:10055000C1F80CD0C3689D46BDE8F08F002383F33B -:1005600011882846A047002002F09CFDFEE702F01B -:1005700021FD00DFFEE700002DE9F04102F09CFFC5 -:10058000074602F0E7FF054600283ED12B4B9F426D -:100590003BD001339F423BD0294B27F0FF029A42C8 -:1005A0003AD1F8B200F052FAA84642F2107400F0C4 -:1005B00057FC08B10024A04600F04EFA064678B376 -:1005C00084BB464635B11F4B9F4203D0002402F046 -:1005D000B9FF2646002002F079FF1B4B9B6813F001 -:1005E000400322D00EB100F031F800F097FC00F08B -:1005F00077FE00F067FF0546CCB100F063FF401BBB -:10060000A04214D900F022F8F3E7A8460024CEE770 -:1006100004464FF00108CAE780464FF47A74C6E7F3 -:100620000446CFE74FF47A74CCE71C46DDE700F0D0 -:1006300025FD012002F03CFDDEE700BF010007B010 -:10064000000008B0263A09B0000C014038B51D4A38 -:100650001D4B1968013134D004339342F9D11B4C3E -:10066000194DD4F80424AA422BD3194B9B6803F1EB -:10067000006303F5C8439A4223D202F037FF02F029 -:1006800049FF002000F046FE0220124B187000F0D7 -:100690007DFE114BDA690022DA61D96999699A61A4 -:1006A0009B6972B64FF0E023C3F8085DD4F80034BC -:1006B000D4F80424202181F311889D4683F308880F -:1006C000104738BD2064000800640008006000087E -:1006D00000110020281100200010024049F269009A -:1006E000084A136899B21B0C00FB013344F25061B5 -:1006F0001360054B186882B2000C01FB0200186001 -:1007000080B27047201100201C11002010B5044653 -:100710000021102200F056FE034B03CB20606160E5 -:100720001868A06010BD00BFE8F7FF1F2DE9F04377 -:10073000BBB000F0C7FE40F2ED22204DAB68C31AFB -:10074000934232D906AF2B4628220021A8603846B2 -:1007500001F0C2FB05F10E0000F02CFE002604465D -:100760005FFA80F905F10E08F3B2F100994501F145 -:10077000280107D908EB06030822384601F0ACFB34 -:100780000136F1E708230122CDE902320C4B053492 -:1007900001933023A4B20093CDE9047405A3D3E9F7 -:1007A0000023297B074801F0ADF93BB0BDE8F08399 -:1007B000AFF3008078F6339F93CACD8D702100206F -:1007C0007D2100204421002070B50D4614461E46B0 -:1007D00001F02EF950B9022E10D1012C0ED112A326 -:1007E000D3E900230120C5E9002307E0282C10D01D -:1007F00005D8012C09D0052C0FD0002070BD302C5D -:10080000FBD10BA3D3E90023ECE70BA3D3E900232F -:10081000E8E70BA3D3E90023E4E70BA3D3E9002324 -:10082000E0E700BFAFF30080401DA12026812A0B26 -:1008300078F6339F93CACD8D9E6AC421818A46EE95 -:1008400026417272DF25D7B7F017304A39059E5618 -:1008500038B50D460446034620222846002101F003 -:100860003BFB22792346032A28BF0322284603F8AC -:10087000042F2021022201F02FFB62792346072A50 -:1008800028BF0722284603F8052F2221032201F062 -:1008900023FBA2792346072A28BF0722284603F80C -:1008A000062F2521032201F017FB284610222821BC -:1008B00004F1080301F010FB382038BD2DE9F04F9A -:1008C0000024ADF5017D0EAE40F2751280460F4654 -:1008D00022A82146219400F075FD21464822304689 -:1008E00000F070FD00F0EEFD4FF47A72B0FBF2F014 -:1008F000544B21AD186093E80700012386E80700F8 -:100900000DF15A003382FFF701FF4EF603033384E3 -:1009100006AB18464C4903F0B3F81C222946306454 -:10092000304686F83C20FFF793FF08220446014634 -:1009300012AB284601F0D0FA08222846A1180DF182 -:10094000490301F0C9FA082228460DF14A0304F1CF -:10095000100101F0C1FA2022284613AB04F118015E -:1009600001F0BAFA4022284614AB04F1380101F034 -:10097000B3FA0822284616AB04F1780101F0ACFA6C -:10098000082228460DF1590304F1800101F0A4FA70 -:1009900004F1880A0DF15A0904F5847B4B4651464F -:1009A000082228460AF1080A01F096FAD34509F10F -:1009B0000109F3D10822594628461BAB01F08CFAF5 -:1009C0004FF0000904F5887496F834304B450AD985 -:1009D000B36B21464B440822284601F07DFA0834C7 -:1009E00009F10109F0E74FF0000996F83C3004EBFB -:1009F000C9014B4508D9336C08224B44284601F005 -:100A00006BFA09F10109F0E700230393BB7E07317C -:100A1000029307F1190301930123C1F3CF01CDE93B -:100A200004510093404605A3D3E90023F97E01F069 -:100A300069F80DF5017DBDE8F08F00BF9E6AC42105 -:100A4000818A46EE2C110020903A0008014B187064 -:100A5000704700BF38110020F0B5334B85B01C7BC8 -:100A600034B10E22314B1A810024204605B0F0BD6E -:100A70002F4A02AB1068516803C308232D492E4842 -:100A80000DEB030202F0DCFF054630B90A22274BCA -:100A90002A481A8100F0E2FCE6E70169B1F5CE3F91 -:100AA00006D90B22214B26481A8100F0D7FCDCE73F -:100AB000438BB3F57A7F09D00C211C4A2148118160 -:100AC0004FF47A72194600F0C9FCCEE71E4A024480 -:100AD00002F11003994204D21022144B1B481A81D0 -:100AE000E3E710398E1A2046134900F0EFFC074661 -:100AF0003246204605F1180100F0E8FCAB689F4241 -:100B000002D1EB6898420AD00D22084B1A8100905E -:100B10003B46D5E902120E4800F0A0FCA4E70D48C0 -:100B200000F09CFC0124A0E7702100202C11002083 -:100B3000413B0008DC9B010000640008B03A00085B -:100B4000BC3A0008CE3A0008089CFFF7EC3A0008CF -:100B5000093B0008323B00082DE9F04FADB006AF6D -:100B600080460C4600F064FF0546002859D1237EDC -:100B7000022B1AD1E38A012B17D100F0A3FC064601 -:100B8000FFF7ACFD4FF4C873B0FBF3F202FB1300A8 -:100B9000DFF8B49206F5167680B2E37E0644C9F813 -:100BA000006033B90022A94B1A709C37BD46BDE8DE -:100BB000F08FA38AEEB2013BB34205F101050BD9D8 -:100BC0003B1D1E44E900002308222046009601F048 -:100BD000F80101F043F8ECE707F11400FFF796FD88 -:100BE000324607F11401381D02F01AFF03460028AF -:100BF000D8D10F2E08D8954B1E70D9F80030A3F528 -:100C00001673C9F80030D0E7FA1CF870014600925C -:100C10002046072201F022F84046F97800F000FF54 -:100C2000C3E7E38A282B26D010D8012B1ED0052B32 -:100C3000BBD1BFF34F8F8649864BCA6802F4E0628E -:100C40001343CB60BFF34F8F00BFFDE7302BACD118 -:100C5000637E814D01336A7BDBB29342E94603D167 -:100C6000E27E2B7B9A4265D0CD469EE721464046E8 -:100C7000FFF724FE99E7A38A013B9BB2C92B94D8C6 -:100C8000754D2E7B26BB05F10C03009308223346DD -:100C90003146204600F0E2FF731CF2B2D9001E4636 -:100CA000A38A013B9A4205DA0E322A4400920023BD -:100CB0000822EEE700230022C5E900230023AB60F1 -:100CC00085F8D730C5F8D8302B7B0BB9E37E2B7372 -:100CD000002507F114060822294630463B1DC7E9C6 -:100CE0000155FD6001F0F8F83B7A05F10109AB42CE -:100CF0004FEAC90107D9FB6808222B44304601F0AE -:100D0000EBF84D46F0E70023C1F3CF01E07ECDE9DB -:100D100004610393A37E19340293282301460093B0 -:100D2000404647A3D3E90023019400F0EBFEFFF710 -:100D3000FDFC3AE74FF0000807F11403A7F8148010 -:100D40001022009341460123204600F087FFA68A27 -:100D5000023EB6B2F31C9B109B000733DB08A9EBE5 -:100D6000C3039D460DF1180A1FFA88F34FEAC80124 -:100D7000B34201F110010AD20AEB080300930822E2 -:100D80000023204600F06AFF08F10108ECE795F81F -:100D9000D70000F0C9FAD5F8D83004461BB995F849 -:100DA000D70000F0D1FAD5F8D83033449C4204D2B1 -:100DB00095F8D700013000F0C7FA4FF000084FEA6D -:100DC000960B1FFA88F18B45D5E9003209D90AEB59 -:100DD000880103EB8800012200F0FCFA08F1010809 -:100DE000EFE7F31842F10002C5E90032D5F8D83038 -:100DF00095F8D70006EB0308C5F8D88000F094FA00 -:100E0000804509D395F8D730D5F8D8000133001BB9 -:100E100085F8D730C5F8D800FF2E08D800232B73EB -:100E200000F0A4FAFFF718FE08B1FFF70FFC2B68DB -:100E30000A4A9B0A013313810023AB6014E700BF09 -:100E400026417272DF25D7B7402100203D210020C6 -:100E500000ED00E00400FA05702100202C110020B4 -:100E600030B54FF00054244B226885B09A4207D029 -:100E700002F07AFB0446A8B90024204605B030BD34 -:100E8000627D1E4B1E481A70237DC92203731D49C3 -:100E90000E3000F085FA2046E022002100F092FAA0 -:100EA0000124EAE7184A194DD36943F00073D3616E -:100EB000AA6D174B9A42DFD12B6E013B7E2BDBD8FC -:100EC000144A01AB07CA83E807001846032100F063 -:100ED00013FB6B6D83424FF00003CDD12A6D8A4224 -:100EE00003BFAB652A6E054B1C4601BF1A70EA6D45 -:100EF000094B1A60C1E700BF9AAD44C53811002004 -:100F00007021002016000020001002400066004002 -:100F10005041A0B0586600401811002002232DE96E -:100F2000F0434A4C85B0637100230293484BD3F8D9 -:100F300000C0BCF57A7F12D3464F474BB7FBFCF598 -:100F40009C458CBF0A231123B5FBF3F603FB165215 -:100F5000591EC8B2002A3ED002290B46F4D89DF88B -:100F60000B303E495A1E9DF80A303D48013B1B0498 -:100F700043EA0253BDF80820013A13434B6001F0E5 -:100F800037FD00230193374B374900934FF48052CC -:100F9000364B374800F01CFD364B197811B13448F8 -:100FA00000F03EFD00F08EFA0546FFF797FB4FF488 -:100FB000C873B0FBF3F202FB130305F516709BB286 -:100FC00018442D4B186002F0C5FA08B10F23238195 -:100FD00005B0BDE8F083731EB3F5806FBFD24FF448 -:100FE0007A75C0EBC00E0EF103034FEAE30909FB6B -:100FF0000555C3F3C703C11AC9B209F101088844F2 -:10100000B5FBF8F5B5F5617F08D90EF1FF33C3F3F1 -:10101000C703C11A581E0F28C9B214D84A1E072A7E -:101020008CBF00220122581800FB0660B7FBF0F7C6 -:10103000BC4594D1002A92D0ADF808608DF80A30F2 -:101040008DF80B108BE71346EDE700BF2C11002045 -:1010500018110020005125023F420F0010110020FE -:1010600088220020C90700083C110020590B000805 -:101070004421002038110020402100202DE9F04FAC -:1010800093A7D7E900670FF25029D9E90089854D68 -:1010900093B0DFF814B2854C284600F097FD0DF1AF -:1010A000300A079070B310220021504600F08AF9F0 -:1010B0004FF00002079B197B61F303028DF830208B -:1010C000586899680EAA03C21B680D9A584663F3C4 -:1010D0001C029DF830300D9243F020038DF8303023 -:1010E00000235246194601F093FC079028B9284680 -:1010F00000F070FD079B2370CEE72378072B3CD8C8 -:101100000133237018220021504600F05BF9DFF80C -:1011100098B1674C002352461946584601F0A0FC8E -:10112000014670BB102208A800F04CF9E36883F078 -:101130001003E36000F0C8F90DF1240C0B4612A96E -:10114000024611E903008CE803009DF83410C1F356 -:101150000300890649BF0E99BDF83810C1F31C0180 -:1011600041F0004158BFC1F30A018DF82C000891ED -:10117000284608A900F0F8FECCE7284600F02AFD32 -:10118000C0E7284600F054FC8346002844D100F014 -:1011900099F9484B1A6890423ED300F093F90446FF -:1011A000FFF79CFA4FF4C872B0FBF2F101FB12009A -:1011B0008DF820B0DFF800B13E4B04F5167480B214 -:1011C0009BF8001004441C6011B901238DF82030F5 -:1011D00050460791FFF79AFA07990DF12100C1F1E6 -:1011E0001004E4B2062C28BF06245144224600F025 -:1011F000D7F808AB039318230293304B01340193C3 -:101200000123E4B2009332463B462846049400F0A2 -:1012100011FC00238BF8003000F054F9284A294CC7 -:101220001368C31AB3F57A7F31D3106000F04CF91C -:1012300002460B46284600F0D7FC284600F0F8FB93 -:1012400028B3237BDFF880B0002B14BF03230223D5 -:101250008BF8053000F036F94FF47A73B0FBF3F0F9 -:101260005146CBF800005846FFF7F2FA18230293D4 -:10127000164B0730019340F25513C0F3CF00CDE970 -:1012800003A0009342464B46284600F0D3FB237B45 -:101290002BB1FFF74BFA237B002B7FF4FAAE13B090 -:1012A000BDE8F08F44210020882200205522002034 -:1012B00000080140402100203D2100203C21002069 -:1012C00050220020702100202C11002054220020E8 -:1012D000401DA12026812A0BF1C6A7C1D068080FA6 -:1012E00070B501F0BFFF0024084E094D308028681A -:1012F0003388834208D901F0B1FF2B6804440133DD -:10130000B4F5C84F2B60F2D370BD00BF842200201B -:101310005822002002F044B800F10060920000F56D -:10132000C84001F0DFBF0000054B1A68054B1B8861 -:101330009B1A834202D9104401F090BF00207047ED -:10134000582200208422002038B50446064D286823 -:10135000204401F089FF28B928682044BDE83840BE -:1013600001F094BF38BD00BF58220020064991F813 -:10137000243033B100230822086A81F82430FFF7B3 -:10138000CBBF0120704700BF5C220020022802BFB3 -:101390004FF48012014B1A61704700BF00080140F2 -:1013A000002310B5934203D0CC5CC4540133F9E759 -:1013B00010BD000003460246D01A12F9011B002995 -:1013C000FAD1704703460244934202D003F8011B4E -:1013D000FAE770472DE9F8431F4D144695F824208D -:1013E0000746884652BBDFF870909CB395F82430CE -:1013F0002BB92022FF2148462F62FFF7E3FF95F823 -:1014000024004146C0F10802A24228BF224605EB53 -:101410008000D6B29200FFF7C3FF95F82430A41BDA -:101420001E44F6B2082E17449044E4B285F82460B6 -:10143000DBD1FFF79BFF0028D7D108E02B6A03EB35 -:1014400082038342CFD0FFF791FF0028CBD1002049 -:10145000BDE8F8830120FBE75C2200200FB40020E8 -:1014600004B07047EFF30983EFF30583044B9A6BE5 -:10147000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE72A -:1014800000ED00E0EFF30983EFF30583044B9A6B63 -:101490009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF8F -:1014A00000ED00E0EFF30983EFF30583034B5A6B84 -:1014B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E065 -:1014C000FEE7000001F0A6BF01F07EBF30B5094D78 -:1014D0000A4491420DD011F8013B5840082340F3D3 -:1014E0000004013B2C4013F0FF0384EA5000F6D1C6 -:1014F000EFE730BD2083B8ED4FF0FF33F7B500EBD9 -:1015000081061946DFF848C0DFF848E0B0421BD03A -:1015100050F8042B01AF0192042217F8014B81EA25 -:10152000046108240D46DB184941013C002DBCBF75 -:1015300083EA0C0381EA0E0114F0FF04F2D1013AB0 -:1015400012F0FF02E9D1E1E7D843C94303B0F0BD8F -:101550009336EAA9EBE1F0422DE9F041C56915B9EE -:10156000C161BDE8F0814B68AC4623F06047C3F32E -:101570008A4616EA230638BF3E464FEAD37EC3F3B7 -:1015800080782B465A68BEEBD27F22F060440AD0A6 -:10159000002A18DAA40CB44217D19D420FD10D6075 -:1015A000DEE71346EEE7A74207D102F08044C2F31C -:1015B000807242450BD054B1EFE708D2EDE7CCF88A -:1015C00000100B60CDE7B44201D0B442E5D81A68F0 -:1015D0009C46002AE5D11960C3E700002DE9F047D9 -:1015E0004FF47F49089D01F007044FEAD5082244D3 -:1015F00005F0070500EBD100944201D1BDE8F0876A -:1016000004F0070705F0070A57453E4638BF56461F -:10161000111BC6F108068E4228BF0E46E108415C48 -:1016200008EBD50E13F80EC0B94029FA06F721FAD7 -:101630000AF1FFB28CEA010147FA0AF739408CEA55 -:10164000010C03F80EC034443544D5E7082341F2B9 -:10165000210280EA012001B24000002980B203F19A -:10166000FF33B8BF504013F0FF03F4D170470000C0 -:1016700038B50C468D18A54200D138BD14F8011BB1 -:10168000FFF7E4FFF7E700000346006848B102688F -:1016900019891A60DA88013292B29142DA8038BF31 -:1016A0001A81704770B504460D4688B0202200218B -:1016B0006846FFF787FE20460495FFF7E5FF0246E0 -:1016C00058B16B46054608AE1C4603CCB4422860B0 -:1016D0006960234605F10805F6D1104608B070BDD3 -:1016E000082817D909280CD00A280CD00B280CD0B0 -:1016F0000C280CD00D280CD00E2814BF4020302010 -:1017000070470C2070471020704714207047182035 -:101710007047202070470000082817D90C280CD9E2 -:1017200010280CD914280CD918280CD920280CD929 -:1017300030288CBF0F200E207047092070470A20E8 -:1017400070470B2070470C2070470D207047000039 -:1017500010B54B6823B9CA8A63F30902CA8210BD67 -:10176000C4681A681C60C360438A013B43824A60B4 -:10177000EFE700002DE9F84F1D46CB8A0F46C3F373 -:1017800009010629814692460B4630D00020AAB2B4 -:1017900007F119049EB2052E1FFA80F80FD8904564 -:1017A00003F1010306D3FB8A0A4462F30903012013 -:1017B000FB821AE01AF800600130E654EAE790452F -:1017C000F1D21C23A1F1060BBBFBF3F203FB12BB0E -:1017D0007C681FFA8BF6002C45D14846FFF754FF72 -:1017E000044638B978606FF00200BDE8F88F4FF01A -:1017F0000008E6E70026066078604FF0000BADB207 -:10180000454510D90AEB0803221D13F8011B08F106 -:1018100001089155B1B21B291FFA88F82BD0454514 -:1018200006F10106F1D8FB8AC3F30902154465F3FA -:101830000903BCE71C46013292B22368002BF9D1A0 -:10184000AB1F0B441C21B3FBF1F301339BB29A4253 -:10185000D3D2BBF1000FD0D14846FFF715FF20B916 -:10186000C4F800B0BFE70122E7E7C0F800B05E4669 -:1018700020600446C1E74545D5D94846FFF704FF37 -:1018800008B92060AFE7C0F800B000262060044629 -:10189000B6E700002DE9F04F85B007469146CDE947 -:1018A0000113BDF83C50002A00F08F802DB10E9B33 -:1018B000002B00F08A80072D30D807F10C00FFF7CD -:1018C000E3FE044628B96FF00204204605B0BDE8E7 -:1018D000F08F14220021FFF775FD2A460E9904F1BE -:1018E0000800FFF75DFD681CC0B2FFF715FFFFF7AA -:1018F000F7FE207499F80020431E9BB202F01F02ED -:10190000234462F03F021A72019B384643F00041C3 -:1019100061602146FFF720FE0124D6E74FF0000862 -:101920004FF0800A4646444600F10C0303930398A7 -:10193000FFF7AAFE83460028C5D014220021FFF736 -:1019400041FD002E38D10220029BABF808300E9BDF -:1019500000F10802D2B299195A440130C0B20828E5 -:1019600001D0AE422AD3FFF7D7FEFFF7B9FEAE4251 -:1019700008BF4FF0400A99F80020019B411E02F079 -:101980001F0242EA4812C9B24AEA020A594443F025 -:10199000004281F808A08BF8100059463846CBF871 -:1019A0000420FFF7D9FD0134AE424FF0000A24B203 -:1019B00088F00108BBD188E70020C8E711F801CB07 -:1019C000013602F801CBB6B2C7E76FF001047CE73D -:1019D000F8B5044615460E46282200211F46FFF79B -:1019E000F1FC069BB5F5001F6360079B28BF4FF60F -:1019F000FF7223624FF0000338BF6A09A76004F149 -:101A00000C0097B29A4205D80023036027826382B4 -:101A1000A382F8BD0660013330462036F2E70000AD -:101A200003781BB94BB2002BC8BF01707047000090 -:101A3000007870472DE9F74FDDF83C9080469246DC -:101A40009B46BDF830500D9E9DF83840BDF8407063 -:101A5000B9F1000F01D1002F51D11F2C4FD898F8A8 -:101A60000000B0B9072F47D835F0030347D13A46F5 -:101A700049464FF6FF70FFF7FBFD20F001002D02F5 -:101A8000400445EA0464400C44EA40244FF6FF73E6 -:101A900021E040EA0520072F40EA0464F6D900253A -:101AA0004FF6FF73C5F12000A5F120022AFA05F1D7 -:101AB0000BFA00F001432BFA02F211431846C9B2A7 -:101AC000FFF7C4FD0835402D0346EBD13A464946A1 -:101AD000FFF7CEFD0346324621464046CDE900974A -:101AE000FFF7D8FE33780133DBB21F2B88BF00230A -:101AF000337003B0BDE8F08F6FF00300F9E76FF0CB -:101B00000100F6E72DE9F04F85B0DDF848809246F8 -:101B100006469B460F9D9DF840209DF84490BDF8D9 -:101B20004C70B8F1000F01D1002F48D11F2A46D8C0 -:101B30003378002B46D00C0244EA02649DF838103A -:101B400044EAC93444EA01441C43072F44F08004AA -:101B500032D900234FF6FF72C3F1200CA3F120000D -:101B60002AFA03F10BFA0CFC41EA0C012BFA00F003 -:101B70000143C9B210460393FFF768FD039B024679 -:101B80000833402BE8D13A464146FFF771FD034642 -:101B90002A4621463046CDE90087FFF77BFEB9F1A2 -:101BA000010F06D12B780133DBB21F2B88BF002336 -:101BB0002B7005B0BDE8F08F4FF6FF73E8E76FF0CC -:101BC0000100F6E76FF00300F3E70000C06900B121 -:101BD00004307047C3691A68C261C2681A60C36082 -:101BE000438A013B438270472DE9F041D0F81880C9 -:101BF00014461D4641460027174E09B9BDE8F0813D -:101C0000D1E90223A21A65EB0303964277EB0303A3 -:101C10001ED283698B420DD1FFF79AFD83691B6841 -:101C20008361C3680B60438AC1608169013B884658 -:101C30004382E2E7FFF78CFD0B68C8F80030C36809 -:101C40000B60438AC160013B4382D8F80010D4E79F -:101C500088460968D1E700BF80841E002DE9F04F57 -:101C60008BB00D4614469B468046DDF85090002808 -:101C700000F01A81B9F1000F00F01681531E3F2BBE -:101C800000F21281012A03D1BBF1000F40F00C8158 -:101C90000023CDE90833B8F81430B5EBC30F4FEA91 -:101CA000C30703D300200BB0BDE8F08F2B199F4270 -:101CB000D8F80C3036BF7F1B2746FFB21BB9D8F8C7 -:101CC0001030002B7BD02F2D4ED8C5F13006B742F7 -:101CD0004FF0000334BF3E46F6B200932946324629 -:101CE000D8F8080008ABFFF779FCA7EB060A3544E3 -:101CF0005FFA8AFA3021B8F8143003F10053063B3A -:101D0000DB000493D8F80C300393039B13B1BAF1B2 -:101D1000000F2CD1D8F8100040B1BAF1000F05D057 -:101D20005246009608AB691AFFF758FC38B2002FEC -:101D3000B8D066070AD00AAB03EBD40111F8083C0F -:101D4000624202F00702134101F8083C082C3DD919 -:101D5000102C40F2B680202C40F2B880BBF1000F6E -:101D600000F09D80082335E0BA460026C2E7049BB8 -:101D7000E02B28BFE02306930B44AB42059315D913 -:101D80005A1B924538BF5246039828BFD2B20096DC -:101D9000691A08AB04300792FFF720FC079A164433 -:101DA000AAEB020A1544F6B25FFA8AFA049B069A75 -:101DB00005999B1A0493039B1B680393A5E7009363 -:101DC0003A462946D8F8080008ABADE7BBF1000F4A -:101DD00013D00123B4EBC30F6CD0082C12D89DF89C -:101DE0002030621E23FA02F2D50706D54FF0FF32EB -:101DF00002FA04F423438DF820309DF8203089F84E -:101E0000003050E7102C12D8BDF82030621E23FAA3 -:101E100002F2D10706D54FF0FF3202FA04F4234351 -:101E2000ADF82030BDF82030A9F800303BE7202C79 -:101E30000FD80899631E21FA03F3DA0705D54FF08E -:101E4000FF3202FA04F40C430894089BC9F80030EE -:101E500029E7402C2BD0DDE90865611EC4F1210281 -:101E6000A4F1210326FA01F105FA02F225FA03F39F -:101E700011431943CB0712D50122A4F12003C4F169 -:101E8000200102FA03F322FA01F1A240524243EA8E -:101E9000010363EB430332432B43CDE90823DDE920 -:101EA0000823C9E90023FEE66FF00100FBE66FF0AE -:101EB0000800F8E6082CA0D9102CB3D9202CEED8B5 -:101EC000C3E7BBF1000FADD0022383E7BBF1000FE6 -:101ED000BBD004237EE70000012A30B5144638BF8A -:101EE00001220025402A28BF402285B0012CCDE9DF -:101EF000025517D81B788DF8083053070AD004AB69 -:101F000003EBD20515F8083C544204F00704A34043 -:101F100005F8083C0346009102A80021FFF75EFB8C -:101F200005B030BD082CE5D9102C03D81B88ADF8BE -:101F30000830E2E7202C02D81B680293DDE7D3E9E2 -:101F40000045CDE90245D8E710B5CB681BB98B60D9 -:101F50000B618B8210BDC4681A681C60C360438A21 -:101F6000013B4382CA60F0E72DE9F04FD1F80080D1 -:101F700093B018F0800FCDE90323C8F3C01207BF58 -:101F80004FF0020B1646C8F3C03BC8F30626B8F163 -:101F9000000F04460D4680F2D48118F0C04305932B -:101FA00040F0CF810B7B002B00F0CB81BBF1020F07 -:101FB00003D00178B14240F0C78108F07F0107915A -:101FC0007AB3C8F3074A2B4493F80390760646EA9F -:101FD0000B4608F07F0246EA82465FEAD91346EADA -:101FE0000A06069300F0918000220023CDE90A231F -:101FF00008F07F03009352465B46204667680AA9B3 -:10200000B84700287ED0A7699FB9314604F10C007B -:10201000FFF748FB0746E0B96FF0020013B0BDE8D8 -:10202000F08FC8F30F2A18F07F0F08BF0AF0030AD9 -:10203000C9E73B699E420DD03F68002FF9D1314678 -:1020400004F10C00FFF72EFB07460028E4D0A3693B -:102050003B60A7610026DDE90A234FF6FF70C6F159 -:10206000200E22FA06F103FA0EFEA6F1200C23FA46 -:102070000CFC41EA0E0141EA0C01C9B20836099292 -:102080000893FFF7E3FADDE90832402EE7D1B88282 -:10209000FB7D09F01F06C3F384039B1B98B2002B42 -:1020A000BCBF00F120031BB2D7E9022152EA0100B4 -:1020B000C8F304680FD00398821A049860EB0101FA -:1020C000A74890424FF000028A4104D3069A002AA2 -:1020D0005BD0012B23DDFA7D4FEA890302F0030276 -:1020E00003F07C031343FB7539462046FFF730FBB2 -:1020F000069BA3B9FB7DC3F38402013262F386031E -:10210000FB7504E06FF00B0088E7A76917B96FF063 -:102110000C0083E73B699E42BAD03F68F6E719F0AE -:10212000400F32D0039B1422BB60049B0021FB6054 -:102130000DA8FFF747F9039B20460A93049BADF8CF -:102140003EA00B932B1D0C932B7B8DF840B0013BD5 -:10215000DBB2ADF83C30079B8DF841608DF8433021 -:1021600094F824308DF8428083F001038DF84430D8 -:102170000AA9A3689847FB7DC3F38403013303F0E6 -:102180001F039B02FB82002048E7FB7DC9F340123E -:10219000B2EBD31F40F0DB80C3F38403B34240F0C3 -:1021A000D98006992B7B4FEA9912002934D0D207A7 -:1021B00041D4032B40F2D180039BAE1DBB60049B36 -:1021C0003246FB602B7B3946033BDBB204F10C004B -:1021D000FFF7D0FA00280DDA20463946FFF7B8FAA3 -:1021E000FB7D0320C3F38403013303F01F039B0231 -:1021F000FB8213E7AB883B832A7B033AB88AD2B2CF -:102200003146FFF735FAFB7DB882DA43C2F3C012DC -:1022100062F3C713FB75B6E76AB92E1D013B324660 -:102220003946DBB204F10C00FFF7A4FA0028D3DB37 -:102230002A7B013AE2E7F98A013BC1F3090105294A -:10224000DAB25BD80023281D07F11A0C9A4208D98C -:1022500010F801EB01330CF801E001310629DBB283 -:10226000F4D1934228BF0023039938BF04330A9165 -:10227000049938BFDBB20B9107F11A010C91796810 -:1022800038BF5B190D910E93FB8AADF83EA0C3F3E6 -:1022900009031A44079BADF83C208DF8433094F8AD -:1022A00024308DF840B083F001038DF844300023D2 -:1022B0008DF841608DF842807B602A7BB88A013AB4 -:1022C000291DFFF7D5F93B8BB882834203D1204605 -:1022D000A3680AA9984720460AA9FFF735FEFB7DA7 -:1022E000B88AC3F38403013303F01F039B02FB820C -:1022F0003B8B984214BF112000208FE67B68002B97 -:10230000AFD0062001E063461C30D3F800C0BCF11A -:10231000000FF8D1091A081D05F1040C1844DDF866 -:1023200014E09DF814308E44BEF11B0F99D89A42E8 -:1023300097D91CF8013B00F8013B059B013305933D -:10234000EDE76FF0090069E66FF00A0066E66FF0EE -:102350000D0063E66FF00E0060E66FF00F005DE6C3 -:1023600080841E00F0B53F4D3F4FEB6943F0007392 -:10237000EB61EB693D4B9B6AD3F800623E4046F04F -:102380000106C3F80062D3F800423C4044EA00244E -:1023900044F00104C3F80042002955D0002006464D -:1023A000C3F81C02C3F80402C3F80C02C3F81402F9 -:1023B00003EBC00401300E28C4F84062C4F8446244 -:1023C000F6D100274FF0010C9678148816F0010F13 -:1023D00018BFD3F804E20CFA04F01CBF40EA0E0E5A -:1023E000C3F804E216F0020F18BFD3F80CE203EBB7 -:1023F000C4041CBF40EA0E0EC3F80CE2760748BFC7 -:10240000D3F8146207F1010744BF0643C3F814620E -:102410005668B942C4F84062966802F10C02C4F8EA -:102420004462D3F81C4240EA0400C3F81C02CBD13A -:10243000D3F8002222F00102C3F80022EB6923F056 -:102440000073EB61EB69F0BD0122C3F84012C3F8E1 -:102450004412C3F80412C3F81412C3F80C22C3F8D0 -:102460001C22E5E7001002400000FFFF8822002048 -:10247000184A08B5916A8B688B6013F0010104D08B -:1024800013F00C0F18BF4FF48031D80506D513F4A4 -:10249000406F14BF41F4003141F00201D80306D56A -:1024A00013F4402F14BF41F4802141F00401D3699B -:1024B0000BB108489847202383F311880021064870 -:1024C00000F01EFE002383F31188BDE8084001F0F0 -:1024D00083B800BF882200209022002038B5124C1B -:1024E000A36ADD68AA0712D05A6922F002025A6173 -:1024F000A36913B1012120469847202383F3118853 -:1025000000210A4800F0FCFD002383F31188EB064C -:1025100006D51021A36AD960236A0BB102489847F7 -:10252000BDE8384001F058B88822002098220020E9 -:1025300038B5124CA36A1D69AA0712D05A6922F055 -:1025400010025A61A36913B1022120469847202343 -:1025500083F3118800210A4800F0D2FD002383F3A1 -:102560001188EB0606D51021A36A1961236A0BB105 -:1025700002489847BDE8384001F02EB88822002074 -:102580009822002038B50F4CA36A5D682A075D6069 -:102590000AD5042222701A6822F002021A60636AC5 -:1025A00013B10021204698476B0706D5A36A9969A5 -:1025B000236A13B1034809049847BDE8384001F085 -:1025C0000BB800BF8822002010B50E4C204600F04A -:1025D000FDF90D4B0B211320A36200F0D7F90B215D -:1025E000142000F0D3F90B21152000F0CFF90B21B6 -:1025F000162000F0CBF9BDE8104000220E20114655 -:10260000FFF7B0BE88220020006400400F4B10B5D9 -:102610009842044605D10E4BDA6942F00072DA6145 -:10262000DB690122A36A1A60A36A5A68D20707D538 -:10263000626851681268D9611A60064A5A6110BD11 -:102640000121082000F052FCEEE700BF88220020A4 -:10265000001002405B87010003291AD8DFE801F06F -:10266000020A0F14836A9B6813F0E05F14BF012015 -:1026700000207047836A9868C0F380607047836A5F -:102680009868C0F3C0607047836A9868C0F30070B0 -:10269000704700207047000010B5032927D8DFE8F5 -:1026A00001F002272B2F836A9968C1F30161183169 -:1026B00003EB01131078840648BF5468C0F300117F -:1026C00058BF94884FEA410148BF41EAC40100F075 -:1026D0000F00586048BF41F00401906858BF41EABC -:1026E0004451D26841F001019860DA60196010BD70 -:1026F000836A03F5C073DDE7836A03F5C873D9E71E -:10270000836A03F5D073D5E701290AD002290FD0D7 -:1027100081B9836ADA68920701D1186903E0012060 -:102720007047836AD86810F0030018BF0120704713 -:10273000836AF2E70020704710B539B9836AD96817 -:1027400089071BD11B699C0704D110BD012915D035 -:102750000229FAD1816AD1F8C031D1F8C441D1F847 -:10276000C8011061D1F8CC015061202008610869CE -:10277000800717D1486940F0100012E0816AD1F853 -:10278000B031D1F8B441D1F8B8011061D1F8BC0131 -:1027900050612020C860C868800703D1486940F0B4 -:1027A00002004861C3F34000C3F38001000140EA26 -:1027B0004111107920F030000143117189064BBF9F -:1027C00091681189DB085B0D4CBF63F31C0163F357 -:1027D0000A01137948BF916064F3030313714FEA50 -:1027E00014234FEA144458BF118113705480ACE78E -:1027F000026843680A43026003B11847704700004B -:10280000024AD36843F0C003D360704700380140E8 -:10281000024AD36843F0C003D360704700440040CD -:102820002DE9F041D0F89C600446F7683368DA057A -:102830009DB20DD5202383F311884FF4007104302D -:10284000FFF7D6FF6FF480733360002383F31188A2 -:10285000202383F3118804F1040815F02F033AD1E3 -:1028600083F31188380615D5290613D5202383F361 -:10287000118804F1380000F02FFA00284DDA082101 -:10288000201DFFF7B5FF4FF67F733B40F360002339 -:1028900083F311887A0616D56B0614D5202383F3AB -:1028A0001188D4E913239A420AD1236C43B127F04B -:1028B00040073F041021201D3F0CFFF799FFF760F0 -:1028C000002383F31188D4F8A420D3683BB3BDE878 -:1028D000F041106918472B0713D015F0080F0CBFF3 -:1028E00000218021E80748BF41F02001AA0748BF26 -:1028F00041F040016B07404648BF41F48071FFF74B -:1029000077FFAD06736805D594F8A01020461940EE -:1029100000F082FA3568ADB29FE77060B7E7BDE8B6 -:10292000F081000008B50348FFF77AFFBDE80840D2 -:1029300000F052BEB422002008B50348FFF770FF34 -:10294000BDE8084000F048BE5C23002010B5094CEB -:1029500000212046084A00F03FFA084B0021C4F845 -:102960009C30074C074A204600F036FA064BC4F864 -:102970009C3010BDB422002001280008003801401E -:102980005C230020112800080044004001220901B6 -:1029900000F1604303F56143C9B283F8001300F00E -:1029A0001F039A4043099B0003F1604303F5614311 -:1029B000C3F880211A607047090100F16040C9B274 -:1029C00000F56D4001767047FFF7FEBD01230370EF -:1029D000002300F10802C0E9022200F11002C0E960 -:1029E0000422C0E90633C0E90833436070470000A1 -:1029F00010B52023044683F311880223416003703D -:102A0000FFF704FE04232370002383F3118810BD15 -:102A10002DE9F0411F4604460D461646202383F358 -:102A2000118800F108082378052B0DD0294620468F -:102A3000FFF712FE40B1204632462946FFF72CFE32 -:102A4000002080F3118808E03946404600F03CFB46 -:102A50000028E8D0002383F31188BDE8F08100004E -:102A60002DE9F0411F4604460D461646202383F308 -:102A7000118800F110082378052B0DD02946204637 -:102A8000FFF742FE40B1204632462946FFF754FE8A -:102A9000002080F3118808E03946404600F014FB1E -:102AA0000028E8D0002383F31188BDE8F0810000FE -:102AB000F8B5154682680B46AA428169066938BF97 -:102AC0008568761AB54204460BD218462A46FEF7A8 -:102AD00067FCA3692B44A361A36828465B1BA36022 -:102AE000F8BD0CD918463246FEF75AFCAF1B3A46E1 -:102AF000E1683044FEF754FCE3683B44EBE71846DA -:102B00002A46FEF74DFCE368E5E700002DE9F041B9 -:102B1000154683680446934238BF8568D0E904703F -:102B20003F1ABD420E460BD22A46FEF739FC6369B6 -:102B30002B446361A36828465B1BA360BDE8F0815A -:102B40000CD93A46A5EB0708FEF72AFC4246E06896 -:102B5000F119FEF725FCE3684344EAE72A46FEF74D -:102B60001FFCE368E5E7000010B50024C361029B89 -:102B7000C0E90511C1601144C0E900008460016131 -:102B8000036210BD08B5D0E90532934201D18268D5 -:102B900092B98268013282605A1C42611970D0E990 -:102BA00004329A4228BFC3684FF0000128BF436136 -:102BB00000F09AFA002008BD4FF0FF30FBE700005C -:102BC00070B5202304460D4683F31188A668A6B18C -:102BD000A368A269013BA360531CA3611578226915 -:102BE000934224BFE368A361E3690BB12046984791 -:102BF000002383F31188284607E02946204600F089 -:102C000063FA0028E2DA86F3118870BD2DE9F74FE8 -:102C100004460E4617469846D0F81C904FF0200AFE -:102C20008AF311884FF0000B154665B12A463146EC -:102C30002046FFF73DFF034660B94146204600F0BD -:102C400043FA0028F1D0002383F31188781B03B0E6 -:102C5000BDE8F08FB9F1000F03D001902046C847BE -:102C6000019B8BF31188ED1A1E448AF31188DCE76F -:102C7000C361009BC0E90511C1601144C0E90000B7 -:102C80008260016103627047F8B504460D4616463E -:102C9000202383F31188A768A7B1A368013BA36031 -:102CA00063695A1C62611D70D4E904329A4224BFE0 -:102CB000E3686361E3690BB120469847002080F325 -:102CC000118807E03146204600F0FEF90028E2DADC -:102CD00087F31188F8BD0000D0E905239A4210B5AA -:102CE00001D182687AB982680021013282605A1C5F -:102CF00082611C7803699A4224BFC368836100F033 -:102D0000F3F9204610BD4FF0FF30FBE72DE9F74FF8 -:102D100004460E4617469846D0F81C904FF0200AFD -:102D20008AF311884FF0000B154665B12A463146EB -:102D30002046FFF7EBFE034660B94146204600F00F -:102D4000C3F90028F1D0002383F31188781B03B066 -:102D5000BDE8F08FB9F1000F03D001902046C847BD -:102D6000019B8BF31188ED1A1E448AF31188DCE76E -:102D7000026843680A43026003B1184770470000C5 -:102D80001430FFF743BF00004FF0FF331430FFF75C -:102D90003DBF00003830FFF7B9BF00004FF0FF33F0 -:102DA0003830FFF7B3BF00001430FFF709BF000051 -:102DB0004FF0FF311430FFF703BF00003830FFF74A -:102DC00063BF00004FF0FF323830FFF75DBF0000F7 -:102DD00000207047FFF7BABD37B515460D4A0446C7 -:102DE000026000224260C0E9022201220B46027406 -:102DF00000F15C01009020221430FFF7B5FE2B4655 -:102E00002022009404F17C0104F13800FFF730FF28 -:102E100003B030BD4C3B000838B5C36904460D46CD -:102E20001BB904210844FFF7A3FF294604F114004D -:102E3000FFF7A8FE002806DA201D4FF48061BDE8E8 -:102E40003840FFF795BF38BD0022024BC3E900337D -:102E50009A60704704240020002382680374054BA5 -:102E60001B6899689142FBD25A6803604260106007 -:102E7000586070470424002008B5202383F311888C -:102E8000037C032B05D0042B0DD02BB983F31188C1 -:102E900008BD002243691A604FF0FF334361FFF71A -:102EA000DBFF0023F2E7D0E9003213605A60F3E75A -:102EB000002382680374054B1B6899689142FBD814 -:102EC0005A68036042601060586070470424002014 -:102ED000054B196908741868026853601A60186114 -:102EE00001230374FDF732BB0424002030B54B1CD2 -:102EF00004460B4D87B010D02B690A4A01A800F098 -:102F00001BF92046FFF7E4FF049B13B101A800F072 -:102F10002FF92B69586907B030BDFFF7D9FFF8E7E3 -:102F200004240020792E000838B50C4D41612B692E -:102F300081689A680446914203D8BDE83840FFF79B -:102F40008BBF1846FFF7B4FF01232C6101462374A1 -:102F50002046BDE83840FDF7F9BA00BF0424002040 -:102F6000044B1A681B6990689B68984294BF0020C4 -:102F7000012070470424002010B5084C2368206904 -:102F80001A6854602260012223611A74FFF790FFCF -:102F900001462069BDE81040FDF7D8BA042400209E -:102FA00008B5FFF7DDFF18B1BDE80840FFF7E4BF43 -:102FB00008BD0000FFF7E0BFFEE7000010B50C4CB5 -:102FC000FFF742FF00F0AAF880220A49204600F0ED -:102FD00031F8012344F8180C037400F0D9FA0023E7 -:102FE00083F3118862B6BDE81040034800F042B890 -:102FF0002C240020743B0008843B000800F0CAB871 -:10300000EFF3118020B9EFF30583202282F31188BA -:103010007047000010B530B9EFF30584C4F308041D -:1030200014B180F3118810BDFFF7BAFF84F3118843 -:10303000F9E7000082600222028270478368A3F1F0 -:103040003C0243F80C2C026943F83C2C426943F8DB -:10305000382C074A43F81C2CC268A3F1180043F827 -:10306000102C022203F8082C002203F8072C7047CA -:103070005D05000810B5202383F31188FFF7DEFFFC -:1030800000210446FFF750FF002383F311882046F8 -:1030900010BD0000024B1B6958610F20FFF718BFDD -:1030A00004240020202383F31188FFF7F3BF0000DE -:1030B00008B50146202383F311880820FFF716FF87 -:1030C000002383F3118808BD49B1064B42681B6990 -:1030D00018605A60136043600420FFF707BF4FF089 -:1030E000FF3070470424002003460068834205D067 -:1030F00002681A6053604161FFF7AEBE704700007E -:1031000038B504460D462068844200D138BD0368B6 -:1031100023605C604561FFF79FFEF4E7054B03F118 -:103120001402C3E905224FF0FF32DA6100221A626D -:10313000704700BF0424002010B5C0E903230B4AE8 -:10314000136A53699C68A1420CD85C688160036073 -:103150004460206058609868411A99604FF0FF33CE -:10316000D36110BD1B68091BECE700BF04240020DD -:10317000036881689A680A449A60426813605A60DA -:1031800000234FF0FF32C360014BDA61704700BF8C -:103190000424002038B50F4C2246236A01332362F1 -:1031A00052F8143F934206D020259A68013A9A605B -:1031B00063699A6802B138BDD3E9001001604860C4 -:1031C000D968DA6082F311881869884785F3118815 -:1031D000EEE700BF0424002000207047FEE7000057 -:1031E000704700004FF0FF3070470000BFF34F8F73 -:1031F000024AD368DB07FCD4704700BF00200240BE -:1032000008B5074B1B7853B9FFF7F0FF054B1A6958 -:10321000120641BF044A5A6002F188325A6008BD62 -:1032200008250020002002402301674508B5054B12 -:103230001B7833B9FFF7DAFF034A136943F08003C1 -:10324000136108BD08250020002002407F289ABF96 -:1032500000F5003080020020704700004FF48060CD -:1032600070470000802070477F2808B50BD8FFF713 -:10327000EDFF00F580630268013204D1043083421F -:10328000F9D1012008BD0020FCE700007F2838B5F7 -:10329000044623D8FFF7B4FEFFF7A8FFFFF7B0FFFF -:1032A000F3220F4B0546DA60022220461A61FFF72F -:1032B000CDFF58611A694FF4806142F040021A61F3 -:1032C000FFF794FF00F010F92846FFF7AFFFFFF774 -:1032D000A1FE2046BDE83840FFF7C6BF002038BD3C -:1032E000002002402DE9F047044612F001000E468E -:1032F000154606D040F2BD22234B1A600020BDE8DF -:10330000F087224BA2189A4204D940F2C2221E4BE7 -:103310001A60F4E7FFF774FE4FF0010AFFF770FF41 -:10332000FFF764FFDFF868903146A61B012D884641 -:1033300006EB010705D8FFF779FFFFF76BFE0120C9 -:10334000DDE7B8F80030C9F810A03B800024FFF793 -:103350004DFFC9F810403B8831F8022B9BB29A42CE -:103360000FD040F2D922084B1A600A4B1F600A4B5B -:103370001D600A4BC3F80080FFF758FFFFF74AFEB5 -:10338000BCE7023DD2E700BF042500200000020890 -:1033900000200240F824002000250020FC2400200A -:1033A000084908B50B7828B11BB9FFF729FF01239D -:1033B0000B7008BD002BFCD0BDE808400870FFF77B -:1033C00035BF00BF0825002070B5FFF719FE4FF488 -:1033D0007A710D4B0D4E1B6A326801FB03F3934269 -:1033E00037BF0B4A0A495168156836BF4C1CD1E9F2 -:1033F000005454605D1944F100043360FFF70AFE85 -:103400002846214670BD00BF042400200C25002062 -:103410001025002070B5FFF7F3FD4FF47A710F4BC4 -:103420000F4E1B6A326801FB03F3934237BF0D4A0C -:103430000C49516815683ABF4C1C5460D1E90054DE -:103440005D1944F100043360FFF7E4FD4FF47A7234 -:10345000002328462146FCF783FE70BD042400208B -:103460000C2500201025002010B5094C013AD2B2DD -:10347000FF2A00D110BD500854F82030013054F814 -:1034800020009BB243EA004341F8043BEEE700BF53 -:10349000046C004010B50748013AD2B2FF2A00D1AF -:1034A00010BD0C88530840F823404C88013340F885 -:1034B0002340F1E7046C004007B50122002001A978 -:1034C000FFF7D2FF019803B05DF804FB13B5044683 -:1034D000FFF7F2FFA04205D00122002001A90194CC -:1034E000FFF7D8FF02B010BD7047000045F25552FB -:1034F000064B1A6002225A6040F6FF729A604CF640 -:10350000CC421A600122024B1A7070470030004012 -:103510001C250020034B1B781BB14AF6AA22024B44 -:103520001A6070471C25002000300040044B1A68C8 -:103530002AB902F1804202F50432526A1A607047D9 -:10354000182500204FF08072014B5A62704700BF6F -:103550000010024008B5FFF7E9FF024B1868C0F3FE -:10356000407008BD1825002008B5FFF7DFFF024BAB -:103570001868C0F3007008BD18250020EFF3098318 -:10358000203383F30988002383F3118870470000F8 -:10359000202080F3118862B60C4B0D4AD96821F4C3 -:1035A000E0610904090C0A43DA60D3F8FC200949F8 -:1035B00042F08072C3F8FC200A6842F001020A60FF -:1035C0001022DA7783F82200704700BF00ED00E098 -:1035D0000003FA05001000E0202310B583F31188E2 -:1035E0000B4B5B6813F400630FD0EFF309844FF0CB -:1035F0008073203CE36184F30988FFF7B1FC10B1CC -:10360000044BA36110BD044BFBE783F31188F9E77A -:1036100000ED00E06F05000872050008704700002B -:10362000FEE700000A4B0B480B4A90420BD30B4BB2 -:10363000C11EDA1C121A22F003028B4238BF00228C -:103640000021FDF7BFBE53F8041B40F8041BECE754 -:10365000043C0008A0250020A0250020A025002073 -:103660007047000000F030B808B500F063F9FFF7CC -:10367000A5FCBDE80840FFF759BF000070470000F7 -:103680004FF0FF310E4B1A6919611A6900221A6155 -:103690001869D868D960D968DA60DA68DA6942F0FE -:1036A0008052DA61DA69DA6942F00062DA61054A69 -:1036B000DB69136843F48073136000F01BB900BF2B -:1036C0000010024000700040194B1A6842F00102DD -:1036D0001A601A689007FCD51A6802F0F9021A609D -:1036E00000225A605A6812F00C0FFBD11A6842F49B -:1036F00080321A601A689103FCD55A6842F4E812C5 -:103700005A601A6842F080721A601A689201FCD5F9 -:103710001221084A5A60084A11605A6842F00202AF -:103720005A605A6802F00C02082AFAD1704700BFAA -:103730000010024000641D0000200240084A08B545 -:10374000516913680B4003F00103536123B1054A2B -:1037500013680BB150689847BDE80840FFF73CBFBD -:103760000004014020250020084A08B5516913686B -:103770000B4003F00203536123B1054A93680BB178 -:10378000D0689847BDE80840FFF726BF0004014015 -:1037900020250020084A08B5516913680B4003F042 -:1037A0000403536123B1054A13690BB1506998476B -:1037B000BDE80840FFF710BF0004014020250020AD -:1037C000084A08B5516913680B4003F008035361B8 -:1037D00023B1054A93690BB1D0699847BDE8084009 -:1037E000FFF7FABE0004014020250020084A08B572 -:1037F000516913680B4003F01003536123B1054A6C -:10380000136A0BB1506A9847BDE80840FFF7E4BE61 -:103810000004014020250020174B10B55A691C6890 -:10382000144004F478725A61A30604D5134A936ACB -:103830000BB1D06A9847600604D5104A136B0BB1E0 -:10384000506B9847210604D50C4A936B0BB1D06B93 -:103850009847E20504D5094A136C0BB1506C9847A0 -:10386000A30504D5054A936C0BB1D06C9847BDE80D -:103870001040FFF7B1BE00BF00040140202500202A -:103880001A4B10B55A691C68144004F47C425A6102 -:10389000620504D5164A136D0BB1506D9847230588 -:1038A00004D5134A936D0BB1D06D9847E00404D54D -:1038B0000F4A136E0BB1506E9847A10404D50C4A01 -:1038C000936E0BB1D06E9847620404D5084A136F0B -:1038D0000BB1506F9847230404D5054A936F0BB181 -:1038E000D06F9847BDE81040FFF776BE0004014056 -:1038F00020250020062108B50846FFF747F80621D5 -:103900000720FFF743F806210820FFF73FF80621BC -:103910000920FFF73BF806210A20FFF737F80621B8 -:103920001720FFF733F8BDE8084006212820FFF7ED -:103930002DB8000008B5FFF7A3FE064800F00EF80A -:10394000FFF742F8FFF746FAFFF798FEBDE8084098 -:1039500000F002B89C3B000800F042B80023194672 -:103960001C4A0133102BC2E9001102F10802F8D100 -:10397000194B9A6942F07D029A619B690268174B64 -:10398000DA6082685A6042681A60C26803F5806330 -:10399000DA6042695A6002691A608269C3F80C24CD -:1039A000026AC3F80424C269C3F80024426AC3F857 -:1039B0000C28C26AC3F80428826AC3F80028026B84 -:1039C000C3F80C2C826BC3F8042C426BC3F8002C98 -:1039D000704700BF20250020001002400008014071 -:1039E0004FF0E023044A08215A6100229A6107221D -:1039F0000B201A61FEF7E0BF3F19010008B5202334 -:103A000083F31188FFF7FAFA002383F3118808BDC6 -:103A100008B5FFF7F3FFBDE80840FFF7DDBD000084 -:103A200010B501390244904201D1002005E003782D -:103A300011F8014FA34201D0181B10BD0130F2E76D -:103A40002DE9F0419BB10446C91A1778014403F1EE -:103A5000FF3C8C42204601D9002008E00578013463 -:103A6000BD42F6D10CEB0405D618A54201D1BDE844 -:103A7000F08115F8018D16F801EDF045F5D0E8E775 -:103A8000034611F8012B03F8012B002AF9D17047E6 -:103A90006F72672E6172647570696C6F742E6170DD -:103AA0005F7065726970685F616473620000000036 -:103AB0004E6F20617070207369670A004261642054 -:103AC0006677206C656E6774682025750A00426110 -:103AD0006420626F6172645F696420257520736879 -:103AE0006F756C642062652025750A004261642050 -:103AF00066772064657363726970746F72206C6599 -:103B00006E6774682025750A0042616420617070D8 -:103B100020435243203078253038783A30782530A9 -:103B20003878203078253038783A30782530387831 -:103B30000A00476F6F64206669726D776172650A6B -:103B40000040A2E4F164689106000000000000005B -:103B50009D2D0008892D0008C52D0008B12D0008F5 -:103B6000BD2D0008A92D0008952D0008812D000805 -:103B7000D12D00086D61696E0000000069646C65FC -:103B8000000000007C3B000848240020F8240020AE -:103B900001000000B92F0008000000000C1E00000A -:103BA000447B4144B457494401000000424444442A -:103BB00044444444000000004444444444444444D5 -:103BC00000000000444444444444444400000000D5 -:103BD0004444444444444444B8C5FF7F01000000C9 -:103BE000E803000000000000009C0100000000004D -:103BF000640000000000000040420F00FE2A0100A7 -:043C0000D2040000EA +:10000000000900202D080008B11C0008811C000810 +:100010009D1C0008811C0008951C00082F08000882 +:100020002F0800082F0800082F080008E5370008EF +:100030002F0800082F0800082F080008F93C0008C6 +:100040002F0800082F0800082F0800082F080008B4 +:100050002F0800082F080008293A0008553A000820 +:10006000813A0008AD3A0008D93A00082F08000884 +:100070002F0800082F0800082F0800082F08000884 +:100080002F0800082F0800082F080008AD2C0008D2 +:10009000192D00086D2D0008C12D0008053B000832 +:1000A0002F0800082F0800082F0800082F08000854 +:1000B0002F0800082F0800082F0800082F08000844 +:1000C0002F0800082F0800082F0800082F08000834 +:1000D0002F0800082F0800082F0800082F08000824 +:1000E0006D3B00082F0800082F0800082F080008A3 +:1000F0002F0800082F0800082F0800082F08000804 +:100100002F0800082F0800082F0800082F080008F3 +:100110002F0800082F0800082F0800082F080008E3 +:100120002F0800082F0800082F0800082F080008D3 +:100130002F0800082F0800082F0800082F080008C3 +:100140002F0800082F0800082F0800082F080008B3 +:100150002F0800082F0800082F0800082F080008A3 +:100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A +:100170000C0F93EA0C0F6FD01A4480EA010C400276 +:1001800018BF5FEA41211ED04FF0006343EA5010D0 +:1001900043EA5111A0FB01310CF00040B1F5000F12 +:1001A0003EBF490041EAD3715B0040EA010062F1C1 +:1001B0007F02FD2A1DD8B3F1004F40EBC25008BFAB +:1001C00020F00100704790F0000F0CF0004C08BFC9 +:1001D00049024CEA502040EA51207F3AC2BFD2F196 +:1001E000FF0340EAC250704740F400004FF00003A4 +:1001F000013A5DDC12F1190FDCBF00F000407047DE +:10020000C2F10002410021FA02F1C2F1200200FA1B +:1002100002FC5FEA310040F1000053EA4C0308BFE2 +:1002200020EADC70704792F0000F00F0004C02BF33 +:10023000400010F4000F013AF9D040EA0C0093F0AE +:10024000000F01F0004C02BF490011F4000F013B08 +:10025000F9D041EA0C018FE70CEAD15392EA0C0F76 +:1002600018BF93EA0C0F0AD030F0004C18BF31F0E1 +:10027000004CD8D180EA010000F00040704790F0B7 +:10028000000F17BF90F0004F084691F0000F91F05B +:10029000004F14D092EA0C0F01D142020FD193EA21 +:1002A0000C0F03D14B0218BF084608D180EA0100A9 +:1002B00000F0004040F0FE4040F40000704740F085 +:1002C000FE4040F44000704780F0004002E000BF74 +:1002D00081F0004142001FBF5FEA410392EA030F31 +:1002E0007FEA226C7FEA236C6AD04FEA1262D2EB7B +:1002F0001363C1BFD218414048404140B8BF5B4280 +:10030000192B88BF704710F0004F40F4000020F018 +:100310007F4018BF404211F0004F41F4000121F02E +:100320007F4118BF494292EA030F3FD0A2F1010278 +:1003300041FA03FC10EB0C00C3F1200301FA03F1B6 +:1003400000F0004302D5494260EB4000B0F5000FD9 +:1003500013D3B0F1807F06D340084FEA310102F198 +:100360000102FE2A51D2B1F1004F40EBC25008BF4A +:1003700020F0010040EA03007047490040EB000014 +:10038000013A28BFB0F5000FEDD2B0FA80FCACF115 +:10039000080CB2EB0C0200FA0CF0AABF00EBC25042 +:1003A00052421843BCBFD0401843704792F0000F30 +:1003B00081F4000106BF80F400000132013BB5E783 +:1003C0004FEA41037FEA226C18BF7FEA236C21D0F9 +:1003D00092EA030F04D092F0000F08BF084670475E +:1003E00090EA010F1CBF0020704712F07F4F04D12C +:1003F000400028BF40F00040704712F100723CBF3F +:1004000000F50000704700F0004343F0FE4040F468 +:10041000000070477FEA226216BF08467FEA236326 +:100420000146420206BF5FEA412390EA010F40F411 +:10043000800070474FF0000304E000BF10F000435D +:1004400048BF40425FEA000C08BF704743F0964344 +:1004500001464FF000001CE050EA010208BF70475F +:100460004FF000030AE000BF50EA010208BF7047E6 +:1004700011F0004302D5404261EB41015FEA010CFB +:1004800002BF84460146002043F0B64308BFA3F1F3 +:100490008053A3F50003BCFA8CF2083AA3EBC253D5 +:1004A00010DB01FA02FC634400FA02FCC2F12002F4 +:1004B000BCF1004F20FA02F243EB020008BF20F02B +:1004C0000100704702F1200201FA02FCC2F1200291 +:1004D00050EA4C0021FA02F243EB020008BF20EA86 +:1004E000DC70704742000ED2B2F1FE4F0BD34FF0DA +:1004F0009E03B3EB126209D44FEA002343F000439A +:1005000023FA02F070474FF00000704712F1610FBC +:1005100001D1420202D14FF0FF3070474FF000008E +:10052000704700BF53B94AB9002908BF00281CBF53 +:100530004FF0FF314FF0FF3000F076B9ADF1080C0D +:100540006DE904CE00F006F8DDF804E0DDE90223F1 +:1005500004B070472DE9F047089E0D4604468846D2 +:10056000002B4DD18A42944668D9B2FA82F252B138 +:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 +:1005800041EA030894404FEA1C41B8FBF1F71FFA17 +:100590008CFE01FB178807FB0EF0230C43EA08438F +:1005A00098420AD91CEB030307F1FF3580F01E8146 +:1005B000984240F21B81023F63441B1AB3FBF1F0E7 +:1005C00001FB103300FB0EFEA4B244EA0344A6452F +:1005D0000AD91CEB040400F1FF3380F00981A64521 +:1005E00040F20681644402380021A4EB0E0440EA84 +:1005F00007401EB10023D440C6E90043BDE8F087A0 +:100600008B4208D9002E00F0EE800021C6E90005DB +:100610000846BDE8F087B3FA83F100294AD1AB421E +:1006200002D3824200F2FC80841A65EB03030120AE +:100630009846002EE2D0C6E90048DFE702B9FFDEA7 +:10064000B2FA82F2002A40F09180A1EB0C00012165 +:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 +:10066000250C45EA00450EFB03F0A84208D91CEB17 +:10067000050503F1FF3802D2A84200F2CE804346BE +:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 +:1006900044EA0544A64508D91CEB040400F1FF35E3 +:1006A00002D2A64500F2B6802846A4EB0E0440EA2A +:1006B00003409EE7C1F120078B4022FA07FC4CEA79 +:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D +:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 +:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 +:1006F00001F20BD91CEB040408F1FF3A80F088806A +:10070000A04240F28580A8F102086444241AB4FB98 +:10071000F9F009FB104400FB0EFEADB245EA0444BB +:10072000A64508D91CEB040400F1FF356CD2A645A0 +:100730006AD90238644440EA0840A0FB0295A4EB61 +:100740000E04AC42C846AE4656D353D0002E69D0F4 +:10075000B3EB080264EB0E0422FA01F304FA07F784 +:100760001F43CC40C6E90074002147E70CFA02FCA5 +:10077000C2F1200125FA01F34FEA1C4720FA01F1EA +:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 +:10079000280C40EA034001FB0EF3834204FA02F402 +:1007A00008D91CEB000001F1FF382FD283422DD96C +:1007B00002396044C01AB0FBF7F307FB1300ADB277 +:1007C00045EA004503FB0EF0A84208D91CEB0505DD +:1007D00003F1FF3816D2A84214D9023B6544281A07 +:1007E00043EA014138E73146304607E72F46E4E661 +:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 +:100800000138A3E74346EAE7284694E74146D1E7A3 +:10081000D0467BE76444023847E7023B65442FE754 +:10082000084606E73146E9E6704700BF02E000F0FF +:1008300000F8FEE772B6264880F30888254880F362 +:100840000988254825490860022080F31488BFF3F1 +:100850006F8F03F017F803F07BF84FF05530204905 +:100860001B4A91423CBF41F8040BFAE71D49194A63 +:1008700091423CBF41F8040BFAE71B491B4A1C4B51 +:100880009A423EBF51F8040B42F8040BF8E70020EF +:100890001849194A91423CBF41F8040BFAE702F0AB +:1008A000F5FF03F057F8154C154DAC4203DA54F838 +:1008B000041B8847F9E700F03FF8124C124DAC4298 +:1008C00003DA54F8041B8847F9E702F0DDBF0000A3 +:1008D00000090020001100200000000808ED00E0E1 +:1008E0000001002000090020083E0008001100203F +:1008F0002411002028110020E025002060010008BC +:100900006001000860010008600100082DE9F04F57 +:10091000C1F80CD0C3689D46BDE8F08F002383F377 +:1009200011882846A047002002F010FDFEE702F0E3 +:1009300083FC00DFFEE70000F8B500F03DFE02F0AA +:10094000EFFE074602F03AFF0546002840D12C4B47 +:100950009F423DD001339F423DD02A4B27F0FF02FA +:100960009A423BD1F8B200F003FC2E4642F21074DA +:1009700000F004FC08B10024264601F007F988B312 +:100980000024032000F044F8264635B11E4B9F4258 +:1009900003D0002402F00AFF2646002002F0CAFE1F +:1009A0001A4B9B6813F0400322D00EB100F046F8BA +:1009B00000F044FC00F002FE01F07CF90546CCB1E9 +:1009C00001F078F9401BA04214D900F037F8F3E7A2 +:1009D0002E460024CCE704460126C9E706464FF41C +:1009E0007A74C5E7002CD0D04FF47A740126CCE796 +:1009F0001C46DDE700F0D4FC012002F0ADFCDEE790 +:100A0000010007B0000008B0263A09B0000C014010 +:100A1000084B187003280CD8DFE800F0080502081E +:100A2000022000F027BE022000F01CBE0022024B74 +:100A30005A607047281100202C11002038B501F0B1 +:100A4000A5F830B103221F4B1A7000221E4B5A60CA +:100A500038BD1E4B1E4A19680131F9D00433934248 +:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 +:100A70009B6803F1006303F5C8439A42E8D202F091 +:100A800069FE02F07BFE002000F0B2FD0220FFF7BD +:100A9000BFFF124BDA690022DA61D96999699A615C +:100AA0009B6972B64FF0E023C3F8085D3021D4F89B +:100AB0000034D4F8042481F311889D4683F3088818 +:100AC0001047C5E7281100202C1100200064000801 +:100AD000206400080060000800110020001002409F +:100AE00049F26900084A136899B21B0C00FB0133F4 +:100AF00044F250611360054B186882B2000C01FB90 +:100B00000200186080B27047201100201C110020E4 +:100B100010B504460021102200F0C8FD034B03CBA2 +:100B2000206061601868A06010BD00BFE8F7FF1F7B +:100B30002DE9F0410026ADF54E7D6CAC40F275120A +:100B400007460D460EA831460D9600F0AFFD4FF456 +:100B5000C4723146204600F0A9FD01F0ABF84FF415 +:100B60007A72B0FBF2F0264B0DF13408186093E86E +:100B70000700022384E807000DF5E9702382FFF7E0 +:100B8000C7FF4EF603031F4907A8238403F0ECF8C0 +:100B900017230DF2E32284F832310DF12C0C07AB50 +:100BA0001E4603CE664510605160334602F10802CE +:100BB000F6D130681060B188B37920469180937186 +:100BC0004146012200F0BEFD00230393AB7E80B2BC +:100BD000029305F1190301930123CDE904800093E9 +:100BE000384605A3D3E90023E97E01F0A9FB0DF502 +:100BF0004E7DBDE8F08100BF9E6AC421818A46EE29 +:100C000034110020783D00082DE9F041264D804642 +:100C10002B7A0C46DAB0FBB9204627A900F0A2FED9 +:100C20000746002836D19DF89D60C82E32D801466F +:100C30004FF4FA72284600F039FD32460DF19E015C +:100C400005F1090000F020FD9DF89C302E447772DC +:100C50002B720BB9E37E2B728122002106AD27A8EF +:100C600000F024FD0122294627A800F0B7FE00234A +:100C70000393A37E80B2029304F119030193282306 +:100C8000CDE904500093404605A3D3E90023E17E5B +:100C900001F056FB5AB0BDE8F08100BFAFF3008011 +:100CA00026417272DF25D7B77C210020F0B54FF4C2 +:100CB0008A750024234EF1B005FB006596F8D83004 +:100CC000D822214685F8DC3085F8E8403AA800F0C3 +:100CD000EDFC06F1090000F0E1FCD5F8E430C2B209 +:100CE00006AF8DF8F00006F109010DF1F100CDE934 +:100CF0003A3400F0C9FC394601223AA800F09AFEC5 +:100D000080B2CDE9047008230127CDE9023706F14E +:100D1000D80301933023317A00930B4807A3D3E91A +:100D2000002301F00DFBA04206DD00F0C3FFC5F873 +:100D3000E000384671B0F0BD2046FBE778F6339FFF +:100D400093CACD8D7C2100204C210020F0B51E4E91 +:100D50001E4F1F4D85B0304601F01EFB044660B3A8 +:100D600010220021684600F0A1FC4FF00003227B16 +:100D70006068A16862F303038DF8003002AB03C31F +:100D8000019B2268384662F31C0301939DF80030F2 +:100D90006A4643F020038DF800300023194602F024 +:100DA00087F9044620B9304601F0FAFA2C70D2E7F0 +:100DB0002B78072B03D801332B7005B0F0BD024808 +:100DC00001F0EEFAF9E700BF4C210020A823002033 +:100DD0007523002070B50D4614461E4601F00CFA2E +:100DE00050B9022E10D1012C0ED112A3D3E9002349 +:100DF0000120C5E9002307E0282C10D005D8012CDC +:100E000009D0052C0FD0002070BD302CFBD10BA3D6 +:100E1000D3E90023ECE70BA3D3E90023E8E70BA316 +:100E2000D3E90023E4E70BA3D3E90023E0E700BF05 +:100E3000AFF30080401DA12026812A0B78F6339F56 +:100E400093CACD8D9E6AC421818A46EE2641727274 +:100E5000DF25D7B7F017304A39059E5638B5054615 +:100E60000E4C0021013500F0E5FBA4F8F051B4F878 +:100E7000F00100F0C7FB78B1B4F8F00100F0D2FB4C +:100E8000014648B9B4F8F00100F0D4FBB4F8F031F1 +:100E90000133A4F8F031EAE738BD00BF7C2100201F +:100EA0002DE9F04F8DB000AF04460D4601F0A4F9D6 +:100EB000002846D12B7E022B1AD1EB8A012B17D1A9 +:100EC00000F0F8FE0646FFF70BFE4FF4C873B0FBC8 +:100ED000F3F202FB1303DFF878829BB206F5167675 +:100EE0003344C8F80030EB7E33B90022994B1A70B6 +:100EF0003437BD46BDE8F08F284607F11C0100F0ED +:100F0000EFFC0028F4D107F10C00FFF701FEBD7FD4 +:100F100007F10C012A4607F11F0002F0F5FE002838 +:100F2000E3D10F2D08D88B4B1D70D8F80030A3F5F6 +:100F30001673C8F80030DBE72046397F01F054F91A +:100F4000D6E7EB8A282B6BD010D8012B63D0052B6A +:100F5000CED1BFF34F8F8049804BCA6802F4E06264 +:100F60001343CB60BFF34F8F00BFFDE7302BBFD1E2 +:100F70007B4CEA7E237A9A42BAD194F8DC206B7ECD +:100F80009A42B5D1284604F1EA0100F07FFD0646F9 +:100F90000028ADD1012384F8E83000F08BFED4F8AE +:100FA000E030C01A192840F6B83338BF19209842EB +:100FB00028BF1846FFF73EFA6A49FFF7D1F8054601 +:100FC0002068FFF737FA6849FFF7CAF80146284654 +:100FD000FFF780F9FFF786FA20604FF48A7194F8E2 +:100FE000D9307B607A68636801FB02F5621992F878 +:100FF000E80050B1D2F8E400E946834215D000235E +:1010000082F8E830C2F8E030CD466368574A9B0A60 +:10101000013313816CE729462046FFF789FD67E716 +:1010200029462046FFF7F0FD62E7B2F8EC803B600E +:1010300008F1030A4FEA9A0A4FEA8A02D11DC90849 +:10104000A9EBC1039D46EB460021584600F02EFB5C +:1010500005F1EE0142465846214400F015FB3B687D +:1010600013B9012000F0C4FA94F8D20000F0CAFAD3 +:10107000054630B9207200F0E5FA284600F0B8FACB +:10108000C2E7D4F8D4303BB994F8D200B4F8F031C8 +:10109000834201D8FFF7E2FED4F8D43043449D42A6 +:1010A00008D294F8D200B4F8F0310130834201D86C +:1010B000FFF7D4FE594660685FFA8AF200F0FEFA44 +:1010C00008B9CD4689E7636894F8D2004344636069 +:1010D000D4F8D43008EB030AC4F8D4A000F092FA94 +:1010E000824509D394F8D230D4F8D4000133401BA0 +:1010F00084F8D230C4F8D400B8F1FF0F0FD800251F +:10110000257200F09FFA284600F072FA00F03EFDCA +:10111000164B188108B9FFF791FCCD46E8E64FF46D +:101120008A727B6894F8D90002FB0343D3F8E42069 +:1011300083F8E86002F58072C3F8E060C3F8E42049 +:10114000FFF7B4FDFFF702FE84F8D960B9E700BFEE +:10115000482100204521002000ED00E00400FA05B0 +:101160007C210020CDCCCC3D6666663F341100204A +:10117000014B1870704700BF4011002030B54FF090 +:101180000054254B226885B09A4207D002F020FB1C +:101190000446C0B90024204605B030BD0025627D5C +:1011A0001E4B1F481A70237DC92203721D49C0F8C7 +:1011B000E450093000F068FA2046E022294600F0A9 +:1011C00075FA0124E7E7184A184DD36943F0007314 +:1011D000D361AA6D164B9A42DCD12B6E013B7E2B5C +:1011E000D8D8144A01AB07CA83E807001846032180 +:1011F00000F09CFC6B6D83424FF00003CAD12A6D56 +:101200008A4203BFAB652A6E044B1C4601BF1A70AD +:10121000EA6D094B1A60BEE79AAD44C54011002043 +:101220007C210020160000200010024000660040D3 +:101230005041A0B058660040181100202DE9F0433D +:1012400085B000F0A3FC0223494C63710023029394 +:10125000484B2081D3F800C0BCF57A7F12D3464FAB +:10126000464BB7FBFCF59C458CBF0A231123B5FB0D +:10127000F3F603FB1652591EC8B2002A3ED00229CB +:101280000B46F4D89DF80B303D495A1E9DF80A30A4 +:101290003C48013B1B0443EA0253BDF80820013AD5 +:1012A00013434B6001F0F4FE00230193364B3749A2 +:1012B00000934FF48052364B364800F06BFF364BAC +:1012C000197811B1334800F08FFF00F0F3FC0546A8 +:1012D000FFF706FC4FF4C873B0FBF3F202FB1303F5 +:1012E00005F516709BB218442C4B186002F066FA94 +:1012F00008B10F23238105B0BDE8F083731EB3F559 +:10130000806FBFD24FF47A75C0EBC00E0EF10303AD +:101310004FEAE30909FB0555C3F3C703C11AC9B274 +:1013200009F101088844B5FBF8F5B5F5617F08D9E6 +:101330000EF1FF33C3F3C703C11A581E0F28C9B2F9 +:1013400014D84A1E072A8CBF00220122581800FB1D +:101350000660B7FBF0F7BC4594D1002A92D0ADF8F7 +:1013600008608DF80A308DF80B108BE71346EDE717 +:101370003411002018110020005125023F420F00B7 +:1013800010110020A8230020D50D000844110020D2 +:10139000A10E00084C21002040110020482100200F +:1013A0002DE9F04F80A7D7E900670FF20429D9E9AA +:1013B0000089734D93B00DF1300AFFF7C7FC182276 +:1013C0000021504600F072F9DFF8B8B16E4C0023EE +:1013D00052461946584601F093FE014650BB102272 +:1013E00008A800F063F9E36883F01003E36000F0FD +:1013F00063FC0DF1240C0B4612A9024611E903000F +:101400008CE803009DF83410C1F30300890649BF3E +:101410000E99BDF83810C1F31C0141F0004158BFCE +:10142000C1F30A018DF82C000891284608A901F0A3 +:1014300097F9CCE7284600F0DFFE0446002847D1A4 +:1014400000F038FCDFF844B1DBF8003098423FD3BD +:1014500000F030FC0790FFF743FB4FF4C873B0FB7C +:10146000F3F101FB1300079A83B202F516701844DA +:10147000CBF80000DFF818B18DF820409BF8001081 +:1014800011B901238DF8203050460791FFF740FB3A +:1014900007990DF12100C1F11004E4B2062C28BF18 +:1014A00006245144224600F0EFF808AB03931823BA +:1014B0000293384B013401930123E4B20093324686 +:1014C0003B462846049400F0DDFE00238BF80030F4 +:1014D00000F0F0FB304A314C1368C31AB3F57A7F41 +:1014E00030D3106000F0E8FB02460B46284600F0BF +:1014F00061FF284600F080FE20B3237ADFF8A0B019 +:10150000002B14BF032302238BF8053000F0D2FB1D +:101510004FF47A73B0FBF3F00122CBF80000514690 +:10152000584600F0B5F9182302931E4B80B2019380 +:1015300040F25513CDE903A0009342464B4628469E +:1015400000F0A0FE237ABBB100F0B4FB94F8E830C1 +:1015500073B9D4F8E03043B1C01A2368FA2B38BF0E +:10156000FA230533B0EB430F02D30020FFF79EFBB5 +:10157000237A002B7FF41FAF13B0BDE8F08F00BFBC +:101580004C210020A8230020000801404821002011 +:101590004521002044210020702300207C210020D0 +:1015A0003411002074230020401DA12026812A0B25 +:1015B000F1C6A7C1D068080F7047000070B501F0F0 +:1015C00095FF0024084E094D3080286833888342F7 +:1015D00008D901F087FF2B6804440133B4F5C84FE4 +:1015E0002B60F2D370BD00BFA4230020782300201D +:1015F00002F00AB800F10060920000F5C84001F066 +:10160000AFBF0000054B1A68054B1B889B1A83422D +:1016100002D9104401F066BF0020704778230020F3 +:10162000A4230020024B1B68184401F061BF00BFD7 +:1016300078230020024B1B68184401F06BBF00BFE9 +:1016400078230020064991F8243033B10023082282 +:10165000086A81F82430FFF7CDBF0120704700BF32 +:101660007C230020022802BF1022014B1A61704720 +:1016700000080140022802BF4FF48012014B1A619A +:10168000704700BF00080140002310B5934203D00B +:10169000CC5CC4540133F9E710BD00000346024698 +:1016A000D01A12F9011B0029FAD1704703460244EF +:1016B000934202D003F8011BFAE770472DE9F84383 +:1016C0001F4D144695F824200746884652BBDFF884 +:1016D00070909CB395F824302BB92022FF21484606 +:1016E0002F62FFF7E3FF95F824004146C0F108029E +:1016F000A24228BF224605EB8000D6B29200FFF737 +:10170000C3FF95F82430A41B1E44F6B2082E1744DC +:101710009044E4B285F82460DBD1FFF793FF002802 +:10172000D7D108E02B6A03EB82038342CFD0FFF7C7 +:1017300089FF0028CBD10020BDE8F8830120FBE71A +:101740007C2300202DE9F0470D46044600219046F9 +:10175000284640F27912FFF7A9FF234620220021F4 +:10176000284600F09FFF022220212846231D00F07A +:1017700099FF032222212846631D00F093FF0322D4 +:1017800025212846A31D00F08DFF10222821284680 +:1017900004F1080300F086FF08223821284604F1EE +:1017A000100300F07FFF08224021284604F11103B6 +:1017B00000F078FF08224821284604F1120300F0C7 +:1017C00071FF20225021284604F1140300F06AFF23 +:1017D00040227021284604F1180300F063FF08221C +:1017E000B021284604F1200300F05CFF0822B82154 +:1017F000284604F1210300F055FFC02604F122071A +:101800003B46314608222846083600F04BFFB6F525 +:10181000A07F07F10107F3D108223146284604F1E1 +:10182000320300F03FFF002704F1330A94F832300E +:101830004FEAC7099F4209F5A47615D3B8F1000F06 +:1018400008D131460722284604F5997300F02AFF93 +:1018500009F24F16274694F832213B1B93420CD3D2 +:10186000F01DC008BDE8F0870AEB070308223146E7 +:10187000284600F017FF0137D8E7314607F2331347 +:101880000822284600F00EFF08360137E3E7000083 +:1018900038B50C460021054621600346C4F8031004 +:1018A0002046202200F0FEFE20462B1D0222202191 +:1018B00000F0F8FE20466B1D0322222100F0F2FE0C +:1018C0002046AB1D0322252100F0ECFE204610220D +:1018D000282105F1080300F0E5FE072038BD0000CF +:1018E0000023F7B50E460546047F072200911946EE +:1018F00000F09AFD731C0093012200230721284663 +:1019000000F092FDC4B9B31C0093052223460821C0 +:10191000284600F089FD0D243746B278BB1B934260 +:1019200011D32B7FE01DC008AC8ABBB9A04294BF85 +:101930000020012003B0F0BDAB8A0824DB00083B87 +:10194000DB08B370E8E7FB1C214600930822002364 +:10195000284600F069FD08340137DEE7001B18BF98 +:101960000120E7E70023F7B50E46047F0822009127 +:101970001946054600F058FD731CC4B908220093AF +:1019800011462346284600F04FFD102401237278AB +:101990005F1C013B934211D32B7FE01DC008AC8A32 +:1019A000BBB9A04294BF0020012003B0F0BDAB8AB8 +:1019B0000824DB00083BDB087370E7E7F3192146D6 +:1019C000009308220023284600F02EFD08343B46F1 +:1019D000DDE7001B18BF0120E7E70000F8B50E4661 +:1019E00005461446002181223046FFF75FFE2B4654 +:1019F00008220021304600F055FE7CB9072208215C +:101A000030466B1C00F04EFE0F2401236A785F1CE9 +:101A1000013B934204D3E01DC008F8BD0824F4E75D +:101A20002146EB190822304600F03CFE08343B46C4 +:101A3000ECE70000F8B50E46054614460021CE221C +:101A40003046FFF733FE2B4628220021304600F0B7 +:101A500029FE7CB908222821304605F1080300F050 +:101A600021FE30242F462A7A7B1B934204D3E01DAB +:101A7000C008F8BD2824F5E7214607F1090308222C +:101A8000304600F00FFE08340137ECE7F7B5047F6D +:101A90000E460091012310220021054600F0C4FCEF +:101AA000C4B9B31C0093092223461021284600F034 +:101AB000BBFC192437467288BB1B9A4211D82B7F76 +:101AC000E01DC008AC8ABBB9A04294BF0020012031 +:101AD00003B0F0BDAB8A1024DB00103BDB08738041 +:101AE000E8E73B1D2146009308220023284600F02A +:101AF0009BFC08340137DEE7001B18BF0120E7E735 +:101B000030B5094D0A4491420DD011F8013B5840BF +:101B1000082340F30004013B2C4013F0FF0384EA48 +:101B20005000F6D1EFE730BD2083B8ED4FF0FF3322 +:101B3000F7B500EB81061946DFF848C0DFF848E04A +:101B4000B0421BD050F8042B01AF0192042217F8C9 +:101B5000014B81EA046108240D46DB184941013C30 +:101B6000002DBCBF83EA0C0381EA0E0114F0FF04D0 +:101B7000F2D1013A12F0FF02E9D1E1E7D843C943BB +:101B800003B0F0BD9336EAA9EBE1F042F7B56B463E +:101B9000354A106851686A4603C3082333493448FC +:101BA00002F0C2F8044690BB0A256B46314A106821 +:101BB00051686A4603C308232F492D4802F0B4F840 +:101BC0000446002847D00369B3F5CE3F43D8B0F8A8 +:101BD0006620B2F57A7F3ED1284A024402F15C01C8 +:101BE0008B4238D35C3B224900209E1AFFF788FFC6 +:101BF00007463246002004F16401FFF781FFA36825 +:101C00009F4228D1E368984208BF002523E003697A +:101C1000B3F5CE3F26D8428BB2F57A7F20D1174A52 +:101C2000024402F110018B4218D3103B10490020EE +:101C30009D1AFFF765FF06462A46002004F11801A9 +:101C4000FFF75EFFA3689E4202D1E368984201D08D +:101C50000D25AAE70025284603B0F0BD1025A4E70E +:101C60000C25A2E70B25A0E7903D0008DC9B0100B6 +:101C700000640008993D0008909B0100089CFFF754 +:101C8000EFF30983EFF30583014B9B6BFEE700BF86 +:101C900000ED00E008B5FFF7F3FF0000EFF3098364 +:101CA000EFF30583014B5B6BFEE700BF00ED00E047 +:101CB000FEE7000001F0E2BC01F0BABC2DE9F04102 +:101CC000456A15B94162BDE8F0814B68AC4623F026 +:101CD0006047C3F38A4616EA230638BF3E464FEAFA +:101CE000D37EC3F380782B465A68BEEBD27F22F0B6 +:101CF00060440AD0002A18DAA40CB44217D19D42DD +:101D00000FD10D60DEE71346EEE7A74207D102F0E0 +:101D10008044C2F3807242450BD054B1EFE708D241 +:101D2000EDE7CCF800100B60CDE7B44201D0B4422F +:101D3000E5D81A689C46002AE5D11960C3E700007F +:101D40002DE9F0474FF47F49089D01F007044FEA61 +:101D5000D508224405F0070500EBD100944201D1DB +:101D6000BDE8F08704F0070705F0070A57453E462F +:101D700038BF5646111BC6F108068E4228BF0E46D4 +:101D8000E108415C08EBD50E13F80EC0B94029FA02 +:101D900006F721FA0AF1FFB28CEA010147FA0AF7C5 +:101DA00039408CEA010C03F80EC034443544D5E7C1 +:101DB000082341F2210280EA012001B240000029FB +:101DC00080B203F1FF33B8BF504013F0FF03F4D1EA +:101DD0007047000038B50C468D18A54200D138BDBB +:101DE00014F8011BFFF7E4FFF7E700000346406823 +:101DF00048B1026899895A605A89013292B2914277 +:101E00005A8138BF9A81704770B504460D4688B034 +:101E1000202200216846FFF749FC20460495FFF781 +:101E2000E5FF024658B16B46054608AE1C4603CC9A +:101E3000B44228606960234605F10805F6D11046D2 +:101E400008B070BD082817D909280CD00A280CD072 +:101E50000B280CD00C280CD00D280CD00E2814BF49 +:101E60004020302070470C2070471020704714200D +:101E7000704718207047202070470000082817D9A5 +:101E80000C280CD910280CD914280CD918280CD9D6 +:101E900020280CD930288CBF0F200E207047092035 +:101EA00070470A2070470B2070470C2070470D20A8 +:101EB000704700002DE9F843078C0446072F1ED910 +:101EC000D0E9029800254FF6FF73C5F12006A5F171 +:101ED000200029FA05F108FA06F628FA00F0314345 +:101EE0000143C9B21846FFF763FF0835402D03468A +:101EF000EBD13A46E169BDE8F843FFF76BBF4FF617 +:101F0000FF70BDE8F883000010B54B6823B9CA8A9A +:101F100063F30902CA8210BD04691A681C60036178 +:101F2000C38A013BC3824A60EFE700002DE9F84F06 +:101F30001D46CB8A0F46C3F3090105298146924607 +:101F40000B4630D00020AAB207F11A049EB2042E2C +:101F50001FFA80F80FD8904503F1010306D3FB8ADE +:101F60000A4462F309030120FB821AE01AF80060B8 +:101F70000130E654EAE79045F1D21C23A1F1050BAC +:101F8000BBFBF3F203FB12BB7C681FFA8BF6002C41 +:101F900045D14846FFF72AFF044638B978606FF00C +:101FA0000200BDE8F88F4FF00008E6E70026066063 +:101FB00078604FF0000BADB2454510D90AEB08032D +:101FC000221D13F8011B08F101089155B1B21B291C +:101FD0001FFA88F82BD0454506F10106F1D8FB8A97 +:101FE000C3F30902154465F30903BCE71C4601323B +:101FF00092B22368002BF9D16B1F0B441C21B3FB59 +:10200000F1F301339BB29A42D3D2BBF1000FD0D18E +:102010004846FFF7EBFE20B9C4F800B0BFE7012245 +:10202000E7E7C0F800B05E4620600446C1E74545DA +:10203000D5D94846FFF7DAFE08B92060AFE7C0F807 +:1020400000B0002620600446B6E700002DE9F74FF7 +:102050001C465B69074688460092002B00F097807B +:10206000238C2BB1E269002A00F09180072B33D832 +:1020700007F10C00FFF7BAFE054628B96FF002051C +:10208000284603B0BDE8F08F14220021FFF70EFBB5 +:10209000228CE16905F10800FFF7F6FA208C48F080 +:1020A0000041013080B2FFF7E9FEFFF7CBFE0138B7 +:1020B00080B22084013028746369228C1B782A4402 +:1020C00003F01F0363F03F0313723846696029462B +:1020D000FFF7F4FD0125D3E74FF000094FF0800A28 +:1020E0004E464D4600F10C0301930198FFF77EFE2A +:1020F00083460028C2D014220021FFF7D7FA002E11 +:102100003BD10222009BABF808300BF1080E1FFAFE +:1021100082FC0CF10100BCF1060F218C80B201D8C9 +:102120008E422CD3FFF7AAFEFFF78CFE8E4208BF2B +:102130004FF0400A62690138127880B202F01F0243 +:1021400042EA49120BEB00014AEA020A013048F068 +:10215000004281F808A08BF8100059463846CBF8A9 +:102160000420FFF7ABFD238C0135B3424FF0000A8A +:102170002DB289F00109B8D182E70022C5E7E169F3 +:10218000895D01360EF80210B6B20132BFE76FF07A +:10219000010575E7F8B5044615460E4630220021C4 +:1021A0001F46FFF783FA069BB5F5001F6360079B88 +:1021B00028BF4FF6FF72A3624FF0000338BF6A09D1 +:1021C000A760E66197B204F110009A4206D8002396 +:1021D0000360A782E3822383E360F8BD06600133D6 +:1021E00030462036F1E7000003781BB94BB2002BD4 +:1021F000C8BF01707047000000787047F8B50C4602 +:10220000C969074611B9238C002B37D1257E1F2DB4 +:1022100034D8387828BB228C072A2CD8268A36F066 +:1022200003032BD14FF6FF70FFF7D4FD4FF6FF727B +:1022300020F001003602400446EA0565400C45EAFC +:102240004025234629463846FFF700FF002807DDD2 +:10225000626913780133DBB21F2B88BF0023137030 +:10226000F8BD218A2D0645EA012505432046FFF7E2 +:1022700021FE0246E5E76FF00300F1E76FF0010091 +:10228000EEE7000070B504461D4616468AB02822C7 +:1022900000216846FFF70AFABDF838306946ADF804 +:1022A00010300F9B204605939DF84030CDE9026524 +:1022B0008DF81830119B0793BDF84830ADF82030E9 +:1022C000FFF79CFF0AB070BD2DE9F041D3690546C8 +:1022D0000C4616460BB9138C5BBB377E1F2F28D8D4 +:1022E00095F80080B8F1000F26D03046FFF7E2FDE8 +:1022F0003378210241EAC33141EA0801338A41EAD5 +:10230000076141EA034102463346284641F0800115 +:10231000FFF79CFE00280ADD3378012B07D1726994 +:1023200013780133DBB21F2B88BF00231370BDE885 +:10233000F0816FF00100FAE76FF00300F7E70000AB +:10234000F0B504460D461E4617468BB028220021E4 +:102350006846FFF7ABF99DF84C3029465A1E5342A8 +:1023600053418DF800309DF840306A46ADF810308A +:10237000119B204605939DF84830CDE902768DF8F3 +:102380001830149B0793BDF85430ADF82030FFF798 +:102390009BFF0BB0F0BD0000406A00B104307047F5 +:1023A000436A1A68426202691A600361C38A013B88 +:1023B000C38270472DE9F041D0F8208014461D46B5 +:1023C00041460027174E09B9BDE8F081D1E9022343 +:1023D000A21A65EB0303964277EB03031ED2036A4E +:1023E0008B420DD1FFF790FD036A1B6803620369FE +:1023F0000B60C38A0161016A013B8846C382E2E740 +:10240000FFF782FD0B68C8F8003003690B60C38AD0 +:102410000161013BC382D8F80010D4E788460968FF +:10242000D1E700BF80841E002DE9F04F8BB00D4630 +:1024300014469B468046DDF85090002800F01A8133 +:10244000B9F1000F00F01681531E3F2B00F21281EC +:10245000012A03D1BBF1000F40F00C810023CDE92C +:102460000833B8F81430B5EBC30F4FEAC30703D3F2 +:1024700000200BB0BDE8F08F2B199F42D8F80C302C +:1024800036BF7F1B2746FFB21BB9D8F81030002B90 +:102490007BD0272D4ED8C5F12806B7424FF0000358 +:1024A00034BF3E46F6B2009329463246D8F80800BB +:1024B00008ABFFF745FCA7EB060A35445FFA8AFA3A +:1024C0002821B8F8143003F10053053BDB000493D6 +:1024D000D8F80C300393039B13B1BAF1000F2CD141 +:1024E000D8F8100040B1BAF1000F05D0524600965E +:1024F00008AB691AFFF724FC38B2002FB8D0660782 +:102500000AD00AAB03EBD40111F8083C624202F096 +:102510000702134101F8083C082C3DD9102C40F269 +:10252000B680202C40F2B880BBF1000F00F09D80F7 +:10253000082335E0BA460026C2E7049BE02B28BFFB +:10254000E02306930B44AB42059315D95A1B9245E1 +:1025500038BF5246039828BFD2B20096691A08AB1A +:1025600004300792FFF7ECFB079A1644AAEB020A25 +:102570001544F6B25FFA8AFA049B069A05999B1AEB +:102580000493039B1B680393A5E700933A462946EF +:10259000D8F8080008ABADE7BBF1000F13D001235A +:1025A000B4EBC30F6CD0082C12D89DF82030621EFB +:1025B00023FA02F2D50706D54FF0FF3202FA04F4EF +:1025C00023438DF820309DF8203089F8003050E703 +:1025D000102C12D8BDF82030621E23FA02F2D10767 +:1025E00006D54FF0FF3202FA04F42343ADF8203051 +:1025F000BDF82030A9F800303BE7202C0FD808990F +:10260000631E21FA03F3DA0705D54FF0FF3202FA11 +:1026100004F40C430894089BC9F8003029E7402CC7 +:102620002BD0DDE90865611EC4F12102A4F121036C +:1026300026FA01F105FA02F225FA03F311431943D0 +:10264000CB0712D50122A4F12003C4F1200102FA24 +:1026500003F322FA01F1A240524243EA010363EB81 +:10266000430332432B43CDE90823DDE90823C9E9BD +:102670000023FEE66FF00100FBE66FF00800F8E6CD +:10268000082CA0D9102CB3D9202CEED8C3E7BBF16D +:10269000000FADD0022383E7BBF1000FBBD00423B2 +:1026A0007EE70000012A30B5144638BF012200251C +:1026B000402A28BF402285B0012CCDE9025517D809 +:1026C0001B788DF8083053070AD004AB03EBD20512 +:1026D00015F8083C544204F00704A34005F8083CF0 +:1026E0000346009102A80021FFF72AFB05B030BD88 +:1026F000082CE5D9102C03D81B88ADF80830E2E788 +:10270000202C02D81B680293DDE7D3E90045CDE910 +:102710000245D8E710B5CB681BB98B600B618B8283 +:1027200010BD04691A681C600361C38A013BC3823F +:10273000CA60F0E703064CBFC0F3C0300220704708 +:1027400008B50246FFF7F6FF022806D15306C2F38A +:102750000F2001D100F0030008BDC2F30740FBE7E2 +:102760002DE9F04F93B0CDE903230A6804461046E3 +:10277000FFF7E0FF02280CBF0026C2F30626002A5E +:102780000D46824680F2F98112F0C04940F0F58191 +:10279000097B002900F0F181022803D02378B3429D +:1027A00040F0EE81C2F304631046069302F07F030B +:1027B0000593FFF7C5FF059B00224FEA83480023DE +:1027C00048EA0A48294448EA4668CE78CDE9082311 +:1027D000F309834648EA0008029367D0059B024646 +:1027E000009320465346676808A9B847002800F0C0 +:1027F000CA81276A4FB9414604F10C00FFF704FB78 +:10280000074690B96FF0020054E03B6998450DD03F +:102810003F68002FF9D1414604F10C00FFF7F4FAAC +:1028200007460028EED0236A3B60276297F817C05E +:1028300006F01F08CCF3840CACEB08001FFA80FEF6 +:102840000028B8BF0EF12000A8EB0C031FFA83FE8E +:10285000B8BF00B2002B0793BEBF0EF120031BB21E +:102860000793D7E9022152EA010338D04FF0000C58 +:10287000039BDFF8F8E19A1A049B63EB010196458C +:102880007CEB01032BD36B7B97F81AE0734519D1CE +:10289000029B002B78D0012821DC7868F8B9DFF89A +:1028A000D0C1944570EB010316D337E0276A27B9EE +:1028B0006FF00C0013B0BDE8F08F3B699845B5D0C0 +:1028C0003F68F4E76A4890427CEB010301D30020A3 +:1028D000F0E7029B002BFAD0079B0F2B17DCFA7D49 +:1028E000B30002F0030203F07C031343FB75394687 +:1028F0002046FFF709FB6B7BBB76029B3BB9FB7D58 +:10290000C3F38402013262F38603FB75D0E76A7B6E +:10291000BB7E9A42DBD1029B002B35D0B309022B40 +:1029200032D0039B1422BB60049B0021FB600DA8E6 +:10293000FEF7BCFE039B20460A93049BADF83EB015 +:102940000B932B1D0C932B7B8DF840A0013BDBB22E +:10295000ADF83C30069B8DF841808DF84230059BE8 +:102960000AA98DF8433094F82C3083F001038DF8D8 +:102970004430A3689847FB7DC3F38403013303F01D +:102980001F039B02FB82A2E7FB7DC6F34012B2EB62 +:10299000D31F40F0FB80C3F38403434540F0F9802C +:1029A000029A2B7BB609002A4DD0F20762D4032B82 +:1029B00040F2F280039BAE1DBB60049B3246FB607D +:1029C0002B7B3946033BDBB204F10C00FFF7AEFA78 +:1029D00000280CDA39462046FFF796FAFB7DC3F350 +:1029E0008403013303F01F039B02FB820AE7AB88D9 +:1029F000DDE908843B834FF6FF73C9F12000A9F19C +:102A0000200228FA09F104FA00F0014324FA02F244 +:102A100011431846C9B2FFF7CBF909F10809B9F11A +:102A2000400F0346E9D13146B8822A7B033AD2B23D +:102A3000FFF7D0F9FB7DB882DA43C2F3C01262F32C +:102A4000C713FB7543E7AEB92E1D013B324639462D +:102A5000DBB204F10C00FFF769FA0028BADB2A7B2D +:102A60003146013AB88AD2B2E2E700BF80841E0044 +:102A700040420F00F98A013BC1F309010429DAB28F +:102A80005DD80023281D07F11B069A4208D910F8CB +:102A900001CB013306F801C001310529DBB2F4D1C5 +:102AA000934228BF0023039938BF04330A91049945 +:102AB00038BFDBB20B9107F11B010C91796838BF6D +:102AC0005B190D910E93FB8AADF83EB0C3F3090379 +:102AD0001A44069BADF83C208DF84230059B8DF8DA +:102AE00040A08DF8433094F82C308DF8418083F06D +:102AF00001038DF8443000237B602A7BB88A013AB9 +:102B0000291DFFF767F93B8BB882834203D120462A +:102B1000A3680AA9984720460AA9FFF7FBFDFB7D99 +:102B2000BA8AC3F38403013303F01F039B02FB82C1 +:102B30003B8B9A420CBF00206FF01000BAE67B6816 +:102B4000002BADD0052001E033461C301E68002E5E +:102B5000FAD1091A081D2E1D184401EB090CBCF10D +:102B60001B0F5FFA89F39BD89A4299D916F8013B5B +:102B700009F1010900F8013BEFE76FF0090099E660 +:102B80006FF00A0096E66FF00B0093E66FF00D0011 +:102B900090E66FF00E008DE66FF00F008AE600BF42 +:102BA000F0B53F4D3F4FEB6943F00073EB61EB69CC +:102BB0003D4B9B6AD3F800623E4046F00106C3F8E5 +:102BC0000062D3F800423C4044EA002444F001048F +:102BD000C3F80042002955D000200646C3F81C0265 +:102BE000C3F80402C3F80C02C3F8140203EBC004D8 +:102BF00001300E28C4F84062C4F84462F6D10027C0 +:102C00004FF0010C9678148816F0010F18BFD3F816 +:102C100004E20CFA04F01CBF40EA0E0EC3F804E212 +:102C200016F0020F18BFD3F80CE203EBC4041CBF6C +:102C300040EA0E0EC3F80CE2760748BFD3F81462E0 +:102C400007F1010744BF0643C3F814625668B9424E +:102C5000C4F84062966802F10C02C4F84462D3F8EA +:102C60001C4240EA0400C3F81C02CBD1D3F8002276 +:102C700022F00102C3F80022EB6923F00073EB613C +:102C8000EB69F0BD0122C3F84012C3F84412C3F847 +:102C90000412C3F81412C3F80C22C3F81C22E5E78F +:102CA000001002400000FFFFA8230020184A08B5CA +:102CB000916A8B688B6013F0010104D013F00C0F44 +:102CC00018BF4FF48031D80506D513F4406F14BFF8 +:102CD00041F4003141F00201D80306D513F4402F2E +:102CE00014BF41F4802141F00401D3690BB10848BD +:102CF0009847302383F311880021064800F048FBF1 +:102D0000002383F31188BDE8084000F099BD00BF9F +:102D1000A8230020B023002038B5124CA36ADD6838 +:102D2000AA0712D05A6922F002025A61A36913B1AC +:102D3000012120469847302383F3118800210A4857 +:102D400000F026FB002383F31188EB0606D5102143 +:102D5000A36AD960236A0BB102489847BDE838409E +:102D600000F06EBDA8230020B823002038B5124C17 +:102D7000A36A1D69AA0712D05A6922F010025A618B +:102D8000A36913B1022120469847302383F31188A9 +:102D900000210A4800F0FCFA002383F31188EB06B7 +:102DA00006D51021A36A1961236A0BB1024898471E +:102DB000BDE8384000F044BDA8230020B82300201F +:102DC00038B50F4CA36A5D682A075D600AD50422F6 +:102DD00022701A6822F002021A60636A13B100219D +:102DE000204698476B0706D5A36A9969236A13B1F1 +:102DF000034809049847BDE8384000F021BD00BFF2 +:102E0000A823002010B50E4C204600F02FF90D4BE2 +:102E10000B211320A36200F009F90B21142000F00C +:102E200005F90B21152000F001F90B21162000F007 +:102E3000FDF8BDE8104000220E201146FFF7B0BE9D +:102E4000A8230020006400400F4B10B598420446B0 +:102E500005D10E4BDA6942F00072DA61DB690122BA +:102E6000A36A1A60A36A5A68D20707D562685168D4 +:102E70001268D9611A60064A5A6110BD0121082002 +:102E800000F0B0F9EEE700BFA823002000100240D8 +:102E90005B87010003291AD8DFE801F0020A0F144A +:102EA000836A9B6813F0E05F14BF01200020704725 +:102EB000836A9868C0F380607047836A9868C0F33B +:102EC000C0607047836A9868C0F300707047002044 +:102ED0007047000010B5032927D8DFE801F002276A +:102EE0002B2F836A9968C1F30161183103EB011339 +:102EF0001078840648BF5468C0F3001158BF948806 +:102F00004FEA410148BF41EAC40100F00F00586098 +:102F100048BF41F00401906858BF41EA4451D2686B +:102F200041F001019860DA60196010BD836A03F511 +:102F3000C073DDE7836A03F5C873D9E7836A03F5D5 +:102F4000D073D5E701290AD002290FD081B9836A4D +:102F5000DA68920701D1186903E001207047836A9B +:102F6000D86810F0030018BF01207047836AF2E7A9 +:102F70000020704710B539B9836AD96889071BD119 +:102F80001B699C0704D110BD012915D00229FAD173 +:102F9000816AD1F8C031D1F8C441D1F8C8011061BB +:102FA000D1F8CC015061202008610869800717D151 +:102FB000486940F0100012E0816AD1F8B031D1F8D0 +:102FC000B441D1F8B8011061D1F8BC0150612020A2 +:102FD000C860C868800703D1486940F002004861B2 +:102FE000C3F34000C3F38001000140EA41111079AE +:102FF00020F030000143117189064BBF916811899F +:10300000DB085B0D4CBF63F31C0163F30A0113790A +:1030100048BF916064F3030313714FEA14234FEA2E +:10302000144458BF118113705480ACE70122090188 +:1030300000F1604303F56143C9B283F8001300F067 +:103040001F039A4043099B0003F1604303F561436A +:10305000C3F880211A607047090100F16040C9B2CD +:1030600000F56D4001767047FFF7CCBE0123037079 +:10307000002300F10802C0E9022200F11002C0E9B9 +:103080000422C0E90633C0E90833436070470000FA +:1030900010B53023044683F3118802234160037086 +:1030A000FFF7D2FE04230020237080F3118810BDA7 +:1030B0002DE9F0411F4604460D461646302383F3A2 +:1030C000118800F108082378052B0DD029462046E9 +:1030D000FFF7E0FE40B1204632462946FFF7FAFEF0 +:1030E000002080F3118808E03946404600F040F99E +:1030F0000028E8D0002383F31188BDE8F0810000A8 +:103100002DE9F0411F4604460D461646302383F351 +:10311000118800F110082378052B0DD02946204690 +:10312000FFF710FF40B1204632462946FFF722FF45 +:10313000002080F3118808E03946404600F018F975 +:103140000028E8D0002383F31188BDE8F081000057 +:1031500000238268037503691B6899689142FBD25A +:103160005A680360426010605860704700238268AC +:10317000037503691B6899689142FBD85A6803601C +:10318000426010605860704708B50846302383F3EA +:1031900011880B7D032B05D0042B0DD02BB983F3A5 +:1031A000118808BD00228B691A604FF0FF338361DC +:1031B000FFF7CEFF0023F2E7D1E9003213605A6037 +:1031C000F3E70000FFF7C4BF054BD968087518681E +:1031D000026853601A6001220275D860FDF796BB41 +:1031E000D823002030B50C4B0446DD684B1C87B05B +:1031F0000FD02B466846094A00F0F0F82046FFF74A +:10320000E3FF009B13B1684600F0F0F8A86907B02F +:1032100030BDFFF7D9FFF9E7D82300208931000836 +:10322000044B1A68DB6890689B68984294BF002042 +:1032300001207047D8230020084B10B51C68D868BF +:10324000226853601A6001222275DC60FFF78EFF4E +:1032500001462046BDE81040FDF758BBD8230020AA +:10326000044B1A68DB6892689B689A4201D9FFF7A1 +:10327000E3BF7047D823002038B501230025064C52 +:10328000064907482370656000F020FB0223237085 +:1032900085F3118838BD00BF30250020A83D000807 +:1032A000D823002000F0B4B8EFF3118020B9EFF379 +:1032B0000583302282F311887047000010B530B9C1 +:1032C000EFF30584C4F3080414B180F3118810BD32 +:1032D000FFF7C6FF84F31188F9E700008B60022333 +:1032E00008618B82084670478368A3F1440243F863 +:1032F000142C026943F8442C426943F8402C094AD3 +:1033000043F8242CC268A3F1200043F8182C0222B1 +:1033100003F80C2C002203F80B2C034A43F8102C62 +:10332000704700BF1D090008D823002008B5FFF72B +:10333000DBFFBDE80840FFF745BF0000024BDB683C +:1033400098610F20FFF740BFD8230020302383F37C +:103350001188FFF7F3BF000008B50146302383F35F +:1033600011880820FFF73EFF002383F3118808BD72 +:10337000064BDB6839B1426818605A6013604360DD +:103380000420FFF72FBF4FF0FF307047D8230020F5 +:1033900038B504460D462068844200D138BD036824 +:1033A00023605C608561FFF70DFFF4E710B50A4C00 +:1033B00023699A6891420CD85A6881600360426020 +:1033C00010609A685860511A99604FF0FF33A361FA +:1033D00010BD1B68891AECE7D8230020C0E903233D +:1033E000002310B410BC4361FFF7E0BF036881689D +:1033F0009A680A449A60426813605A6000234FF04A +:10340000FF320360014B9A61704700BFD823002050 +:1034100070B5124D2A46EB690133EB6152F8103F4B +:10342000934206D030269A68013A9A602C69A368C4 +:1034300003B170BDD4E900210A605160236083F3B9 +:1034400011882046D4E90331984786F311886169D1 +:103450000029EBD02046FFF7A9FFE7E7D82300209B +:1034600000207047FEE70000704700004FF0FF307B +:1034700070470000BFF34F8F024AD368DB07FCD4CC +:10348000704700BF0020024008B5074B1B7853B9B6 +:10349000FFF7F0FF054B1A69120641BF044A5A6054 +:1034A00002F188325A6008BD482500200020024001 +:1034B0002301674508B5054B1B7833B9FFF7DAFFE1 +:1034C000034A136943F08003136108BD48250020B7 +:1034D000002002407F289ABF00F5003080020020C3 +:1034E000704700004FF480607047000080207047F4 +:1034F0007F2808B50BD8FFF7EDFF00F58063026861 +:10350000013204D104308342F9D1012008BD0020EA +:10351000FCE700007F2810B504461CD8FFF7AAFF7F +:10352000FFF7B2FFF3220D4B4FF48061DA60022205 +:103530001A61FFF7CFFF58611A6942F040021A6121 +:10354000FFF798FF00F004F9FFF7B4FF2046BDE84D +:103550001040FFF7CDBF002010BD00BF002002408B +:103560002DE9F843054612F00100144606D040F25A +:10357000F32200201E4B1A60BDE8F8831D4BAA18E9 +:103580009A4204D94FF43E72194B1A60F4E7FFF7E0 +:103590007BFF4FF00109FFF76DFFDFF85C806D1ACC +:1035A000012C0F4605EB010603D8FFF783FF01202E +:1035B000E2E73B88C8F8109033800020FFF75AFFFD +:1035C000C8F81000338831F8022B9BB29A420CD015 +:1035D00040F20F32064B1A60084B1E60084B1C600D +:1035E000084B1F60FFF766FFC6E7023CD8E700BF45 +:1035F0004425002000000208002002403825002059 +:10360000402500203C250020084908B50B7828B14A +:103610001BB9FFF739FF01230B7008BD002BFCD04D +:10362000BDE808400870FFF745BF00BF48250020EF +:1036300070B5FFF739FE4FF47A710D4B0D4EDB6913 +:10364000326801FB03F3934237BF0B4A0A495168C2 +:10365000156836BF4C1CD1E9005454605D1944F123 +:1036600000043360FFF72AFE2846214670BD00BFE4 +:10367000D82300204C2500205025002070B5FFF7EE +:1036800013FE4FF47A710F4B0F4EDB69326801FB6A +:1036900003F3934237BF0D4A0C49516815683ABF8E +:1036A0004C1C5460D1E900545D1944F100043360AE +:1036B000FFF704FE4FF47A72002328462146FCF7F8 +:1036C00031FF70BDD82300204C250020502500205C +:1036D00010B5094C013AD2B2FF2A00D110BD5008F2 +:1036E00054F82030013054F820009BB243EA0043E4 +:1036F00041F8043BEEE700BF046C004010B50748FA +:10370000013AD2B2FF2A00D110BD0C88530840F80C +:1037100023404C88013340F82340F1E7046C00401B +:1037200007B50122002001A9FFF7D2FF019803B0DD +:103730005DF804FB13B50446FFF7F2FFA04205D085 +:103740000122002001A90194FFF7D8FF02B010BDAB +:103750007047000045F25552064B1A6002225A602B +:1037600040F6FF729A604CF6CC421A600122024B7E +:103770001A707047003000405C250020034B1B7816 +:103780001BB14AF6AA22024B1A6070475C25002042 +:1037900000300040044B1A682AB902F1804202F559 +:1037A0000432526A1A607047582500204FF0807228 +:1037B000014B5A62704700BF0010024008B5FFF786 +:1037C000E9FF024B1868C0F3407008BD582500207F +:1037D00008B5FFF7DFFF024B1868C0F3007008BDA3 +:1037E00058250020EFF30983203383F30988002351 +:1037F00083F3118870470000302080F3118862B68F +:103800000C4B0D4AD96821F4E0610904090C0A4304 +:10381000DA60D3F8FC20094942F08072C3F8FC203A +:103820000A6842F001020A602022DA7783F8220057 +:10383000704700BF00ED00E00003FA05001000E053 +:10384000302310B583F311880B4B5B6813F40063CE +:103850000FD0EFF309844FF08073203CE36184F3D1 +:103860000988FFF7DDFC10B1044BA36110BD044BC8 +:10387000FBE783F31188F9E700ED00E02F0900086A +:103880003209000870470000FEE700000A4B0B48B1 +:103890000B4A90420BD30B4BC11EDA1C121A22F0BA +:1038A00003028B4238BF00220021FDF7FFBE53F810 +:1038B000041B40F8041BECE72C3E0008E025002028 +:1038C000E0250020E0250020FEE7000070B500257F +:1038D00004461A4B86B05860856201630E46FFF7B6 +:1038E0008BFF04F11003C4E904334FF0FF33A361ED +:1038F000134BE561D9692B460A462046C4E90823E3 +:1039000004F134018023C4E900440E4AA560E56255 +:103910002565FFF7E3FC01230B4AE0600375009285 +:10392000726868460192B268CDE90223074BCDE97F +:103930000435FFF7FBFC06B070BD00BF302500204A +:10394000D8230020B43D0008B93D0008C93800085C +:1039500000F030B808B500F063F9FFF78DFCBDE862 +:103960000840FFF717BF0000704700004FF0FF311D +:103970000E4B1A6919611A6900221A611869D86810 +:10398000D960D968DA60DA68DA6942F08052DA61BF +:10399000DA69DA6942F00062DA61054ADB691368C4 +:1039A00043F48073136000F01BB900BF00100240A5 +:1039B00000700040194B1A6842F001021A601A6840 +:1039C0009007FCD51A6802F0F9021A6000225A60CA +:1039D0005A6812F00C0FFBD11A6842F480321A6058 +:1039E0001A689103FCD55A6842F4E8125A601A68C2 +:1039F00042F080721A601A689201FCD51221084ABE +:103A00005A60084A11605A6842F002025A605A68C5 +:103A100002F00C02082AFAD1704700BF00100240E1 +:103A200000641D0000200240084A08B5516913686F +:103A30000B4003F00103536123B1054A13680BB136 +:103A400050689847BDE80840FFF7FABE00040140FF +:103A500060250020084A08B5516913680B4003F03F +:103A60000203536123B1054A93680BB1D0689847AC +:103A7000BDE80840FFF7E4BE0004014060250020D7 +:103A8000084A08B5516913680B4003F004035361F9 +:103A900023B1054A13690BB150699847BDE8084046 +:103AA000FFF7CEBE0004014060250020084A08B59B +:103AB000516913680B4003F00803536123B1054AB1 +:103AC00093690BB1D0699847BDE80840FFF7B8BECD +:103AD0000004014060250020084A08B551691368B8 +:103AE0000B4003F01003536123B1054A136A0BB175 +:103AF000506A9847BDE80840FFF7A2BE00040140A5 +:103B000060250020174B10B55A691C68144004F456 +:103B100078725A61A30604D5134A936A0BB1D06A2E +:103B20009847600604D5104A136B0BB1506B984749 +:103B3000210604D50C4A936B0BB1D06B9847E20574 +:103B400004D5094A136C0BB1506C9847A30504D5F2 +:103B5000054A936C0BB1D06C9847BDE81040FFF755 +:103B60006FBE00BF00040140602500201A4B10B555 +:103B70005A691C68144004F47C425A61620504D5F9 +:103B8000164A136D0BB1506D9847230504D5134A9F +:103B9000936D0BB1D06D9847E00404D50F4A136EB6 +:103BA0000BB1506E9847A10404D50C4A936E0BB12B +:103BB000D06E9847620404D5084A136F0BB1506F5A +:103BC0009847230404D5054A936F0BB1D06F9847EB +:103BD000BDE81040FFF734BE00040140602500201E +:103BE000062108B50846FFF721FA06210720FFF74E +:103BF0001DFA06210820FFF719FA06210920FFF710 +:103C000015FA06210A20FFF711FA06211720FFF7FF +:103C10000DFABDE8084006212820FFF707BA00008A +:103C200008B5FFF7A3FE054800F00CF8FFF71CFAF3 +:103C3000FFF79AFEBDE8084000F002B8C03D00085A +:103C400000F042B8002319461C4A0133102BC2E988 +:103C5000001102F10802F8D1194B9A6942F07D0275 +:103C60009A619B690268174BDA6082685A60426801 +:103C70001A60C26803F58063DA6042695A600269BB +:103C80001A608269C3F80C24026AC3F80424C2696A +:103C9000C3F80024426AC3F80C28C26AC3F8042897 +:103CA000826AC3F80028026BC3F80C2C826BC3F83D +:103CB000042C426BC3F8002C704700BF6025002025 +:103CC00000100240000801404FF0E023044A0821A0 +:103CD0005A6100229A6107220B201A61FFF7BCB9D2 +:103CE0003F19010008B5302383F31188FFF7DAFA92 +:103CF000002383F3118808BD08B5FFF7F3FFBDE883 +:103D00000840FFF79DBD000010B501390244904204 +:103D100001D1002005E0037811F8014FA34201D042 +:103D2000181B10BD0130F2E72DE9F0419BB10446AC +:103D3000C91A1778014403F1FF3C8C42204601D98F +:103D4000002008E005780134BD42F6D10CEB0405F3 +:103D5000D618A54201D1BDE8F08115F8018D16F8FD +:103D600001EDF045F5D0E8E7034611F8012B03F823 +:103D7000012B002AF9D170476F72672E617264754A +:103D800070696C6F742E663130332D41445342009C +:103D900040A2E4F1646891060041A3E5F2656992EE +:103DA0000700000063300000A43D0008302400201C +:103DB000302500206D61696E0069646C650000004B +:103DC00000180000444441444454494401000000A8 +:103DD00042444444444444440000000044444444B5 +:103DE00044444444000000004444444444444444A3 +:103DF00000000000444444444444444458C7FF7F06 +:103E00000100000000000000E803000000000000C6 +:103E1000009C0100000000006400000000000000A1 +:0C3E200040420F00FE2A0100D204000006 :00000001FF diff --git a/Tools/bootloaders/f103-Airspeed_bl.bin b/Tools/bootloaders/f103-Airspeed_bl.bin index e4a956a818d214..9e902bbc231556 100755 Binary files a/Tools/bootloaders/f103-Airspeed_bl.bin and b/Tools/bootloaders/f103-Airspeed_bl.bin differ diff --git a/Tools/bootloaders/f103-Airspeed_bl.elf b/Tools/bootloaders/f103-Airspeed_bl.elf index 1c6a11b66ece2b..2756e4071d7194 100755 Binary files a/Tools/bootloaders/f103-Airspeed_bl.elf and b/Tools/bootloaders/f103-Airspeed_bl.elf differ diff --git a/Tools/bootloaders/f103-Airspeed_bl.hex b/Tools/bootloaders/f103-Airspeed_bl.hex index 3396e12d545f3d..11db8402437a6e 100644 --- a/Tools/bootloaders/f103-Airspeed_bl.hex +++ b/Tools/bootloaders/f103-Airspeed_bl.hex @@ -1,963 +1,997 @@ :020000040800F2 -:100000000009002069040008C114000865140008F4 -:10001000A514000865140008851400086B04000886 -:100020006B0400086B0400086B0400087D350008B1 -:100030006B0400086B0400086B040008113A000808 -:100040006B0400086B0400086B0400086B040008D4 -:100050006B0400086B0400083D370008693700088E -:1000600095370008C1370008ED3700086B04000819 -:100070006B0400086B0400086B0400086B040008A4 -:100080006B0400086B0400086B040008712400086E -:10009000DD240008312500088525000819380008EE -:1000A0006B0400086B0400086B0400086B04000874 -:1000B0006B0400086B0400086B0400086B04000864 -:1000C0006B0400086B0400086B0400086B04000854 -:1000D0006B04000825290008392900086B04000872 -:1000E000813800086B0400086B0400086B040008EA -:1000F0006B0400086B0400086B0400086B04000824 -:100100006B0400086B0400086B0400086B04000813 -:100110006B0400086B0400086B0400086B04000803 -:100120006B0400086B0400086B0400086B040008F3 -:100130006B0400086B0400086B0400086B040008E3 -:100140006B0400086B0400086B0400086B040008D3 -:100150006B0400086B0400086B0400086B040008C3 -:1001600053B94AB9002908BF00281CBF4FF0FF311E -:100170004FF0FF3000F076B9ADF1080C6DE904CE18 -:1001800000F006F8DDF804E0DDE9022304B0704772 -:100190002DE9F047089E0D4604468846002B4DD1B8 -:1001A0008A42944668D9B2FA82F252B101FA02F355 -:1001B000C2F1200120FA01F10CFA02FC41EA030825 -:1001C00094404FEA1C41B8FBF1F71FFA8CFE01FB8B -:1001D000178807FB0EF0230C43EA084398420AD91C -:1001E0001CEB030307F1FF3580F01E81984240F2BB -:1001F0001B81023F63441B1AB3FBF1F001FB103378 -:1002000000FB0EFEA4B244EA0344A6450AD91CEB47 -:10021000040400F1FF3380F00981A64540F2068115 -:10022000644402380021A4EB0E0440EA07401EB1EA -:100230000023D440C6E90043BDE8F0878B4208D9CB -:10024000002E00F0EE800021C6E900050846BDE85A -:10025000F087B3FA83F100294AD1AB4202D382423C -:1002600000F2FC80841A65EB030301209846002EFF -:10027000E2D0C6E90048DFE702B9FFDEB2FA82F257 -:10028000002A40F09180A1EB0C0001214FEA1C47AD -:100290001FFA8CFEB0FBF7F307FB1300250C45EAB1 -:1002A00000450EFB03F0A84208D91CEB050503F13D -:1002B000FF3802D2A84200F2CE8043462D1AB5FB89 -:1002C000F7F007FB10550EFB00FEA4B244EA05440C -:1002D000A64508D91CEB040400F1FF3502D2A6455F -:1002E00000F2B6802846A4EB0E0440EA03409EE7E5 -:1002F000C1F120078B4022FA07FC4CEA030C25FAD7 -:1003000007FA4FEA1C49BAFBF9F820FA07F309FB90 -:1003100018AA8D401FFA8CFE1D4300FA01F308FB5A -:100320000EF02C0C44EA0A44A04202FA01F20BD966 -:100330001CEB040408F1FF3A80F08880A04240F2F0 -:100340008580A8F102086444241AB4FBF9F009FB83 -:10035000104400FB0EFEADB245EA0444A64508D9A0 -:100360001CEB040400F1FF356CD2A6456AD90238B3 -:10037000644440EA0840A0FB0295A4EB0E04AC42A2 -:10038000C846AE4656D353D0002E69D0B3EB080210 -:1003900064EB0E0422FA01F304FA07F71F43CC4082 -:1003A000C6E90074002147E70CFA02FCC2F1200103 -:1003B00025FA01F34FEA1C4720FA01F195400D435D -:1003C000B3FBF7F107FB11331FFA8CFE280C40EA50 -:1003D000034001FB0EF3834204FA02F408D91CEB3C -:1003E000000001F1FF382FD283422DD90239604439 -:1003F000C01AB0FBF7F307FB1300ADB245EA0045A6 -:1004000003FB0EF0A84208D91CEB050503F1FF38E9 -:1004100016D2A84214D9023B6544281A43EA014186 -:1004200038E73146304607E72F46E4E61846F9E656 -:100430004B45A9D2B9EB020865EB0C0E0138A3E7D6 -:100440004346EAE7284694E74146D1E7D0467BE7B2 -:100450006444023847E7023B65442FE7084606E755 -:100460003146E9E6704700BF02E000F000F8FEE721 -:1004700072B6284880F30888274880F309882748FF -:100480004EF60851CEF200010860022080F3148875 -:10049000BFF36F8F03F0E4F803F0C0F803F0E2F865 -:1004A0004FF055301E491B4A91423CBF41F8040BA6 -:1004B000FAE71C49184A91423CBF41F8040BFAE79D -:1004C00019491A4A1A4B9A423EBF51F8040B42F896 -:1004D000040BF8E700201749174A91423CBF41F846 -:1004E000040BFAE703F09EF803F0BEF8134C144D2A -:1004F000AC4203DA54F8041B8847F9E700F03CF8F3 -:10050000104C114DAC4203DA54F8041B8847F9E74C -:1005100003F086B800090020001100200000000848 -:100520000001002000090020E03B0008001100202D -:100530002411002028110020A025002060010008BF -:100540006001000860010008600100082DE9F04F1B -:10055000C1F80CD0C3689D46BDE8F08F002383F33B -:1005600011882846A047002002F09CFDFEE702F01B -:1005700021FD00DFFEE700002DE9F04102F09CFFC5 -:10058000074602F0E7FF054600283ED12B4B9F426D -:100590003BD001339F423BD0294B27F0FF029A42C8 -:1005A0003AD1F8B200F052FAA84642F2107400F0C4 -:1005B00057FC08B10024A04600F04EFA064678B376 -:1005C00084BB464635B11F4B9F4203D0002402F046 -:1005D000B9FF2646002002F079FF1B4B9B6813F001 -:1005E000400322D00EB100F031F800F097FC00F08B -:1005F00077FE00F067FF0546CCB100F063FF401BBB -:10060000A04214D900F022F8F3E7A8460024CEE770 -:1006100004464FF00108CAE780464FF47A74C6E7F3 -:100620000446CFE74FF47A74CCE71C46DDE700F0D0 -:1006300025FD012002F03CFDDEE700BF010007B010 -:10064000000008B0263A09B0000C014038B51D4A38 -:100650001D4B1968013134D004339342F9D11B4C3E -:10066000194DD4F80424AA422BD3194B9B6803F1EB -:10067000006303F5C8439A4223D202F037FF02F029 -:1006800049FF002000F046FE0220124B187000F0D7 -:100690007DFE114BDA690022DA61D96999699A61A4 -:1006A0009B6972B64FF0E023C3F8085DD4F80034BC -:1006B000D4F80424202181F311889D4683F308880F -:1006C000104738BD2064000800640008006000087E -:1006D00000110020281100200010024049F269009A -:1006E000084A136899B21B0C00FB013344F25061B5 -:1006F0001360054B186882B2000C01FB0200186001 -:1007000080B27047201100201C11002010B5044653 -:100710000021102200F056FE034B03CB20606160E5 -:100720001868A06010BD00BFE8F7FF1F2DE9F04377 -:10073000BBB000F0C7FE40F2ED22204DAB68C31AFB -:10074000934232D906AF2B4628220021A8603846B2 -:1007500001F0C2FB05F10E0000F02CFE002604465D -:100760005FFA80F905F10E08F3B2F100994501F145 -:10077000280107D908EB06030822384601F0ACFB34 -:100780000136F1E708230122CDE902320C4B053492 -:1007900001933023A4B20093CDE9047405A3D3E9F7 -:1007A0000023297B074801F0ADF93BB0BDE8F08399 -:1007B000AFF3008078F6339F93CACD8D702100206F -:1007C0007D2100204421002070B50D4614461E46B0 -:1007D00001F02EF950B9022E10D1012C0ED112A326 -:1007E000D3E900230120C5E9002307E0282C10D01D -:1007F00005D8012C09D0052C0FD0002070BD302C5D -:10080000FBD10BA3D3E90023ECE70BA3D3E900232F -:10081000E8E70BA3D3E90023E4E70BA3D3E9002324 -:10082000E0E700BFAFF30080401DA12026812A0B26 -:1008300078F6339F93CACD8D9E6AC421818A46EE95 -:1008400026417272DF25D7B7F017304A39059E5618 -:1008500038B50D460446034620222846002101F003 -:100860003BFB22792346032A28BF0322284603F8AC -:10087000042F2021022201F02FFB62792346072A50 -:1008800028BF0722284603F8052F2221032201F062 -:1008900023FBA2792346072A28BF0722284603F80C -:1008A000062F2521032201F017FB284610222821BC -:1008B00004F1080301F010FB382038BD2DE9F04F9A -:1008C0000024ADF5017D0EAE40F2751280460F4654 -:1008D00022A82146219400F075FD21464822304689 -:1008E00000F070FD00F0EEFD4FF47A72B0FBF2F014 -:1008F000544B21AD186093E80700012386E80700F8 -:100900000DF15A003382FFF701FF4EF603033384E3 -:1009100007AB18464C4903F0B3F81B222946306454 -:10092000304686F83C20FFF793FF08220446014634 -:1009300012AB284601F0D0FA08222846A1180DF182 -:10094000490301F0C9FA082228460DF14A0304F1CF -:10095000100101F0C1FA2022284613AB04F118015E -:1009600001F0BAFA4022284614AB04F1380101F034 -:10097000B3FA0822284616AB04F1780101F0ACFA6C -:10098000082228460DF1590304F1800101F0A4FA70 -:1009900004F1880A0DF15A0904F5847B4B4651464F -:1009A000082228460AF1080A01F096FAD34509F10F -:1009B0000109F3D10822594628461BAB01F08CFAF5 -:1009C0004FF0000904F5887496F834304B450AD985 -:1009D000B36B21464B440822284601F07DFA0834C7 -:1009E00009F10109F0E74FF0000996F83C3004EBFB -:1009F000C9014B4508D9336C08224B44284601F005 -:100A00006BFA09F10109F0E700230393BB7E07317C -:100A1000029307F1190301930123C1F3CF01CDE93B -:100A200004510093404605A3D3E90023F97E01F069 -:100A300069F80DF5017DBDE8F08F00BF9E6AC42105 -:100A4000818A46EE2C110020903A0008014B187064 -:100A5000704700BF38110020F0B5334B85B01C7BC8 -:100A600034B10E22314B1A810024204605B0F0BD6E -:100A70002F4A02AB1068516803C308232D492E4842 -:100A80000DEB030202F0DCFF054630B90A22274BCA -:100A90002A481A8100F0E2FCE6E70169B1F5CE3F91 -:100AA00006D90B22214B26481A8100F0D7FCDCE73F -:100AB000438BB3F57A7F09D00C211C4A2148118160 -:100AC0004FF47A72194600F0C9FCCEE71E4A024480 -:100AD00002F11003994204D21022144B1B481A81D0 -:100AE000E3E710398E1A2046134900F0EFFC074661 -:100AF0003246204605F1180100F0E8FCAB689F4241 -:100B000002D1EB6898420AD00D22084B1A8100905E -:100B10003B46D5E902120E4800F0A0FCA4E70D48C0 -:100B200000F09CFC0124A0E7702100202C11002083 -:100B30003D3B0008DC9B010000640008AC3A000863 -:100B4000B83A0008CA3A0008089CFFF7E83A0008DB -:100B5000053B00082E3B00082DE9F04FADB006AF75 -:100B600080460C4600F064FF0546002859D1237EDC -:100B7000022B1AD1E38A012B17D100F0A3FC064601 -:100B8000FFF7ACFD4FF4C873B0FBF3F202FB1300A8 -:100B9000DFF8B49206F5167680B2E37E0644C9F813 -:100BA000006033B90022A94B1A709C37BD46BDE8DE -:100BB000F08FA38AEEB2013BB34205F101050BD9D8 -:100BC0003B1D1E44E900002308222046009601F048 -:100BD000F80101F043F8ECE707F11400FFF796FD88 -:100BE000324607F11401381D02F01AFF03460028AF -:100BF000D8D10F2E08D8954B1E70D9F80030A3F528 -:100C00001673C9F80030D0E7FA1CF870014600925C -:100C10002046072201F022F84046F97800F000FF54 -:100C2000C3E7E38A282B26D010D8012B1ED0052B32 -:100C3000BBD1BFF34F8F8649864BCA6802F4E0628E -:100C40001343CB60BFF34F8F00BFFDE7302BACD118 -:100C5000637E814D01336A7BDBB29342E94603D167 -:100C6000E27E2B7B9A4265D0CD469EE721464046E8 -:100C7000FFF724FE99E7A38A013B9BB2C92B94D8C6 -:100C8000754D2E7B26BB05F10C03009308223346DD -:100C90003146204600F0E2FF731CF2B2D9001E4636 -:100CA000A38A013B9A4205DA0E322A4400920023BD -:100CB0000822EEE700230022C5E900230023AB60F1 -:100CC00085F8D730C5F8D8302B7B0BB9E37E2B7372 -:100CD000002507F114060822294630463B1DC7E9C6 -:100CE0000155FD6001F0F8F83B7A05F10109AB42CE -:100CF0004FEAC90107D9FB6808222B44304601F0AE -:100D0000EBF84D46F0E70023C1F3CF01E07ECDE9DB -:100D100004610393A37E19340293282301460093B0 -:100D2000404647A3D3E90023019400F0EBFEFFF710 -:100D3000FDFC3AE74FF0000807F11403A7F8148010 -:100D40001022009341460123204600F087FFA68A27 -:100D5000023EB6B2F31C9B109B000733DB08A9EBE5 -:100D6000C3039D460DF1180A1FFA88F34FEAC80124 -:100D7000B34201F110010AD20AEB080300930822E2 -:100D80000023204600F06AFF08F10108ECE795F81F -:100D9000D70000F0C9FAD5F8D83004461BB995F849 -:100DA000D70000F0D1FAD5F8D83033449C4204D2B1 -:100DB00095F8D700013000F0C7FA4FF000084FEA6D -:100DC000960B1FFA88F18B45D5E9003209D90AEB59 -:100DD000880103EB8800012200F0FCFA08F1010809 -:100DE000EFE7F31842F10002C5E90032D5F8D83038 -:100DF00095F8D70006EB0308C5F8D88000F094FA00 -:100E0000804509D395F8D730D5F8D8000133001BB9 -:100E100085F8D730C5F8D800FF2E08D800232B73EB -:100E200000F0A4FAFFF718FE08B1FFF70FFC2B68DB -:100E30000A4A9B0A013313810023AB6014E700BF09 -:100E400026417272DF25D7B7402100203D210020C6 -:100E500000ED00E00400FA05702100202C110020B4 -:100E600030B54FF00054244B226885B09A4207D029 -:100E700002F07AFB0446A8B90024204605B030BD34 -:100E8000627D1E4B1E481A70237DC92203731D49C3 -:100E90000E3000F085FA2046E022002100F092FAA0 -:100EA0000124EAE7184A194DD36943F00073D3616E -:100EB000AA6D174B9A42DFD12B6E013B7E2BDBD8FC -:100EC000144A01AB07CA83E807001846032100F063 -:100ED00013FB6B6D83424FF00003CDD12A6D8A4224 -:100EE00003BFAB652A6E054B1C4601BF1A70EA6D45 -:100EF000094B1A60C1E700BF9AAD44C53811002004 -:100F00007021002016000020001002400066004002 -:100F10005041A0B0586600401811002002232DE96E -:100F2000F0434A4C85B0637100230293484BD3F8D9 -:100F300000C0BCF57A7F12D3464F474BB7FBFCF598 -:100F40009C458CBF0A231123B5FBF3F603FB165215 -:100F5000591EC8B2002A3ED002290B46F4D89DF88B -:100F60000B303E495A1E9DF80A303D48013B1B0498 -:100F700043EA0253BDF80820013A13434B6001F0E5 -:100F800037FD00230193374B374900934FF48052CC -:100F9000364B374800F01CFD364B197811B13448F8 -:100FA00000F03EFD00F08EFA0546FFF797FB4FF488 -:100FB000C873B0FBF3F202FB130305F516709BB286 -:100FC00018442D4B186002F0C5FA08B10F23238195 -:100FD00005B0BDE8F083731EB3F5806FBFD24FF448 -:100FE0007A75C0EBC00E0EF103034FEAE30909FB6B -:100FF0000555C3F3C703C11AC9B209F101088844F2 -:10100000B5FBF8F5B5F5617F08D90EF1FF33C3F3F1 -:10101000C703C11A581E0F28C9B214D84A1E072A7E -:101020008CBF00220122581800FB0660B7FBF0F7C6 -:10103000BC4594D1002A92D0ADF808608DF80A30F2 -:101040008DF80B108BE71346EDE700BF2C11002045 -:1010500018110020005125023F420F0010110020FE -:1010600088220020C90700083C110020590B000805 -:101070004421002038110020402100202DE9F04FAC -:1010800093A7D7E900670FF25029D9E90089854D68 -:1010900093B0DFF814B2854C284600F097FD0DF1AF -:1010A000300A079070B310220021504600F08AF9F0 -:1010B0004FF00002079B197B61F303028DF830208B -:1010C000586899680EAA03C21B680D9A584663F3C4 -:1010D0001C029DF830300D9243F020038DF8303023 -:1010E00000235246194601F093FC079028B9284680 -:1010F00000F070FD079B2370CEE72378072B3CD8C8 -:101100000133237018220021504600F05BF9DFF80C -:1011100098B1674C002352461946584601F0A0FC8E -:10112000014670BB102208A800F04CF9E36883F078 -:101130001003E36000F0C8F90DF1240C0B4612A96E -:10114000024611E903008CE803009DF83410C1F356 -:101150000300890649BF0E99BDF83810C1F31C0180 -:1011600041F0004158BFC1F30A018DF82C000891ED -:10117000284608A900F0F8FECCE7284600F02AFD32 -:10118000C0E7284600F054FC8346002844D100F014 -:1011900099F9484B1A6890423ED300F093F90446FF -:1011A000FFF79CFA4FF4C872B0FBF2F101FB12009A -:1011B0008DF820B0DFF800B13E4B04F5167480B214 -:1011C0009BF8001004441C6011B901238DF82030F5 -:1011D00050460791FFF79AFA07990DF12100C1F1E6 -:1011E0001004E4B2062C28BF06245144224600F025 -:1011F000D7F808AB039318230293304B01340193C3 -:101200000123E4B2009332463B462846049400F0A2 -:1012100011FC00238BF8003000F054F9284A294CC7 -:101220001368C31AB3F57A7F31D3106000F04CF91C -:1012300002460B46284600F0D7FC284600F0F8FB93 -:1012400028B3237BDFF880B0002B14BF03230223D5 -:101250008BF8053000F036F94FF47A73B0FBF3F0F9 -:101260005146CBF800005846FFF7F2FA18230293D4 -:10127000164B0730019340F25513C0F3CF00CDE970 -:1012800003A0009342464B46284600F0D3FB237B45 -:101290002BB1FFF74BFA237B002B7FF4FAAE13B090 -:1012A000BDE8F08F44210020882200205522002034 -:1012B00000080140402100203D2100203C21002069 -:1012C00050220020702100202C11002054220020E8 -:1012D000401DA12026812A0BF1C6A7C1D068080FA6 -:1012E00070B501F0BFFF0024084E094D308028681A -:1012F0003388834208D901F0B1FF2B6804440133DD -:10130000B4F5C84F2B60F2D370BD00BF842200201B -:101310005822002002F044B800F10060920000F56D -:10132000C84001F0DFBF0000054B1A68054B1B8861 -:101330009B1A834202D9104401F090BF00207047ED -:10134000582200208422002038B50446064D286823 -:10135000204401F089FF28B928682044BDE83840BE -:1013600001F094BF38BD00BF58220020064991F813 -:10137000243033B100230822086A81F82430FFF7B3 -:10138000CBBF0120704700BF5C220020022802BFB3 -:101390004FF48012014B1A61704700BF00080140F2 -:1013A000002310B5934203D0CC5CC4540133F9E759 -:1013B00010BD000003460246D01A12F9011B002995 -:1013C000FAD1704703460244934202D003F8011B4E -:1013D000FAE770472DE9F8431F4D144695F824208D -:1013E0000746884652BBDFF870909CB395F82430CE -:1013F0002BB92022FF2148462F62FFF7E3FF95F823 -:1014000024004146C0F10802A24228BF224605EB53 -:101410008000D6B29200FFF7C3FF95F82430A41BDA -:101420001E44F6B2082E17449044E4B285F82460B6 -:10143000DBD1FFF79BFF0028D7D108E02B6A03EB35 -:1014400082038342CFD0FFF791FF0028CBD1002049 -:10145000BDE8F8830120FBE75C2200200FB40020E8 -:1014600004B07047EFF30983EFF30583044B9A6BE5 -:10147000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE72A -:1014800000ED00E0EFF30983EFF30583044B9A6B63 -:101490009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF8F -:1014A00000ED00E0EFF30983EFF30583034B5A6B84 -:1014B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E065 -:1014C000FEE7000001F0A6BF01F07EBF30B5094D78 -:1014D0000A4491420DD011F8013B5840082340F3D3 -:1014E0000004013B2C4013F0FF0384EA5000F6D1C6 -:1014F000EFE730BD2083B8ED4FF0FF33F7B500EBD9 -:1015000081061946DFF848C0DFF848E0B0421BD03A -:1015100050F8042B01AF0192042217F8014B81EA25 -:10152000046108240D46DB184941013C002DBCBF75 -:1015300083EA0C0381EA0E0114F0FF04F2D1013AB0 -:1015400012F0FF02E9D1E1E7D843C94303B0F0BD8F -:101550009336EAA9EBE1F0422DE9F041C56915B9EE -:10156000C161BDE8F0814B68AC4623F06047C3F32E -:101570008A4616EA230638BF3E464FEAD37EC3F3B7 -:1015800080782B465A68BEEBD27F22F060440AD0A6 -:10159000002A18DAA40CB44217D19D420FD10D6075 -:1015A000DEE71346EEE7A74207D102F08044C2F31C -:1015B000807242450BD054B1EFE708D2EDE7CCF88A -:1015C00000100B60CDE7B44201D0B442E5D81A68F0 -:1015D0009C46002AE5D11960C3E700002DE9F047D9 -:1015E0004FF47F49089D01F007044FEAD5082244D3 -:1015F00005F0070500EBD100944201D1BDE8F0876A -:1016000004F0070705F0070A57453E4638BF56461F -:10161000111BC6F108068E4228BF0E46E108415C48 -:1016200008EBD50E13F80EC0B94029FA06F721FAD7 -:101630000AF1FFB28CEA010147FA0AF739408CEA55 -:10164000010C03F80EC034443544D5E7082341F2B9 -:10165000210280EA012001B24000002980B203F19A -:10166000FF33B8BF504013F0FF03F4D170470000C0 -:1016700038B50C468D18A54200D138BD14F8011BB1 -:10168000FFF7E4FFF7E700000346006848B102688F -:1016900019891A60DA88013292B29142DA8038BF31 -:1016A0001A81704770B504460D4688B0202200218B -:1016B0006846FFF787FE20460495FFF7E5FF0246E0 -:1016C00058B16B46054608AE1C4603CCB4422860B0 -:1016D0006960234605F10805F6D1104608B070BDD3 -:1016E000082817D909280CD00A280CD00B280CD0B0 -:1016F0000C280CD00D280CD00E2814BF4020302010 -:1017000070470C2070471020704714207047182035 -:101710007047202070470000082817D90C280CD9E2 -:1017200010280CD914280CD918280CD920280CD929 -:1017300030288CBF0F200E207047092070470A20E8 -:1017400070470B2070470C2070470D207047000039 -:1017500010B54B6823B9CA8A63F30902CA8210BD67 -:10176000C4681A681C60C360438A013B43824A60B4 -:10177000EFE700002DE9F84F1D46CB8A0F46C3F373 -:1017800009010629814692460B4630D00020AAB2B4 -:1017900007F119049EB2052E1FFA80F80FD8904564 -:1017A00003F1010306D3FB8A0A4462F30903012013 -:1017B000FB821AE01AF800600130E654EAE790452F -:1017C000F1D21C23A1F1060BBBFBF3F203FB12BB0E -:1017D0007C681FFA8BF6002C45D14846FFF754FF72 -:1017E000044638B978606FF00200BDE8F88F4FF01A -:1017F0000008E6E70026066078604FF0000BADB207 -:10180000454510D90AEB0803221D13F8011B08F106 -:1018100001089155B1B21B291FFA88F82BD0454514 -:1018200006F10106F1D8FB8AC3F30902154465F3FA -:101830000903BCE71C46013292B22368002BF9D1A0 -:10184000AB1F0B441C21B3FBF1F301339BB29A4253 -:10185000D3D2BBF1000FD0D14846FFF715FF20B916 -:10186000C4F800B0BFE70122E7E7C0F800B05E4669 -:1018700020600446C1E74545D5D94846FFF704FF37 -:1018800008B92060AFE7C0F800B000262060044629 -:10189000B6E700002DE9F04F85B007469146CDE947 -:1018A0000113BDF83C50002A00F08F802DB10E9B33 -:1018B000002B00F08A80072D30D807F10C00FFF7CD -:1018C000E3FE044628B96FF00204204605B0BDE8E7 -:1018D000F08F14220021FFF775FD2A460E9904F1BE -:1018E0000800FFF75DFD681CC0B2FFF715FFFFF7AA -:1018F000F7FE207499F80020431E9BB202F01F02ED -:10190000234462F03F021A72019B384643F00041C3 -:1019100061602146FFF720FE0124D6E74FF0000862 -:101920004FF0800A4646444600F10C0303930398A7 -:10193000FFF7AAFE83460028C5D014220021FFF736 -:1019400041FD002E38D10220029BABF808300E9BDF -:1019500000F10802D2B299195A440130C0B20828E5 -:1019600001D0AE422AD3FFF7D7FEFFF7B9FEAE4251 -:1019700008BF4FF0400A99F80020019B411E02F079 -:101980001F0242EA4812C9B24AEA020A594443F025 -:10199000004281F808A08BF8100059463846CBF871 -:1019A0000420FFF7D9FD0134AE424FF0000A24B203 -:1019B00088F00108BBD188E70020C8E711F801CB07 -:1019C000013602F801CBB6B2C7E76FF001047CE73D -:1019D000F8B5044615460E46282200211F46FFF79B -:1019E000F1FC069BB5F5001F6360079B28BF4FF60F -:1019F000FF7223624FF0000338BF6A09A76004F149 -:101A00000C0097B29A4205D80023036027826382B4 -:101A1000A382F8BD0660013330462036F2E70000AD -:101A200003781BB94BB2002BC8BF01707047000090 -:101A3000007870472DE9F74FDDF83C9080469246DC -:101A40009B46BDF830500D9E9DF83840BDF8407063 -:101A5000B9F1000F01D1002F51D11F2C4FD898F8A8 -:101A60000000B0B9072F47D835F0030347D13A46F5 -:101A700049464FF6FF70FFF7FBFD20F001002D02F5 -:101A8000400445EA0464400C44EA40244FF6FF73E6 -:101A900021E040EA0520072F40EA0464F6D900253A -:101AA0004FF6FF73C5F12000A5F120022AFA05F1D7 -:101AB0000BFA00F001432BFA02F211431846C9B2A7 -:101AC000FFF7C4FD0835402D0346EBD13A464946A1 -:101AD000FFF7CEFD0346324621464046CDE900974A -:101AE000FFF7D8FE33780133DBB21F2B88BF00230A -:101AF000337003B0BDE8F08F6FF00300F9E76FF0CB -:101B00000100F6E72DE9F04F85B0DDF848809246F8 -:101B100006469B460F9D9DF840209DF84490BDF8D9 -:101B20004C70B8F1000F01D1002F48D11F2A46D8C0 -:101B30003378002B46D00C0244EA02649DF838103A -:101B400044EAC93444EA01441C43072F44F08004AA -:101B500032D900234FF6FF72C3F1200CA3F120000D -:101B60002AFA03F10BFA0CFC41EA0C012BFA00F003 -:101B70000143C9B210460393FFF768FD039B024679 -:101B80000833402BE8D13A464146FFF771FD034642 -:101B90002A4621463046CDE90087FFF77BFEB9F1A2 -:101BA000010F06D12B780133DBB21F2B88BF002336 -:101BB0002B7005B0BDE8F08F4FF6FF73E8E76FF0CC -:101BC0000100F6E76FF00300F3E70000C06900B121 -:101BD00004307047C3691A68C261C2681A60C36082 -:101BE000438A013B438270472DE9F041D0F81880C9 -:101BF00014461D4641460027174E09B9BDE8F0813D -:101C0000D1E90223A21A65EB0303964277EB0303A3 -:101C10001ED283698B420DD1FFF79AFD83691B6841 -:101C20008361C3680B60438AC1608169013B884658 -:101C30004382E2E7FFF78CFD0B68C8F80030C36809 -:101C40000B60438AC160013B4382D8F80010D4E79F -:101C500088460968D1E700BF80841E002DE9F04F57 -:101C60008BB00D4614469B468046DDF85090002808 -:101C700000F01A81B9F1000F00F01681531E3F2BBE -:101C800000F21281012A03D1BBF1000F40F00C8158 -:101C90000023CDE90833B8F81430B5EBC30F4FEA91 -:101CA000C30703D300200BB0BDE8F08F2B199F4270 -:101CB000D8F80C3036BF7F1B2746FFB21BB9D8F8C7 -:101CC0001030002B7BD02F2D4ED8C5F13006B742F7 -:101CD0004FF0000334BF3E46F6B200932946324629 -:101CE000D8F8080008ABFFF779FCA7EB060A3544E3 -:101CF0005FFA8AFA3021B8F8143003F10053063B3A -:101D0000DB000493D8F80C300393039B13B1BAF1B2 -:101D1000000F2CD1D8F8100040B1BAF1000F05D057 -:101D20005246009608AB691AFFF758FC38B2002FEC -:101D3000B8D066070AD00AAB03EBD40111F8083C0F -:101D4000624202F00702134101F8083C082C3DD919 -:101D5000102C40F2B680202C40F2B880BBF1000F6E -:101D600000F09D80082335E0BA460026C2E7049BB8 -:101D7000E02B28BFE02306930B44AB42059315D913 -:101D80005A1B924538BF5246039828BFD2B20096DC -:101D9000691A08AB04300792FFF720FC079A164433 -:101DA000AAEB020A1544F6B25FFA8AFA049B069A75 -:101DB00005999B1A0493039B1B680393A5E7009363 -:101DC0003A462946D8F8080008ABADE7BBF1000F4A -:101DD00013D00123B4EBC30F6CD0082C12D89DF89C -:101DE0002030621E23FA02F2D50706D54FF0FF32EB -:101DF00002FA04F423438DF820309DF8203089F84E -:101E0000003050E7102C12D8BDF82030621E23FAA3 -:101E100002F2D10706D54FF0FF3202FA04F4234351 -:101E2000ADF82030BDF82030A9F800303BE7202C79 -:101E30000FD80899631E21FA03F3DA0705D54FF08E -:101E4000FF3202FA04F40C430894089BC9F80030EE -:101E500029E7402C2BD0DDE90865611EC4F1210281 -:101E6000A4F1210326FA01F105FA02F225FA03F39F -:101E700011431943CB0712D50122A4F12003C4F169 -:101E8000200102FA03F322FA01F1A240524243EA8E -:101E9000010363EB430332432B43CDE90823DDE920 -:101EA0000823C9E90023FEE66FF00100FBE66FF0AE -:101EB0000800F8E6082CA0D9102CB3D9202CEED8B5 -:101EC000C3E7BBF1000FADD0022383E7BBF1000FE6 -:101ED000BBD004237EE70000012A30B5144638BF8A -:101EE00001220025402A28BF402285B0012CCDE9DF -:101EF000025517D81B788DF8083053070AD004AB69 -:101F000003EBD20515F8083C544204F00704A34043 -:101F100005F8083C0346009102A80021FFF75EFB8C -:101F200005B030BD082CE5D9102C03D81B88ADF8BE -:101F30000830E2E7202C02D81B680293DDE7D3E9E2 -:101F40000045CDE90245D8E710B5CB681BB98B60D9 -:101F50000B618B8210BDC4681A681C60C360438A21 -:101F6000013B4382CA60F0E72DE9F04FD1F80080D1 -:101F700093B018F0800FCDE90323C8F3C01207BF58 -:101F80004FF0020B1646C8F3C03BC8F30626B8F163 -:101F9000000F04460D4680F2D48118F0C04305932B -:101FA00040F0CF810B7B002B00F0CB81BBF1020F07 -:101FB00003D00178B14240F0C78108F07F0107915A -:101FC0007AB3C8F3074A2B4493F80390760646EA9F -:101FD0000B4608F07F0246EA82465FEAD91346EADA -:101FE0000A06069300F0918000220023CDE90A231F -:101FF00008F07F03009352465B46204667680AA9B3 -:10200000B84700287ED0A7699FB9314604F10C007B -:10201000FFF748FB0746E0B96FF0020013B0BDE8D8 -:10202000F08FC8F30F2A18F07F0F08BF0AF0030AD9 -:10203000C9E73B699E420DD03F68002FF9D1314678 -:1020400004F10C00FFF72EFB07460028E4D0A3693B -:102050003B60A7610026DDE90A234FF6FF70C6F159 -:10206000200E22FA06F103FA0EFEA6F1200C23FA46 -:102070000CFC41EA0E0141EA0C01C9B20836099292 -:102080000893FFF7E3FADDE90832402EE7D1B88282 -:10209000FB7D09F01F06C3F384039B1B98B2002B42 -:1020A000BCBF00F120031BB2D7E9022152EA0100B4 -:1020B000C8F304680FD00398821A049860EB0101FA -:1020C000A74890424FF000028A4104D3069A002AA2 -:1020D0005BD0012B23DDFA7D4FEA890302F0030276 -:1020E00003F07C031343FB7539462046FFF730FBB2 -:1020F000069BA3B9FB7DC3F38402013262F386031E -:10210000FB7504E06FF00B0088E7A76917B96FF063 -:102110000C0083E73B699E42BAD03F68F6E719F0AE -:10212000400F32D0039B1422BB60049B0021FB6054 -:102130000DA8FFF747F9039B20460A93049BADF8CF -:102140003EA00B932B1D0C932B7B8DF840B0013BD5 -:10215000DBB2ADF83C30079B8DF841608DF8433021 -:1021600094F824308DF8428083F001038DF84430D8 -:102170000AA9A3689847FB7DC3F38403013303F0E6 -:102180001F039B02FB82002048E7FB7DC9F340123E -:10219000B2EBD31F40F0DB80C3F38403B34240F0C3 -:1021A000D98006992B7B4FEA9912002934D0D207A7 -:1021B00041D4032B40F2D180039BAE1DBB60049B36 -:1021C0003246FB602B7B3946033BDBB204F10C004B -:1021D000FFF7D0FA00280DDA20463946FFF7B8FAA3 -:1021E000FB7D0320C3F38403013303F01F039B0231 -:1021F000FB8213E7AB883B832A7B033AB88AD2B2CF -:102200003146FFF735FAFB7DB882DA43C2F3C012DC -:1022100062F3C713FB75B6E76AB92E1D013B324660 -:102220003946DBB204F10C00FFF7A4FA0028D3DB37 -:102230002A7B013AE2E7F98A013BC1F3090105294A -:10224000DAB25BD80023281D07F11A0C9A4208D98C -:1022500010F801EB01330CF801E001310629DBB283 -:10226000F4D1934228BF0023039938BF04330A9165 -:10227000049938BFDBB20B9107F11A010C91796810 -:1022800038BF5B190D910E93FB8AADF83EA0C3F3E6 -:1022900009031A44079BADF83C208DF8433094F8AD -:1022A00024308DF840B083F001038DF844300023D2 -:1022B0008DF841608DF842807B602A7BB88A013AB4 -:1022C000291DFFF7D5F93B8BB882834203D1204605 -:1022D000A3680AA9984720460AA9FFF735FEFB7DA7 -:1022E000B88AC3F38403013303F01F039B02FB820C -:1022F0003B8B984214BF112000208FE67B68002B97 -:10230000AFD0062001E063461C30D3F800C0BCF11A -:10231000000FF8D1091A081D05F1040C1844DDF866 -:1023200014E09DF814308E44BEF11B0F99D89A42E8 -:1023300097D91CF8013B00F8013B059B013305933D -:10234000EDE76FF0090069E66FF00A0066E66FF0EE -:102350000D0063E66FF00E0060E66FF00F005DE6C3 -:1023600080841E00F0B53F4D3F4FEB6943F0007392 -:10237000EB61EB693D4B9B6AD3F800623E4046F04F -:102380000106C3F80062D3F800423C4044EA00244E -:1023900044F00104C3F80042002955D0002006464D -:1023A000C3F81C02C3F80402C3F80C02C3F81402F9 -:1023B00003EBC00401300E28C4F84062C4F8446244 -:1023C000F6D100274FF0010C9678148816F0010F13 -:1023D00018BFD3F804E20CFA04F01CBF40EA0E0E5A -:1023E000C3F804E216F0020F18BFD3F80CE203EBB7 -:1023F000C4041CBF40EA0E0EC3F80CE2760748BFC7 -:10240000D3F8146207F1010744BF0643C3F814620E -:102410005668B942C4F84062966802F10C02C4F8EA -:102420004462D3F81C4240EA0400C3F81C02CBD13A -:10243000D3F8002222F00102C3F80022EB6923F056 -:102440000073EB61EB69F0BD0122C3F84012C3F8E1 -:102450004412C3F80412C3F81412C3F80C22C3F8D0 -:102460001C22E5E7001002400000FFFF8822002048 -:10247000184A08B5916A8B688B6013F0010104D08B -:1024800013F00C0F18BF4FF48031D80506D513F4A4 -:10249000406F14BF41F4003141F00201D80306D56A -:1024A00013F4402F14BF41F4802141F00401D3699B -:1024B0000BB108489847202383F311880021064870 -:1024C00000F01EFE002383F31188BDE8084001F0F0 -:1024D00083B800BF882200209022002038B5124C1B -:1024E000A36ADD68AA0712D05A6922F002025A6173 -:1024F000A36913B1012120469847202383F3118853 -:1025000000210A4800F0FCFD002383F31188EB064C -:1025100006D51021A36AD960236A0BB102489847F7 -:10252000BDE8384001F058B88822002098220020E9 -:1025300038B5124CA36A1D69AA0712D05A6922F055 -:1025400010025A61A36913B1022120469847202343 -:1025500083F3118800210A4800F0D2FD002383F3A1 -:102560001188EB0606D51021A36A1961236A0BB105 -:1025700002489847BDE8384001F02EB88822002074 -:102580009822002038B50F4CA36A5D682A075D6069 -:102590000AD5042222701A6822F002021A60636AC5 -:1025A00013B10021204698476B0706D5A36A9969A5 -:1025B000236A13B1034809049847BDE8384001F085 -:1025C0000BB800BF8822002010B50E4C204600F04A -:1025D000FDF90D4B0B211320A36200F0D7F90B215D -:1025E000142000F0D3F90B21152000F0CFF90B21B6 -:1025F000162000F0CBF9BDE8104000220E20114655 -:10260000FFF7B0BE88220020006400400F4B10B5D9 -:102610009842044605D10E4BDA6942F00072DA6145 -:10262000DB690122A36A1A60A36A5A68D20707D538 -:10263000626851681268D9611A60064A5A6110BD11 -:102640000121082000F052FCEEE700BF88220020A4 -:10265000001002405B87010003291AD8DFE801F06F -:10266000020A0F14836A9B6813F0E05F14BF012015 -:1026700000207047836A9868C0F380607047836A5F -:102680009868C0F3C0607047836A9868C0F30070B0 -:10269000704700207047000010B5032927D8DFE8F5 -:1026A00001F002272B2F836A9968C1F30161183169 -:1026B00003EB01131078840648BF5468C0F300117F -:1026C00058BF94884FEA410148BF41EAC40100F075 -:1026D0000F00586048BF41F00401906858BF41EABC -:1026E0004451D26841F001019860DA60196010BD70 -:1026F000836A03F5C073DDE7836A03F5C873D9E71E -:10270000836A03F5D073D5E701290AD002290FD0D7 -:1027100081B9836ADA68920701D1186903E0012060 -:102720007047836AD86810F0030018BF0120704713 -:10273000836AF2E70020704710B539B9836AD96817 -:1027400089071BD11B699C0704D110BD012915D035 -:102750000229FAD1816AD1F8C031D1F8C441D1F847 -:10276000C8011061D1F8CC015061202008610869CE -:10277000800717D1486940F0100012E0816AD1F853 -:10278000B031D1F8B441D1F8B8011061D1F8BC0131 -:1027900050612020C860C868800703D1486940F0B4 -:1027A00002004861C3F34000C3F38001000140EA26 -:1027B0004111107920F030000143117189064BBF9F -:1027C00091681189DB085B0D4CBF63F31C0163F357 -:1027D0000A01137948BF916064F3030313714FEA50 -:1027E00014234FEA144458BF118113705480ACE78E -:1027F000026843680A43026003B11847704700004B -:10280000024AD36843F0C003D360704700380140E8 -:10281000024AD36843F0C003D360704700440040CD -:102820002DE9F041D0F89C600446F7683368DA057A -:102830009DB20DD5202383F311884FF4007104302D -:10284000FFF7D6FF6FF480733360002383F31188A2 -:10285000202383F3118804F1040815F02F033AD1E3 -:1028600083F31188380615D5290613D5202383F361 -:10287000118804F1380000F02FFA00284DDA082101 -:10288000201DFFF7B5FF4FF67F733B40F360002339 -:1028900083F311887A0616D56B0614D5202383F3AB -:1028A0001188D4E913239A420AD1236C43B127F04B -:1028B00040073F041021201D3F0CFFF799FFF760F0 -:1028C000002383F31188D4F8A420D3683BB3BDE878 -:1028D000F041106918472B0713D015F0080F0CBFF3 -:1028E00000218021E80748BF41F02001AA0748BF26 -:1028F00041F040016B07404648BF41F48071FFF74B -:1029000077FFAD06736805D594F8A01020461940EE -:1029100000F082FA3568ADB29FE77060B7E7BDE8B6 -:10292000F081000008B50348FFF77AFFBDE80840D2 -:1029300000F052BEB422002008B50348FFF770FF34 -:10294000BDE8084000F048BE5C23002010B5094CEB -:1029500000212046084A00F03FFA084B0021C4F845 -:102960009C30074C074A204600F036FA064BC4F864 -:102970009C3010BDB422002001280008003801401E -:102980005C230020112800080044004001220901B6 -:1029900000F1604303F56143C9B283F8001300F00E -:1029A0001F039A4043099B0003F1604303F5614311 -:1029B000C3F880211A607047090100F16040C9B274 -:1029C00000F56D4001767047FFF7FEBD01230370EF -:1029D000002300F10802C0E9022200F11002C0E960 -:1029E0000422C0E90633C0E90833436070470000A1 -:1029F00010B52023044683F311880223416003703D -:102A0000FFF704FE04232370002383F3118810BD15 -:102A10002DE9F0411F4604460D461646202383F358 -:102A2000118800F108082378052B0DD0294620468F -:102A3000FFF712FE40B1204632462946FFF72CFE32 -:102A4000002080F3118808E03946404600F03CFB46 -:102A50000028E8D0002383F31188BDE8F08100004E -:102A60002DE9F0411F4604460D461646202383F308 -:102A7000118800F110082378052B0DD02946204637 -:102A8000FFF742FE40B1204632462946FFF754FE8A -:102A9000002080F3118808E03946404600F014FB1E -:102AA0000028E8D0002383F31188BDE8F0810000FE -:102AB000F8B5154682680B46AA428169066938BF97 -:102AC0008568761AB54204460BD218462A46FEF7A8 -:102AD00067FCA3692B44A361A36828465B1BA36022 -:102AE000F8BD0CD918463246FEF75AFCAF1B3A46E1 -:102AF000E1683044FEF754FCE3683B44EBE71846DA -:102B00002A46FEF74DFCE368E5E700002DE9F041B9 -:102B1000154683680446934238BF8568D0E904703F -:102B20003F1ABD420E460BD22A46FEF739FC6369B6 -:102B30002B446361A36828465B1BA360BDE8F0815A -:102B40000CD93A46A5EB0708FEF72AFC4246E06896 -:102B5000F119FEF725FCE3684344EAE72A46FEF74D -:102B60001FFCE368E5E7000010B50024C361029B89 -:102B7000C0E90511C1601144C0E900008460016131 -:102B8000036210BD08B5D0E90532934201D18268D5 -:102B900092B98268013282605A1C42611970D0E990 -:102BA00004329A4228BFC3684FF0000128BF436136 -:102BB00000F09AFA002008BD4FF0FF30FBE700005C -:102BC00070B5202304460D4683F31188A668A6B18C -:102BD000A368A269013BA360531CA3611578226915 -:102BE000934224BFE368A361E3690BB12046984791 -:102BF000002383F31188284607E02946204600F089 -:102C000063FA0028E2DA86F3118870BD2DE9F74FE8 -:102C100004460E4617469846D0F81C904FF0200AFE -:102C20008AF311884FF0000B154665B12A463146EC -:102C30002046FFF73DFF034660B94146204600F0BD -:102C400043FA0028F1D0002383F31188781B03B0E6 -:102C5000BDE8F08FB9F1000F03D001902046C847BE -:102C6000019B8BF31188ED1A1E448AF31188DCE76F -:102C7000C361009BC0E90511C1601144C0E90000B7 -:102C80008260016103627047F8B504460D4616463E -:102C9000202383F31188A768A7B1A368013BA36031 -:102CA00063695A1C62611D70D4E904329A4224BFE0 -:102CB000E3686361E3690BB120469847002080F325 -:102CC000118807E03146204600F0FEF90028E2DADC -:102CD00087F31188F8BD0000D0E905239A4210B5AA -:102CE00001D182687AB982680021013282605A1C5F -:102CF00082611C7803699A4224BFC368836100F033 -:102D0000F3F9204610BD4FF0FF30FBE72DE9F74FF8 -:102D100004460E4617469846D0F81C904FF0200AFD -:102D20008AF311884FF0000B154665B12A463146EB -:102D30002046FFF7EBFE034660B94146204600F00F -:102D4000C3F90028F1D0002383F31188781B03B066 -:102D5000BDE8F08FB9F1000F03D001902046C847BD -:102D6000019B8BF31188ED1A1E448AF31188DCE76E -:102D7000026843680A43026003B1184770470000C5 -:102D80001430FFF743BF00004FF0FF331430FFF75C -:102D90003DBF00003830FFF7B9BF00004FF0FF33F0 -:102DA0003830FFF7B3BF00001430FFF709BF000051 -:102DB0004FF0FF311430FFF703BF00003830FFF74A -:102DC00063BF00004FF0FF323830FFF75DBF0000F7 -:102DD00000207047FFF7BABD37B515460D4A0446C7 -:102DE000026000224260C0E9022201220B46027406 -:102DF00000F15C01009020221430FFF7B5FE2B4655 -:102E00002022009404F17C0104F13800FFF730FF28 -:102E100003B030BD483B000838B5C36904460D46D1 -:102E20001BB904210844FFF7A3FF294604F114004D -:102E3000FFF7A8FE002806DA201D4FF48061BDE8E8 -:102E40003840FFF795BF38BD0022024BC3E900337D -:102E50009A60704704240020002382680374054BA5 -:102E60001B6899689142FBD25A6803604260106007 -:102E7000586070470424002008B5202383F311888C -:102E8000037C032B05D0042B0DD02BB983F31188C1 -:102E900008BD002243691A604FF0FF334361FFF71A -:102EA000DBFF0023F2E7D0E9003213605A60F3E75A -:102EB000002382680374054B1B6899689142FBD814 -:102EC0005A68036042601060586070470424002014 -:102ED000054B196908741868026853601A60186114 -:102EE00001230374FDF732BB0424002030B54B1CD2 -:102EF00004460B4D87B010D02B690A4A01A800F098 -:102F00001BF92046FFF7E4FF049B13B101A800F072 -:102F10002FF92B69586907B030BDFFF7D9FFF8E7E3 -:102F200004240020792E000838B50C4D41612B692E -:102F300081689A680446914203D8BDE83840FFF79B -:102F40008BBF1846FFF7B4FF01232C6101462374A1 -:102F50002046BDE83840FDF7F9BA00BF0424002040 -:102F6000044B1A681B6990689B68984294BF0020C4 -:102F7000012070470424002010B5084C2368206904 -:102F80001A6854602260012223611A74FFF790FFCF -:102F900001462069BDE81040FDF7D8BA042400209E -:102FA00008B5FFF7DDFF18B1BDE80840FFF7E4BF43 -:102FB00008BD0000FFF7E0BFFEE7000010B50C4CB5 -:102FC000FFF742FF00F0AAF880220A49204600F0ED -:102FD00031F8012344F8180C037400F0D9FA0023E7 -:102FE00083F3118862B6BDE81040034800F042B890 -:102FF0002C240020703B0008803B000800F0CAB879 -:10300000EFF3118020B9EFF30583202282F31188BA -:103010007047000010B530B9EFF30584C4F308041D -:1030200014B180F3118810BDFFF7BAFF84F3118843 -:10303000F9E7000082600222028270478368A3F1F0 -:103040003C0243F80C2C026943F83C2C426943F8DB -:10305000382C074A43F81C2CC268A3F1180043F827 -:10306000102C022203F8082C002203F8072C7047CA -:103070005D05000810B5202383F31188FFF7DEFFFC -:1030800000210446FFF750FF002383F311882046F8 -:1030900010BD0000024B1B6958610F20FFF718BFDD -:1030A00004240020202383F31188FFF7F3BF0000DE -:1030B00008B50146202383F311880820FFF716FF87 -:1030C000002383F3118808BD49B1064B42681B6990 -:1030D00018605A60136043600420FFF707BF4FF089 -:1030E000FF3070470424002003460068834205D067 -:1030F00002681A6053604161FFF7AEBE704700007E -:1031000038B504460D462068844200D138BD0368B6 -:1031100023605C604561FFF79FFEF4E7054B03F118 -:103120001402C3E905224FF0FF32DA6100221A626D -:10313000704700BF0424002010B5C0E903230B4AE8 -:10314000136A53699C68A1420CD85C688160036073 -:103150004460206058609868411A99604FF0FF33CE -:10316000D36110BD1B68091BECE700BF04240020DD -:10317000036881689A680A449A60426813605A60DA -:1031800000234FF0FF32C360014BDA61704700BF8C -:103190000424002038B50F4C2246236A01332362F1 -:1031A00052F8143F934206D020259A68013A9A605B -:1031B00063699A6802B138BDD3E9001001604860C4 -:1031C000D968DA6082F311881869884785F3118815 -:1031D000EEE700BF0424002000207047FEE7000057 -:1031E000704700004FF0FF3070470000BFF34F8F73 -:1031F000024AD368DB07FCD4704700BF00200240BE -:1032000008B5074B1B7853B9FFF7F0FF054B1A6958 -:10321000120641BF044A5A6002F188325A6008BD62 -:1032200008250020002002402301674508B5054B12 -:103230001B7833B9FFF7DAFF034A136943F08003C1 -:10324000136108BD08250020002002407F289ABF96 -:1032500000F5003080020020704700004FF48060CD -:1032600070470000802070477F2808B50BD8FFF713 -:10327000EDFF00F580630268013204D1043083421F -:10328000F9D1012008BD0020FCE700007F2838B5F7 -:10329000044623D8FFF7B4FEFFF7A8FFFFF7B0FFFF -:1032A000F3220F4B0546DA60022220461A61FFF72F -:1032B000CDFF58611A694FF4806142F040021A61F3 -:1032C000FFF794FF00F010F92846FFF7AFFFFFF774 -:1032D000A1FE2046BDE83840FFF7C6BF002038BD3C -:1032E000002002402DE9F047044612F001000E468E -:1032F000154606D040F2BD22234B1A600020BDE8DF -:10330000F087224BA2189A4204D940F2C2221E4BE7 -:103310001A60F4E7FFF774FE4FF0010AFFF770FF41 -:10332000FFF764FFDFF868903146A61B012D884641 -:1033300006EB010705D8FFF779FFFFF76BFE0120C9 -:10334000DDE7B8F80030C9F810A03B800024FFF793 -:103350004DFFC9F810403B8831F8022B9BB29A42CE -:103360000FD040F2D922084B1A600A4B1F600A4B5B -:103370001D600A4BC3F80080FFF758FFFFF74AFEB5 -:10338000BCE7023DD2E700BF042500200000020890 -:1033900000200240F824002000250020FC2400200A -:1033A000084908B50B7828B11BB9FFF729FF01239D -:1033B0000B7008BD002BFCD0BDE808400870FFF77B -:1033C00035BF00BF0825002070B5FFF719FE4FF488 -:1033D0007A710D4B0D4E1B6A326801FB03F3934269 -:1033E00037BF0B4A0A495168156836BF4C1CD1E9F2 -:1033F000005454605D1944F100043360FFF70AFE85 -:103400002846214670BD00BF042400200C25002062 -:103410001025002070B5FFF7F3FD4FF47A710F4BC4 -:103420000F4E1B6A326801FB03F3934237BF0D4A0C -:103430000C49516815683ABF4C1C5460D1E90054DE -:103440005D1944F100043360FFF7E4FD4FF47A7234 -:10345000002328462146FCF783FE70BD042400208B -:103460000C2500201025002010B5094C013AD2B2DD -:10347000FF2A00D110BD500854F82030013054F814 -:1034800020009BB243EA004341F8043BEEE700BF53 -:10349000046C004010B50748013AD2B2FF2A00D1AF -:1034A00010BD0C88530840F823404C88013340F885 -:1034B0002340F1E7046C004007B50122002001A978 -:1034C000FFF7D2FF019803B05DF804FB13B5044683 -:1034D000FFF7F2FFA04205D00122002001A90194CC -:1034E000FFF7D8FF02B010BD7047000045F25552FB -:1034F000064B1A6002225A6040F6FF729A604CF640 -:10350000CC421A600122024B1A7070470030004012 -:103510001C250020034B1B781BB14AF6AA22024B44 -:103520001A6070471C25002000300040044B1A68C8 -:103530002AB902F1804202F50432526A1A607047D9 -:10354000182500204FF08072014B5A62704700BF6F -:103550000010024008B5FFF7E9FF024B1868C0F3FE -:10356000407008BD1825002008B5FFF7DFFF024BAB -:103570001868C0F3007008BD18250020EFF3098318 -:10358000203383F30988002383F3118870470000F8 -:10359000202080F3118862B60C4B0D4AD96821F4C3 -:1035A000E0610904090C0A43DA60D3F8FC200949F8 -:1035B00042F08072C3F8FC200A6842F001020A60FF -:1035C0001022DA7783F82200704700BF00ED00E098 -:1035D0000003FA05001000E0202310B583F31188E2 -:1035E0000B4B5B6813F400630FD0EFF309844FF0CB -:1035F0008073203CE36184F30988FFF7B1FC10B1CC -:10360000044BA36110BD044BFBE783F31188F9E77A -:1036100000ED00E06F05000872050008704700002B -:10362000FEE700000A4B0B480B4A90420BD30B4BB2 -:10363000C11EDA1C121A22F003028B4238BF00228C -:103640000021FDF7BFBE53F8041B40F8041BECE754 -:10365000043C0008A0250020A0250020A025002073 -:103660007047000000F030B808B500F063F9FFF7CC -:10367000A5FCBDE80840FFF759BF000070470000F7 -:103680004FF0FF310E4B1A6919611A6900221A6155 -:103690001869D868D960D968DA60DA68DA6942F0FE -:1036A0008052DA61DA69DA6942F00062DA61054A69 -:1036B000DB69136843F48073136000F01BB900BF2B -:1036C0000010024000700040194B1A6842F00102DD -:1036D0001A601A689007FCD51A6802F0F9021A609D -:1036E00000225A605A6812F00C0FFBD11A6842F49B -:1036F00080321A601A689103FCD55A6842F4E812C5 -:103700005A601A6842F080721A601A689201FCD5F9 -:103710001221084A5A60084A11605A6842F00202AF -:103720005A605A6802F00C02082AFAD1704700BFAA -:103730000010024000641D0000200240084A08B545 -:10374000516913680B4003F00103536123B1054A2B -:1037500013680BB150689847BDE80840FFF73CBFBD -:103760000004014020250020084A08B5516913686B -:103770000B4003F00203536123B1054A93680BB178 -:10378000D0689847BDE80840FFF726BF0004014015 -:1037900020250020084A08B5516913680B4003F042 -:1037A0000403536123B1054A13690BB1506998476B -:1037B000BDE80840FFF710BF0004014020250020AD -:1037C000084A08B5516913680B4003F008035361B8 -:1037D00023B1054A93690BB1D0699847BDE8084009 -:1037E000FFF7FABE0004014020250020084A08B572 -:1037F000516913680B4003F01003536123B1054A6C -:10380000136A0BB1506A9847BDE80840FFF7E4BE61 -:103810000004014020250020174B10B55A691C6890 -:10382000144004F478725A61A30604D5134A936ACB -:103830000BB1D06A9847600604D5104A136B0BB1E0 -:10384000506B9847210604D50C4A936B0BB1D06B93 -:103850009847E20504D5094A136C0BB1506C9847A0 -:10386000A30504D5054A936C0BB1D06C9847BDE80D -:103870001040FFF7B1BE00BF00040140202500202A -:103880001A4B10B55A691C68144004F47C425A6102 -:10389000620504D5164A136D0BB1506D9847230588 -:1038A00004D5134A936D0BB1D06D9847E00404D54D -:1038B0000F4A136E0BB1506E9847A10404D50C4A01 -:1038C000936E0BB1D06E9847620404D5084A136F0B -:1038D0000BB1506F9847230404D5054A936F0BB181 -:1038E000D06F9847BDE81040FFF776BE0004014056 -:1038F00020250020062108B50846FFF747F80621D5 -:103900000720FFF743F806210820FFF73FF80621BC -:103910000920FFF73BF806210A20FFF737F80621B8 -:103920001720FFF733F8BDE8084006212820FFF7ED -:103930002DB8000008B5FFF7A3FE064800F00EF80A -:10394000FFF742F8FFF746FAFFF798FEBDE8084098 -:1039500000F002B8983B000800F042B80023194676 -:103960001C4A0133102BC2E9001102F10802F8D100 -:10397000194B9A6942F07D029A619B690268174B64 -:10398000DA6082685A6042681A60C26803F5806330 -:10399000DA6042695A6002691A608269C3F80C24CD -:1039A000026AC3F80424C269C3F80024426AC3F857 -:1039B0000C28C26AC3F80428826AC3F80028026B84 -:1039C000C3F80C2C826BC3F8042C426BC3F8002C98 -:1039D000704700BF20250020001002400008014071 -:1039E0004FF0E023044A08215A6100229A6107221D -:1039F0000B201A61FEF7E0BF3F19010008B5202334 -:103A000083F31188FFF7FAFA002383F3118808BDC6 -:103A100008B5FFF7F3FFBDE80840FFF7DDBD000084 -:103A200010B501390244904201D1002005E003782D -:103A300011F8014FA34201D0181B10BD0130F2E76D -:103A40002DE9F0419BB10446C91A1778014403F1EE -:103A5000FF3C8C42204601D9002008E00578013463 -:103A6000BD42F6D10CEB0405D618A54201D1BDE844 -:103A7000F08115F8018D16F801EDF045F5D0E8E775 -:103A8000034611F8012B03F8012B002AF9D17047E6 -:103A90006F72672E6172647570696C6F742E663117 -:103AA00030335F6169727370656564004E6F2061C9 -:103AB0007070207369670A00426164206677206C29 -:103AC000656E6774682025750A0042616420626F24 -:103AD0006172645F69642025752073686F756C641A -:103AE0002062652025750A004261642066772064A3 -:103AF000657363726970746F72206C656E67746849 -:103B00002025750A00426164206170702043524391 -:103B1000203078253038783A3078253038782030A1 -:103B200078253038783A3078253038780A00476F71 -:103B30006F64206669726D776172650A0040A2E465 -:103B4000F164689106000000000000009D2D00084F -:103B5000892D0008C52D0008B12D0008BD2D0008D5 -:103B6000A92D0008952D0008812D0008D12D0008F1 -:103B70006D61696E0000000069646C650000000002 -:103B8000783B000848240020F824002001000000B1 -:103B9000B92F0008000000000C1E0000447B4144C7 -:103BA000B45749440100000042444444444444445E -:103BB00000000000444444444444444400000000E5 -:103BC00044444444444444440000000044444444C5 -:103BD00044444444BCC5FF7F0100000000000000D5 -:103BE000E803000000000000009C0100000000004D -:103BF000640000000000000040420F00FE2A0100A7 -:043C0000D2040000EA +:10000000000900202D080008B11C0008811C000810 +:100010009D1C0008811C0008951C00082F08000882 +:100020002F0800082F0800082F080008E5370008EF +:100030002F0800082F0800082F080008F93C0008C6 +:100040002F0800082F0800082F0800082F080008B4 +:100050002F0800082F080008293A0008553A000820 +:10006000813A0008AD3A0008D93A00082F08000884 +:100070002F0800082F0800082F0800082F08000884 +:100080002F0800082F0800082F080008AD2C0008D2 +:10009000192D00086D2D0008C12D0008053B000832 +:1000A0002F0800082F0800082F0800082F08000854 +:1000B0002F0800082F0800082F0800082F08000844 +:1000C0002F0800082F0800082F0800082F08000834 +:1000D0002F0800082F0800082F0800082F08000824 +:1000E0006D3B00082F0800082F0800082F080008A3 +:1000F0002F0800082F0800082F0800082F08000804 +:100100002F0800082F0800082F0800082F080008F3 +:100110002F0800082F0800082F0800082F080008E3 +:100120002F0800082F0800082F0800082F080008D3 +:100130002F0800082F0800082F0800082F080008C3 +:100140002F0800082F0800082F0800082F080008B3 +:100150002F0800082F0800082F0800082F080008A3 +:100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A +:100170000C0F93EA0C0F6FD01A4480EA010C400276 +:1001800018BF5FEA41211ED04FF0006343EA5010D0 +:1001900043EA5111A0FB01310CF00040B1F5000F12 +:1001A0003EBF490041EAD3715B0040EA010062F1C1 +:1001B0007F02FD2A1DD8B3F1004F40EBC25008BFAB +:1001C00020F00100704790F0000F0CF0004C08BFC9 +:1001D00049024CEA502040EA51207F3AC2BFD2F196 +:1001E000FF0340EAC250704740F400004FF00003A4 +:1001F000013A5DDC12F1190FDCBF00F000407047DE +:10020000C2F10002410021FA02F1C2F1200200FA1B +:1002100002FC5FEA310040F1000053EA4C0308BFE2 +:1002200020EADC70704792F0000F00F0004C02BF33 +:10023000400010F4000F013AF9D040EA0C0093F0AE +:10024000000F01F0004C02BF490011F4000F013B08 +:10025000F9D041EA0C018FE70CEAD15392EA0C0F76 +:1002600018BF93EA0C0F0AD030F0004C18BF31F0E1 +:10027000004CD8D180EA010000F00040704790F0B7 +:10028000000F17BF90F0004F084691F0000F91F05B +:10029000004F14D092EA0C0F01D142020FD193EA21 +:1002A0000C0F03D14B0218BF084608D180EA0100A9 +:1002B00000F0004040F0FE4040F40000704740F085 +:1002C000FE4040F44000704780F0004002E000BF74 +:1002D00081F0004142001FBF5FEA410392EA030F31 +:1002E0007FEA226C7FEA236C6AD04FEA1262D2EB7B +:1002F0001363C1BFD218414048404140B8BF5B4280 +:10030000192B88BF704710F0004F40F4000020F018 +:100310007F4018BF404211F0004F41F4000121F02E +:100320007F4118BF494292EA030F3FD0A2F1010278 +:1003300041FA03FC10EB0C00C3F1200301FA03F1B6 +:1003400000F0004302D5494260EB4000B0F5000FD9 +:1003500013D3B0F1807F06D340084FEA310102F198 +:100360000102FE2A51D2B1F1004F40EBC25008BF4A +:1003700020F0010040EA03007047490040EB000014 +:10038000013A28BFB0F5000FEDD2B0FA80FCACF115 +:10039000080CB2EB0C0200FA0CF0AABF00EBC25042 +:1003A00052421843BCBFD0401843704792F0000F30 +:1003B00081F4000106BF80F400000132013BB5E783 +:1003C0004FEA41037FEA226C18BF7FEA236C21D0F9 +:1003D00092EA030F04D092F0000F08BF084670475E +:1003E00090EA010F1CBF0020704712F07F4F04D12C +:1003F000400028BF40F00040704712F100723CBF3F +:1004000000F50000704700F0004343F0FE4040F468 +:10041000000070477FEA226216BF08467FEA236326 +:100420000146420206BF5FEA412390EA010F40F411 +:10043000800070474FF0000304E000BF10F000435D +:1004400048BF40425FEA000C08BF704743F0964344 +:1004500001464FF000001CE050EA010208BF70475F +:100460004FF000030AE000BF50EA010208BF7047E6 +:1004700011F0004302D5404261EB41015FEA010CFB +:1004800002BF84460146002043F0B64308BFA3F1F3 +:100490008053A3F50003BCFA8CF2083AA3EBC253D5 +:1004A00010DB01FA02FC634400FA02FCC2F12002F4 +:1004B000BCF1004F20FA02F243EB020008BF20F02B +:1004C0000100704702F1200201FA02FCC2F1200291 +:1004D00050EA4C0021FA02F243EB020008BF20EA86 +:1004E000DC70704742000ED2B2F1FE4F0BD34FF0DA +:1004F0009E03B3EB126209D44FEA002343F000439A +:1005000023FA02F070474FF00000704712F1610FBC +:1005100001D1420202D14FF0FF3070474FF000008E +:10052000704700BF53B94AB9002908BF00281CBF53 +:100530004FF0FF314FF0FF3000F076B9ADF1080C0D +:100540006DE904CE00F006F8DDF804E0DDE90223F1 +:1005500004B070472DE9F047089E0D4604468846D2 +:10056000002B4DD18A42944668D9B2FA82F252B138 +:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 +:1005800041EA030894404FEA1C41B8FBF1F71FFA17 +:100590008CFE01FB178807FB0EF0230C43EA08438F +:1005A00098420AD91CEB030307F1FF3580F01E8146 +:1005B000984240F21B81023F63441B1AB3FBF1F0E7 +:1005C00001FB103300FB0EFEA4B244EA0344A6452F +:1005D0000AD91CEB040400F1FF3380F00981A64521 +:1005E00040F20681644402380021A4EB0E0440EA84 +:1005F00007401EB10023D440C6E90043BDE8F087A0 +:100600008B4208D9002E00F0EE800021C6E90005DB +:100610000846BDE8F087B3FA83F100294AD1AB421E +:1006200002D3824200F2FC80841A65EB03030120AE +:100630009846002EE2D0C6E90048DFE702B9FFDEA7 +:10064000B2FA82F2002A40F09180A1EB0C00012165 +:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 +:10066000250C45EA00450EFB03F0A84208D91CEB17 +:10067000050503F1FF3802D2A84200F2CE804346BE +:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 +:1006900044EA0544A64508D91CEB040400F1FF35E3 +:1006A00002D2A64500F2B6802846A4EB0E0440EA2A +:1006B00003409EE7C1F120078B4022FA07FC4CEA79 +:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D +:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 +:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 +:1006F00001F20BD91CEB040408F1FF3A80F088806A +:10070000A04240F28580A8F102086444241AB4FB98 +:10071000F9F009FB104400FB0EFEADB245EA0444BB +:10072000A64508D91CEB040400F1FF356CD2A645A0 +:100730006AD90238644440EA0840A0FB0295A4EB61 +:100740000E04AC42C846AE4656D353D0002E69D0F4 +:10075000B3EB080264EB0E0422FA01F304FA07F784 +:100760001F43CC40C6E90074002147E70CFA02FCA5 +:10077000C2F1200125FA01F34FEA1C4720FA01F1EA +:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 +:10079000280C40EA034001FB0EF3834204FA02F402 +:1007A00008D91CEB000001F1FF382FD283422DD96C +:1007B00002396044C01AB0FBF7F307FB1300ADB277 +:1007C00045EA004503FB0EF0A84208D91CEB0505DD +:1007D00003F1FF3816D2A84214D9023B6544281A07 +:1007E00043EA014138E73146304607E72F46E4E661 +:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 +:100800000138A3E74346EAE7284694E74146D1E7A3 +:10081000D0467BE76444023847E7023B65442FE754 +:10082000084606E73146E9E6704700BF02E000F0FF +:1008300000F8FEE772B6264880F30888254880F362 +:100840000988254825490860022080F31488BFF3F1 +:100850006F8F03F017F803F07BF84FF05530204905 +:100860001B4A91423CBF41F8040BFAE71D49194A63 +:1008700091423CBF41F8040BFAE71B491B4A1C4B51 +:100880009A423EBF51F8040B42F8040BF8E70020EF +:100890001849194A91423CBF41F8040BFAE702F0AB +:1008A000F5FF03F057F8154C154DAC4203DA54F838 +:1008B000041B8847F9E700F03FF8124C124DAC4298 +:1008C00003DA54F8041B8847F9E702F0DDBF0000A3 +:1008D00000090020001100200000000808ED00E0E1 +:1008E0000001002000090020083E0008001100203F +:1008F0002411002028110020E025002060010008BC +:100900006001000860010008600100082DE9F04F57 +:10091000C1F80CD0C3689D46BDE8F08F002383F377 +:1009200011882846A047002002F010FDFEE702F0E3 +:1009300083FC00DFFEE70000F8B500F03DFE02F0AA +:10094000EFFE074602F03AFF0546002840D12C4B47 +:100950009F423DD001339F423DD02A4B27F0FF02FA +:100960009A423BD1F8B200F003FC2E4642F21074DA +:1009700000F004FC08B10024264601F007F988B312 +:100980000024032000F044F8264635B11E4B9F4258 +:1009900003D0002402F00AFF2646002002F0CAFE1F +:1009A0001A4B9B6813F0400322D00EB100F046F8BA +:1009B00000F044FC00F002FE01F07CF90546CCB1E9 +:1009C00001F078F9401BA04214D900F037F8F3E7A2 +:1009D0002E460024CCE704460126C9E706464FF41C +:1009E0007A74C5E7002CD0D04FF47A740126CCE796 +:1009F0001C46DDE700F0D4FC012002F0ADFCDEE790 +:100A0000010007B0000008B0263A09B0000C014010 +:100A1000084B187003280CD8DFE800F0080502081E +:100A2000022000F027BE022000F01CBE0022024B74 +:100A30005A607047281100202C11002038B501F0B1 +:100A4000A5F830B103221F4B1A7000221E4B5A60CA +:100A500038BD1E4B1E4A19680131F9D00433934248 +:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 +:100A70009B6803F1006303F5C8439A42E8D202F091 +:100A800069FE02F07BFE002000F0B2FD0220FFF7BD +:100A9000BFFF124BDA690022DA61D96999699A615C +:100AA0009B6972B64FF0E023C3F8085D3021D4F89B +:100AB0000034D4F8042481F311889D4683F3088818 +:100AC0001047C5E7281100202C1100200064000801 +:100AD000206400080060000800110020001002409F +:100AE00049F26900084A136899B21B0C00FB0133F4 +:100AF00044F250611360054B186882B2000C01FB90 +:100B00000200186080B27047201100201C110020E4 +:100B100010B504460021102200F0C8FD034B03CBA2 +:100B2000206061601868A06010BD00BFE8F7FF1F7B +:100B30002DE9F0410026ADF54E7D6CAC40F275120A +:100B400007460D460EA831460D9600F0AFFD4FF456 +:100B5000C4723146204600F0A9FD01F0ABF84FF415 +:100B60007A72B0FBF2F0264B0DF13408186093E86E +:100B70000700022384E807000DF5E9702382FFF7E0 +:100B8000C7FF4EF603031F4906A8238403F0ECF8C1 +:100B90001B230DF2E32284F832310DF1300C06AB49 +:100BA0001E4603CE664510605160334602F10802CE +:100BB000F6D13188B37820461180937041460122E6 +:100BC00000F0C0FD00230393AB7E80B2029305F1D9 +:100BD000190301930123CDE904800093384606A34D +:100BE000D3E90023E97E01F0ABFB0DF54E7DBDE8B6 +:100BF000F08100BFAFF300809E6AC421818A46EE77 +:100C000034110020783D00082DE9F041264D804642 +:100C10002B7A0C46DAB0FBB9204627A900F0A2FED9 +:100C20000746002836D19DF89D60C82E32D801466F +:100C30004FF4FA72284600F039FD32460DF19E015C +:100C400005F1090000F020FD9DF89C302E447772DC +:100C50002B720BB9E37E2B728122002106AD27A8EF +:100C600000F024FD0122294627A800F0B7FE00234A +:100C70000393A37E80B2029304F119030193282306 +:100C8000CDE904500093404605A3D3E90023E17E5B +:100C900001F056FB5AB0BDE8F08100BFAFF3008011 +:100CA00026417272DF25D7B77C210020F0B54FF4C2 +:100CB0008A750024234EF1B005FB006596F8D83004 +:100CC000D822214685F8DC3085F8E8403AA800F0C3 +:100CD000EDFC06F1090000F0E1FCD5F8E430C2B209 +:100CE00006AF8DF8F00006F109010DF1F100CDE934 +:100CF0003A3400F0C9FC394601223AA800F09AFEC5 +:100D000080B2CDE9047008230127CDE9023706F14E +:100D1000D80301933023317A00930B4807A3D3E91A +:100D2000002301F00DFBA04206DD00F0C3FFC5F873 +:100D3000E000384671B0F0BD2046FBE778F6339FFF +:100D400093CACD8D7C2100204C210020F0B51E4E91 +:100D50001E4F1F4D85B0304601F01EFB044660B3A8 +:100D600010220021684600F0A1FC4FF00003227B16 +:100D70006068A16862F303038DF8003002AB03C31F +:100D8000019B2268384662F31C0301939DF80030F2 +:100D90006A4643F020038DF800300023194602F024 +:100DA00087F9044620B9304601F0FAFA2C70D2E7F0 +:100DB0002B78072B03D801332B7005B0F0BD024808 +:100DC00001F0EEFAF9E700BF4C210020A823002033 +:100DD0007523002070B50D4614461E4601F00CFA2E +:100DE00050B9022E10D1012C0ED112A3D3E9002349 +:100DF0000120C5E9002307E0282C10D005D8012CDC +:100E000009D0052C0FD0002070BD302CFBD10BA3D6 +:100E1000D3E90023ECE70BA3D3E90023E8E70BA316 +:100E2000D3E90023E4E70BA3D3E90023E0E700BF05 +:100E3000AFF30080401DA12026812A0B78F6339F56 +:100E400093CACD8D9E6AC421818A46EE2641727274 +:100E5000DF25D7B7F017304A39059E5638B5054615 +:100E60000E4C0021013500F0E5FBA4F8F051B4F878 +:100E7000F00100F0C7FB78B1B4F8F00100F0D2FB4C +:100E8000014648B9B4F8F00100F0D4FBB4F8F031F1 +:100E90000133A4F8F031EAE738BD00BF7C2100201F +:100EA0002DE9F04F8DB000AF04460D4601F0A4F9D6 +:100EB000002846D12B7E022B1AD1EB8A012B17D1A9 +:100EC00000F0F8FE0646FFF70BFE4FF4C873B0FBC8 +:100ED000F3F202FB1303DFF878829BB206F5167675 +:100EE0003344C8F80030EB7E33B90022994B1A70B6 +:100EF0003437BD46BDE8F08F284607F11C0100F0ED +:100F0000EFFC0028F4D107F10C00FFF701FEBD7FD4 +:100F100007F10C012A4607F11F0002F0F5FE002838 +:100F2000E3D10F2D08D88B4B1D70D8F80030A3F5F6 +:100F30001673C8F80030DBE72046397F01F054F91A +:100F4000D6E7EB8A282B6BD010D8012B63D0052B6A +:100F5000CED1BFF34F8F8049804BCA6802F4E06264 +:100F60001343CB60BFF34F8F00BFFDE7302BBFD1E2 +:100F70007B4CEA7E237A9A42BAD194F8DC206B7ECD +:100F80009A42B5D1284604F1EA0100F07FFD0646F9 +:100F90000028ADD1012384F8E83000F08BFED4F8AE +:100FA000E030C01A192840F6B83338BF19209842EB +:100FB00028BF1846FFF73EFA6A49FFF7D1F8054601 +:100FC0002068FFF737FA6849FFF7CAF80146284654 +:100FD000FFF780F9FFF786FA20604FF48A7194F8E2 +:100FE000D9307B607A68636801FB02F5621992F878 +:100FF000E80050B1D2F8E400E946834215D000235E +:1010000082F8E830C2F8E030CD466368574A9B0A60 +:10101000013313816CE729462046FFF789FD67E716 +:1010200029462046FFF7F0FD62E7B2F8EC803B600E +:1010300008F1030A4FEA9A0A4FEA8A02D11DC90849 +:10104000A9EBC1039D46EB460021584600F02EFB5C +:1010500005F1EE0142465846214400F015FB3B687D +:1010600013B9012000F0C4FA94F8D20000F0CAFAD3 +:10107000054630B9207200F0E5FA284600F0B8FACB +:10108000C2E7D4F8D4303BB994F8D200B4F8F031C8 +:10109000834201D8FFF7E2FED4F8D43043449D42A6 +:1010A00008D294F8D200B4F8F0310130834201D86C +:1010B000FFF7D4FE594660685FFA8AF200F0FEFA44 +:1010C00008B9CD4689E7636894F8D2004344636069 +:1010D000D4F8D43008EB030AC4F8D4A000F092FA94 +:1010E000824509D394F8D230D4F8D4000133401BA0 +:1010F00084F8D230C4F8D400B8F1FF0F0FD800251F +:10110000257200F09FFA284600F072FA00F03EFDCA +:10111000164B188108B9FFF791FCCD46E8E64FF46D +:101120008A727B6894F8D90002FB0343D3F8E42069 +:1011300083F8E86002F58072C3F8E060C3F8E42049 +:10114000FFF7B4FDFFF702FE84F8D960B9E700BFEE +:10115000482100204521002000ED00E00400FA05B0 +:101160007C210020CDCCCC3D6666663F341100204A +:10117000014B1870704700BF4011002030B54FF090 +:101180000054254B226885B09A4207D002F020FB1C +:101190000446C0B90024204605B030BD0025627D5C +:1011A0001E4B1F481A70237DC92203721D49C0F8C7 +:1011B000E450093000F068FA2046E022294600F0A9 +:1011C00075FA0124E7E7184A184DD36943F0007314 +:1011D000D361AA6D164B9A42DCD12B6E013B7E2B5C +:1011E000D8D8144A01AB07CA83E807001846032180 +:1011F00000F09CFC6B6D83424FF00003CAD12A6D56 +:101200008A4203BFAB652A6E044B1C4601BF1A70AD +:10121000EA6D094B1A60BEE79AAD44C54011002043 +:101220007C210020160000200010024000660040D3 +:101230005041A0B058660040181100202DE9F0433D +:1012400085B000F0A3FC0223494C63710023029394 +:10125000484B2081D3F800C0BCF57A7F12D3464FAB +:10126000464BB7FBFCF59C458CBF0A231123B5FB0D +:10127000F3F603FB1652591EC8B2002A3ED00229CB +:101280000B46F4D89DF80B303D495A1E9DF80A30A4 +:101290003C48013B1B0443EA0253BDF80820013AD5 +:1012A00013434B6001F0F4FE00230193364B3749A2 +:1012B00000934FF48052364B364800F06BFF364BAC +:1012C000197811B1334800F08FFF00F0F3FC0546A8 +:1012D000FFF706FC4FF4C873B0FBF3F202FB1303F5 +:1012E00005F516709BB218442C4B186002F066FA94 +:1012F00008B10F23238105B0BDE8F083731EB3F559 +:10130000806FBFD24FF47A75C0EBC00E0EF10303AD +:101310004FEAE30909FB0555C3F3C703C11AC9B274 +:1013200009F101088844B5FBF8F5B5F5617F08D9E6 +:101330000EF1FF33C3F3C703C11A581E0F28C9B2F9 +:1013400014D84A1E072A8CBF00220122581800FB1D +:101350000660B7FBF0F7BC4594D1002A92D0ADF8F7 +:1013600008608DF80A308DF80B108BE71346EDE717 +:101370003411002018110020005125023F420F00B7 +:1013800010110020A8230020D50D000844110020D2 +:10139000A10E00084C21002040110020482100200F +:1013A0002DE9F04F80A7D7E900670FF20429D9E9AA +:1013B0000089734D93B00DF1300AFFF7C7FC182276 +:1013C0000021504600F072F9DFF8B8B16E4C0023EE +:1013D00052461946584601F093FE014650BB102272 +:1013E00008A800F063F9E36883F01003E36000F0FD +:1013F00063FC0DF1240C0B4612A9024611E903000F +:101400008CE803009DF83410C1F30300890649BF3E +:101410000E99BDF83810C1F31C0141F0004158BFCE +:10142000C1F30A018DF82C000891284608A901F0A3 +:1014300097F9CCE7284600F0DFFE0446002847D1A4 +:1014400000F038FCDFF844B1DBF8003098423FD3BD +:1014500000F030FC0790FFF743FB4FF4C873B0FB7C +:10146000F3F101FB1300079A83B202F516701844DA +:10147000CBF80000DFF818B18DF820409BF8001081 +:1014800011B901238DF8203050460791FFF740FB3A +:1014900007990DF12100C1F11004E4B2062C28BF18 +:1014A00006245144224600F0EFF808AB03931823BA +:1014B0000293384B013401930123E4B20093324686 +:1014C0003B462846049400F0DDFE00238BF80030F4 +:1014D00000F0F0FB304A314C1368C31AB3F57A7F41 +:1014E00030D3106000F0E8FB02460B46284600F0BF +:1014F00061FF284600F080FE20B3237ADFF8A0B019 +:10150000002B14BF032302238BF8053000F0D2FB1D +:101510004FF47A73B0FBF3F00122CBF80000514690 +:10152000584600F0B5F9182302931E4B80B2019380 +:1015300040F25513CDE903A0009342464B4628469E +:1015400000F0A0FE237ABBB100F0B4FB94F8E830C1 +:1015500073B9D4F8E03043B1C01A2368FA2B38BF0E +:10156000FA230533B0EB430F02D30020FFF79EFBB5 +:10157000237A002B7FF41FAF13B0BDE8F08F00BFBC +:101580004C210020A8230020000801404821002011 +:101590004521002044210020702300207C210020D0 +:1015A0003411002074230020401DA12026812A0B25 +:1015B000F1C6A7C1D068080F7047000070B501F0F0 +:1015C00095FF0024084E094D3080286833888342F7 +:1015D00008D901F087FF2B6804440133B4F5C84FE4 +:1015E0002B60F2D370BD00BFA4230020782300201D +:1015F00002F00AB800F10060920000F5C84001F066 +:10160000AFBF0000054B1A68054B1B889B1A83422D +:1016100002D9104401F066BF0020704778230020F3 +:10162000A4230020024B1B68184401F061BF00BFD7 +:1016300078230020024B1B68184401F06BBF00BFE9 +:1016400078230020064991F8243033B10023082282 +:10165000086A81F82430FFF7CDBF0120704700BF32 +:101660007C230020022802BF1022014B1A61704720 +:1016700000080140022802BF4FF48012014B1A619A +:10168000704700BF00080140002310B5934203D00B +:10169000CC5CC4540133F9E710BD00000346024698 +:1016A000D01A12F9011B0029FAD1704703460244EF +:1016B000934202D003F8011BFAE770472DE9F84383 +:1016C0001F4D144695F824200746884652BBDFF884 +:1016D00070909CB395F824302BB92022FF21484606 +:1016E0002F62FFF7E3FF95F824004146C0F108029E +:1016F000A24228BF224605EB8000D6B29200FFF737 +:10170000C3FF95F82430A41B1E44F6B2082E1744DC +:101710009044E4B285F82460DBD1FFF793FF002802 +:10172000D7D108E02B6A03EB82038342CFD0FFF7C7 +:1017300089FF0028CBD10020BDE8F8830120FBE71A +:101740007C2300202DE9F0470D46044600219046F9 +:10175000284640F27912FFF7A9FF234620220021F4 +:10176000284600F09FFF022220212846231D00F07A +:1017700099FF032222212846631D00F093FF0322D4 +:1017800025212846A31D00F08DFF10222821284680 +:1017900004F1080300F086FF08223821284604F1EE +:1017A000100300F07FFF08224021284604F11103B6 +:1017B00000F078FF08224821284604F1120300F0C7 +:1017C00071FF20225021284604F1140300F06AFF23 +:1017D00040227021284604F1180300F063FF08221C +:1017E000B021284604F1200300F05CFF0822B82154 +:1017F000284604F1210300F055FFC02604F122071A +:101800003B46314608222846083600F04BFFB6F525 +:10181000A07F07F10107F3D108223146284604F1E1 +:10182000320300F03FFF002704F1330A94F832300E +:101830004FEAC7099F4209F5A47615D3B8F1000F06 +:1018400008D131460722284604F5997300F02AFF93 +:1018500009F24F16274694F832213B1B93420CD3D2 +:10186000F01DC008BDE8F0870AEB070308223146E7 +:10187000284600F017FF0137D8E7314607F2331347 +:101880000822284600F00EFF08360137E3E7000083 +:1018900038B50C460021054621600346C4F8031004 +:1018A0002046202200F0FEFE20462B1D0222202191 +:1018B00000F0F8FE20466B1D0322222100F0F2FE0C +:1018C0002046AB1D0322252100F0ECFE204610220D +:1018D000282105F1080300F0E5FE072038BD0000CF +:1018E0000023F7B50E460546047F072200911946EE +:1018F00000F09AFD731C0093012200230721284663 +:1019000000F092FDC4B9B31C0093052223460821C0 +:10191000284600F089FD0D243746B278BB1B934260 +:1019200011D32B7FE01DC008AC8ABBB9A04294BF85 +:101930000020012003B0F0BDAB8A0824DB00083B87 +:10194000DB08B370E8E7FB1C214600930822002364 +:10195000284600F069FD08340137DEE7001B18BF98 +:101960000120E7E70023F7B50E46047F0822009127 +:101970001946054600F058FD731CC4B908220093AF +:1019800011462346284600F04FFD102401237278AB +:101990005F1C013B934211D32B7FE01DC008AC8A32 +:1019A000BBB9A04294BF0020012003B0F0BDAB8AB8 +:1019B0000824DB00083BDB087370E7E7F3192146D6 +:1019C000009308220023284600F02EFD08343B46F1 +:1019D000DDE7001B18BF0120E7E70000F8B50E4661 +:1019E00005461446002181223046FFF75FFE2B4654 +:1019F00008220021304600F055FE7CB9072208215C +:101A000030466B1C00F04EFE0F2401236A785F1CE9 +:101A1000013B934204D3E01DC008F8BD0824F4E75D +:101A20002146EB190822304600F03CFE08343B46C4 +:101A3000ECE70000F8B50E46054614460021CE221C +:101A40003046FFF733FE2B4628220021304600F0B7 +:101A500029FE7CB908222821304605F1080300F050 +:101A600021FE30242F462A7A7B1B934204D3E01DAB +:101A7000C008F8BD2824F5E7214607F1090308222C +:101A8000304600F00FFE08340137ECE7F7B5047F6D +:101A90000E460091012310220021054600F0C4FCEF +:101AA000C4B9B31C0093092223461021284600F034 +:101AB000BBFC192437467288BB1B9A4211D82B7F76 +:101AC000E01DC008AC8ABBB9A04294BF0020012031 +:101AD00003B0F0BDAB8A1024DB00103BDB08738041 +:101AE000E8E73B1D2146009308220023284600F02A +:101AF0009BFC08340137DEE7001B18BF0120E7E735 +:101B000030B5094D0A4491420DD011F8013B5840BF +:101B1000082340F30004013B2C4013F0FF0384EA48 +:101B20005000F6D1EFE730BD2083B8ED4FF0FF3322 +:101B3000F7B500EB81061946DFF848C0DFF848E04A +:101B4000B0421BD050F8042B01AF0192042217F8C9 +:101B5000014B81EA046108240D46DB184941013C30 +:101B6000002DBCBF83EA0C0381EA0E0114F0FF04D0 +:101B7000F2D1013A12F0FF02E9D1E1E7D843C943BB +:101B800003B0F0BD9336EAA9EBE1F042F7B56B463E +:101B9000354A106851686A4603C3082333493448FC +:101BA00002F0C2F8044690BB0A256B46314A106821 +:101BB00051686A4603C308232F492D4802F0B4F840 +:101BC0000446002847D00369B3F5CE3F43D8B0F8A8 +:101BD0006620B2F57A7F3ED1284A024402F15C01C8 +:101BE0008B4238D35C3B224900209E1AFFF788FFC6 +:101BF00007463246002004F16401FFF781FFA36825 +:101C00009F4228D1E368984208BF002523E003697A +:101C1000B3F5CE3F26D8428BB2F57A7F20D1174A52 +:101C2000024402F110018B4218D3103B10490020EE +:101C30009D1AFFF765FF06462A46002004F11801A9 +:101C4000FFF75EFFA3689E4202D1E368984201D08D +:101C50000D25AAE70025284603B0F0BD1025A4E70E +:101C60000C25A2E70B25A0E7943D0008DC9B0100B2 +:101C7000006400089D3D0008909B0100089CFFF750 +:101C8000EFF30983EFF30583014B9B6BFEE700BF86 +:101C900000ED00E008B5FFF7F3FF0000EFF3098364 +:101CA000EFF30583014B5B6BFEE700BF00ED00E047 +:101CB000FEE7000001F0E2BC01F0BABC2DE9F04102 +:101CC000456A15B94162BDE8F0814B68AC4623F026 +:101CD0006047C3F38A4616EA230638BF3E464FEAFA +:101CE000D37EC3F380782B465A68BEEBD27F22F0B6 +:101CF00060440AD0002A18DAA40CB44217D19D42DD +:101D00000FD10D60DEE71346EEE7A74207D102F0E0 +:101D10008044C2F3807242450BD054B1EFE708D241 +:101D2000EDE7CCF800100B60CDE7B44201D0B4422F +:101D3000E5D81A689C46002AE5D11960C3E700007F +:101D40002DE9F0474FF47F49089D01F007044FEA61 +:101D5000D508224405F0070500EBD100944201D1DB +:101D6000BDE8F08704F0070705F0070A57453E462F +:101D700038BF5646111BC6F108068E4228BF0E46D4 +:101D8000E108415C08EBD50E13F80EC0B94029FA02 +:101D900006F721FA0AF1FFB28CEA010147FA0AF7C5 +:101DA00039408CEA010C03F80EC034443544D5E7C1 +:101DB000082341F2210280EA012001B240000029FB +:101DC00080B203F1FF33B8BF504013F0FF03F4D1EA +:101DD0007047000038B50C468D18A54200D138BDBB +:101DE00014F8011BFFF7E4FFF7E700000346406823 +:101DF00048B1026899895A605A89013292B2914277 +:101E00005A8138BF9A81704770B504460D4688B034 +:101E1000202200216846FFF749FC20460495FFF781 +:101E2000E5FF024658B16B46054608AE1C4603CC9A +:101E3000B44228606960234605F10805F6D11046D2 +:101E400008B070BD082817D909280CD00A280CD072 +:101E50000B280CD00C280CD00D280CD00E2814BF49 +:101E60004020302070470C2070471020704714200D +:101E7000704718207047202070470000082817D9A5 +:101E80000C280CD910280CD914280CD918280CD9D6 +:101E900020280CD930288CBF0F200E207047092035 +:101EA00070470A2070470B2070470C2070470D20A8 +:101EB000704700002DE9F843078C0446072F1ED910 +:101EC000D0E9029800254FF6FF73C5F12006A5F171 +:101ED000200029FA05F108FA06F628FA00F0314345 +:101EE0000143C9B21846FFF763FF0835402D03468A +:101EF000EBD13A46E169BDE8F843FFF76BBF4FF617 +:101F0000FF70BDE8F883000010B54B6823B9CA8A9A +:101F100063F30902CA8210BD04691A681C60036178 +:101F2000C38A013BC3824A60EFE700002DE9F84F06 +:101F30001D46CB8A0F46C3F3090105298146924607 +:101F40000B4630D00020AAB207F11A049EB2042E2C +:101F50001FFA80F80FD8904503F1010306D3FB8ADE +:101F60000A4462F309030120FB821AE01AF80060B8 +:101F70000130E654EAE79045F1D21C23A1F1050BAC +:101F8000BBFBF3F203FB12BB7C681FFA8BF6002C41 +:101F900045D14846FFF72AFF044638B978606FF00C +:101FA0000200BDE8F88F4FF00008E6E70026066063 +:101FB00078604FF0000BADB2454510D90AEB08032D +:101FC000221D13F8011B08F101089155B1B21B291C +:101FD0001FFA88F82BD0454506F10106F1D8FB8A97 +:101FE000C3F30902154465F30903BCE71C4601323B +:101FF00092B22368002BF9D16B1F0B441C21B3FB59 +:10200000F1F301339BB29A42D3D2BBF1000FD0D18E +:102010004846FFF7EBFE20B9C4F800B0BFE7012245 +:10202000E7E7C0F800B05E4620600446C1E74545DA +:10203000D5D94846FFF7DAFE08B92060AFE7C0F807 +:1020400000B0002620600446B6E700002DE9F74FF7 +:102050001C465B69074688460092002B00F097807B +:10206000238C2BB1E269002A00F09180072B33D832 +:1020700007F10C00FFF7BAFE054628B96FF002051C +:10208000284603B0BDE8F08F14220021FFF70EFBB5 +:10209000228CE16905F10800FFF7F6FA208C48F080 +:1020A0000041013080B2FFF7E9FEFFF7CBFE0138B7 +:1020B00080B22084013028746369228C1B782A4402 +:1020C00003F01F0363F03F0313723846696029462B +:1020D000FFF7F4FD0125D3E74FF000094FF0800A28 +:1020E0004E464D4600F10C0301930198FFF77EFE2A +:1020F00083460028C2D014220021FFF7D7FA002E11 +:102100003BD10222009BABF808300BF1080E1FFAFE +:1021100082FC0CF10100BCF1060F218C80B201D8C9 +:102120008E422CD3FFF7AAFEFFF78CFE8E4208BF2B +:102130004FF0400A62690138127880B202F01F0243 +:1021400042EA49120BEB00014AEA020A013048F068 +:10215000004281F808A08BF8100059463846CBF8A9 +:102160000420FFF7ABFD238C0135B3424FF0000A8A +:102170002DB289F00109B8D182E70022C5E7E169F3 +:10218000895D01360EF80210B6B20132BFE76FF07A +:10219000010575E7F8B5044615460E4630220021C4 +:1021A0001F46FFF783FA069BB5F5001F6360079B88 +:1021B00028BF4FF6FF72A3624FF0000338BF6A09D1 +:1021C000A760E66197B204F110009A4206D8002396 +:1021D0000360A782E3822383E360F8BD06600133D6 +:1021E00030462036F1E7000003781BB94BB2002BD4 +:1021F000C8BF01707047000000787047F8B50C4602 +:10220000C969074611B9238C002B37D1257E1F2DB4 +:1022100034D8387828BB228C072A2CD8268A36F066 +:1022200003032BD14FF6FF70FFF7D4FD4FF6FF727B +:1022300020F001003602400446EA0565400C45EAFC +:102240004025234629463846FFF700FF002807DDD2 +:10225000626913780133DBB21F2B88BF0023137030 +:10226000F8BD218A2D0645EA012505432046FFF7E2 +:1022700021FE0246E5E76FF00300F1E76FF0010091 +:10228000EEE7000070B504461D4616468AB02822C7 +:1022900000216846FFF70AFABDF838306946ADF804 +:1022A00010300F9B204605939DF84030CDE9026524 +:1022B0008DF81830119B0793BDF84830ADF82030E9 +:1022C000FFF79CFF0AB070BD2DE9F041D3690546C8 +:1022D0000C4616460BB9138C5BBB377E1F2F28D8D4 +:1022E00095F80080B8F1000F26D03046FFF7E2FDE8 +:1022F0003378210241EAC33141EA0801338A41EAD5 +:10230000076141EA034102463346284641F0800115 +:10231000FFF79CFE00280ADD3378012B07D1726994 +:1023200013780133DBB21F2B88BF00231370BDE885 +:10233000F0816FF00100FAE76FF00300F7E70000AB +:10234000F0B504460D461E4617468BB028220021E4 +:102350006846FFF7ABF99DF84C3029465A1E5342A8 +:1023600053418DF800309DF840306A46ADF810308A +:10237000119B204605939DF84830CDE902768DF8F3 +:102380001830149B0793BDF85430ADF82030FFF798 +:102390009BFF0BB0F0BD0000406A00B104307047F5 +:1023A000436A1A68426202691A600361C38A013B88 +:1023B000C38270472DE9F041D0F8208014461D46B5 +:1023C00041460027174E09B9BDE8F081D1E9022343 +:1023D000A21A65EB0303964277EB03031ED2036A4E +:1023E0008B420DD1FFF790FD036A1B6803620369FE +:1023F0000B60C38A0161016A013B8846C382E2E740 +:10240000FFF782FD0B68C8F8003003690B60C38AD0 +:102410000161013BC382D8F80010D4E788460968FF +:10242000D1E700BF80841E002DE9F04F8BB00D4630 +:1024300014469B468046DDF85090002800F01A8133 +:10244000B9F1000F00F01681531E3F2B00F21281EC +:10245000012A03D1BBF1000F40F00C810023CDE92C +:102460000833B8F81430B5EBC30F4FEAC30703D3F2 +:1024700000200BB0BDE8F08F2B199F42D8F80C302C +:1024800036BF7F1B2746FFB21BB9D8F81030002B90 +:102490007BD0272D4ED8C5F12806B7424FF0000358 +:1024A00034BF3E46F6B2009329463246D8F80800BB +:1024B00008ABFFF745FCA7EB060A35445FFA8AFA3A +:1024C0002821B8F8143003F10053053BDB000493D6 +:1024D000D8F80C300393039B13B1BAF1000F2CD141 +:1024E000D8F8100040B1BAF1000F05D0524600965E +:1024F00008AB691AFFF724FC38B2002FB8D0660782 +:102500000AD00AAB03EBD40111F8083C624202F096 +:102510000702134101F8083C082C3DD9102C40F269 +:10252000B680202C40F2B880BBF1000F00F09D80F7 +:10253000082335E0BA460026C2E7049BE02B28BFFB +:10254000E02306930B44AB42059315D95A1B9245E1 +:1025500038BF5246039828BFD2B20096691A08AB1A +:1025600004300792FFF7ECFB079A1644AAEB020A25 +:102570001544F6B25FFA8AFA049B069A05999B1AEB +:102580000493039B1B680393A5E700933A462946EF +:10259000D8F8080008ABADE7BBF1000F13D001235A +:1025A000B4EBC30F6CD0082C12D89DF82030621EFB +:1025B00023FA02F2D50706D54FF0FF3202FA04F4EF +:1025C00023438DF820309DF8203089F8003050E703 +:1025D000102C12D8BDF82030621E23FA02F2D10767 +:1025E00006D54FF0FF3202FA04F42343ADF8203051 +:1025F000BDF82030A9F800303BE7202C0FD808990F +:10260000631E21FA03F3DA0705D54FF0FF3202FA11 +:1026100004F40C430894089BC9F8003029E7402CC7 +:102620002BD0DDE90865611EC4F12102A4F121036C +:1026300026FA01F105FA02F225FA03F311431943D0 +:10264000CB0712D50122A4F12003C4F1200102FA24 +:1026500003F322FA01F1A240524243EA010363EB81 +:10266000430332432B43CDE90823DDE90823C9E9BD +:102670000023FEE66FF00100FBE66FF00800F8E6CD +:10268000082CA0D9102CB3D9202CEED8C3E7BBF16D +:10269000000FADD0022383E7BBF1000FBBD00423B2 +:1026A0007EE70000012A30B5144638BF012200251C +:1026B000402A28BF402285B0012CCDE9025517D809 +:1026C0001B788DF8083053070AD004AB03EBD20512 +:1026D00015F8083C544204F00704A34005F8083CF0 +:1026E0000346009102A80021FFF72AFB05B030BD88 +:1026F000082CE5D9102C03D81B88ADF80830E2E788 +:10270000202C02D81B680293DDE7D3E90045CDE910 +:102710000245D8E710B5CB681BB98B600B618B8283 +:1027200010BD04691A681C600361C38A013BC3823F +:10273000CA60F0E703064CBFC0F3C0300220704708 +:1027400008B50246FFF7F6FF022806D15306C2F38A +:102750000F2001D100F0030008BDC2F30740FBE7E2 +:102760002DE9F04F93B0CDE903230A6804461046E3 +:10277000FFF7E0FF02280CBF0026C2F30626002A5E +:102780000D46824680F2F98112F0C04940F0F58191 +:10279000097B002900F0F181022803D02378B3429D +:1027A00040F0EE81C2F304631046069302F07F030B +:1027B0000593FFF7C5FF059B00224FEA83480023DE +:1027C00048EA0A48294448EA4668CE78CDE9082311 +:1027D000F309834648EA0008029367D0059B024646 +:1027E000009320465346676808A9B847002800F0C0 +:1027F000CA81276A4FB9414604F10C00FFF704FB78 +:10280000074690B96FF0020054E03B6998450DD03F +:102810003F68002FF9D1414604F10C00FFF7F4FAAC +:1028200007460028EED0236A3B60276297F817C05E +:1028300006F01F08CCF3840CACEB08001FFA80FEF6 +:102840000028B8BF0EF12000A8EB0C031FFA83FE8E +:10285000B8BF00B2002B0793BEBF0EF120031BB21E +:102860000793D7E9022152EA010338D04FF0000C58 +:10287000039BDFF8F8E19A1A049B63EB010196458C +:102880007CEB01032BD36B7B97F81AE0734519D1CE +:10289000029B002B78D0012821DC7868F8B9DFF89A +:1028A000D0C1944570EB010316D337E0276A27B9EE +:1028B0006FF00C0013B0BDE8F08F3B699845B5D0C0 +:1028C0003F68F4E76A4890427CEB010301D30020A3 +:1028D000F0E7029B002BFAD0079B0F2B17DCFA7D49 +:1028E000B30002F0030203F07C031343FB75394687 +:1028F0002046FFF709FB6B7BBB76029B3BB9FB7D58 +:10290000C3F38402013262F38603FB75D0E76A7B6E +:10291000BB7E9A42DBD1029B002B35D0B309022B40 +:1029200032D0039B1422BB60049B0021FB600DA8E6 +:10293000FEF7BCFE039B20460A93049BADF83EB015 +:102940000B932B1D0C932B7B8DF840A0013BDBB22E +:10295000ADF83C30069B8DF841808DF84230059BE8 +:102960000AA98DF8433094F82C3083F001038DF8D8 +:102970004430A3689847FB7DC3F38403013303F01D +:102980001F039B02FB82A2E7FB7DC6F34012B2EB62 +:10299000D31F40F0FB80C3F38403434540F0F9802C +:1029A000029A2B7BB609002A4DD0F20762D4032B82 +:1029B00040F2F280039BAE1DBB60049B3246FB607D +:1029C0002B7B3946033BDBB204F10C00FFF7AEFA78 +:1029D00000280CDA39462046FFF796FAFB7DC3F350 +:1029E0008403013303F01F039B02FB820AE7AB88D9 +:1029F000DDE908843B834FF6FF73C9F12000A9F19C +:102A0000200228FA09F104FA00F0014324FA02F244 +:102A100011431846C9B2FFF7CBF909F10809B9F11A +:102A2000400F0346E9D13146B8822A7B033AD2B23D +:102A3000FFF7D0F9FB7DB882DA43C2F3C01262F32C +:102A4000C713FB7543E7AEB92E1D013B324639462D +:102A5000DBB204F10C00FFF769FA0028BADB2A7B2D +:102A60003146013AB88AD2B2E2E700BF80841E0044 +:102A700040420F00F98A013BC1F309010429DAB28F +:102A80005DD80023281D07F11B069A4208D910F8CB +:102A900001CB013306F801C001310529DBB2F4D1C5 +:102AA000934228BF0023039938BF04330A91049945 +:102AB00038BFDBB20B9107F11B010C91796838BF6D +:102AC0005B190D910E93FB8AADF83EB0C3F3090379 +:102AD0001A44069BADF83C208DF84230059B8DF8DA +:102AE00040A08DF8433094F82C308DF8418083F06D +:102AF00001038DF8443000237B602A7BB88A013AB9 +:102B0000291DFFF767F93B8BB882834203D120462A +:102B1000A3680AA9984720460AA9FFF7FBFDFB7D99 +:102B2000BA8AC3F38403013303F01F039B02FB82C1 +:102B30003B8B9A420CBF00206FF01000BAE67B6816 +:102B4000002BADD0052001E033461C301E68002E5E +:102B5000FAD1091A081D2E1D184401EB090CBCF10D +:102B60001B0F5FFA89F39BD89A4299D916F8013B5B +:102B700009F1010900F8013BEFE76FF0090099E660 +:102B80006FF00A0096E66FF00B0093E66FF00D0011 +:102B900090E66FF00E008DE66FF00F008AE600BF42 +:102BA000F0B53F4D3F4FEB6943F00073EB61EB69CC +:102BB0003D4B9B6AD3F800623E4046F00106C3F8E5 +:102BC0000062D3F800423C4044EA002444F001048F +:102BD000C3F80042002955D000200646C3F81C0265 +:102BE000C3F80402C3F80C02C3F8140203EBC004D8 +:102BF00001300E28C4F84062C4F84462F6D10027C0 +:102C00004FF0010C9678148816F0010F18BFD3F816 +:102C100004E20CFA04F01CBF40EA0E0EC3F804E212 +:102C200016F0020F18BFD3F80CE203EBC4041CBF6C +:102C300040EA0E0EC3F80CE2760748BFD3F81462E0 +:102C400007F1010744BF0643C3F814625668B9424E +:102C5000C4F84062966802F10C02C4F84462D3F8EA +:102C60001C4240EA0400C3F81C02CBD1D3F8002276 +:102C700022F00102C3F80022EB6923F00073EB613C +:102C8000EB69F0BD0122C3F84012C3F84412C3F847 +:102C90000412C3F81412C3F80C22C3F81C22E5E78F +:102CA000001002400000FFFFA8230020184A08B5CA +:102CB000916A8B688B6013F0010104D013F00C0F44 +:102CC00018BF4FF48031D80506D513F4406F14BFF8 +:102CD00041F4003141F00201D80306D513F4402F2E +:102CE00014BF41F4802141F00401D3690BB10848BD +:102CF0009847302383F311880021064800F048FBF1 +:102D0000002383F31188BDE8084000F099BD00BF9F +:102D1000A8230020B023002038B5124CA36ADD6838 +:102D2000AA0712D05A6922F002025A61A36913B1AC +:102D3000012120469847302383F3118800210A4857 +:102D400000F026FB002383F31188EB0606D5102143 +:102D5000A36AD960236A0BB102489847BDE838409E +:102D600000F06EBDA8230020B823002038B5124C17 +:102D7000A36A1D69AA0712D05A6922F010025A618B +:102D8000A36913B1022120469847302383F31188A9 +:102D900000210A4800F0FCFA002383F31188EB06B7 +:102DA00006D51021A36A1961236A0BB1024898471E +:102DB000BDE8384000F044BDA8230020B82300201F +:102DC00038B50F4CA36A5D682A075D600AD50422F6 +:102DD00022701A6822F002021A60636A13B100219D +:102DE000204698476B0706D5A36A9969236A13B1F1 +:102DF000034809049847BDE8384000F021BD00BFF2 +:102E0000A823002010B50E4C204600F02FF90D4BE2 +:102E10000B211320A36200F009F90B21142000F00C +:102E200005F90B21152000F001F90B21162000F007 +:102E3000FDF8BDE8104000220E201146FFF7B0BE9D +:102E4000A8230020006400400F4B10B598420446B0 +:102E500005D10E4BDA6942F00072DA61DB690122BA +:102E6000A36A1A60A36A5A68D20707D562685168D4 +:102E70001268D9611A60064A5A6110BD0121082002 +:102E800000F0B0F9EEE700BFA823002000100240D8 +:102E90005B87010003291AD8DFE801F0020A0F144A +:102EA000836A9B6813F0E05F14BF01200020704725 +:102EB000836A9868C0F380607047836A9868C0F33B +:102EC000C0607047836A9868C0F300707047002044 +:102ED0007047000010B5032927D8DFE801F002276A +:102EE0002B2F836A9968C1F30161183103EB011339 +:102EF0001078840648BF5468C0F3001158BF948806 +:102F00004FEA410148BF41EAC40100F00F00586098 +:102F100048BF41F00401906858BF41EA4451D2686B +:102F200041F001019860DA60196010BD836A03F511 +:102F3000C073DDE7836A03F5C873D9E7836A03F5D5 +:102F4000D073D5E701290AD002290FD081B9836A4D +:102F5000DA68920701D1186903E001207047836A9B +:102F6000D86810F0030018BF01207047836AF2E7A9 +:102F70000020704710B539B9836AD96889071BD119 +:102F80001B699C0704D110BD012915D00229FAD173 +:102F9000816AD1F8C031D1F8C441D1F8C8011061BB +:102FA000D1F8CC015061202008610869800717D151 +:102FB000486940F0100012E0816AD1F8B031D1F8D0 +:102FC000B441D1F8B8011061D1F8BC0150612020A2 +:102FD000C860C868800703D1486940F002004861B2 +:102FE000C3F34000C3F38001000140EA41111079AE +:102FF00020F030000143117189064BBF916811899F +:10300000DB085B0D4CBF63F31C0163F30A0113790A +:1030100048BF916064F3030313714FEA14234FEA2E +:10302000144458BF118113705480ACE70122090188 +:1030300000F1604303F56143C9B283F8001300F067 +:103040001F039A4043099B0003F1604303F561436A +:10305000C3F880211A607047090100F16040C9B2CD +:1030600000F56D4001767047FFF7CCBE0123037079 +:10307000002300F10802C0E9022200F11002C0E9B9 +:103080000422C0E90633C0E90833436070470000FA +:1030900010B53023044683F3118802234160037086 +:1030A000FFF7D2FE04230020237080F3118810BDA7 +:1030B0002DE9F0411F4604460D461646302383F3A2 +:1030C000118800F108082378052B0DD029462046E9 +:1030D000FFF7E0FE40B1204632462946FFF7FAFEF0 +:1030E000002080F3118808E03946404600F040F99E +:1030F0000028E8D0002383F31188BDE8F0810000A8 +:103100002DE9F0411F4604460D461646302383F351 +:10311000118800F110082378052B0DD02946204690 +:10312000FFF710FF40B1204632462946FFF722FF45 +:10313000002080F3118808E03946404600F018F975 +:103140000028E8D0002383F31188BDE8F081000057 +:1031500000238268037503691B6899689142FBD25A +:103160005A680360426010605860704700238268AC +:10317000037503691B6899689142FBD85A6803601C +:10318000426010605860704708B50846302383F3EA +:1031900011880B7D032B05D0042B0DD02BB983F3A5 +:1031A000118808BD00228B691A604FF0FF338361DC +:1031B000FFF7CEFF0023F2E7D1E9003213605A6037 +:1031C000F3E70000FFF7C4BF054BD968087518681E +:1031D000026853601A6001220275D860FDF796BB41 +:1031E000D823002030B50C4B0446DD684B1C87B05B +:1031F0000FD02B466846094A00F0F0F82046FFF74A +:10320000E3FF009B13B1684600F0F0F8A86907B02F +:1032100030BDFFF7D9FFF9E7D82300208931000836 +:10322000044B1A68DB6890689B68984294BF002042 +:1032300001207047D8230020084B10B51C68D868BF +:10324000226853601A6001222275DC60FFF78EFF4E +:1032500001462046BDE81040FDF758BBD8230020AA +:10326000044B1A68DB6892689B689A4201D9FFF7A1 +:10327000E3BF7047D823002038B501230025064C52 +:10328000064907482370656000F020FB0223237085 +:1032900085F3118838BD00BF30250020AC3D000803 +:1032A000D823002000F0B4B8EFF3118020B9EFF379 +:1032B0000583302282F311887047000010B530B9C1 +:1032C000EFF30584C4F3080414B180F3118810BD32 +:1032D000FFF7C6FF84F31188F9E700008B60022333 +:1032E00008618B82084670478368A3F1440243F863 +:1032F000142C026943F8442C426943F8402C094AD3 +:1033000043F8242CC268A3F1200043F8182C0222B1 +:1033100003F80C2C002203F80B2C034A43F8102C62 +:10332000704700BF1D090008D823002008B5FFF72B +:10333000DBFFBDE80840FFF745BF0000024BDB683C +:1033400098610F20FFF740BFD8230020302383F37C +:103350001188FFF7F3BF000008B50146302383F35F +:1033600011880820FFF73EFF002383F3118808BD72 +:10337000064BDB6839B1426818605A6013604360DD +:103380000420FFF72FBF4FF0FF307047D8230020F5 +:1033900038B504460D462068844200D138BD036824 +:1033A00023605C608561FFF70DFFF4E710B50A4C00 +:1033B00023699A6891420CD85A6881600360426020 +:1033C00010609A685860511A99604FF0FF33A361FA +:1033D00010BD1B68891AECE7D8230020C0E903233D +:1033E000002310B410BC4361FFF7E0BF036881689D +:1033F0009A680A449A60426813605A6000234FF04A +:10340000FF320360014B9A61704700BFD823002050 +:1034100070B5124D2A46EB690133EB6152F8103F4B +:10342000934206D030269A68013A9A602C69A368C4 +:1034300003B170BDD4E900210A605160236083F3B9 +:1034400011882046D4E90331984786F311886169D1 +:103450000029EBD02046FFF7A9FFE7E7D82300209B +:1034600000207047FEE70000704700004FF0FF307B +:1034700070470000BFF34F8F024AD368DB07FCD4CC +:10348000704700BF0020024008B5074B1B7853B9B6 +:10349000FFF7F0FF054B1A69120641BF044A5A6054 +:1034A00002F188325A6008BD482500200020024001 +:1034B0002301674508B5054B1B7833B9FFF7DAFFE1 +:1034C000034A136943F08003136108BD48250020B7 +:1034D000002002407F289ABF00F5003080020020C3 +:1034E000704700004FF480607047000080207047F4 +:1034F0007F2808B50BD8FFF7EDFF00F58063026861 +:10350000013204D104308342F9D1012008BD0020EA +:10351000FCE700007F2810B504461CD8FFF7AAFF7F +:10352000FFF7B2FFF3220D4B4FF48061DA60022205 +:103530001A61FFF7CFFF58611A6942F040021A6121 +:10354000FFF798FF00F004F9FFF7B4FF2046BDE84D +:103550001040FFF7CDBF002010BD00BF002002408B +:103560002DE9F843054612F00100144606D040F25A +:10357000F32200201E4B1A60BDE8F8831D4BAA18E9 +:103580009A4204D94FF43E72194B1A60F4E7FFF7E0 +:103590007BFF4FF00109FFF76DFFDFF85C806D1ACC +:1035A000012C0F4605EB010603D8FFF783FF01202E +:1035B000E2E73B88C8F8109033800020FFF75AFFFD +:1035C000C8F81000338831F8022B9BB29A420CD015 +:1035D00040F20F32064B1A60084B1E60084B1C600D +:1035E000084B1F60FFF766FFC6E7023CD8E700BF45 +:1035F0004425002000000208002002403825002059 +:10360000402500203C250020084908B50B7828B14A +:103610001BB9FFF739FF01230B7008BD002BFCD04D +:10362000BDE808400870FFF745BF00BF48250020EF +:1036300070B5FFF739FE4FF47A710D4B0D4EDB6913 +:10364000326801FB03F3934237BF0B4A0A495168C2 +:10365000156836BF4C1CD1E9005454605D1944F123 +:1036600000043360FFF72AFE2846214670BD00BFE4 +:10367000D82300204C2500205025002070B5FFF7EE +:1036800013FE4FF47A710F4B0F4EDB69326801FB6A +:1036900003F3934237BF0D4A0C49516815683ABF8E +:1036A0004C1C5460D1E900545D1944F100043360AE +:1036B000FFF704FE4FF47A72002328462146FCF7F8 +:1036C00031FF70BDD82300204C250020502500205C +:1036D00010B5094C013AD2B2FF2A00D110BD5008F2 +:1036E00054F82030013054F820009BB243EA0043E4 +:1036F00041F8043BEEE700BF046C004010B50748FA +:10370000013AD2B2FF2A00D110BD0C88530840F80C +:1037100023404C88013340F82340F1E7046C00401B +:1037200007B50122002001A9FFF7D2FF019803B0DD +:103730005DF804FB13B50446FFF7F2FFA04205D085 +:103740000122002001A90194FFF7D8FF02B010BDAB +:103750007047000045F25552064B1A6002225A602B +:1037600040F6FF729A604CF6CC421A600122024B7E +:103770001A707047003000405C250020034B1B7816 +:103780001BB14AF6AA22024B1A6070475C25002042 +:1037900000300040044B1A682AB902F1804202F559 +:1037A0000432526A1A607047582500204FF0807228 +:1037B000014B5A62704700BF0010024008B5FFF786 +:1037C000E9FF024B1868C0F3407008BD582500207F +:1037D00008B5FFF7DFFF024B1868C0F3007008BDA3 +:1037E00058250020EFF30983203383F30988002351 +:1037F00083F3118870470000302080F3118862B68F +:103800000C4B0D4AD96821F4E0610904090C0A4304 +:10381000DA60D3F8FC20094942F08072C3F8FC203A +:103820000A6842F001020A602022DA7783F8220057 +:10383000704700BF00ED00E00003FA05001000E053 +:10384000302310B583F311880B4B5B6813F40063CE +:103850000FD0EFF309844FF08073203CE36184F3D1 +:103860000988FFF7DDFC10B1044BA36110BD044BC8 +:10387000FBE783F31188F9E700ED00E02F0900086A +:103880003209000870470000FEE700000A4B0B48B1 +:103890000B4A90420BD30B4BC11EDA1C121A22F0BA +:1038A00003028B4238BF00220021FDF7FFBE53F810 +:1038B000041B40F8041BECE72C3E0008E025002028 +:1038C000E0250020E0250020FEE7000070B500257F +:1038D00004461A4B86B05860856201630E46FFF7B6 +:1038E0008BFF04F11003C4E904334FF0FF33A361ED +:1038F000134BE561D9692B460A462046C4E90823E3 +:1039000004F134018023C4E900440E4AA560E56255 +:103910002565FFF7E3FC01230B4AE0600375009285 +:10392000726868460192B268CDE90223074BCDE97F +:103930000435FFF7FBFC06B070BD00BF302500204A +:10394000D8230020B83D0008BD3D0008C938000854 +:1039500000F030B808B500F063F9FFF78DFCBDE862 +:103960000840FFF717BF0000704700004FF0FF311D +:103970000E4B1A6919611A6900221A611869D86810 +:10398000D960D968DA60DA68DA6942F08052DA61BF +:10399000DA69DA6942F00062DA61054ADB691368C4 +:1039A00043F48073136000F01BB900BF00100240A5 +:1039B00000700040194B1A6842F001021A601A6840 +:1039C0009007FCD51A6802F0F9021A6000225A60CA +:1039D0005A6812F00C0FFBD11A6842F480321A6058 +:1039E0001A689103FCD55A6842F4E8125A601A68C2 +:1039F00042F080721A601A689201FCD51221084ABE +:103A00005A60084A11605A6842F002025A605A68C5 +:103A100002F00C02082AFAD1704700BF00100240E1 +:103A200000641D0000200240084A08B5516913686F +:103A30000B4003F00103536123B1054A13680BB136 +:103A400050689847BDE80840FFF7FABE00040140FF +:103A500060250020084A08B5516913680B4003F03F +:103A60000203536123B1054A93680BB1D0689847AC +:103A7000BDE80840FFF7E4BE0004014060250020D7 +:103A8000084A08B5516913680B4003F004035361F9 +:103A900023B1054A13690BB150699847BDE8084046 +:103AA000FFF7CEBE0004014060250020084A08B59B +:103AB000516913680B4003F00803536123B1054AB1 +:103AC00093690BB1D0699847BDE80840FFF7B8BECD +:103AD0000004014060250020084A08B551691368B8 +:103AE0000B4003F01003536123B1054A136A0BB175 +:103AF000506A9847BDE80840FFF7A2BE00040140A5 +:103B000060250020174B10B55A691C68144004F456 +:103B100078725A61A30604D5134A936A0BB1D06A2E +:103B20009847600604D5104A136B0BB1506B984749 +:103B3000210604D50C4A936B0BB1D06B9847E20574 +:103B400004D5094A136C0BB1506C9847A30504D5F2 +:103B5000054A936C0BB1D06C9847BDE81040FFF755 +:103B60006FBE00BF00040140602500201A4B10B555 +:103B70005A691C68144004F47C425A61620504D5F9 +:103B8000164A136D0BB1506D9847230504D5134A9F +:103B9000936D0BB1D06D9847E00404D50F4A136EB6 +:103BA0000BB1506E9847A10404D50C4A936E0BB12B +:103BB000D06E9847620404D5084A136F0BB1506F5A +:103BC0009847230404D5054A936F0BB1D06F9847EB +:103BD000BDE81040FFF734BE00040140602500201E +:103BE000062108B50846FFF721FA06210720FFF74E +:103BF0001DFA06210820FFF719FA06210920FFF710 +:103C000015FA06210A20FFF711FA06211720FFF7FF +:103C10000DFABDE8084006212820FFF707BA00008A +:103C200008B5FFF7A3FE054800F00CF8FFF71CFAF3 +:103C3000FFF79AFEBDE8084000F002B8C43D000856 +:103C400000F042B8002319461C4A0133102BC2E988 +:103C5000001102F10802F8D1194B9A6942F07D0275 +:103C60009A619B690268174BDA6082685A60426801 +:103C70001A60C26803F58063DA6042695A600269BB +:103C80001A608269C3F80C24026AC3F80424C2696A +:103C9000C3F80024426AC3F80C28C26AC3F8042897 +:103CA000826AC3F80028026BC3F80C2C826BC3F83D +:103CB000042C426BC3F8002C704700BF6025002025 +:103CC00000100240000801404FF0E023044A0821A0 +:103CD0005A6100229A6107220B201A61FFF7BCB9D2 +:103CE0003F19010008B5302383F31188FFF7DAFA92 +:103CF000002383F3118808BD08B5FFF7F3FFBDE883 +:103D00000840FFF79DBD000010B501390244904204 +:103D100001D1002005E0037811F8014FA34201D042 +:103D2000181B10BD0130F2E72DE9F0419BB10446AC +:103D3000C91A1778014403F1FF3C8C42204601D98F +:103D4000002008E005780134BD42F6D10CEB0405F3 +:103D5000D618A54201D1BDE8F08115F8018D16F8FD +:103D600001EDF045F5D0E8E7034611F8012B03F823 +:103D7000012B002AF9D170476F72672E617264754A +:103D800070696C6F742E663130332D4169727370B7 +:103D90006565640040A2E4F1646891060041A3E512 +:103DA000F26569920700000063300000A83D00083A +:103DB00030240020302500206D61696E0069646C3C +:103DC0006500000000180000444441444454494444 +:103DD00001000000424444444444444400000000C4 +:103DE00044444444444444440000000044444444A3 +:103DF0004444444400000000444444444444444493 +:103E000054C7FF7F01000000E8030000000000002D +:103E1000009C0100000000006400000000000000A1 +:0C3E200040420F00FE2A0100D204000006 :00000001FF diff --git a/Tools/bootloaders/f103-GPS_bl.bin b/Tools/bootloaders/f103-GPS_bl.bin index d3e5b71c81ab90..5b6a77a88f3fd6 100755 Binary files a/Tools/bootloaders/f103-GPS_bl.bin and b/Tools/bootloaders/f103-GPS_bl.bin differ diff --git a/Tools/bootloaders/f103-GPS_bl.hex b/Tools/bootloaders/f103-GPS_bl.hex index 33ff7afe6a4e29..301d4e22175d65 100644 --- a/Tools/bootloaders/f103-GPS_bl.hex +++ b/Tools/bootloaders/f103-GPS_bl.hex @@ -1,963 +1,997 @@ :020000040800F2 -:100000000009002069040008C114000865140008F4 -:10001000A514000865140008851400086B04000886 -:100020006B0400086B0400086B0400087D350008B1 -:100030006B0400086B0400086B040008113A000808 -:100040006B0400086B0400086B0400086B040008D4 -:100050006B0400086B0400083D370008693700088E -:1000600095370008C1370008ED3700086B04000819 -:100070006B0400086B0400086B0400086B040008A4 -:100080006B0400086B0400086B040008712400086E -:10009000DD240008312500088525000819380008EE -:1000A0006B0400086B0400086B0400086B04000874 -:1000B0006B0400086B0400086B0400086B04000864 -:1000C0006B0400086B0400086B0400086B04000854 -:1000D0006B04000825290008392900086B04000872 -:1000E000813800086B0400086B0400086B040008EA -:1000F0006B0400086B0400086B0400086B04000824 -:100100006B0400086B0400086B0400086B04000813 -:100110006B0400086B0400086B0400086B04000803 -:100120006B0400086B0400086B0400086B040008F3 -:100130006B0400086B0400086B0400086B040008E3 -:100140006B0400086B0400086B0400086B040008D3 -:100150006B0400086B0400086B0400086B040008C3 -:1001600053B94AB9002908BF00281CBF4FF0FF311E -:100170004FF0FF3000F076B9ADF1080C6DE904CE18 -:1001800000F006F8DDF804E0DDE9022304B0704772 -:100190002DE9F047089E0D4604468846002B4DD1B8 -:1001A0008A42944668D9B2FA82F252B101FA02F355 -:1001B000C2F1200120FA01F10CFA02FC41EA030825 -:1001C00094404FEA1C41B8FBF1F71FFA8CFE01FB8B -:1001D000178807FB0EF0230C43EA084398420AD91C -:1001E0001CEB030307F1FF3580F01E81984240F2BB -:1001F0001B81023F63441B1AB3FBF1F001FB103378 -:1002000000FB0EFEA4B244EA0344A6450AD91CEB47 -:10021000040400F1FF3380F00981A64540F2068115 -:10022000644402380021A4EB0E0440EA07401EB1EA -:100230000023D440C6E90043BDE8F0878B4208D9CB -:10024000002E00F0EE800021C6E900050846BDE85A -:10025000F087B3FA83F100294AD1AB4202D382423C -:1002600000F2FC80841A65EB030301209846002EFF -:10027000E2D0C6E90048DFE702B9FFDEB2FA82F257 -:10028000002A40F09180A1EB0C0001214FEA1C47AD -:100290001FFA8CFEB0FBF7F307FB1300250C45EAB1 -:1002A00000450EFB03F0A84208D91CEB050503F13D -:1002B000FF3802D2A84200F2CE8043462D1AB5FB89 -:1002C000F7F007FB10550EFB00FEA4B244EA05440C -:1002D000A64508D91CEB040400F1FF3502D2A6455F -:1002E00000F2B6802846A4EB0E0440EA03409EE7E5 -:1002F000C1F120078B4022FA07FC4CEA030C25FAD7 -:1003000007FA4FEA1C49BAFBF9F820FA07F309FB90 -:1003100018AA8D401FFA8CFE1D4300FA01F308FB5A -:100320000EF02C0C44EA0A44A04202FA01F20BD966 -:100330001CEB040408F1FF3A80F08880A04240F2F0 -:100340008580A8F102086444241AB4FBF9F009FB83 -:10035000104400FB0EFEADB245EA0444A64508D9A0 -:100360001CEB040400F1FF356CD2A6456AD90238B3 -:10037000644440EA0840A0FB0295A4EB0E04AC42A2 -:10038000C846AE4656D353D0002E69D0B3EB080210 -:1003900064EB0E0422FA01F304FA07F71F43CC4082 -:1003A000C6E90074002147E70CFA02FCC2F1200103 -:1003B00025FA01F34FEA1C4720FA01F195400D435D -:1003C000B3FBF7F107FB11331FFA8CFE280C40EA50 -:1003D000034001FB0EF3834204FA02F408D91CEB3C -:1003E000000001F1FF382FD283422DD90239604439 -:1003F000C01AB0FBF7F307FB1300ADB245EA0045A6 -:1004000003FB0EF0A84208D91CEB050503F1FF38E9 -:1004100016D2A84214D9023B6544281A43EA014186 -:1004200038E73146304607E72F46E4E61846F9E656 -:100430004B45A9D2B9EB020865EB0C0E0138A3E7D6 -:100440004346EAE7284694E74146D1E7D0467BE7B2 -:100450006444023847E7023B65442FE7084606E755 -:100460003146E9E6704700BF02E000F000F8FEE721 -:1004700072B6284880F30888274880F309882748FF -:100480004EF60851CEF200010860022080F3148875 -:10049000BFF36F8F03F0E4F803F0C0F803F0E2F865 -:1004A0004FF055301E491B4A91423CBF41F8040BA6 -:1004B000FAE71C49184A91423CBF41F8040BFAE79D -:1004C00019491A4A1A4B9A423EBF51F8040B42F896 -:1004D000040BF8E700201749174A91423CBF41F846 -:1004E000040BFAE703F09EF803F0BEF8134C144D2A -:1004F000AC4203DA54F8041B8847F9E700F03CF8F3 -:10050000104C114DAC4203DA54F8041B8847F9E74C -:1005100003F086B800090020001100200000000848 -:100520000001002000090020E03B0008001100202D -:100530002411002028110020A025002060010008BF -:100540006001000860010008600100082DE9F04F1B -:10055000C1F80CD0C3689D46BDE8F08F002383F33B -:1005600011882846A047002002F09CFDFEE702F01B -:1005700021FD00DFFEE700002DE9F04102F09CFFC5 -:10058000074602F0E7FF054600283ED12B4B9F426D -:100590003BD001339F423BD0294B27F0FF029A42C8 -:1005A0003AD1F8B200F052FAA84642F2107400F0C4 -:1005B00057FC08B10024A04600F04EFA064678B376 -:1005C00084BB464635B11F4B9F4203D0002402F046 -:1005D000B9FF2646002002F079FF1B4B9B6813F001 -:1005E000400322D00EB100F031F800F097FC00F08B -:1005F00077FE00F067FF0546CCB100F063FF401BBB -:10060000A04214D900F022F8F3E7A8460024CEE770 -:1006100004464FF00108CAE780464FF47A74C6E7F3 -:100620000446CFE74FF47A74CCE71C46DDE700F0D0 -:1006300025FD012002F03CFDDEE700BF010007B010 -:10064000000008B0263A09B0000C014038B51D4A38 -:100650001D4B1968013134D004339342F9D11B4C3E -:10066000194DD4F80424AA422BD3194B9B6803F1EB -:10067000006303F5C8439A4223D202F037FF02F029 -:1006800049FF002000F046FE0220124B187000F0D7 -:100690007DFE114BDA690022DA61D96999699A61A4 -:1006A0009B6972B64FF0E023C3F8085DD4F80034BC -:1006B000D4F80424202181F311889D4683F308880F -:1006C000104738BD2064000800640008006000087E -:1006D00000110020281100200010024049F269009A -:1006E000084A136899B21B0C00FB013344F25061B5 -:1006F0001360054B186882B2000C01FB0200186001 -:1007000080B27047201100201C11002010B5044653 -:100710000021102200F056FE034B03CB20606160E5 -:100720001868A06010BD00BFE8F7FF1F2DE9F04377 -:10073000BBB000F0C7FE40F2ED22204DAB68C31AFB -:10074000934232D906AF2B4628220021A8603846B2 -:1007500001F0C2FB05F10E0000F02CFE002604465D -:100760005FFA80F905F10E08F3B2F100994501F145 -:10077000280107D908EB06030822384601F0ACFB34 -:100780000136F1E708230122CDE902320C4B053492 -:1007900001933023A4B20093CDE9047405A3D3E9F7 -:1007A0000023297B074801F0ADF93BB0BDE8F08399 -:1007B000AFF3008078F6339F93CACD8D702100206F -:1007C0007D2100204421002070B50D4614461E46B0 -:1007D00001F02EF950B9022E10D1012C0ED112A326 -:1007E000D3E900230120C5E9002307E0282C10D01D -:1007F00005D8012C09D0052C0FD0002070BD302C5D -:10080000FBD10BA3D3E90023ECE70BA3D3E900232F -:10081000E8E70BA3D3E90023E4E70BA3D3E9002324 -:10082000E0E700BFAFF30080401DA12026812A0B26 -:1008300078F6339F93CACD8D9E6AC421818A46EE95 -:1008400026417272DF25D7B7F017304A39059E5618 -:1008500038B50D460446034620222846002101F003 -:100860003BFB22792346032A28BF0322284603F8AC -:10087000042F2021022201F02FFB62792346072A50 -:1008800028BF0722284603F8052F2221032201F062 -:1008900023FBA2792346072A28BF0722284603F80C -:1008A000062F2521032201F017FB284610222821BC -:1008B00004F1080301F010FB382038BD2DE9F04F9A -:1008C0000024ADF5017D0EAE40F2751280460F4654 -:1008D00022A82146219400F075FD21464822304689 -:1008E00000F070FD00F0EEFD4FF47A72B0FBF2F014 -:1008F000544B21AD186093E80700012386E80700F8 -:100900000DF15A003382FFF701FF4EF603033384E3 -:1009100007AB18464C4903F0B3F81B222946306454 -:10092000304686F83C20FFF793FF08220446014634 -:1009300012AB284601F0D0FA08222846A1180DF182 -:10094000490301F0C9FA082228460DF14A0304F1CF -:10095000100101F0C1FA2022284613AB04F118015E -:1009600001F0BAFA4022284614AB04F1380101F034 -:10097000B3FA0822284616AB04F1780101F0ACFA6C -:10098000082228460DF1590304F1800101F0A4FA70 -:1009900004F1880A0DF15A0904F5847B4B4651464F -:1009A000082228460AF1080A01F096FAD34509F10F -:1009B0000109F3D10822594628461BAB01F08CFAF5 -:1009C0004FF0000904F5887496F834304B450AD985 -:1009D000B36B21464B440822284601F07DFA0834C7 -:1009E00009F10109F0E74FF0000996F83C3004EBFB -:1009F000C9014B4508D9336C08224B44284601F005 -:100A00006BFA09F10109F0E700230393BB7E07317C -:100A1000029307F1190301930123C1F3CF01CDE93B -:100A200004510093404605A3D3E90023F97E01F069 -:100A300069F80DF5017DBDE8F08F00BF9E6AC42105 -:100A4000818A46EE2C110020903A0008014B187064 -:100A5000704700BF38110020F0B5334B85B01C7BC8 -:100A600034B10E22314B1A810024204605B0F0BD6E -:100A70002F4A02AB1068516803C308232D492E4842 -:100A80000DEB030202F0DCFF054630B90A22274BCA -:100A90002A481A8100F0E2FCE6E70169B1F5CE3F91 -:100AA00006D90B22214B26481A8100F0D7FCDCE73F -:100AB000438BB3F57A7F09D00C211C4A2148118160 -:100AC0004FF47A72194600F0C9FCCEE71E4A024480 -:100AD00002F11003994204D21022144B1B481A81D0 -:100AE000E3E710398E1A2046134900F0EFFC074661 -:100AF0003246204605F1180100F0E8FCAB689F4241 -:100B000002D1EB6898420AD00D22084B1A8100905E -:100B10003B46D5E902120E4800F0A0FCA4E70D48C0 -:100B200000F09CFC0124A0E7702100202C11002083 -:100B30003D3B0008DC9B010000640008AC3A000863 -:100B4000B83A0008CA3A0008089CFFF7E83A0008DB -:100B5000053B00082E3B00082DE9F04FADB006AF75 -:100B600080460C4600F064FF0546002859D1237EDC -:100B7000022B1AD1E38A012B17D100F0A3FC064601 -:100B8000FFF7ACFD4FF4C873B0FBF3F202FB1300A8 -:100B9000DFF8B49206F5167680B2E37E0644C9F813 -:100BA000006033B90022A94B1A709C37BD46BDE8DE -:100BB000F08FA38AEEB2013BB34205F101050BD9D8 -:100BC0003B1D1E44E900002308222046009601F048 -:100BD000F80101F043F8ECE707F11400FFF796FD88 -:100BE000324607F11401381D02F01AFF03460028AF -:100BF000D8D10F2E08D8954B1E70D9F80030A3F528 -:100C00001673C9F80030D0E7FA1CF870014600925C -:100C10002046072201F022F84046F97800F000FF54 -:100C2000C3E7E38A282B26D010D8012B1ED0052B32 -:100C3000BBD1BFF34F8F8649864BCA6802F4E0628E -:100C40001343CB60BFF34F8F00BFFDE7302BACD118 -:100C5000637E814D01336A7BDBB29342E94603D167 -:100C6000E27E2B7B9A4265D0CD469EE721464046E8 -:100C7000FFF724FE99E7A38A013B9BB2C92B94D8C6 -:100C8000754D2E7B26BB05F10C03009308223346DD -:100C90003146204600F0E2FF731CF2B2D9001E4636 -:100CA000A38A013B9A4205DA0E322A4400920023BD -:100CB0000822EEE700230022C5E900230023AB60F1 -:100CC00085F8D730C5F8D8302B7B0BB9E37E2B7372 -:100CD000002507F114060822294630463B1DC7E9C6 -:100CE0000155FD6001F0F8F83B7A05F10109AB42CE -:100CF0004FEAC90107D9FB6808222B44304601F0AE -:100D0000EBF84D46F0E70023C1F3CF01E07ECDE9DB -:100D100004610393A37E19340293282301460093B0 -:100D2000404647A3D3E90023019400F0EBFEFFF710 -:100D3000FDFC3AE74FF0000807F11403A7F8148010 -:100D40001022009341460123204600F087FFA68A27 -:100D5000023EB6B2F31C9B109B000733DB08A9EBE5 -:100D6000C3039D460DF1180A1FFA88F34FEAC80124 -:100D7000B34201F110010AD20AEB080300930822E2 -:100D80000023204600F06AFF08F10108ECE795F81F -:100D9000D70000F0C9FAD5F8D83004461BB995F849 -:100DA000D70000F0D1FAD5F8D83033449C4204D2B1 -:100DB00095F8D700013000F0C7FA4FF000084FEA6D -:100DC000960B1FFA88F18B45D5E9003209D90AEB59 -:100DD000880103EB8800012200F0FCFA08F1010809 -:100DE000EFE7F31842F10002C5E90032D5F8D83038 -:100DF00095F8D70006EB0308C5F8D88000F094FA00 -:100E0000804509D395F8D730D5F8D8000133001BB9 -:100E100085F8D730C5F8D800FF2E08D800232B73EB -:100E200000F0A4FAFFF718FE08B1FFF70FFC2B68DB -:100E30000A4A9B0A013313810023AB6014E700BF09 -:100E400026417272DF25D7B7402100203D210020C6 -:100E500000ED00E00400FA05702100202C110020B4 -:100E600030B54FF00054244B226885B09A4207D029 -:100E700002F07AFB0446A8B90024204605B030BD34 -:100E8000627D1E4B1E481A70237DC92203731D49C3 -:100E90000E3000F085FA2046E022002100F092FAA0 -:100EA0000124EAE7184A194DD36943F00073D3616E -:100EB000AA6D174B9A42DFD12B6E013B7E2BDBD8FC -:100EC000144A01AB07CA83E807001846032100F063 -:100ED00013FB6B6D83424FF00003CDD12A6D8A4224 -:100EE00003BFAB652A6E054B1C4601BF1A70EA6D45 -:100EF000094B1A60C1E700BF9AAD44C53811002004 -:100F00007021002016000020001002400066004002 -:100F10005041A0B0586600401811002002232DE96E -:100F2000F0434A4C85B0637100230293484BD3F8D9 -:100F300000C0BCF57A7F12D3464F474BB7FBFCF598 -:100F40009C458CBF0A231123B5FBF3F603FB165215 -:100F5000591EC8B2002A3ED002290B46F4D89DF88B -:100F60000B303E495A1E9DF80A303D48013B1B0498 -:100F700043EA0253BDF80820013A13434B6001F0E5 -:100F800037FD00230193374B374900934FF48052CC -:100F9000364B374800F01CFD364B197811B13448F8 -:100FA00000F03EFD00F08EFA0546FFF797FB4FF488 -:100FB000C873B0FBF3F202FB130305F516709BB286 -:100FC00018442D4B186002F0C5FA08B10F23238195 -:100FD00005B0BDE8F083731EB3F5806FBFD24FF448 -:100FE0007A75C0EBC00E0EF103034FEAE30909FB6B -:100FF0000555C3F3C703C11AC9B209F101088844F2 -:10100000B5FBF8F5B5F5617F08D90EF1FF33C3F3F1 -:10101000C703C11A581E0F28C9B214D84A1E072A7E -:101020008CBF00220122581800FB0660B7FBF0F7C6 -:10103000BC4594D1002A92D0ADF808608DF80A30F2 -:101040008DF80B108BE71346EDE700BF2C11002045 -:1010500018110020005125023F420F0010110020FE -:1010600088220020C90700083C110020590B000805 -:101070004421002038110020402100202DE9F04FAC -:1010800093A7D7E900670FF25029D9E90089854D68 -:1010900093B0DFF814B2854C284600F097FD0DF1AF -:1010A000300A079070B310220021504600F08AF9F0 -:1010B0004FF00002079B197B61F303028DF830208B -:1010C000586899680EAA03C21B680D9A584663F3C4 -:1010D0001C029DF830300D9243F020038DF8303023 -:1010E00000235246194601F093FC079028B9284680 -:1010F00000F070FD079B2370CEE72378072B3CD8C8 -:101100000133237018220021504600F05BF9DFF80C -:1011100098B1674C002352461946584601F0A0FC8E -:10112000014670BB102208A800F04CF9E36883F078 -:101130001003E36000F0C8F90DF1240C0B4612A96E -:10114000024611E903008CE803009DF83410C1F356 -:101150000300890649BF0E99BDF83810C1F31C0180 -:1011600041F0004158BFC1F30A018DF82C000891ED -:10117000284608A900F0F8FECCE7284600F02AFD32 -:10118000C0E7284600F054FC8346002844D100F014 -:1011900099F9484B1A6890423ED300F093F90446FF -:1011A000FFF79CFA4FF4C872B0FBF2F101FB12009A -:1011B0008DF820B0DFF800B13E4B04F5167480B214 -:1011C0009BF8001004441C6011B901238DF82030F5 -:1011D00050460791FFF79AFA07990DF12100C1F1E6 -:1011E0001004E4B2062C28BF06245144224600F025 -:1011F000D7F808AB039318230293304B01340193C3 -:101200000123E4B2009332463B462846049400F0A2 -:1012100011FC00238BF8003000F054F9284A294CC7 -:101220001368C31AB3F57A7F31D3106000F04CF91C -:1012300002460B46284600F0D7FC284600F0F8FB93 -:1012400028B3237BDFF880B0002B14BF03230223D5 -:101250008BF8053000F036F94FF47A73B0FBF3F0F9 -:101260005146CBF800005846FFF7F2FA18230293D4 -:10127000164B0730019340F25513C0F3CF00CDE970 -:1012800003A0009342464B46284600F0D3FB237B45 -:101290002BB1FFF74BFA237B002B7FF4FAAE13B090 -:1012A000BDE8F08F44210020882200205522002034 -:1012B00000080140402100203D2100203C21002069 -:1012C00050220020702100202C11002054220020E8 -:1012D000401DA12026812A0BF1C6A7C1D068080FA6 -:1012E00070B501F0BFFF0024084E094D308028681A -:1012F0003388834208D901F0B1FF2B6804440133DD -:10130000B4F5C84F2B60F2D370BD00BF842200201B -:101310005822002002F044B800F10060920000F56D -:10132000C84001F0DFBF0000054B1A68054B1B8861 -:101330009B1A834202D9104401F090BF00207047ED -:10134000582200208422002038B50446064D286823 -:10135000204401F089FF28B928682044BDE83840BE -:1013600001F094BF38BD00BF58220020064991F813 -:10137000243033B100230822086A81F82430FFF7B3 -:10138000CBBF0120704700BF5C220020022802BFB3 -:101390004FF48012014B1A61704700BF00080140F2 -:1013A000002310B5934203D0CC5CC4540133F9E759 -:1013B00010BD000003460246D01A12F9011B002995 -:1013C000FAD1704703460244934202D003F8011B4E -:1013D000FAE770472DE9F8431F4D144695F824208D -:1013E0000746884652BBDFF870909CB395F82430CE -:1013F0002BB92022FF2148462F62FFF7E3FF95F823 -:1014000024004146C0F10802A24228BF224605EB53 -:101410008000D6B29200FFF7C3FF95F82430A41BDA -:101420001E44F6B2082E17449044E4B285F82460B6 -:10143000DBD1FFF79BFF0028D7D108E02B6A03EB35 -:1014400082038342CFD0FFF791FF0028CBD1002049 -:10145000BDE8F8830120FBE75C2200200FB40020E8 -:1014600004B07047EFF30983EFF30583044B9A6BE5 -:10147000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE72A -:1014800000ED00E0EFF30983EFF30583044B9A6B63 -:101490009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF8F -:1014A00000ED00E0EFF30983EFF30583034B5A6B84 -:1014B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E065 -:1014C000FEE7000001F0A6BF01F07EBF30B5094D78 -:1014D0000A4491420DD011F8013B5840082340F3D3 -:1014E0000004013B2C4013F0FF0384EA5000F6D1C6 -:1014F000EFE730BD2083B8ED4FF0FF33F7B500EBD9 -:1015000081061946DFF848C0DFF848E0B0421BD03A -:1015100050F8042B01AF0192042217F8014B81EA25 -:10152000046108240D46DB184941013C002DBCBF75 -:1015300083EA0C0381EA0E0114F0FF04F2D1013AB0 -:1015400012F0FF02E9D1E1E7D843C94303B0F0BD8F -:101550009336EAA9EBE1F0422DE9F041C56915B9EE -:10156000C161BDE8F0814B68AC4623F06047C3F32E -:101570008A4616EA230638BF3E464FEAD37EC3F3B7 -:1015800080782B465A68BEEBD27F22F060440AD0A6 -:10159000002A18DAA40CB44217D19D420FD10D6075 -:1015A000DEE71346EEE7A74207D102F08044C2F31C -:1015B000807242450BD054B1EFE708D2EDE7CCF88A -:1015C00000100B60CDE7B44201D0B442E5D81A68F0 -:1015D0009C46002AE5D11960C3E700002DE9F047D9 -:1015E0004FF47F49089D01F007044FEAD5082244D3 -:1015F00005F0070500EBD100944201D1BDE8F0876A -:1016000004F0070705F0070A57453E4638BF56461F -:10161000111BC6F108068E4228BF0E46E108415C48 -:1016200008EBD50E13F80EC0B94029FA06F721FAD7 -:101630000AF1FFB28CEA010147FA0AF739408CEA55 -:10164000010C03F80EC034443544D5E7082341F2B9 -:10165000210280EA012001B24000002980B203F19A -:10166000FF33B8BF504013F0FF03F4D170470000C0 -:1016700038B50C468D18A54200D138BD14F8011BB1 -:10168000FFF7E4FFF7E700000346006848B102688F -:1016900019891A60DA88013292B29142DA8038BF31 -:1016A0001A81704770B504460D4688B0202200218B -:1016B0006846FFF787FE20460495FFF7E5FF0246E0 -:1016C00058B16B46054608AE1C4603CCB4422860B0 -:1016D0006960234605F10805F6D1104608B070BDD3 -:1016E000082817D909280CD00A280CD00B280CD0B0 -:1016F0000C280CD00D280CD00E2814BF4020302010 -:1017000070470C2070471020704714207047182035 -:101710007047202070470000082817D90C280CD9E2 -:1017200010280CD914280CD918280CD920280CD929 -:1017300030288CBF0F200E207047092070470A20E8 -:1017400070470B2070470C2070470D207047000039 -:1017500010B54B6823B9CA8A63F30902CA8210BD67 -:10176000C4681A681C60C360438A013B43824A60B4 -:10177000EFE700002DE9F84F1D46CB8A0F46C3F373 -:1017800009010629814692460B4630D00020AAB2B4 -:1017900007F119049EB2052E1FFA80F80FD8904564 -:1017A00003F1010306D3FB8A0A4462F30903012013 -:1017B000FB821AE01AF800600130E654EAE790452F -:1017C000F1D21C23A1F1060BBBFBF3F203FB12BB0E -:1017D0007C681FFA8BF6002C45D14846FFF754FF72 -:1017E000044638B978606FF00200BDE8F88F4FF01A -:1017F0000008E6E70026066078604FF0000BADB207 -:10180000454510D90AEB0803221D13F8011B08F106 -:1018100001089155B1B21B291FFA88F82BD0454514 -:1018200006F10106F1D8FB8AC3F30902154465F3FA -:101830000903BCE71C46013292B22368002BF9D1A0 -:10184000AB1F0B441C21B3FBF1F301339BB29A4253 -:10185000D3D2BBF1000FD0D14846FFF715FF20B916 -:10186000C4F800B0BFE70122E7E7C0F800B05E4669 -:1018700020600446C1E74545D5D94846FFF704FF37 -:1018800008B92060AFE7C0F800B000262060044629 -:10189000B6E700002DE9F04F85B007469146CDE947 -:1018A0000113BDF83C50002A00F08F802DB10E9B33 -:1018B000002B00F08A80072D30D807F10C00FFF7CD -:1018C000E3FE044628B96FF00204204605B0BDE8E7 -:1018D000F08F14220021FFF775FD2A460E9904F1BE -:1018E0000800FFF75DFD681CC0B2FFF715FFFFF7AA -:1018F000F7FE207499F80020431E9BB202F01F02ED -:10190000234462F03F021A72019B384643F00041C3 -:1019100061602146FFF720FE0124D6E74FF0000862 -:101920004FF0800A4646444600F10C0303930398A7 -:10193000FFF7AAFE83460028C5D014220021FFF736 -:1019400041FD002E38D10220029BABF808300E9BDF -:1019500000F10802D2B299195A440130C0B20828E5 -:1019600001D0AE422AD3FFF7D7FEFFF7B9FEAE4251 -:1019700008BF4FF0400A99F80020019B411E02F079 -:101980001F0242EA4812C9B24AEA020A594443F025 -:10199000004281F808A08BF8100059463846CBF871 -:1019A0000420FFF7D9FD0134AE424FF0000A24B203 -:1019B00088F00108BBD188E70020C8E711F801CB07 -:1019C000013602F801CBB6B2C7E76FF001047CE73D -:1019D000F8B5044615460E46282200211F46FFF79B -:1019E000F1FC069BB5F5001F6360079B28BF4FF60F -:1019F000FF7223624FF0000338BF6A09A76004F149 -:101A00000C0097B29A4205D80023036027826382B4 -:101A1000A382F8BD0660013330462036F2E70000AD -:101A200003781BB94BB2002BC8BF01707047000090 -:101A3000007870472DE9F74FDDF83C9080469246DC -:101A40009B46BDF830500D9E9DF83840BDF8407063 -:101A5000B9F1000F01D1002F51D11F2C4FD898F8A8 -:101A60000000B0B9072F47D835F0030347D13A46F5 -:101A700049464FF6FF70FFF7FBFD20F001002D02F5 -:101A8000400445EA0464400C44EA40244FF6FF73E6 -:101A900021E040EA0520072F40EA0464F6D900253A -:101AA0004FF6FF73C5F12000A5F120022AFA05F1D7 -:101AB0000BFA00F001432BFA02F211431846C9B2A7 -:101AC000FFF7C4FD0835402D0346EBD13A464946A1 -:101AD000FFF7CEFD0346324621464046CDE900974A -:101AE000FFF7D8FE33780133DBB21F2B88BF00230A -:101AF000337003B0BDE8F08F6FF00300F9E76FF0CB -:101B00000100F6E72DE9F04F85B0DDF848809246F8 -:101B100006469B460F9D9DF840209DF84490BDF8D9 -:101B20004C70B8F1000F01D1002F48D11F2A46D8C0 -:101B30003378002B46D00C0244EA02649DF838103A -:101B400044EAC93444EA01441C43072F44F08004AA -:101B500032D900234FF6FF72C3F1200CA3F120000D -:101B60002AFA03F10BFA0CFC41EA0C012BFA00F003 -:101B70000143C9B210460393FFF768FD039B024679 -:101B80000833402BE8D13A464146FFF771FD034642 -:101B90002A4621463046CDE90087FFF77BFEB9F1A2 -:101BA000010F06D12B780133DBB21F2B88BF002336 -:101BB0002B7005B0BDE8F08F4FF6FF73E8E76FF0CC -:101BC0000100F6E76FF00300F3E70000C06900B121 -:101BD00004307047C3691A68C261C2681A60C36082 -:101BE000438A013B438270472DE9F041D0F81880C9 -:101BF00014461D4641460027174E09B9BDE8F0813D -:101C0000D1E90223A21A65EB0303964277EB0303A3 -:101C10001ED283698B420DD1FFF79AFD83691B6841 -:101C20008361C3680B60438AC1608169013B884658 -:101C30004382E2E7FFF78CFD0B68C8F80030C36809 -:101C40000B60438AC160013B4382D8F80010D4E79F -:101C500088460968D1E700BF80841E002DE9F04F57 -:101C60008BB00D4614469B468046DDF85090002808 -:101C700000F01A81B9F1000F00F01681531E3F2BBE -:101C800000F21281012A03D1BBF1000F40F00C8158 -:101C90000023CDE90833B8F81430B5EBC30F4FEA91 -:101CA000C30703D300200BB0BDE8F08F2B199F4270 -:101CB000D8F80C3036BF7F1B2746FFB21BB9D8F8C7 -:101CC0001030002B7BD02F2D4ED8C5F13006B742F7 -:101CD0004FF0000334BF3E46F6B200932946324629 -:101CE000D8F8080008ABFFF779FCA7EB060A3544E3 -:101CF0005FFA8AFA3021B8F8143003F10053063B3A -:101D0000DB000493D8F80C300393039B13B1BAF1B2 -:101D1000000F2CD1D8F8100040B1BAF1000F05D057 -:101D20005246009608AB691AFFF758FC38B2002FEC -:101D3000B8D066070AD00AAB03EBD40111F8083C0F -:101D4000624202F00702134101F8083C082C3DD919 -:101D5000102C40F2B680202C40F2B880BBF1000F6E -:101D600000F09D80082335E0BA460026C2E7049BB8 -:101D7000E02B28BFE02306930B44AB42059315D913 -:101D80005A1B924538BF5246039828BFD2B20096DC -:101D9000691A08AB04300792FFF720FC079A164433 -:101DA000AAEB020A1544F6B25FFA8AFA049B069A75 -:101DB00005999B1A0493039B1B680393A5E7009363 -:101DC0003A462946D8F8080008ABADE7BBF1000F4A -:101DD00013D00123B4EBC30F6CD0082C12D89DF89C -:101DE0002030621E23FA02F2D50706D54FF0FF32EB -:101DF00002FA04F423438DF820309DF8203089F84E -:101E0000003050E7102C12D8BDF82030621E23FAA3 -:101E100002F2D10706D54FF0FF3202FA04F4234351 -:101E2000ADF82030BDF82030A9F800303BE7202C79 -:101E30000FD80899631E21FA03F3DA0705D54FF08E -:101E4000FF3202FA04F40C430894089BC9F80030EE -:101E500029E7402C2BD0DDE90865611EC4F1210281 -:101E6000A4F1210326FA01F105FA02F225FA03F39F -:101E700011431943CB0712D50122A4F12003C4F169 -:101E8000200102FA03F322FA01F1A240524243EA8E -:101E9000010363EB430332432B43CDE90823DDE920 -:101EA0000823C9E90023FEE66FF00100FBE66FF0AE -:101EB0000800F8E6082CA0D9102CB3D9202CEED8B5 -:101EC000C3E7BBF1000FADD0022383E7BBF1000FE6 -:101ED000BBD004237EE70000012A30B5144638BF8A -:101EE00001220025402A28BF402285B0012CCDE9DF -:101EF000025517D81B788DF8083053070AD004AB69 -:101F000003EBD20515F8083C544204F00704A34043 -:101F100005F8083C0346009102A80021FFF75EFB8C -:101F200005B030BD082CE5D9102C03D81B88ADF8BE -:101F30000830E2E7202C02D81B680293DDE7D3E9E2 -:101F40000045CDE90245D8E710B5CB681BB98B60D9 -:101F50000B618B8210BDC4681A681C60C360438A21 -:101F6000013B4382CA60F0E72DE9F04FD1F80080D1 -:101F700093B018F0800FCDE90323C8F3C01207BF58 -:101F80004FF0020B1646C8F3C03BC8F30626B8F163 -:101F9000000F04460D4680F2D48118F0C04305932B -:101FA00040F0CF810B7B002B00F0CB81BBF1020F07 -:101FB00003D00178B14240F0C78108F07F0107915A -:101FC0007AB3C8F3074A2B4493F80390760646EA9F -:101FD0000B4608F07F0246EA82465FEAD91346EADA -:101FE0000A06069300F0918000220023CDE90A231F -:101FF00008F07F03009352465B46204667680AA9B3 -:10200000B84700287ED0A7699FB9314604F10C007B -:10201000FFF748FB0746E0B96FF0020013B0BDE8D8 -:10202000F08FC8F30F2A18F07F0F08BF0AF0030AD9 -:10203000C9E73B699E420DD03F68002FF9D1314678 -:1020400004F10C00FFF72EFB07460028E4D0A3693B -:102050003B60A7610026DDE90A234FF6FF70C6F159 -:10206000200E22FA06F103FA0EFEA6F1200C23FA46 -:102070000CFC41EA0E0141EA0C01C9B20836099292 -:102080000893FFF7E3FADDE90832402EE7D1B88282 -:10209000FB7D09F01F06C3F384039B1B98B2002B42 -:1020A000BCBF00F120031BB2D7E9022152EA0100B4 -:1020B000C8F304680FD00398821A049860EB0101FA -:1020C000A74890424FF000028A4104D3069A002AA2 -:1020D0005BD0012B23DDFA7D4FEA890302F0030276 -:1020E00003F07C031343FB7539462046FFF730FBB2 -:1020F000069BA3B9FB7DC3F38402013262F386031E -:10210000FB7504E06FF00B0088E7A76917B96FF063 -:102110000C0083E73B699E42BAD03F68F6E719F0AE -:10212000400F32D0039B1422BB60049B0021FB6054 -:102130000DA8FFF747F9039B20460A93049BADF8CF -:102140003EA00B932B1D0C932B7B8DF840B0013BD5 -:10215000DBB2ADF83C30079B8DF841608DF8433021 -:1021600094F824308DF8428083F001038DF84430D8 -:102170000AA9A3689847FB7DC3F38403013303F0E6 -:102180001F039B02FB82002048E7FB7DC9F340123E -:10219000B2EBD31F40F0DB80C3F38403B34240F0C3 -:1021A000D98006992B7B4FEA9912002934D0D207A7 -:1021B00041D4032B40F2D180039BAE1DBB60049B36 -:1021C0003246FB602B7B3946033BDBB204F10C004B -:1021D000FFF7D0FA00280DDA20463946FFF7B8FAA3 -:1021E000FB7D0320C3F38403013303F01F039B0231 -:1021F000FB8213E7AB883B832A7B033AB88AD2B2CF -:102200003146FFF735FAFB7DB882DA43C2F3C012DC -:1022100062F3C713FB75B6E76AB92E1D013B324660 -:102220003946DBB204F10C00FFF7A4FA0028D3DB37 -:102230002A7B013AE2E7F98A013BC1F3090105294A -:10224000DAB25BD80023281D07F11A0C9A4208D98C -:1022500010F801EB01330CF801E001310629DBB283 -:10226000F4D1934228BF0023039938BF04330A9165 -:10227000049938BFDBB20B9107F11A010C91796810 -:1022800038BF5B190D910E93FB8AADF83EA0C3F3E6 -:1022900009031A44079BADF83C208DF8433094F8AD -:1022A00024308DF840B083F001038DF844300023D2 -:1022B0008DF841608DF842807B602A7BB88A013AB4 -:1022C000291DFFF7D5F93B8BB882834203D1204605 -:1022D000A3680AA9984720460AA9FFF735FEFB7DA7 -:1022E000B88AC3F38403013303F01F039B02FB820C -:1022F0003B8B984214BF112000208FE67B68002B97 -:10230000AFD0062001E063461C30D3F800C0BCF11A -:10231000000FF8D1091A081D05F1040C1844DDF866 -:1023200014E09DF814308E44BEF11B0F99D89A42E8 -:1023300097D91CF8013B00F8013B059B013305933D -:10234000EDE76FF0090069E66FF00A0066E66FF0EE -:102350000D0063E66FF00E0060E66FF00F005DE6C3 -:1023600080841E00F0B53F4D3F4FEB6943F0007392 -:10237000EB61EB693D4B9B6AD3F800623E4046F04F -:102380000106C3F80062D3F800423C4044EA00244E -:1023900044F00104C3F80042002955D0002006464D -:1023A000C3F81C02C3F80402C3F80C02C3F81402F9 -:1023B00003EBC00401300E28C4F84062C4F8446244 -:1023C000F6D100274FF0010C9678148816F0010F13 -:1023D00018BFD3F804E20CFA04F01CBF40EA0E0E5A -:1023E000C3F804E216F0020F18BFD3F80CE203EBB7 -:1023F000C4041CBF40EA0E0EC3F80CE2760748BFC7 -:10240000D3F8146207F1010744BF0643C3F814620E -:102410005668B942C4F84062966802F10C02C4F8EA -:102420004462D3F81C4240EA0400C3F81C02CBD13A -:10243000D3F8002222F00102C3F80022EB6923F056 -:102440000073EB61EB69F0BD0122C3F84012C3F8E1 -:102450004412C3F80412C3F81412C3F80C22C3F8D0 -:102460001C22E5E7001002400000FFFF8822002048 -:10247000184A08B5916A8B688B6013F0010104D08B -:1024800013F00C0F18BF4FF48031D80506D513F4A4 -:10249000406F14BF41F4003141F00201D80306D56A -:1024A00013F4402F14BF41F4802141F00401D3699B -:1024B0000BB108489847202383F311880021064870 -:1024C00000F01EFE002383F31188BDE8084001F0F0 -:1024D00083B800BF882200209022002038B5124C1B -:1024E000A36ADD68AA0712D05A6922F002025A6173 -:1024F000A36913B1012120469847202383F3118853 -:1025000000210A4800F0FCFD002383F31188EB064C -:1025100006D51021A36AD960236A0BB102489847F7 -:10252000BDE8384001F058B88822002098220020E9 -:1025300038B5124CA36A1D69AA0712D05A6922F055 -:1025400010025A61A36913B1022120469847202343 -:1025500083F3118800210A4800F0D2FD002383F3A1 -:102560001188EB0606D51021A36A1961236A0BB105 -:1025700002489847BDE8384001F02EB88822002074 -:102580009822002038B50F4CA36A5D682A075D6069 -:102590000AD5042222701A6822F002021A60636AC5 -:1025A00013B10021204698476B0706D5A36A9969A5 -:1025B000236A13B1034809049847BDE8384001F085 -:1025C0000BB800BF8822002010B50E4C204600F04A -:1025D000FDF90D4B0B211320A36200F0D7F90B215D -:1025E000142000F0D3F90B21152000F0CFF90B21B6 -:1025F000162000F0CBF9BDE8104000220E20114655 -:10260000FFF7B0BE88220020006400400F4B10B5D9 -:102610009842044605D10E4BDA6942F00072DA6145 -:10262000DB690122A36A1A60A36A5A68D20707D538 -:10263000626851681268D9611A60064A5A6110BD11 -:102640000121082000F052FCEEE700BF88220020A4 -:10265000001002405B87010003291AD8DFE801F06F -:10266000020A0F14836A9B6813F0E05F14BF012015 -:1026700000207047836A9868C0F380607047836A5F -:102680009868C0F3C0607047836A9868C0F30070B0 -:10269000704700207047000010B5032927D8DFE8F5 -:1026A00001F002272B2F836A9968C1F30161183169 -:1026B00003EB01131078840648BF5468C0F300117F -:1026C00058BF94884FEA410148BF41EAC40100F075 -:1026D0000F00586048BF41F00401906858BF41EABC -:1026E0004451D26841F001019860DA60196010BD70 -:1026F000836A03F5C073DDE7836A03F5C873D9E71E -:10270000836A03F5D073D5E701290AD002290FD0D7 -:1027100081B9836ADA68920701D1186903E0012060 -:102720007047836AD86810F0030018BF0120704713 -:10273000836AF2E70020704710B539B9836AD96817 -:1027400089071BD11B699C0704D110BD012915D035 -:102750000229FAD1816AD1F8C031D1F8C441D1F847 -:10276000C8011061D1F8CC015061202008610869CE -:10277000800717D1486940F0100012E0816AD1F853 -:10278000B031D1F8B441D1F8B8011061D1F8BC0131 -:1027900050612020C860C868800703D1486940F0B4 -:1027A00002004861C3F34000C3F38001000140EA26 -:1027B0004111107920F030000143117189064BBF9F -:1027C00091681189DB085B0D4CBF63F31C0163F357 -:1027D0000A01137948BF916064F3030313714FEA50 -:1027E00014234FEA144458BF118113705480ACE78E -:1027F000026843680A43026003B11847704700004B -:10280000024AD36843F0C003D360704700380140E8 -:10281000024AD36843F0C003D360704700440040CD -:102820002DE9F041D0F89C600446F7683368DA057A -:102830009DB20DD5202383F311884FF4007104302D -:10284000FFF7D6FF6FF480733360002383F31188A2 -:10285000202383F3118804F1040815F02F033AD1E3 -:1028600083F31188380615D5290613D5202383F361 -:10287000118804F1380000F02FFA00284DDA082101 -:10288000201DFFF7B5FF4FF67F733B40F360002339 -:1028900083F311887A0616D56B0614D5202383F3AB -:1028A0001188D4E913239A420AD1236C43B127F04B -:1028B00040073F041021201D3F0CFFF799FFF760F0 -:1028C000002383F31188D4F8A420D3683BB3BDE878 -:1028D000F041106918472B0713D015F0080F0CBFF3 -:1028E00000218021E80748BF41F02001AA0748BF26 -:1028F00041F040016B07404648BF41F48071FFF74B -:1029000077FFAD06736805D594F8A01020461940EE -:1029100000F082FA3568ADB29FE77060B7E7BDE8B6 -:10292000F081000008B50348FFF77AFFBDE80840D2 -:1029300000F052BEB422002008B50348FFF770FF34 -:10294000BDE8084000F048BE5C23002010B5094CEB -:1029500000212046084A00F03FFA084B0021C4F845 -:102960009C30074C074A204600F036FA064BC4F864 -:102970009C3010BDB422002001280008003801401E -:102980005C230020112800080044004001220901B6 -:1029900000F1604303F56143C9B283F8001300F00E -:1029A0001F039A4043099B0003F1604303F5614311 -:1029B000C3F880211A607047090100F16040C9B274 -:1029C00000F56D4001767047FFF7FEBD01230370EF -:1029D000002300F10802C0E9022200F11002C0E960 -:1029E0000422C0E90633C0E90833436070470000A1 -:1029F00010B52023044683F311880223416003703D -:102A0000FFF704FE04232370002383F3118810BD15 -:102A10002DE9F0411F4604460D461646202383F358 -:102A2000118800F108082378052B0DD0294620468F -:102A3000FFF712FE40B1204632462946FFF72CFE32 -:102A4000002080F3118808E03946404600F03CFB46 -:102A50000028E8D0002383F31188BDE8F08100004E -:102A60002DE9F0411F4604460D461646202383F308 -:102A7000118800F110082378052B0DD02946204637 -:102A8000FFF742FE40B1204632462946FFF754FE8A -:102A9000002080F3118808E03946404600F014FB1E -:102AA0000028E8D0002383F31188BDE8F0810000FE -:102AB000F8B5154682680B46AA428169066938BF97 -:102AC0008568761AB54204460BD218462A46FEF7A8 -:102AD00067FCA3692B44A361A36828465B1BA36022 -:102AE000F8BD0CD918463246FEF75AFCAF1B3A46E1 -:102AF000E1683044FEF754FCE3683B44EBE71846DA -:102B00002A46FEF74DFCE368E5E700002DE9F041B9 -:102B1000154683680446934238BF8568D0E904703F -:102B20003F1ABD420E460BD22A46FEF739FC6369B6 -:102B30002B446361A36828465B1BA360BDE8F0815A -:102B40000CD93A46A5EB0708FEF72AFC4246E06896 -:102B5000F119FEF725FCE3684344EAE72A46FEF74D -:102B60001FFCE368E5E7000010B50024C361029B89 -:102B7000C0E90511C1601144C0E900008460016131 -:102B8000036210BD08B5D0E90532934201D18268D5 -:102B900092B98268013282605A1C42611970D0E990 -:102BA00004329A4228BFC3684FF0000128BF436136 -:102BB00000F09AFA002008BD4FF0FF30FBE700005C -:102BC00070B5202304460D4683F31188A668A6B18C -:102BD000A368A269013BA360531CA3611578226915 -:102BE000934224BFE368A361E3690BB12046984791 -:102BF000002383F31188284607E02946204600F089 -:102C000063FA0028E2DA86F3118870BD2DE9F74FE8 -:102C100004460E4617469846D0F81C904FF0200AFE -:102C20008AF311884FF0000B154665B12A463146EC -:102C30002046FFF73DFF034660B94146204600F0BD -:102C400043FA0028F1D0002383F31188781B03B0E6 -:102C5000BDE8F08FB9F1000F03D001902046C847BE -:102C6000019B8BF31188ED1A1E448AF31188DCE76F -:102C7000C361009BC0E90511C1601144C0E90000B7 -:102C80008260016103627047F8B504460D4616463E -:102C9000202383F31188A768A7B1A368013BA36031 -:102CA00063695A1C62611D70D4E904329A4224BFE0 -:102CB000E3686361E3690BB120469847002080F325 -:102CC000118807E03146204600F0FEF90028E2DADC -:102CD00087F31188F8BD0000D0E905239A4210B5AA -:102CE00001D182687AB982680021013282605A1C5F -:102CF00082611C7803699A4224BFC368836100F033 -:102D0000F3F9204610BD4FF0FF30FBE72DE9F74FF8 -:102D100004460E4617469846D0F81C904FF0200AFD -:102D20008AF311884FF0000B154665B12A463146EB -:102D30002046FFF7EBFE034660B94146204600F00F -:102D4000C3F90028F1D0002383F31188781B03B066 -:102D5000BDE8F08FB9F1000F03D001902046C847BD -:102D6000019B8BF31188ED1A1E448AF31188DCE76E -:102D7000026843680A43026003B1184770470000C5 -:102D80001430FFF743BF00004FF0FF331430FFF75C -:102D90003DBF00003830FFF7B9BF00004FF0FF33F0 -:102DA0003830FFF7B3BF00001430FFF709BF000051 -:102DB0004FF0FF311430FFF703BF00003830FFF74A -:102DC00063BF00004FF0FF323830FFF75DBF0000F7 -:102DD00000207047FFF7BABD37B515460D4A0446C7 -:102DE000026000224260C0E9022201220B46027406 -:102DF00000F15C01009020221430FFF7B5FE2B4655 -:102E00002022009404F17C0104F13800FFF730FF28 -:102E100003B030BD483B000838B5C36904460D46D1 -:102E20001BB904210844FFF7A3FF294604F114004D -:102E3000FFF7A8FE002806DA201D4FF48061BDE8E8 -:102E40003840FFF795BF38BD0022024BC3E900337D -:102E50009A60704704240020002382680374054BA5 -:102E60001B6899689142FBD25A6803604260106007 -:102E7000586070470424002008B5202383F311888C -:102E8000037C032B05D0042B0DD02BB983F31188C1 -:102E900008BD002243691A604FF0FF334361FFF71A -:102EA000DBFF0023F2E7D0E9003213605A60F3E75A -:102EB000002382680374054B1B6899689142FBD814 -:102EC0005A68036042601060586070470424002014 -:102ED000054B196908741868026853601A60186114 -:102EE00001230374FDF732BB0424002030B54B1CD2 -:102EF00004460B4D87B010D02B690A4A01A800F098 -:102F00001BF92046FFF7E4FF049B13B101A800F072 -:102F10002FF92B69586907B030BDFFF7D9FFF8E7E3 -:102F200004240020792E000838B50C4D41612B692E -:102F300081689A680446914203D8BDE83840FFF79B -:102F40008BBF1846FFF7B4FF01232C6101462374A1 -:102F50002046BDE83840FDF7F9BA00BF0424002040 -:102F6000044B1A681B6990689B68984294BF0020C4 -:102F7000012070470424002010B5084C2368206904 -:102F80001A6854602260012223611A74FFF790FFCF -:102F900001462069BDE81040FDF7D8BA042400209E -:102FA00008B5FFF7DDFF18B1BDE80840FFF7E4BF43 -:102FB00008BD0000FFF7E0BFFEE7000010B50C4CB5 -:102FC000FFF742FF00F0AAF880220A49204600F0ED -:102FD00031F8012344F8180C037400F0D9FA0023E7 -:102FE00083F3118862B6BDE81040034800F042B890 -:102FF0002C240020703B0008803B000800F0CAB879 -:10300000EFF3118020B9EFF30583202282F31188BA -:103010007047000010B530B9EFF30584C4F308041D -:1030200014B180F3118810BDFFF7BAFF84F3118843 -:10303000F9E7000082600222028270478368A3F1F0 -:103040003C0243F80C2C026943F83C2C426943F8DB -:10305000382C074A43F81C2CC268A3F1180043F827 -:10306000102C022203F8082C002203F8072C7047CA -:103070005D05000810B5202383F31188FFF7DEFFFC -:1030800000210446FFF750FF002383F311882046F8 -:1030900010BD0000024B1B6958610F20FFF718BFDD -:1030A00004240020202383F31188FFF7F3BF0000DE -:1030B00008B50146202383F311880820FFF716FF87 -:1030C000002383F3118808BD49B1064B42681B6990 -:1030D00018605A60136043600420FFF707BF4FF089 -:1030E000FF3070470424002003460068834205D067 -:1030F00002681A6053604161FFF7AEBE704700007E -:1031000038B504460D462068844200D138BD0368B6 -:1031100023605C604561FFF79FFEF4E7054B03F118 -:103120001402C3E905224FF0FF32DA6100221A626D -:10313000704700BF0424002010B5C0E903230B4AE8 -:10314000136A53699C68A1420CD85C688160036073 -:103150004460206058609868411A99604FF0FF33CE -:10316000D36110BD1B68091BECE700BF04240020DD -:10317000036881689A680A449A60426813605A60DA -:1031800000234FF0FF32C360014BDA61704700BF8C -:103190000424002038B50F4C2246236A01332362F1 -:1031A00052F8143F934206D020259A68013A9A605B -:1031B00063699A6802B138BDD3E9001001604860C4 -:1031C000D968DA6082F311881869884785F3118815 -:1031D000EEE700BF0424002000207047FEE7000057 -:1031E000704700004FF0FF3070470000BFF34F8F73 -:1031F000024AD368DB07FCD4704700BF00200240BE -:1032000008B5074B1B7853B9FFF7F0FF054B1A6958 -:10321000120641BF044A5A6002F188325A6008BD62 -:1032200008250020002002402301674508B5054B12 -:103230001B7833B9FFF7DAFF034A136943F08003C1 -:10324000136108BD08250020002002407F289ABF96 -:1032500000F5003080020020704700004FF48060CD -:1032600070470000802070477F2808B50BD8FFF713 -:10327000EDFF00F580630268013204D1043083421F -:10328000F9D1012008BD0020FCE700007F2838B5F7 -:10329000044623D8FFF7B4FEFFF7A8FFFFF7B0FFFF -:1032A000F3220F4B0546DA60022220461A61FFF72F -:1032B000CDFF58611A694FF4806142F040021A61F3 -:1032C000FFF794FF00F010F92846FFF7AFFFFFF774 -:1032D000A1FE2046BDE83840FFF7C6BF002038BD3C -:1032E000002002402DE9F047044612F001000E468E -:1032F000154606D040F2BD22234B1A600020BDE8DF -:10330000F087224BA2189A4204D940F2C2221E4BE7 -:103310001A60F4E7FFF774FE4FF0010AFFF770FF41 -:10332000FFF764FFDFF868903146A61B012D884641 -:1033300006EB010705D8FFF779FFFFF76BFE0120C9 -:10334000DDE7B8F80030C9F810A03B800024FFF793 -:103350004DFFC9F810403B8831F8022B9BB29A42CE -:103360000FD040F2D922084B1A600A4B1F600A4B5B -:103370001D600A4BC3F80080FFF758FFFFF74AFEB5 -:10338000BCE7023DD2E700BF042500200000020890 -:1033900000200240F824002000250020FC2400200A -:1033A000084908B50B7828B11BB9FFF729FF01239D -:1033B0000B7008BD002BFCD0BDE808400870FFF77B -:1033C00035BF00BF0825002070B5FFF719FE4FF488 -:1033D0007A710D4B0D4E1B6A326801FB03F3934269 -:1033E00037BF0B4A0A495168156836BF4C1CD1E9F2 -:1033F000005454605D1944F100043360FFF70AFE85 -:103400002846214670BD00BF042400200C25002062 -:103410001025002070B5FFF7F3FD4FF47A710F4BC4 -:103420000F4E1B6A326801FB03F3934237BF0D4A0C -:103430000C49516815683ABF4C1C5460D1E90054DE -:103440005D1944F100043360FFF7E4FD4FF47A7234 -:10345000002328462146FCF783FE70BD042400208B -:103460000C2500201025002010B5094C013AD2B2DD -:10347000FF2A00D110BD500854F82030013054F814 -:1034800020009BB243EA004341F8043BEEE700BF53 -:10349000046C004010B50748013AD2B2FF2A00D1AF -:1034A00010BD0C88530840F823404C88013340F885 -:1034B0002340F1E7046C004007B50122002001A978 -:1034C000FFF7D2FF019803B05DF804FB13B5044683 -:1034D000FFF7F2FFA04205D00122002001A90194CC -:1034E000FFF7D8FF02B010BD7047000045F25552FB -:1034F000064B1A6002225A6040F6FF729A604CF640 -:10350000CC421A600122024B1A7070470030004012 -:103510001C250020034B1B781BB14AF6AA22024B44 -:103520001A6070471C25002000300040044B1A68C8 -:103530002AB902F1804202F50432526A1A607047D9 -:10354000182500204FF08072014B5A62704700BF6F -:103550000010024008B5FFF7E9FF024B1868C0F3FE -:10356000407008BD1825002008B5FFF7DFFF024BAB -:103570001868C0F3007008BD18250020EFF3098318 -:10358000203383F30988002383F3118870470000F8 -:10359000202080F3118862B60C4B0D4AD96821F4C3 -:1035A000E0610904090C0A43DA60D3F8FC200949F8 -:1035B00042F08072C3F8FC200A6842F001020A60FF -:1035C0001022DA7783F82200704700BF00ED00E098 -:1035D0000003FA05001000E0202310B583F31188E2 -:1035E0000B4B5B6813F400630FD0EFF309844FF0CB -:1035F0008073203CE36184F30988FFF7B1FC10B1CC -:10360000044BA36110BD044BFBE783F31188F9E77A -:1036100000ED00E06F05000872050008704700002B -:10362000FEE700000A4B0B480B4A90420BD30B4BB2 -:10363000C11EDA1C121A22F003028B4238BF00228C -:103640000021FDF7BFBE53F8041B40F8041BECE754 -:10365000043C0008A0250020A0250020A025002073 -:103660007047000000F030B808B500F063F9FFF7CC -:10367000A5FCBDE80840FFF759BF000070470000F7 -:103680004FF0FF310E4B1A6919611A6900221A6155 -:103690001869D868D960D968DA60DA68DA6942F0FE -:1036A0008052DA61DA69DA6942F00062DA61054A69 -:1036B000DB69136843F48073136000F01BB900BF2B -:1036C0000010024000700040194B1A6842F00102DD -:1036D0001A601A689007FCD51A6802F0F9021A609D -:1036E00000225A605A6812F00C0FFBD11A6842F49B -:1036F00080321A601A689103FCD55A6842F4E812C5 -:103700005A601A6842F080721A601A689201FCD5F9 -:103710001221084A5A60084A11605A6842F00202AF -:103720005A605A6802F00C02082AFAD1704700BFAA -:103730000010024000641D0000200240084A08B545 -:10374000516913680B4003F00103536123B1054A2B -:1037500013680BB150689847BDE80840FFF73CBFBD -:103760000004014020250020084A08B5516913686B -:103770000B4003F00203536123B1054A93680BB178 -:10378000D0689847BDE80840FFF726BF0004014015 -:1037900020250020084A08B5516913680B4003F042 -:1037A0000403536123B1054A13690BB1506998476B -:1037B000BDE80840FFF710BF0004014020250020AD -:1037C000084A08B5516913680B4003F008035361B8 -:1037D00023B1054A93690BB1D0699847BDE8084009 -:1037E000FFF7FABE0004014020250020084A08B572 -:1037F000516913680B4003F01003536123B1054A6C -:10380000136A0BB1506A9847BDE80840FFF7E4BE61 -:103810000004014020250020174B10B55A691C6890 -:10382000144004F478725A61A30604D5134A936ACB -:103830000BB1D06A9847600604D5104A136B0BB1E0 -:10384000506B9847210604D50C4A936B0BB1D06B93 -:103850009847E20504D5094A136C0BB1506C9847A0 -:10386000A30504D5054A936C0BB1D06C9847BDE80D -:103870001040FFF7B1BE00BF00040140202500202A -:103880001A4B10B55A691C68144004F47C425A6102 -:10389000620504D5164A136D0BB1506D9847230588 -:1038A00004D5134A936D0BB1D06D9847E00404D54D -:1038B0000F4A136E0BB1506E9847A10404D50C4A01 -:1038C000936E0BB1D06E9847620404D5084A136F0B -:1038D0000BB1506F9847230404D5054A936F0BB181 -:1038E000D06F9847BDE81040FFF776BE0004014056 -:1038F00020250020062108B50846FFF747F80621D5 -:103900000720FFF743F806210820FFF73FF80621BC -:103910000920FFF73BF806210A20FFF737F80621B8 -:103920001720FFF733F8BDE8084006212820FFF7ED -:103930002DB8000008B5FFF7A3FE064800F00EF80A -:10394000FFF742F8FFF746FAFFF798FEBDE8084098 -:1039500000F002B8983B000800F042B80023194676 -:103960001C4A0133102BC2E9001102F10802F8D100 -:10397000194B9A6942F07D029A619B690268174B64 -:10398000DA6082685A6042681A60C26803F5806330 -:10399000DA6042695A6002691A608269C3F80C24CD -:1039A000026AC3F80424C269C3F80024426AC3F857 -:1039B0000C28C26AC3F80428826AC3F80028026B84 -:1039C000C3F80C2C826BC3F8042C426BC3F8002C98 -:1039D000704700BF20250020001002400008014071 -:1039E0004FF0E023044A08215A6100229A6107221D -:1039F0000B201A61FEF7E0BF3F19010008B5202334 -:103A000083F31188FFF7FAFA002383F3118808BDC6 -:103A100008B5FFF7F3FFBDE80840FFF7DDBD000084 -:103A200010B501390244904201D1002005E003782D -:103A300011F8014FA34201D0181B10BD0130F2E76D -:103A40002DE9F0419BB10446C91A1778014403F1EE -:103A5000FF3C8C42204601D9002008E00578013463 -:103A6000BD42F6D10CEB0405D618A54201D1BDE844 -:103A7000F08115F8018D16F801EDF045F5D0E8E775 -:103A8000034611F8012B03F8012B002AF9D17047E6 -:103A90006F72672E6172647570696C6F742E6170DD -:103AA0005F7065726970685F677073004E6F206148 -:103AB0007070207369670A00426164206677206C29 -:103AC000656E6774682025750A0042616420626F24 -:103AD0006172645F69642025752073686F756C641A -:103AE0002062652025750A004261642066772064A3 -:103AF000657363726970746F72206C656E67746849 -:103B00002025750A00426164206170702043524391 -:103B1000203078253038783A3078253038782030A1 -:103B200078253038783A3078253038780A00476F71 -:103B30006F64206669726D776172650A0040A2E465 -:103B4000F164689106000000000000009D2D00084F -:103B5000892D0008C52D0008B12D0008BD2D0008D5 -:103B6000A92D0008952D0008812D0008D12D0008F1 -:103B70006D61696E0000000069646C650000000002 -:103B8000783B000848240020F824002001000000B1 -:103B9000B92F0008000000000C1E0000447B4144C7 -:103BA000B45749440100000042444444444444445E -:103BB00000000000444444444444444400000000E5 -:103BC00044444444444444440000000044444444C5 -:103BD00044444444BCC5FF7F0100000000000000D5 -:103BE000E803000000000000009C0100000000004D -:103BF000640000000000000040420F00FE2A0100A7 -:043C0000D2040000EA +:10000000000900202D080008B11C0008811C000810 +:100010009D1C0008811C0008951C00082F08000882 +:100020002F0800082F0800082F080008E5370008EF +:100030002F0800082F0800082F080008F93C0008C6 +:100040002F0800082F0800082F0800082F080008B4 +:100050002F0800082F080008293A0008553A000820 +:10006000813A0008AD3A0008D93A00082F08000884 +:100070002F0800082F0800082F0800082F08000884 +:100080002F0800082F0800082F080008AD2C0008D2 +:10009000192D00086D2D0008C12D0008053B000832 +:1000A0002F0800082F0800082F0800082F08000854 +:1000B0002F0800082F0800082F0800082F08000844 +:1000C0002F0800082F0800082F0800082F08000834 +:1000D0002F0800082F0800082F0800082F08000824 +:1000E0006D3B00082F0800082F0800082F080008A3 +:1000F0002F0800082F0800082F0800082F08000804 +:100100002F0800082F0800082F0800082F080008F3 +:100110002F0800082F0800082F0800082F080008E3 +:100120002F0800082F0800082F0800082F080008D3 +:100130002F0800082F0800082F0800082F080008C3 +:100140002F0800082F0800082F0800082F080008B3 +:100150002F0800082F0800082F0800082F080008A3 +:100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A +:100170000C0F93EA0C0F6FD01A4480EA010C400276 +:1001800018BF5FEA41211ED04FF0006343EA5010D0 +:1001900043EA5111A0FB01310CF00040B1F5000F12 +:1001A0003EBF490041EAD3715B0040EA010062F1C1 +:1001B0007F02FD2A1DD8B3F1004F40EBC25008BFAB +:1001C00020F00100704790F0000F0CF0004C08BFC9 +:1001D00049024CEA502040EA51207F3AC2BFD2F196 +:1001E000FF0340EAC250704740F400004FF00003A4 +:1001F000013A5DDC12F1190FDCBF00F000407047DE +:10020000C2F10002410021FA02F1C2F1200200FA1B +:1002100002FC5FEA310040F1000053EA4C0308BFE2 +:1002200020EADC70704792F0000F00F0004C02BF33 +:10023000400010F4000F013AF9D040EA0C0093F0AE +:10024000000F01F0004C02BF490011F4000F013B08 +:10025000F9D041EA0C018FE70CEAD15392EA0C0F76 +:1002600018BF93EA0C0F0AD030F0004C18BF31F0E1 +:10027000004CD8D180EA010000F00040704790F0B7 +:10028000000F17BF90F0004F084691F0000F91F05B +:10029000004F14D092EA0C0F01D142020FD193EA21 +:1002A0000C0F03D14B0218BF084608D180EA0100A9 +:1002B00000F0004040F0FE4040F40000704740F085 +:1002C000FE4040F44000704780F0004002E000BF74 +:1002D00081F0004142001FBF5FEA410392EA030F31 +:1002E0007FEA226C7FEA236C6AD04FEA1262D2EB7B +:1002F0001363C1BFD218414048404140B8BF5B4280 +:10030000192B88BF704710F0004F40F4000020F018 +:100310007F4018BF404211F0004F41F4000121F02E +:100320007F4118BF494292EA030F3FD0A2F1010278 +:1003300041FA03FC10EB0C00C3F1200301FA03F1B6 +:1003400000F0004302D5494260EB4000B0F5000FD9 +:1003500013D3B0F1807F06D340084FEA310102F198 +:100360000102FE2A51D2B1F1004F40EBC25008BF4A +:1003700020F0010040EA03007047490040EB000014 +:10038000013A28BFB0F5000FEDD2B0FA80FCACF115 +:10039000080CB2EB0C0200FA0CF0AABF00EBC25042 +:1003A00052421843BCBFD0401843704792F0000F30 +:1003B00081F4000106BF80F400000132013BB5E783 +:1003C0004FEA41037FEA226C18BF7FEA236C21D0F9 +:1003D00092EA030F04D092F0000F08BF084670475E +:1003E00090EA010F1CBF0020704712F07F4F04D12C +:1003F000400028BF40F00040704712F100723CBF3F +:1004000000F50000704700F0004343F0FE4040F468 +:10041000000070477FEA226216BF08467FEA236326 +:100420000146420206BF5FEA412390EA010F40F411 +:10043000800070474FF0000304E000BF10F000435D +:1004400048BF40425FEA000C08BF704743F0964344 +:1004500001464FF000001CE050EA010208BF70475F +:100460004FF000030AE000BF50EA010208BF7047E6 +:1004700011F0004302D5404261EB41015FEA010CFB +:1004800002BF84460146002043F0B64308BFA3F1F3 +:100490008053A3F50003BCFA8CF2083AA3EBC253D5 +:1004A00010DB01FA02FC634400FA02FCC2F12002F4 +:1004B000BCF1004F20FA02F243EB020008BF20F02B +:1004C0000100704702F1200201FA02FCC2F1200291 +:1004D00050EA4C0021FA02F243EB020008BF20EA86 +:1004E000DC70704742000ED2B2F1FE4F0BD34FF0DA +:1004F0009E03B3EB126209D44FEA002343F000439A +:1005000023FA02F070474FF00000704712F1610FBC +:1005100001D1420202D14FF0FF3070474FF000008E +:10052000704700BF53B94AB9002908BF00281CBF53 +:100530004FF0FF314FF0FF3000F076B9ADF1080C0D +:100540006DE904CE00F006F8DDF804E0DDE90223F1 +:1005500004B070472DE9F047089E0D4604468846D2 +:10056000002B4DD18A42944668D9B2FA82F252B138 +:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 +:1005800041EA030894404FEA1C41B8FBF1F71FFA17 +:100590008CFE01FB178807FB0EF0230C43EA08438F +:1005A00098420AD91CEB030307F1FF3580F01E8146 +:1005B000984240F21B81023F63441B1AB3FBF1F0E7 +:1005C00001FB103300FB0EFEA4B244EA0344A6452F +:1005D0000AD91CEB040400F1FF3380F00981A64521 +:1005E00040F20681644402380021A4EB0E0440EA84 +:1005F00007401EB10023D440C6E90043BDE8F087A0 +:100600008B4208D9002E00F0EE800021C6E90005DB +:100610000846BDE8F087B3FA83F100294AD1AB421E +:1006200002D3824200F2FC80841A65EB03030120AE +:100630009846002EE2D0C6E90048DFE702B9FFDEA7 +:10064000B2FA82F2002A40F09180A1EB0C00012165 +:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 +:10066000250C45EA00450EFB03F0A84208D91CEB17 +:10067000050503F1FF3802D2A84200F2CE804346BE +:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 +:1006900044EA0544A64508D91CEB040400F1FF35E3 +:1006A00002D2A64500F2B6802846A4EB0E0440EA2A +:1006B00003409EE7C1F120078B4022FA07FC4CEA79 +:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D +:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 +:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 +:1006F00001F20BD91CEB040408F1FF3A80F088806A +:10070000A04240F28580A8F102086444241AB4FB98 +:10071000F9F009FB104400FB0EFEADB245EA0444BB +:10072000A64508D91CEB040400F1FF356CD2A645A0 +:100730006AD90238644440EA0840A0FB0295A4EB61 +:100740000E04AC42C846AE4656D353D0002E69D0F4 +:10075000B3EB080264EB0E0422FA01F304FA07F784 +:100760001F43CC40C6E90074002147E70CFA02FCA5 +:10077000C2F1200125FA01F34FEA1C4720FA01F1EA +:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 +:10079000280C40EA034001FB0EF3834204FA02F402 +:1007A00008D91CEB000001F1FF382FD283422DD96C +:1007B00002396044C01AB0FBF7F307FB1300ADB277 +:1007C00045EA004503FB0EF0A84208D91CEB0505DD +:1007D00003F1FF3816D2A84214D9023B6544281A07 +:1007E00043EA014138E73146304607E72F46E4E661 +:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 +:100800000138A3E74346EAE7284694E74146D1E7A3 +:10081000D0467BE76444023847E7023B65442FE754 +:10082000084606E73146E9E6704700BF02E000F0FF +:1008300000F8FEE772B6264880F30888254880F362 +:100840000988254825490860022080F31488BFF3F1 +:100850006F8F03F017F803F07BF84FF05530204905 +:100860001B4A91423CBF41F8040BFAE71D49194A63 +:1008700091423CBF41F8040BFAE71B491B4A1C4B51 +:100880009A423EBF51F8040B42F8040BF8E70020EF +:100890001849194A91423CBF41F8040BFAE702F0AB +:1008A000F5FF03F057F8154C154DAC4203DA54F838 +:1008B000041B8847F9E700F03FF8124C124DAC4298 +:1008C00003DA54F8041B8847F9E702F0DDBF0000A3 +:1008D00000090020001100200000000808ED00E0E1 +:1008E0000001002000090020083E0008001100203F +:1008F0002411002028110020E025002060010008BC +:100900006001000860010008600100082DE9F04F57 +:10091000C1F80CD0C3689D46BDE8F08F002383F377 +:1009200011882846A047002002F010FDFEE702F0E3 +:1009300083FC00DFFEE70000F8B500F03DFE02F0AA +:10094000EFFE074602F03AFF0546002840D12C4B47 +:100950009F423DD001339F423DD02A4B27F0FF02FA +:100960009A423BD1F8B200F003FC2E4642F21074DA +:1009700000F004FC08B10024264601F007F988B312 +:100980000024032000F044F8264635B11E4B9F4258 +:1009900003D0002402F00AFF2646002002F0CAFE1F +:1009A0001A4B9B6813F0400322D00EB100F046F8BA +:1009B00000F044FC00F002FE01F07CF90546CCB1E9 +:1009C00001F078F9401BA04214D900F037F8F3E7A2 +:1009D0002E460024CCE704460126C9E706464FF41C +:1009E0007A74C5E7002CD0D04FF47A740126CCE796 +:1009F0001C46DDE700F0D4FC012002F0ADFCDEE790 +:100A0000010007B0000008B0263A09B0000C014010 +:100A1000084B187003280CD8DFE800F0080502081E +:100A2000022000F027BE022000F01CBE0022024B74 +:100A30005A607047281100202C11002038B501F0B1 +:100A4000A5F830B103221F4B1A7000221E4B5A60CA +:100A500038BD1E4B1E4A19680131F9D00433934248 +:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 +:100A70009B6803F1006303F5C8439A42E8D202F091 +:100A800069FE02F07BFE002000F0B2FD0220FFF7BD +:100A9000BFFF124BDA690022DA61D96999699A615C +:100AA0009B6972B64FF0E023C3F8085D3021D4F89B +:100AB0000034D4F8042481F311889D4683F3088818 +:100AC0001047C5E7281100202C1100200064000801 +:100AD000206400080060000800110020001002409F +:100AE00049F26900084A136899B21B0C00FB0133F4 +:100AF00044F250611360054B186882B2000C01FB90 +:100B00000200186080B27047201100201C110020E4 +:100B100010B504460021102200F0C8FD034B03CBA2 +:100B2000206061601868A06010BD00BFE8F7FF1F7B +:100B30002DE9F0410026ADF54E7D6CAC40F275120A +:100B400007460D460EA831460D9600F0AFFD4FF456 +:100B5000C4723146204600F0A9FD01F0ABF84FF415 +:100B60007A72B0FBF2F0264B0DF13408186093E86E +:100B70000700022384E807000DF5E9702382FFF7E0 +:100B8000C7FF4EF603031F4907A8238403F0ECF8C0 +:100B900016230DF2E32284F832310DF12C0C07AB51 +:100BA0001E4603CE664510605160334602F10802CE +:100BB000F6D1306841461060B38820469380012208 +:100BC00000F0C0FD00230393AB7E80B2029305F1D9 +:100BD000190301930123CDE904800093384606A34D +:100BE000D3E90023E97E01F0ABFB0DF54E7DBDE8B6 +:100BF000F08100BFAFF300809E6AC421818A46EE77 +:100C000034110020783D00082DE9F041264D804642 +:100C10002B7A0C46DAB0FBB9204627A900F0A2FED9 +:100C20000746002836D19DF89D60C82E32D801466F +:100C30004FF4FA72284600F039FD32460DF19E015C +:100C400005F1090000F020FD9DF89C302E447772DC +:100C50002B720BB9E37E2B728122002106AD27A8EF +:100C600000F024FD0122294627A800F0B7FE00234A +:100C70000393A37E80B2029304F119030193282306 +:100C8000CDE904500093404605A3D3E90023E17E5B +:100C900001F056FB5AB0BDE8F08100BFAFF3008011 +:100CA00026417272DF25D7B77C210020F0B54FF4C2 +:100CB0008A750024234EF1B005FB006596F8D83004 +:100CC000D822214685F8DC3085F8E8403AA800F0C3 +:100CD000EDFC06F1090000F0E1FCD5F8E430C2B209 +:100CE00006AF8DF8F00006F109010DF1F100CDE934 +:100CF0003A3400F0C9FC394601223AA800F09AFEC5 +:100D000080B2CDE9047008230127CDE9023706F14E +:100D1000D80301933023317A00930B4807A3D3E91A +:100D2000002301F00DFBA04206DD00F0C3FFC5F873 +:100D3000E000384671B0F0BD2046FBE778F6339FFF +:100D400093CACD8D7C2100204C210020F0B51E4E91 +:100D50001E4F1F4D85B0304601F01EFB044660B3A8 +:100D600010220021684600F0A1FC4FF00003227B16 +:100D70006068A16862F303038DF8003002AB03C31F +:100D8000019B2268384662F31C0301939DF80030F2 +:100D90006A4643F020038DF800300023194602F024 +:100DA00087F9044620B9304601F0FAFA2C70D2E7F0 +:100DB0002B78072B03D801332B7005B0F0BD024808 +:100DC00001F0EEFAF9E700BF4C210020A823002033 +:100DD0007523002070B50D4614461E4601F00CFA2E +:100DE00050B9022E10D1012C0ED112A3D3E9002349 +:100DF0000120C5E9002307E0282C10D005D8012CDC +:100E000009D0052C0FD0002070BD302CFBD10BA3D6 +:100E1000D3E90023ECE70BA3D3E90023E8E70BA316 +:100E2000D3E90023E4E70BA3D3E90023E0E700BF05 +:100E3000AFF30080401DA12026812A0B78F6339F56 +:100E400093CACD8D9E6AC421818A46EE2641727274 +:100E5000DF25D7B7F017304A39059E5638B5054615 +:100E60000E4C0021013500F0E5FBA4F8F051B4F878 +:100E7000F00100F0C7FB78B1B4F8F00100F0D2FB4C +:100E8000014648B9B4F8F00100F0D4FBB4F8F031F1 +:100E90000133A4F8F031EAE738BD00BF7C2100201F +:100EA0002DE9F04F8DB000AF04460D4601F0A4F9D6 +:100EB000002846D12B7E022B1AD1EB8A012B17D1A9 +:100EC00000F0F8FE0646FFF70BFE4FF4C873B0FBC8 +:100ED000F3F202FB1303DFF878829BB206F5167675 +:100EE0003344C8F80030EB7E33B90022994B1A70B6 +:100EF0003437BD46BDE8F08F284607F11C0100F0ED +:100F0000EFFC0028F4D107F10C00FFF701FEBD7FD4 +:100F100007F10C012A4607F11F0002F0F5FE002838 +:100F2000E3D10F2D08D88B4B1D70D8F80030A3F5F6 +:100F30001673C8F80030DBE72046397F01F054F91A +:100F4000D6E7EB8A282B6BD010D8012B63D0052B6A +:100F5000CED1BFF34F8F8049804BCA6802F4E06264 +:100F60001343CB60BFF34F8F00BFFDE7302BBFD1E2 +:100F70007B4CEA7E237A9A42BAD194F8DC206B7ECD +:100F80009A42B5D1284604F1EA0100F07FFD0646F9 +:100F90000028ADD1012384F8E83000F08BFED4F8AE +:100FA000E030C01A192840F6B83338BF19209842EB +:100FB00028BF1846FFF73EFA6A49FFF7D1F8054601 +:100FC0002068FFF737FA6849FFF7CAF80146284654 +:100FD000FFF780F9FFF786FA20604FF48A7194F8E2 +:100FE000D9307B607A68636801FB02F5621992F878 +:100FF000E80050B1D2F8E400E946834215D000235E +:1010000082F8E830C2F8E030CD466368574A9B0A60 +:10101000013313816CE729462046FFF789FD67E716 +:1010200029462046FFF7F0FD62E7B2F8EC803B600E +:1010300008F1030A4FEA9A0A4FEA8A02D11DC90849 +:10104000A9EBC1039D46EB460021584600F02EFB5C +:1010500005F1EE0142465846214400F015FB3B687D +:1010600013B9012000F0C4FA94F8D20000F0CAFAD3 +:10107000054630B9207200F0E5FA284600F0B8FACB +:10108000C2E7D4F8D4303BB994F8D200B4F8F031C8 +:10109000834201D8FFF7E2FED4F8D43043449D42A6 +:1010A00008D294F8D200B4F8F0310130834201D86C +:1010B000FFF7D4FE594660685FFA8AF200F0FEFA44 +:1010C00008B9CD4689E7636894F8D2004344636069 +:1010D000D4F8D43008EB030AC4F8D4A000F092FA94 +:1010E000824509D394F8D230D4F8D4000133401BA0 +:1010F00084F8D230C4F8D400B8F1FF0F0FD800251F +:10110000257200F09FFA284600F072FA00F03EFDCA +:10111000164B188108B9FFF791FCCD46E8E64FF46D +:101120008A727B6894F8D90002FB0343D3F8E42069 +:1011300083F8E86002F58072C3F8E060C3F8E42049 +:10114000FFF7B4FDFFF702FE84F8D960B9E700BFEE +:10115000482100204521002000ED00E00400FA05B0 +:101160007C210020CDCCCC3D6666663F341100204A +:10117000014B1870704700BF4011002030B54FF090 +:101180000054254B226885B09A4207D002F020FB1C +:101190000446C0B90024204605B030BD0025627D5C +:1011A0001E4B1F481A70237DC92203721D49C0F8C7 +:1011B000E450093000F068FA2046E022294600F0A9 +:1011C00075FA0124E7E7184A184DD36943F0007314 +:1011D000D361AA6D164B9A42DCD12B6E013B7E2B5C +:1011E000D8D8144A01AB07CA83E807001846032180 +:1011F00000F09CFC6B6D83424FF00003CAD12A6D56 +:101200008A4203BFAB652A6E044B1C4601BF1A70AD +:10121000EA6D094B1A60BEE79AAD44C54011002043 +:101220007C210020160000200010024000660040D3 +:101230005041A0B058660040181100202DE9F0433D +:1012400085B000F0A3FC0223494C63710023029394 +:10125000484B2081D3F800C0BCF57A7F12D3464FAB +:10126000464BB7FBFCF59C458CBF0A231123B5FB0D +:10127000F3F603FB1652591EC8B2002A3ED00229CB +:101280000B46F4D89DF80B303D495A1E9DF80A30A4 +:101290003C48013B1B0443EA0253BDF80820013AD5 +:1012A00013434B6001F0F4FE00230193364B3749A2 +:1012B00000934FF48052364B364800F06BFF364BAC +:1012C000197811B1334800F08FFF00F0F3FC0546A8 +:1012D000FFF706FC4FF4C873B0FBF3F202FB1303F5 +:1012E00005F516709BB218442C4B186002F066FA94 +:1012F00008B10F23238105B0BDE8F083731EB3F559 +:10130000806FBFD24FF47A75C0EBC00E0EF10303AD +:101310004FEAE30909FB0555C3F3C703C11AC9B274 +:1013200009F101088844B5FBF8F5B5F5617F08D9E6 +:101330000EF1FF33C3F3C703C11A581E0F28C9B2F9 +:1013400014D84A1E072A8CBF00220122581800FB1D +:101350000660B7FBF0F7BC4594D1002A92D0ADF8F7 +:1013600008608DF80A308DF80B108BE71346EDE717 +:101370003411002018110020005125023F420F00B7 +:1013800010110020A8230020D50D000844110020D2 +:10139000A10E00084C21002040110020482100200F +:1013A0002DE9F04F80A7D7E900670FF20429D9E9AA +:1013B0000089734D93B00DF1300AFFF7C7FC182276 +:1013C0000021504600F072F9DFF8B8B16E4C0023EE +:1013D00052461946584601F093FE014650BB102272 +:1013E00008A800F063F9E36883F01003E36000F0FD +:1013F00063FC0DF1240C0B4612A9024611E903000F +:101400008CE803009DF83410C1F30300890649BF3E +:101410000E99BDF83810C1F31C0141F0004158BFCE +:10142000C1F30A018DF82C000891284608A901F0A3 +:1014300097F9CCE7284600F0DFFE0446002847D1A4 +:1014400000F038FCDFF844B1DBF8003098423FD3BD +:1014500000F030FC0790FFF743FB4FF4C873B0FB7C +:10146000F3F101FB1300079A83B202F516701844DA +:10147000CBF80000DFF818B18DF820409BF8001081 +:1014800011B901238DF8203050460791FFF740FB3A +:1014900007990DF12100C1F11004E4B2062C28BF18 +:1014A00006245144224600F0EFF808AB03931823BA +:1014B0000293384B013401930123E4B20093324686 +:1014C0003B462846049400F0DDFE00238BF80030F4 +:1014D00000F0F0FB304A314C1368C31AB3F57A7F41 +:1014E00030D3106000F0E8FB02460B46284600F0BF +:1014F00061FF284600F080FE20B3237ADFF8A0B019 +:10150000002B14BF032302238BF8053000F0D2FB1D +:101510004FF47A73B0FBF3F00122CBF80000514690 +:10152000584600F0B5F9182302931E4B80B2019380 +:1015300040F25513CDE903A0009342464B4628469E +:1015400000F0A0FE237ABBB100F0B4FB94F8E830C1 +:1015500073B9D4F8E03043B1C01A2368FA2B38BF0E +:10156000FA230533B0EB430F02D30020FFF79EFBB5 +:10157000237A002B7FF41FAF13B0BDE8F08F00BFBC +:101580004C210020A8230020000801404821002011 +:101590004521002044210020702300207C210020D0 +:1015A0003411002074230020401DA12026812A0B25 +:1015B000F1C6A7C1D068080F7047000070B501F0F0 +:1015C00095FF0024084E094D3080286833888342F7 +:1015D00008D901F087FF2B6804440133B4F5C84FE4 +:1015E0002B60F2D370BD00BFA4230020782300201D +:1015F00002F00AB800F10060920000F5C84001F066 +:10160000AFBF0000054B1A68054B1B889B1A83422D +:1016100002D9104401F066BF0020704778230020F3 +:10162000A4230020024B1B68184401F061BF00BFD7 +:1016300078230020024B1B68184401F06BBF00BFE9 +:1016400078230020064991F8243033B10023082282 +:10165000086A81F82430FFF7CDBF0120704700BF32 +:101660007C230020022802BF1022014B1A61704720 +:1016700000080140022802BF4FF48012014B1A619A +:10168000704700BF00080140002310B5934203D00B +:10169000CC5CC4540133F9E710BD00000346024698 +:1016A000D01A12F9011B0029FAD1704703460244EF +:1016B000934202D003F8011BFAE770472DE9F84383 +:1016C0001F4D144695F824200746884652BBDFF884 +:1016D00070909CB395F824302BB92022FF21484606 +:1016E0002F62FFF7E3FF95F824004146C0F108029E +:1016F000A24228BF224605EB8000D6B29200FFF737 +:10170000C3FF95F82430A41B1E44F6B2082E1744DC +:101710009044E4B285F82460DBD1FFF793FF002802 +:10172000D7D108E02B6A03EB82038342CFD0FFF7C7 +:1017300089FF0028CBD10020BDE8F8830120FBE71A +:101740007C2300202DE9F0470D46044600219046F9 +:10175000284640F27912FFF7A9FF234620220021F4 +:10176000284600F09FFF022220212846231D00F07A +:1017700099FF032222212846631D00F093FF0322D4 +:1017800025212846A31D00F08DFF10222821284680 +:1017900004F1080300F086FF08223821284604F1EE +:1017A000100300F07FFF08224021284604F11103B6 +:1017B00000F078FF08224821284604F1120300F0C7 +:1017C00071FF20225021284604F1140300F06AFF23 +:1017D00040227021284604F1180300F063FF08221C +:1017E000B021284604F1200300F05CFF0822B82154 +:1017F000284604F1210300F055FFC02604F122071A +:101800003B46314608222846083600F04BFFB6F525 +:10181000A07F07F10107F3D108223146284604F1E1 +:10182000320300F03FFF002704F1330A94F832300E +:101830004FEAC7099F4209F5A47615D3B8F1000F06 +:1018400008D131460722284604F5997300F02AFF93 +:1018500009F24F16274694F832213B1B93420CD3D2 +:10186000F01DC008BDE8F0870AEB070308223146E7 +:10187000284600F017FF0137D8E7314607F2331347 +:101880000822284600F00EFF08360137E3E7000083 +:1018900038B50C460021054621600346C4F8031004 +:1018A0002046202200F0FEFE20462B1D0222202191 +:1018B00000F0F8FE20466B1D0322222100F0F2FE0C +:1018C0002046AB1D0322252100F0ECFE204610220D +:1018D000282105F1080300F0E5FE072038BD0000CF +:1018E0000023F7B50E460546047F072200911946EE +:1018F00000F09AFD731C0093012200230721284663 +:1019000000F092FDC4B9B31C0093052223460821C0 +:10191000284600F089FD0D243746B278BB1B934260 +:1019200011D32B7FE01DC008AC8ABBB9A04294BF85 +:101930000020012003B0F0BDAB8A0824DB00083B87 +:10194000DB08B370E8E7FB1C214600930822002364 +:10195000284600F069FD08340137DEE7001B18BF98 +:101960000120E7E70023F7B50E46047F0822009127 +:101970001946054600F058FD731CC4B908220093AF +:1019800011462346284600F04FFD102401237278AB +:101990005F1C013B934211D32B7FE01DC008AC8A32 +:1019A000BBB9A04294BF0020012003B0F0BDAB8AB8 +:1019B0000824DB00083BDB087370E7E7F3192146D6 +:1019C000009308220023284600F02EFD08343B46F1 +:1019D000DDE7001B18BF0120E7E70000F8B50E4661 +:1019E00005461446002181223046FFF75FFE2B4654 +:1019F00008220021304600F055FE7CB9072208215C +:101A000030466B1C00F04EFE0F2401236A785F1CE9 +:101A1000013B934204D3E01DC008F8BD0824F4E75D +:101A20002146EB190822304600F03CFE08343B46C4 +:101A3000ECE70000F8B50E46054614460021CE221C +:101A40003046FFF733FE2B4628220021304600F0B7 +:101A500029FE7CB908222821304605F1080300F050 +:101A600021FE30242F462A7A7B1B934204D3E01DAB +:101A7000C008F8BD2824F5E7214607F1090308222C +:101A8000304600F00FFE08340137ECE7F7B5047F6D +:101A90000E460091012310220021054600F0C4FCEF +:101AA000C4B9B31C0093092223461021284600F034 +:101AB000BBFC192437467288BB1B9A4211D82B7F76 +:101AC000E01DC008AC8ABBB9A04294BF0020012031 +:101AD00003B0F0BDAB8A1024DB00103BDB08738041 +:101AE000E8E73B1D2146009308220023284600F02A +:101AF0009BFC08340137DEE7001B18BF0120E7E735 +:101B000030B5094D0A4491420DD011F8013B5840BF +:101B1000082340F30004013B2C4013F0FF0384EA48 +:101B20005000F6D1EFE730BD2083B8ED4FF0FF3322 +:101B3000F7B500EB81061946DFF848C0DFF848E04A +:101B4000B0421BD050F8042B01AF0192042217F8C9 +:101B5000014B81EA046108240D46DB184941013C30 +:101B6000002DBCBF83EA0C0381EA0E0114F0FF04D0 +:101B7000F2D1013A12F0FF02E9D1E1E7D843C943BB +:101B800003B0F0BD9336EAA9EBE1F042F7B56B463E +:101B9000354A106851686A4603C3082333493448FC +:101BA00002F0C2F8044690BB0A256B46314A106821 +:101BB00051686A4603C308232F492D4802F0B4F840 +:101BC0000446002847D00369B3F5CE3F43D8B0F8A8 +:101BD0006620B2F57A7F3ED1284A024402F15C01C8 +:101BE0008B4238D35C3B224900209E1AFFF788FFC6 +:101BF00007463246002004F16401FFF781FFA36825 +:101C00009F4228D1E368984208BF002523E003697A +:101C1000B3F5CE3F26D8428BB2F57A7F20D1174A52 +:101C2000024402F110018B4218D3103B10490020EE +:101C30009D1AFFF765FF06462A46002004F11801A9 +:101C4000FFF75EFFA3689E4202D1E368984201D08D +:101C50000D25AAE70025284603B0F0BD1025A4E70E +:101C60000C25A2E70B25A0E7903D0008DC9B0100B6 +:101C700000640008993D0008909B0100089CFFF754 +:101C8000EFF30983EFF30583014B9B6BFEE700BF86 +:101C900000ED00E008B5FFF7F3FF0000EFF3098364 +:101CA000EFF30583014B5B6BFEE700BF00ED00E047 +:101CB000FEE7000001F0E2BC01F0BABC2DE9F04102 +:101CC000456A15B94162BDE8F0814B68AC4623F026 +:101CD0006047C3F38A4616EA230638BF3E464FEAFA +:101CE000D37EC3F380782B465A68BEEBD27F22F0B6 +:101CF00060440AD0002A18DAA40CB44217D19D42DD +:101D00000FD10D60DEE71346EEE7A74207D102F0E0 +:101D10008044C2F3807242450BD054B1EFE708D241 +:101D2000EDE7CCF800100B60CDE7B44201D0B4422F +:101D3000E5D81A689C46002AE5D11960C3E700007F +:101D40002DE9F0474FF47F49089D01F007044FEA61 +:101D5000D508224405F0070500EBD100944201D1DB +:101D6000BDE8F08704F0070705F0070A57453E462F +:101D700038BF5646111BC6F108068E4228BF0E46D4 +:101D8000E108415C08EBD50E13F80EC0B94029FA02 +:101D900006F721FA0AF1FFB28CEA010147FA0AF7C5 +:101DA00039408CEA010C03F80EC034443544D5E7C1 +:101DB000082341F2210280EA012001B240000029FB +:101DC00080B203F1FF33B8BF504013F0FF03F4D1EA +:101DD0007047000038B50C468D18A54200D138BDBB +:101DE00014F8011BFFF7E4FFF7E700000346406823 +:101DF00048B1026899895A605A89013292B2914277 +:101E00005A8138BF9A81704770B504460D4688B034 +:101E1000202200216846FFF749FC20460495FFF781 +:101E2000E5FF024658B16B46054608AE1C4603CC9A +:101E3000B44228606960234605F10805F6D11046D2 +:101E400008B070BD082817D909280CD00A280CD072 +:101E50000B280CD00C280CD00D280CD00E2814BF49 +:101E60004020302070470C2070471020704714200D +:101E7000704718207047202070470000082817D9A5 +:101E80000C280CD910280CD914280CD918280CD9D6 +:101E900020280CD930288CBF0F200E207047092035 +:101EA00070470A2070470B2070470C2070470D20A8 +:101EB000704700002DE9F843078C0446072F1ED910 +:101EC000D0E9029800254FF6FF73C5F12006A5F171 +:101ED000200029FA05F108FA06F628FA00F0314345 +:101EE0000143C9B21846FFF763FF0835402D03468A +:101EF000EBD13A46E169BDE8F843FFF76BBF4FF617 +:101F0000FF70BDE8F883000010B54B6823B9CA8A9A +:101F100063F30902CA8210BD04691A681C60036178 +:101F2000C38A013BC3824A60EFE700002DE9F84F06 +:101F30001D46CB8A0F46C3F3090105298146924607 +:101F40000B4630D00020AAB207F11A049EB2042E2C +:101F50001FFA80F80FD8904503F1010306D3FB8ADE +:101F60000A4462F309030120FB821AE01AF80060B8 +:101F70000130E654EAE79045F1D21C23A1F1050BAC +:101F8000BBFBF3F203FB12BB7C681FFA8BF6002C41 +:101F900045D14846FFF72AFF044638B978606FF00C +:101FA0000200BDE8F88F4FF00008E6E70026066063 +:101FB00078604FF0000BADB2454510D90AEB08032D +:101FC000221D13F8011B08F101089155B1B21B291C +:101FD0001FFA88F82BD0454506F10106F1D8FB8A97 +:101FE000C3F30902154465F30903BCE71C4601323B +:101FF00092B22368002BF9D16B1F0B441C21B3FB59 +:10200000F1F301339BB29A42D3D2BBF1000FD0D18E +:102010004846FFF7EBFE20B9C4F800B0BFE7012245 +:10202000E7E7C0F800B05E4620600446C1E74545DA +:10203000D5D94846FFF7DAFE08B92060AFE7C0F807 +:1020400000B0002620600446B6E700002DE9F74FF7 +:102050001C465B69074688460092002B00F097807B +:10206000238C2BB1E269002A00F09180072B33D832 +:1020700007F10C00FFF7BAFE054628B96FF002051C +:10208000284603B0BDE8F08F14220021FFF70EFBB5 +:10209000228CE16905F10800FFF7F6FA208C48F080 +:1020A0000041013080B2FFF7E9FEFFF7CBFE0138B7 +:1020B00080B22084013028746369228C1B782A4402 +:1020C00003F01F0363F03F0313723846696029462B +:1020D000FFF7F4FD0125D3E74FF000094FF0800A28 +:1020E0004E464D4600F10C0301930198FFF77EFE2A +:1020F00083460028C2D014220021FFF7D7FA002E11 +:102100003BD10222009BABF808300BF1080E1FFAFE +:1021100082FC0CF10100BCF1060F218C80B201D8C9 +:102120008E422CD3FFF7AAFEFFF78CFE8E4208BF2B +:102130004FF0400A62690138127880B202F01F0243 +:1021400042EA49120BEB00014AEA020A013048F068 +:10215000004281F808A08BF8100059463846CBF8A9 +:102160000420FFF7ABFD238C0135B3424FF0000A8A +:102170002DB289F00109B8D182E70022C5E7E169F3 +:10218000895D01360EF80210B6B20132BFE76FF07A +:10219000010575E7F8B5044615460E4630220021C4 +:1021A0001F46FFF783FA069BB5F5001F6360079B88 +:1021B00028BF4FF6FF72A3624FF0000338BF6A09D1 +:1021C000A760E66197B204F110009A4206D8002396 +:1021D0000360A782E3822383E360F8BD06600133D6 +:1021E00030462036F1E7000003781BB94BB2002BD4 +:1021F000C8BF01707047000000787047F8B50C4602 +:10220000C969074611B9238C002B37D1257E1F2DB4 +:1022100034D8387828BB228C072A2CD8268A36F066 +:1022200003032BD14FF6FF70FFF7D4FD4FF6FF727B +:1022300020F001003602400446EA0565400C45EAFC +:102240004025234629463846FFF700FF002807DDD2 +:10225000626913780133DBB21F2B88BF0023137030 +:10226000F8BD218A2D0645EA012505432046FFF7E2 +:1022700021FE0246E5E76FF00300F1E76FF0010091 +:10228000EEE7000070B504461D4616468AB02822C7 +:1022900000216846FFF70AFABDF838306946ADF804 +:1022A00010300F9B204605939DF84030CDE9026524 +:1022B0008DF81830119B0793BDF84830ADF82030E9 +:1022C000FFF79CFF0AB070BD2DE9F041D3690546C8 +:1022D0000C4616460BB9138C5BBB377E1F2F28D8D4 +:1022E00095F80080B8F1000F26D03046FFF7E2FDE8 +:1022F0003378210241EAC33141EA0801338A41EAD5 +:10230000076141EA034102463346284641F0800115 +:10231000FFF79CFE00280ADD3378012B07D1726994 +:1023200013780133DBB21F2B88BF00231370BDE885 +:10233000F0816FF00100FAE76FF00300F7E70000AB +:10234000F0B504460D461E4617468BB028220021E4 +:102350006846FFF7ABF99DF84C3029465A1E5342A8 +:1023600053418DF800309DF840306A46ADF810308A +:10237000119B204605939DF84830CDE902768DF8F3 +:102380001830149B0793BDF85430ADF82030FFF798 +:102390009BFF0BB0F0BD0000406A00B104307047F5 +:1023A000436A1A68426202691A600361C38A013B88 +:1023B000C38270472DE9F041D0F8208014461D46B5 +:1023C00041460027174E09B9BDE8F081D1E9022343 +:1023D000A21A65EB0303964277EB03031ED2036A4E +:1023E0008B420DD1FFF790FD036A1B6803620369FE +:1023F0000B60C38A0161016A013B8846C382E2E740 +:10240000FFF782FD0B68C8F8003003690B60C38AD0 +:102410000161013BC382D8F80010D4E788460968FF +:10242000D1E700BF80841E002DE9F04F8BB00D4630 +:1024300014469B468046DDF85090002800F01A8133 +:10244000B9F1000F00F01681531E3F2B00F21281EC +:10245000012A03D1BBF1000F40F00C810023CDE92C +:102460000833B8F81430B5EBC30F4FEAC30703D3F2 +:1024700000200BB0BDE8F08F2B199F42D8F80C302C +:1024800036BF7F1B2746FFB21BB9D8F81030002B90 +:102490007BD0272D4ED8C5F12806B7424FF0000358 +:1024A00034BF3E46F6B2009329463246D8F80800BB +:1024B00008ABFFF745FCA7EB060A35445FFA8AFA3A +:1024C0002821B8F8143003F10053053BDB000493D6 +:1024D000D8F80C300393039B13B1BAF1000F2CD141 +:1024E000D8F8100040B1BAF1000F05D0524600965E +:1024F00008AB691AFFF724FC38B2002FB8D0660782 +:102500000AD00AAB03EBD40111F8083C624202F096 +:102510000702134101F8083C082C3DD9102C40F269 +:10252000B680202C40F2B880BBF1000F00F09D80F7 +:10253000082335E0BA460026C2E7049BE02B28BFFB +:10254000E02306930B44AB42059315D95A1B9245E1 +:1025500038BF5246039828BFD2B20096691A08AB1A +:1025600004300792FFF7ECFB079A1644AAEB020A25 +:102570001544F6B25FFA8AFA049B069A05999B1AEB +:102580000493039B1B680393A5E700933A462946EF +:10259000D8F8080008ABADE7BBF1000F13D001235A +:1025A000B4EBC30F6CD0082C12D89DF82030621EFB +:1025B00023FA02F2D50706D54FF0FF3202FA04F4EF +:1025C00023438DF820309DF8203089F8003050E703 +:1025D000102C12D8BDF82030621E23FA02F2D10767 +:1025E00006D54FF0FF3202FA04F42343ADF8203051 +:1025F000BDF82030A9F800303BE7202C0FD808990F +:10260000631E21FA03F3DA0705D54FF0FF3202FA11 +:1026100004F40C430894089BC9F8003029E7402CC7 +:102620002BD0DDE90865611EC4F12102A4F121036C +:1026300026FA01F105FA02F225FA03F311431943D0 +:10264000CB0712D50122A4F12003C4F1200102FA24 +:1026500003F322FA01F1A240524243EA010363EB81 +:10266000430332432B43CDE90823DDE90823C9E9BD +:102670000023FEE66FF00100FBE66FF00800F8E6CD +:10268000082CA0D9102CB3D9202CEED8C3E7BBF16D +:10269000000FADD0022383E7BBF1000FBBD00423B2 +:1026A0007EE70000012A30B5144638BF012200251C +:1026B000402A28BF402285B0012CCDE9025517D809 +:1026C0001B788DF8083053070AD004AB03EBD20512 +:1026D00015F8083C544204F00704A34005F8083CF0 +:1026E0000346009102A80021FFF72AFB05B030BD88 +:1026F000082CE5D9102C03D81B88ADF80830E2E788 +:10270000202C02D81B680293DDE7D3E90045CDE910 +:102710000245D8E710B5CB681BB98B600B618B8283 +:1027200010BD04691A681C600361C38A013BC3823F +:10273000CA60F0E703064CBFC0F3C0300220704708 +:1027400008B50246FFF7F6FF022806D15306C2F38A +:102750000F2001D100F0030008BDC2F30740FBE7E2 +:102760002DE9F04F93B0CDE903230A6804461046E3 +:10277000FFF7E0FF02280CBF0026C2F30626002A5E +:102780000D46824680F2F98112F0C04940F0F58191 +:10279000097B002900F0F181022803D02378B3429D +:1027A00040F0EE81C2F304631046069302F07F030B +:1027B0000593FFF7C5FF059B00224FEA83480023DE +:1027C00048EA0A48294448EA4668CE78CDE9082311 +:1027D000F309834648EA0008029367D0059B024646 +:1027E000009320465346676808A9B847002800F0C0 +:1027F000CA81276A4FB9414604F10C00FFF704FB78 +:10280000074690B96FF0020054E03B6998450DD03F +:102810003F68002FF9D1414604F10C00FFF7F4FAAC +:1028200007460028EED0236A3B60276297F817C05E +:1028300006F01F08CCF3840CACEB08001FFA80FEF6 +:102840000028B8BF0EF12000A8EB0C031FFA83FE8E +:10285000B8BF00B2002B0793BEBF0EF120031BB21E +:102860000793D7E9022152EA010338D04FF0000C58 +:10287000039BDFF8F8E19A1A049B63EB010196458C +:102880007CEB01032BD36B7B97F81AE0734519D1CE +:10289000029B002B78D0012821DC7868F8B9DFF89A +:1028A000D0C1944570EB010316D337E0276A27B9EE +:1028B0006FF00C0013B0BDE8F08F3B699845B5D0C0 +:1028C0003F68F4E76A4890427CEB010301D30020A3 +:1028D000F0E7029B002BFAD0079B0F2B17DCFA7D49 +:1028E000B30002F0030203F07C031343FB75394687 +:1028F0002046FFF709FB6B7BBB76029B3BB9FB7D58 +:10290000C3F38402013262F38603FB75D0E76A7B6E +:10291000BB7E9A42DBD1029B002B35D0B309022B40 +:1029200032D0039B1422BB60049B0021FB600DA8E6 +:10293000FEF7BCFE039B20460A93049BADF83EB015 +:102940000B932B1D0C932B7B8DF840A0013BDBB22E +:10295000ADF83C30069B8DF841808DF84230059BE8 +:102960000AA98DF8433094F82C3083F001038DF8D8 +:102970004430A3689847FB7DC3F38403013303F01D +:102980001F039B02FB82A2E7FB7DC6F34012B2EB62 +:10299000D31F40F0FB80C3F38403434540F0F9802C +:1029A000029A2B7BB609002A4DD0F20762D4032B82 +:1029B00040F2F280039BAE1DBB60049B3246FB607D +:1029C0002B7B3946033BDBB204F10C00FFF7AEFA78 +:1029D00000280CDA39462046FFF796FAFB7DC3F350 +:1029E0008403013303F01F039B02FB820AE7AB88D9 +:1029F000DDE908843B834FF6FF73C9F12000A9F19C +:102A0000200228FA09F104FA00F0014324FA02F244 +:102A100011431846C9B2FFF7CBF909F10809B9F11A +:102A2000400F0346E9D13146B8822A7B033AD2B23D +:102A3000FFF7D0F9FB7DB882DA43C2F3C01262F32C +:102A4000C713FB7543E7AEB92E1D013B324639462D +:102A5000DBB204F10C00FFF769FA0028BADB2A7B2D +:102A60003146013AB88AD2B2E2E700BF80841E0044 +:102A700040420F00F98A013BC1F309010429DAB28F +:102A80005DD80023281D07F11B069A4208D910F8CB +:102A900001CB013306F801C001310529DBB2F4D1C5 +:102AA000934228BF0023039938BF04330A91049945 +:102AB00038BFDBB20B9107F11B010C91796838BF6D +:102AC0005B190D910E93FB8AADF83EB0C3F3090379 +:102AD0001A44069BADF83C208DF84230059B8DF8DA +:102AE00040A08DF8433094F82C308DF8418083F06D +:102AF00001038DF8443000237B602A7BB88A013AB9 +:102B0000291DFFF767F93B8BB882834203D120462A +:102B1000A3680AA9984720460AA9FFF7FBFDFB7D99 +:102B2000BA8AC3F38403013303F01F039B02FB82C1 +:102B30003B8B9A420CBF00206FF01000BAE67B6816 +:102B4000002BADD0052001E033461C301E68002E5E +:102B5000FAD1091A081D2E1D184401EB090CBCF10D +:102B60001B0F5FFA89F39BD89A4299D916F8013B5B +:102B700009F1010900F8013BEFE76FF0090099E660 +:102B80006FF00A0096E66FF00B0093E66FF00D0011 +:102B900090E66FF00E008DE66FF00F008AE600BF42 +:102BA000F0B53F4D3F4FEB6943F00073EB61EB69CC +:102BB0003D4B9B6AD3F800623E4046F00106C3F8E5 +:102BC0000062D3F800423C4044EA002444F001048F +:102BD000C3F80042002955D000200646C3F81C0265 +:102BE000C3F80402C3F80C02C3F8140203EBC004D8 +:102BF00001300E28C4F84062C4F84462F6D10027C0 +:102C00004FF0010C9678148816F0010F18BFD3F816 +:102C100004E20CFA04F01CBF40EA0E0EC3F804E212 +:102C200016F0020F18BFD3F80CE203EBC4041CBF6C +:102C300040EA0E0EC3F80CE2760748BFD3F81462E0 +:102C400007F1010744BF0643C3F814625668B9424E +:102C5000C4F84062966802F10C02C4F84462D3F8EA +:102C60001C4240EA0400C3F81C02CBD1D3F8002276 +:102C700022F00102C3F80022EB6923F00073EB613C +:102C8000EB69F0BD0122C3F84012C3F84412C3F847 +:102C90000412C3F81412C3F80C22C3F81C22E5E78F +:102CA000001002400000FFFFA8230020184A08B5CA +:102CB000916A8B688B6013F0010104D013F00C0F44 +:102CC00018BF4FF48031D80506D513F4406F14BFF8 +:102CD00041F4003141F00201D80306D513F4402F2E +:102CE00014BF41F4802141F00401D3690BB10848BD +:102CF0009847302383F311880021064800F048FBF1 +:102D0000002383F31188BDE8084000F099BD00BF9F +:102D1000A8230020B023002038B5124CA36ADD6838 +:102D2000AA0712D05A6922F002025A61A36913B1AC +:102D3000012120469847302383F3118800210A4857 +:102D400000F026FB002383F31188EB0606D5102143 +:102D5000A36AD960236A0BB102489847BDE838409E +:102D600000F06EBDA8230020B823002038B5124C17 +:102D7000A36A1D69AA0712D05A6922F010025A618B +:102D8000A36913B1022120469847302383F31188A9 +:102D900000210A4800F0FCFA002383F31188EB06B7 +:102DA00006D51021A36A1961236A0BB1024898471E +:102DB000BDE8384000F044BDA8230020B82300201F +:102DC00038B50F4CA36A5D682A075D600AD50422F6 +:102DD00022701A6822F002021A60636A13B100219D +:102DE000204698476B0706D5A36A9969236A13B1F1 +:102DF000034809049847BDE8384000F021BD00BFF2 +:102E0000A823002010B50E4C204600F02FF90D4BE2 +:102E10000B211320A36200F009F90B21142000F00C +:102E200005F90B21152000F001F90B21162000F007 +:102E3000FDF8BDE8104000220E201146FFF7B0BE9D +:102E4000A8230020006400400F4B10B598420446B0 +:102E500005D10E4BDA6942F00072DA61DB690122BA +:102E6000A36A1A60A36A5A68D20707D562685168D4 +:102E70001268D9611A60064A5A6110BD0121082002 +:102E800000F0B0F9EEE700BFA823002000100240D8 +:102E90005B87010003291AD8DFE801F0020A0F144A +:102EA000836A9B6813F0E05F14BF01200020704725 +:102EB000836A9868C0F380607047836A9868C0F33B +:102EC000C0607047836A9868C0F300707047002044 +:102ED0007047000010B5032927D8DFE801F002276A +:102EE0002B2F836A9968C1F30161183103EB011339 +:102EF0001078840648BF5468C0F3001158BF948806 +:102F00004FEA410148BF41EAC40100F00F00586098 +:102F100048BF41F00401906858BF41EA4451D2686B +:102F200041F001019860DA60196010BD836A03F511 +:102F3000C073DDE7836A03F5C873D9E7836A03F5D5 +:102F4000D073D5E701290AD002290FD081B9836A4D +:102F5000DA68920701D1186903E001207047836A9B +:102F6000D86810F0030018BF01207047836AF2E7A9 +:102F70000020704710B539B9836AD96889071BD119 +:102F80001B699C0704D110BD012915D00229FAD173 +:102F9000816AD1F8C031D1F8C441D1F8C8011061BB +:102FA000D1F8CC015061202008610869800717D151 +:102FB000486940F0100012E0816AD1F8B031D1F8D0 +:102FC000B441D1F8B8011061D1F8BC0150612020A2 +:102FD000C860C868800703D1486940F002004861B2 +:102FE000C3F34000C3F38001000140EA41111079AE +:102FF00020F030000143117189064BBF916811899F +:10300000DB085B0D4CBF63F31C0163F30A0113790A +:1030100048BF916064F3030313714FEA14234FEA2E +:10302000144458BF118113705480ACE70122090188 +:1030300000F1604303F56143C9B283F8001300F067 +:103040001F039A4043099B0003F1604303F561436A +:10305000C3F880211A607047090100F16040C9B2CD +:1030600000F56D4001767047FFF7CCBE0123037079 +:10307000002300F10802C0E9022200F11002C0E9B9 +:103080000422C0E90633C0E90833436070470000FA +:1030900010B53023044683F3118802234160037086 +:1030A000FFF7D2FE04230020237080F3118810BDA7 +:1030B0002DE9F0411F4604460D461646302383F3A2 +:1030C000118800F108082378052B0DD029462046E9 +:1030D000FFF7E0FE40B1204632462946FFF7FAFEF0 +:1030E000002080F3118808E03946404600F040F99E +:1030F0000028E8D0002383F31188BDE8F0810000A8 +:103100002DE9F0411F4604460D461646302383F351 +:10311000118800F110082378052B0DD02946204690 +:10312000FFF710FF40B1204632462946FFF722FF45 +:10313000002080F3118808E03946404600F018F975 +:103140000028E8D0002383F31188BDE8F081000057 +:1031500000238268037503691B6899689142FBD25A +:103160005A680360426010605860704700238268AC +:10317000037503691B6899689142FBD85A6803601C +:10318000426010605860704708B50846302383F3EA +:1031900011880B7D032B05D0042B0DD02BB983F3A5 +:1031A000118808BD00228B691A604FF0FF338361DC +:1031B000FFF7CEFF0023F2E7D1E9003213605A6037 +:1031C000F3E70000FFF7C4BF054BD968087518681E +:1031D000026853601A6001220275D860FDF796BB41 +:1031E000D823002030B50C4B0446DD684B1C87B05B +:1031F0000FD02B466846094A00F0F0F82046FFF74A +:10320000E3FF009B13B1684600F0F0F8A86907B02F +:1032100030BDFFF7D9FFF9E7D82300208931000836 +:10322000044B1A68DB6890689B68984294BF002042 +:1032300001207047D8230020084B10B51C68D868BF +:10324000226853601A6001222275DC60FFF78EFF4E +:1032500001462046BDE81040FDF758BBD8230020AA +:10326000044B1A68DB6892689B689A4201D9FFF7A1 +:10327000E3BF7047D823002038B501230025064C52 +:10328000064907482370656000F020FB0223237085 +:1032900085F3118838BD00BF30250020A83D000807 +:1032A000D823002000F0B4B8EFF3118020B9EFF379 +:1032B0000583302282F311887047000010B530B9C1 +:1032C000EFF30584C4F3080414B180F3118810BD32 +:1032D000FFF7C6FF84F31188F9E700008B60022333 +:1032E00008618B82084670478368A3F1440243F863 +:1032F000142C026943F8442C426943F8402C094AD3 +:1033000043F8242CC268A3F1200043F8182C0222B1 +:1033100003F80C2C002203F80B2C034A43F8102C62 +:10332000704700BF1D090008D823002008B5FFF72B +:10333000DBFFBDE80840FFF745BF0000024BDB683C +:1033400098610F20FFF740BFD8230020302383F37C +:103350001188FFF7F3BF000008B50146302383F35F +:1033600011880820FFF73EFF002383F3118808BD72 +:10337000064BDB6839B1426818605A6013604360DD +:103380000420FFF72FBF4FF0FF307047D8230020F5 +:1033900038B504460D462068844200D138BD036824 +:1033A00023605C608561FFF70DFFF4E710B50A4C00 +:1033B00023699A6891420CD85A6881600360426020 +:1033C00010609A685860511A99604FF0FF33A361FA +:1033D00010BD1B68891AECE7D8230020C0E903233D +:1033E000002310B410BC4361FFF7E0BF036881689D +:1033F0009A680A449A60426813605A6000234FF04A +:10340000FF320360014B9A61704700BFD823002050 +:1034100070B5124D2A46EB690133EB6152F8103F4B +:10342000934206D030269A68013A9A602C69A368C4 +:1034300003B170BDD4E900210A605160236083F3B9 +:1034400011882046D4E90331984786F311886169D1 +:103450000029EBD02046FFF7A9FFE7E7D82300209B +:1034600000207047FEE70000704700004FF0FF307B +:1034700070470000BFF34F8F024AD368DB07FCD4CC +:10348000704700BF0020024008B5074B1B7853B9B6 +:10349000FFF7F0FF054B1A69120641BF044A5A6054 +:1034A00002F188325A6008BD482500200020024001 +:1034B0002301674508B5054B1B7833B9FFF7DAFFE1 +:1034C000034A136943F08003136108BD48250020B7 +:1034D000002002407F289ABF00F5003080020020C3 +:1034E000704700004FF480607047000080207047F4 +:1034F0007F2808B50BD8FFF7EDFF00F58063026861 +:10350000013204D104308342F9D1012008BD0020EA +:10351000FCE700007F2810B504461CD8FFF7AAFF7F +:10352000FFF7B2FFF3220D4B4FF48061DA60022205 +:103530001A61FFF7CFFF58611A6942F040021A6121 +:10354000FFF798FF00F004F9FFF7B4FF2046BDE84D +:103550001040FFF7CDBF002010BD00BF002002408B +:103560002DE9F843054612F00100144606D040F25A +:10357000F32200201E4B1A60BDE8F8831D4BAA18E9 +:103580009A4204D94FF43E72194B1A60F4E7FFF7E0 +:103590007BFF4FF00109FFF76DFFDFF85C806D1ACC +:1035A000012C0F4605EB010603D8FFF783FF01202E +:1035B000E2E73B88C8F8109033800020FFF75AFFFD +:1035C000C8F81000338831F8022B9BB29A420CD015 +:1035D00040F20F32064B1A60084B1E60084B1C600D +:1035E000084B1F60FFF766FFC6E7023CD8E700BF45 +:1035F0004425002000000208002002403825002059 +:10360000402500203C250020084908B50B7828B14A +:103610001BB9FFF739FF01230B7008BD002BFCD04D +:10362000BDE808400870FFF745BF00BF48250020EF +:1036300070B5FFF739FE4FF47A710D4B0D4EDB6913 +:10364000326801FB03F3934237BF0B4A0A495168C2 +:10365000156836BF4C1CD1E9005454605D1944F123 +:1036600000043360FFF72AFE2846214670BD00BFE4 +:10367000D82300204C2500205025002070B5FFF7EE +:1036800013FE4FF47A710F4B0F4EDB69326801FB6A +:1036900003F3934237BF0D4A0C49516815683ABF8E +:1036A0004C1C5460D1E900545D1944F100043360AE +:1036B000FFF704FE4FF47A72002328462146FCF7F8 +:1036C00031FF70BDD82300204C250020502500205C +:1036D00010B5094C013AD2B2FF2A00D110BD5008F2 +:1036E00054F82030013054F820009BB243EA0043E4 +:1036F00041F8043BEEE700BF046C004010B50748FA +:10370000013AD2B2FF2A00D110BD0C88530840F80C +:1037100023404C88013340F82340F1E7046C00401B +:1037200007B50122002001A9FFF7D2FF019803B0DD +:103730005DF804FB13B50446FFF7F2FFA04205D085 +:103740000122002001A90194FFF7D8FF02B010BDAB +:103750007047000045F25552064B1A6002225A602B +:1037600040F6FF729A604CF6CC421A600122024B7E +:103770001A707047003000405C250020034B1B7816 +:103780001BB14AF6AA22024B1A6070475C25002042 +:1037900000300040044B1A682AB902F1804202F559 +:1037A0000432526A1A607047582500204FF0807228 +:1037B000014B5A62704700BF0010024008B5FFF786 +:1037C000E9FF024B1868C0F3407008BD582500207F +:1037D00008B5FFF7DFFF024B1868C0F3007008BDA3 +:1037E00058250020EFF30983203383F30988002351 +:1037F00083F3118870470000302080F3118862B68F +:103800000C4B0D4AD96821F4E0610904090C0A4304 +:10381000DA60D3F8FC20094942F08072C3F8FC203A +:103820000A6842F001020A602022DA7783F8220057 +:10383000704700BF00ED00E00003FA05001000E053 +:10384000302310B583F311880B4B5B6813F40063CE +:103850000FD0EFF309844FF08073203CE36184F3D1 +:103860000988FFF7DDFC10B1044BA36110BD044BC8 +:10387000FBE783F31188F9E700ED00E02F0900086A +:103880003209000870470000FEE700000A4B0B48B1 +:103890000B4A90420BD30B4BC11EDA1C121A22F0BA +:1038A00003028B4238BF00220021FDF7FFBE53F810 +:1038B000041B40F8041BECE72C3E0008E025002028 +:1038C000E0250020E0250020FEE7000070B500257F +:1038D00004461A4B86B05860856201630E46FFF7B6 +:1038E0008BFF04F11003C4E904334FF0FF33A361ED +:1038F000134BE561D9692B460A462046C4E90823E3 +:1039000004F134018023C4E900440E4AA560E56255 +:103910002565FFF7E3FC01230B4AE0600375009285 +:10392000726868460192B268CDE90223074BCDE97F +:103930000435FFF7FBFC06B070BD00BF302500204A +:10394000D8230020B43D0008B93D0008C93800085C +:1039500000F030B808B500F063F9FFF78DFCBDE862 +:103960000840FFF717BF0000704700004FF0FF311D +:103970000E4B1A6919611A6900221A611869D86810 +:10398000D960D968DA60DA68DA6942F08052DA61BF +:10399000DA69DA6942F00062DA61054ADB691368C4 +:1039A00043F48073136000F01BB900BF00100240A5 +:1039B00000700040194B1A6842F001021A601A6840 +:1039C0009007FCD51A6802F0F9021A6000225A60CA +:1039D0005A6812F00C0FFBD11A6842F480321A6058 +:1039E0001A689103FCD55A6842F4E8125A601A68C2 +:1039F00042F080721A601A689201FCD51221084ABE +:103A00005A60084A11605A6842F002025A605A68C5 +:103A100002F00C02082AFAD1704700BF00100240E1 +:103A200000641D0000200240084A08B5516913686F +:103A30000B4003F00103536123B1054A13680BB136 +:103A400050689847BDE80840FFF7FABE00040140FF +:103A500060250020084A08B5516913680B4003F03F +:103A60000203536123B1054A93680BB1D0689847AC +:103A7000BDE80840FFF7E4BE0004014060250020D7 +:103A8000084A08B5516913680B4003F004035361F9 +:103A900023B1054A13690BB150699847BDE8084046 +:103AA000FFF7CEBE0004014060250020084A08B59B +:103AB000516913680B4003F00803536123B1054AB1 +:103AC00093690BB1D0699847BDE80840FFF7B8BECD +:103AD0000004014060250020084A08B551691368B8 +:103AE0000B4003F01003536123B1054A136A0BB175 +:103AF000506A9847BDE80840FFF7A2BE00040140A5 +:103B000060250020174B10B55A691C68144004F456 +:103B100078725A61A30604D5134A936A0BB1D06A2E +:103B20009847600604D5104A136B0BB1506B984749 +:103B3000210604D50C4A936B0BB1D06B9847E20574 +:103B400004D5094A136C0BB1506C9847A30504D5F2 +:103B5000054A936C0BB1D06C9847BDE81040FFF755 +:103B60006FBE00BF00040140602500201A4B10B555 +:103B70005A691C68144004F47C425A61620504D5F9 +:103B8000164A136D0BB1506D9847230504D5134A9F +:103B9000936D0BB1D06D9847E00404D50F4A136EB6 +:103BA0000BB1506E9847A10404D50C4A936E0BB12B +:103BB000D06E9847620404D5084A136F0BB1506F5A +:103BC0009847230404D5054A936F0BB1D06F9847EB +:103BD000BDE81040FFF734BE00040140602500201E +:103BE000062108B50846FFF721FA06210720FFF74E +:103BF0001DFA06210820FFF719FA06210920FFF710 +:103C000015FA06210A20FFF711FA06211720FFF7FF +:103C10000DFABDE8084006212820FFF707BA00008A +:103C200008B5FFF7A3FE054800F00CF8FFF71CFAF3 +:103C3000FFF79AFEBDE8084000F002B8C03D00085A +:103C400000F042B8002319461C4A0133102BC2E988 +:103C5000001102F10802F8D1194B9A6942F07D0275 +:103C60009A619B690268174BDA6082685A60426801 +:103C70001A60C26803F58063DA6042695A600269BB +:103C80001A608269C3F80C24026AC3F80424C2696A +:103C9000C3F80024426AC3F80C28C26AC3F8042897 +:103CA000826AC3F80028026BC3F80C2C826BC3F83D +:103CB000042C426BC3F8002C704700BF6025002025 +:103CC00000100240000801404FF0E023044A0821A0 +:103CD0005A6100229A6107220B201A61FFF7BCB9D2 +:103CE0003F19010008B5302383F31188FFF7DAFA92 +:103CF000002383F3118808BD08B5FFF7F3FFBDE883 +:103D00000840FFF79DBD000010B501390244904204 +:103D100001D1002005E0037811F8014FA34201D042 +:103D2000181B10BD0130F2E72DE9F0419BB10446AC +:103D3000C91A1778014403F1FF3C8C42204601D98F +:103D4000002008E005780134BD42F6D10CEB0405F3 +:103D5000D618A54201D1BDE8F08115F8018D16F8FD +:103D600001EDF045F5D0E8E7034611F8012B03F823 +:103D7000012B002AF9D170476F72672E617264754A +:103D800070696C6F742E663130332D4750530000CC +:103D900040A2E4F1646891060041A3E5F2656992EE +:103DA0000700000063300000A43D0008302400201C +:103DB000302500206D61696E0069646C650000004B +:103DC00000180000444441444454494401000000A8 +:103DD00042444444444444440000000044444444B5 +:103DE00044444444000000004444444444444444A3 +:103DF00000000000444444444444444458C7FF7F06 +:103E00000100000000000000E803000000000000C6 +:103E1000009C0100000000006400000000000000A1 +:0C3E200040420F00FE2A0100D204000006 :00000001FF diff --git a/Tools/bootloaders/f103-HWESC_bl.bin b/Tools/bootloaders/f103-HWESC_bl.bin index 317da7d42b6dfc..1ff1cd6a394bca 100755 Binary files a/Tools/bootloaders/f103-HWESC_bl.bin and b/Tools/bootloaders/f103-HWESC_bl.bin differ diff --git a/Tools/bootloaders/f103-HWESC_bl.hex b/Tools/bootloaders/f103-HWESC_bl.hex index 361ab40014cd8c..9dcc716daf87d0 100644 --- a/Tools/bootloaders/f103-HWESC_bl.hex +++ b/Tools/bootloaders/f103-HWESC_bl.hex @@ -1,1062 +1,997 @@ :020000040800F2 -:1000000000090020A10400081514000819140008B4 -:10001000551400081914000835140008A30400083A -:10002000A3040008A3040008A3040008C5360008C0 -:10003000A3040008A3040008A3040008593A000818 -:10004000A3040008A3040008A3040008A3040008F4 -:10005000A3040008A3040008393800086538000824 -:1000600091380008BD380008E9380008A3040008EA -:10007000A3040008A3040008A3040008A3040008C4 -:10008000A3040008A3040008A304000869250008CD -:10009000D5250008292600087D2600081539000806 -:1000A000A3040008A3040008A3040008A304000894 -:1000B000A3040008A3040008A3040008A304000884 -:1000C000A3040008A3040008A3040008A304000874 -:1000D000A3040008A12A0008B52A0008A304000808 -:1000E0007D390008A3040008A3040008A304000845 -:1000F000A3040008A3040008A3040008A304000844 -:10010000A3040008A3040008A3040008A304000833 -:10011000A3040008A3040008A3040008A304000823 -:10012000A3040008A3040008A3040008A304000813 -:10013000A3040008A3040008A3040008A304000803 -:10014000A3040008A3040008A3040008A3040008F3 -:10015000A3040008A3040008A3040008A3040008E3 -:10016000D0400B1CD1409C46203AD3401843524209 -:1001700063469340184370479140031C90409C464F -:10018000203A9340194352426346D3401943704783 -:1001900053B94AB9002908BF00281CBF4FF0FF31EE -:1001A0004FF0FF3000F07AB9ADF1080C6DE904CEE4 -:1001B00000F006F8DDF804E0DDE9022304B0704742 -:1001C0002DE9F0478C460E460446089D002B50D181 -:1001D0008A4217466CD9B2FA82FEBEF1000F0BD0EC -:1001E000CEF1200C01FA0EF620FA0CFC02FA0EF702 -:1001F0004CEA060C00FA0EF43A0CBCFBF2F9BBB266 -:1002000002FB19CC09FB03FA4FEA144848EA0C46F2 -:10021000B2450AD9F61909F1FF3180F02581B245BE -:1002200040F22281A9F102093E44A6EB0A06B6FB80 -:10023000F2F002FB106600FB03F3A4B244EA0644AA -:10024000A34209D9E41900F1FF3280F00B81A342E7 -:1002500040F2088102383C440021E41A40EA094097 -:10026000002D62D0002324FA0EF42C606B60BDE8F0 -:10027000F0878B4207D9002D55D0002185E8410039 -:100280000846BDE8F087B3FA83F1002940F08F807B -:10029000B34202D3824200F2FC80841A66EB03066A -:1002A0000120B446002D40D085E81010BDE8F0874D -:1002B00012B90127B7FBF2F7B7FA87FEBEF1000FBC -:1002C00035D10121F61B4FEA174C1FFA87F8B6FB10 -:1002D000FCF20CFB126608FB02F0230C43EA064614 -:1002E000B04207D9F61902F1FF3302D2B04200F250 -:1002F000D2801A46361AB6FBFCF00CFB106608FBDF -:1003000000F8A3B243EA0644A04507D9E41900F176 -:10031000FF3302D2A04500F2B9801846A4EB0804CE -:1003200040EA02409CE729462846BDE8F08707FAE4 -:100330000EF7CEF1200326FA03F24FEA174CB2FB78 -:10034000FCF11FFA87F80CFB112206FA0EF620FAD0 -:1003500003F301FB08F933431E0C46EA0246B1459C -:1003600000FA0EF409D9F61901F1FF3280F08C8001 -:10037000B14540F2898002393E44A6EB0906B6FB3E -:10038000FCF00CFB106200FB08F99EB246EA024644 -:10039000B14507D9F61900F1FF3371D2B1456FD9D4 -:1003A00002383E44A6EB090640EA01418FE7C1F15D -:1003B000200722FA07F88B4048EA030326FA07F4DD -:1003C0004FEA134EB4FBFEF91FFA83FC0EFB1944EF -:1003D0008E4020FA07F809FB0CFA48EA06084FEAB3 -:1003E000184646EA0444A24502FA01F200FA01F670 -:1003F00008D9E41809F1FF3044D2A24542D9A9F145 -:1004000002091C44A4EB0A04B4FBFEF00EFB1044EA -:1004100000FB0CFC1FFA88F848EA0444A44507D9FD -:10042000E41800F1FF3E29D2A44527D902381C4424 -:1004300040EA0940A0FB0289A4EB0C0CCC45C24663 -:10044000CE4615D312D055B1B6EB0A036CEB0E06AF -:1004500006FA07F7CB401F43CE402F606E600021A5 -:10046000BDE8F0871046F7E68946DEE64645EAD263 -:10047000B8EB020A69EB030E0138E4E77046D7E7F0 -:1004800018468FE78146BDE7114676E702383C44BF -:1004900044E7084606E7023A3E442BE7704700BFB0 -:1004A00002E000F000F8FEE772B6274880F3088803 -:1004B000264880F3098826484EF60851CEF20001FE -:1004C0000860022080F31488BFF36F8F03F02AF9CD -:1004D00003F046F94FF055301E491B4A91423CBF8C -:1004E00041F8040BFAE71C49184A91423CBF41F815 -:1004F000040BFAE719491A4A1A4B9A423EBF51F8BF -:10050000040B42F8040BF8E700201749174A914200 -:100510003CBF41F8040BFAE703F008F903F022F9B5 -:10052000134C144DAC4203DA54F8041B8847F9E726 -:1005300000F03AF8104C114DAC4203DA54F8041BA9 -:100540008847F9E703F0F0B8000900200011002007 -:10055000000000080001002000090020C041000840 -:1005600000110020741100207811002000260020C6 -:1005700060010008600100086001000860010008D7 -:100580002DE9F04FC1F80CD0C3689D46BDE8F08F4F -:10059000002383F311882846A047002002F07EFE46 -:1005A00002F0A8FD00DFFEE76FF01702364B2DE9E1 -:1005B000F0411A70032200245A7001266FF0630282 -:1005C0009C70DC701C715C719C71DC711C725A72C5 -:1005D0009E72DC7203F020F8804603F06DF8054649 -:1005E000D0BB2A4B984539D03344984537D0284B57 -:1005F00028F0FF029A4234D15FFA88F000F04EFAF8 -:100600002E4642F2107400F077FC00F04DFA0746D7 -:1006100058B364BB374635B11E4B984503D0002410 -:1006200003F042F82746002003F000F81A4B9B68BD -:1006300013F040031ED00FB100F030F800F07EFC44 -:1006400000F018FE00F014FF0546ACB900F0CCFC39 -:10065000012002F029FEF8E70646D4E706462C46BC -:10066000D1E706464FF47A74CDE70446D3E74FF45A -:100670007A74D0E71C46E1E700F0FAFE401BA04286 -:10068000E4D900F00BF8DDE778110020010007B095 -:10069000000008B0263A09B0000C014010B51C4B10 -:1006A0001C4953F8042F013200D110BD8B42F8D100 -:1006B000194C1A4B22689A4228D9194B9B6803F1AE -:1006C000006303F5C8439A4220D202F0C1FF02F052 -:1006D000D3FF002000F0E8FD0220124B187000F05C -:1006E0001FFE114BDA690022DA61D96999699A61B2 -:1006F0009B6972B60D4B0E4A202113601B6822685D -:1007000081F311889D4683F30888104710BD00BF10 -:10071000FC6300081C64000804640008FF63000810 -:1007200078110020841100200010024000640008AD -:1007300008ED00E049F2690008490B689AB21B0C09 -:1007400000FB02330B6044F25061054A136898B213 -:100750001B0C01FB0030106080B270470C110020B0 -:100760000811002010B504460021102200F0F4FD0D -:10077000034B03CB206061601868A06010BD00BF10 -:10078000E8F7FF1FF0B5BBB000F072FE1D4CA36888 -:10079000C31AF92B30D906AD2346A06028220021C8 -:1007A000284601F0F3FB04F10E0000F0CDFD00231C -:1007B000C6B2591D5F1CDBB2B3424FEAC10107DA72 -:1007C0000E3323440822284601F0E0FB3B46F0E7C5 -:1007D00001230393082302930B4B207B01933023C7 -:1007E000C1F3CF0105910093014604A3D3E900238F -:1007F0000495064801F09AF93BB0F0BD78F6339FB6 -:1008000093CACD8DC8210020D5210020A021002031 -:1008100070B50D4614461E4601F02EF950B9022E51 -:100820000ED1012C0CD112A3D3E90023C5E900237A -:10083000012070BD052C14D003D8012C09D0002054 -:1008400070BD282C09D0302CF9D10BA3D3E900239B -:10085000ECE70BA3D3E90023E8E70BA3D3E90023DC -:10086000E4E70BA3D3E90023E0E700BFAFF3008088 -:10087000401DA12026812A0B78F6339F93CACD8D87 -:100880009E6AC421818A46EE26417272DF25D7B75F -:10089000F017304A39059E5638B50D4604460346D2 -:1008A00020222846002101F071FB22792346032AE9 -:1008B00028BF0322284603F8042F2021022201F03A -:1008C00065FB62792346072A28BF0722284603F8DA -:1008D000052F2221032201F059FBA2792346072A82 -:1008E00028BF0722284603F8062F2521032201F0FE -:1008F0004DFB284604F108031022282101F046FB95 -:10090000382038BD2DE9F04FADF5017D21AE0EAD9B -:1009100040F2791280460F463046002100F01CFD5F -:1009200048220021284600F017FD00F0A1FD4FF4F9 -:100930007A72B0FBF2F0574B0DF15A09186093E848 -:10094000070001232B74002385E807000DF15A00EE -:100950006B74FFF707FF032385F82030E82385F841 -:10096000213006AB18464C4903F0E0F81D222864FC -:100970003146284685F83C20FFF78EFF12AB04462F -:1009800001460822304601F001FB08220DF149031F -:10099000A118304601F0FAFA0DF14A03082204F1D9 -:1009A0001001304601F0F2FA13AB202204F11801D5 -:1009B000304601F0EBFA14AB402204F13801304626 -:1009C00001F0E4FA16AB082204F17801304601F098 -:1009D000DDFA0DF15903082204F18001304601F0DF -:1009E000D5FA04F1880A04F5847B4B465146082267 -:1009F00030460AF1080A01F0C9FAD34509F10109A4 -:100A0000F3D11BAB08225946304601F0BFFA4FF034 -:100A1000000904F5887495F834304B4510D84FF030 -:100A2000000995F83C304B4515D92B6C21464B44B9 -:100A30000822304601F0AAFA083409F10109F0E76A -:100A4000AB6B21464B440822304601F09FFA083434 -:100A500009F10109DFE7E31DC3F3CF03F97E059335 -:100A6000002304960393BB7E193702930123019759 -:100A70000093404605A3D3E9002301F057F80DF594 -:100A8000017DBDE8F08F00BFAFF300809E6AC421F6 -:100A9000818A46EE88110020043D0008014B187041 -:100AA000704700BF94110020F0B5334B85B01C7B1C -:100AB00034B10E22314B1A810024204605B0F0BD1E -:100AC0002F4A02AB1068516803C308232D490DEB70 -:100AD00003022D4803F00CF8054630B90A22274BD3 -:100AE0002A481A8100F08CFCE6E70169B1F5CE3F97 -:100AF00006D90B22214B26481A8100F081FCDCE745 -:100B0000438BB3F57A7F09D00C211C4A214811810F -:100B10004FF47A72194600F073FCCEE71E4A024485 -:100B200002F11003994204D21022144B1B481A817F -:100B3000E3E710398E1A2046134900F09DFC074662 -:100B4000324605F11801204600F096FCAB689F4242 -:100B500002D1EB6898420AD00D22084B1A8100900E -:100B60003B46EA68A9680E4800F04AFCA4E70D4835 -:100B700000F046FC0124A0E7C821002088110020D5 -:100B8000D43B0008DC9B010000640008DC3B00084B -:100B9000E83B0008FA3B0008089CFFF7183C0008F7 -:100BA000353C00085E3C00082DE9F04FADB006AFC3 -:100BB00080460C4600F060FF054600286AD1237E7F -:100BC000022B18D1E38A012B15D100F051FC81468C -:100BD000FFF7B0FD4FF4C873B0FBF3F202FB130054 -:100BE000BB4E80B209F51679E37E484430608BB97C -:100BF0000022B84B1A709C37BD46BDE8F08F3B1DF4 -:100C00001D440095002308224FEAC901204601F047 -:100C100021F84D46A38A5FFA85F9013BAB420BD917 -:100C200005F10109B9F1110FE9D140F23911AA4BCF -:100C3000AA4AAB4802F02EFF07F11400FFF792FD1D -:100C40002A4607F11401381D02F042FF034600282E -:100C5000CED1B9F1100F07D09E4B83F800903368C6 -:100C6000A3F516733360C6E707F1980202F8950DF5 -:100C7000014600922046072200F0ECFFF9787F2918 -:100C800004DD984B954A4FF4A871D2E7404600F036 -:100C9000D7FEB0E7E38A052B00F0068106D8012BCA -:100CA000A9D121464046FFF72DFEA4E7282B3DD0D1 -:100CB000302BA0D1637E8C4D01336A7BDBB2934233 -:100CC000E94640F0EF80E27E2B7B9A4240F0EA80DA -:100CD000002607F1980323F8846D00931022012366 -:100CE0003146204600F0B6FFB4F81480A8F102089F -:100CF0001FFA88F808F1030323F003030A3323F0F3 -:100D00000703ADEB030D0DF1180A33469BB2B11C7E -:100D100098454FEAC10106F101066CDD534400938A -:100D200008220023204600F095FFEEE7A38A013B4E -:100D30009BB2C92B3FF65FAF6B4E357B4DBB06F1C7 -:100D40000C03009308222B462946204600F082FF20 -:100D5000A38A05F10109013BEDB29D424FEAC901A9 -:100D600009DA0E353544009500230822204600F0AC -:100D700071FF4D46ECE700230022C6E90023002363 -:100D8000B36086F8D730C6F8D830337B0BB9E37E32 -:100D90003373002507F114063B1D0822294630460F -:100DA0007D60BD60FD6001F0F1F83B7A05F101095D -:100DB000AB424FEAC90107D9FB6808222B443046F1 -:100DC00001F0E4F84D46F0E70023C1F3CF01E07EE7 -:100DD000059104960393A37E1934029328230146B8 -:100DE0000093019438A3D3E90023404600F09EFE0F -:100DF000FFF7C8FCFFE695F8D70000F05FFAD5F8DA -:100E0000D83006461BB995F8D70000F067FAD5F838 -:100E1000D83043449E4204D295F8D700013000F008 -:100E20005DFA00244FEA980BA0B2584504F1010482 -:100E300008DA2B6880000AEB00010122184400F058 -:100E400093FAF1E7D5F8D840D5E9002312EB080270 -:100E500043F10003444495F8D700C5E90023C5F8E1 -:100E6000D84000F02BFA844209D395F8D7300133EB -:100E700085F8D730D5F8D8309E1BC5F8D860B8F1C2 -:100E8000FF0F08DC00232B7300F03AFAFFF70CFE8B -:100E900008B1FFF703FC2B68144A9B0A0133138146 -:100EA0000023AB60CD46A6E6BFF34F8F1049114B30 -:100EB000CA6802F4E0621343CB60BFF34F8F00BFF8 -:100EC000FDE700BFAFF3008026417272DF25D7B780 -:100ED0009C21002099210020703C0008243D00083E -:100EE000C93C0008EB3C0008C82100208811002004 -:100EF00000ED00E00400FA0508B54FF000530B4A7E -:100F0000196891420AD1597D094A0A4811701B7D1E -:100F1000C922037308490E3000F00CFABDE80840FE -:100F2000E02200214FF0005000F016BA9AAD44C5FF -:100F300094110020C821002016000020022330B5A3 -:100F40001F4C85B0637104230025ADF808300123E0 -:100F50000722ADF80C501B498DF80C308DF80B3082 -:100F6000194B1A484B608DF80A2001F0FFFD184B11 -:100F7000019500931749184B4FF48052174800F021 -:100F800029FD174B2546197811B1144800F058FD7A -:100F900000F06EFA0446FFF7CDFB4FF4C873B0FBC8 -:100FA000F3F202FB130304F516749BB21C440D4BC1 -:100FB0001C6002F081FB08B10F232B8105B030BD0E -:100FC000881100200011002003000600E02200200C -:100FD0001108000898110020A90B0008A02100208A -:100FE000941100209C2100202DE9F04F96A7D7E90D -:100FF00000670FF25C29D9E900898F4C93B0DFF8C4 -:1010000058B2DFF858A2204600F0DCFD0CAD079086 -:1010100098B310220021284600F09EF94FF00002FC -:10102000079B197B61F3030219468DF8302051F8B4 -:10103000040F0EAA496803C21B680D9A584663F351 -:101040001C029DF830300D9243F020038DF83030B3 -:1010500000232A46194601F099FD079030B9204631 -:1010600000F0B4FD079B8AF80030CCE79AF8003016 -:10107000072B40DC01338AF8003018220021284673 -:1010800000F06AF9DFF8D0B1DFF8D4A100232A46D6 -:101090001946584601F0A2FD014680BB102208A85F -:1010A00000F05AF9DAF80C3083F01003CAF80C306B -:1010B00000F0E0F90DF1240E0B4612A9024611E9E9 -:1010C00003008EE803009DF83410C1F30300890685 -:1010D00049BF0E99BDF83810C1F31C0141F0004121 -:1010E00058BFC1F30A018DF82C000891204608A9C9 -:1010F00000F0B2FFCAE7204600F068FDBDE72046D9 -:1011000000F0BAFC824600284AD100F0B1F9DFF8BD -:1011100054B1DBF80030984242D300F0A9F90790AF -:10112000FFF708FB4FF4C873B0FBF3F101FB1300AA -:10113000079A80B202F516721044CBF80000DFF86F -:1011400028B18DF820A09BF8001011B901238DF86B -:10115000203028460791FFF705FB07990DF1210084 -:10116000C1F1100A5FFA8AFABAF1060F28BF4FF0F0 -:10117000060A2944524600F0DDF80AF101030493FF -:1011800008AB0393182302932C4B3246019301239F -:10119000204600933B4600F071FC00238BF80030A2 -:1011A00000F066F9264ADFF8C4A01368C31AB3F545 -:1011B0007A7F32D3106000F05DF902460B4620467C -:1011C00000F00AFD204600F057FC30B39AF80C30CE -:1011D000DFF89CB0002B14BF032302238BF80530EB -:1011E00000F046F94FF47A73B0FBF3F02946CBF8E0 -:1011F00000005846FFF750FB18230293114B0730AD -:10120000019340F25513C0F3CF000490009303956F -:1012100042464B46204600F031FC9AF80C300BB1A8 -:10122000FFF7B0FA9AF80C30002B7FF4E8AE13B059 -:10123000BDE8F08FAFF30080A021002098210020AE -:10124000A8220020AC220020401DA12026812A0BCC -:10125000F1C6A7C1D068080FE0220020AD2200200F -:10126000000801409C21002099210020C821002075 -:101270008811002070B502F0CDF80025084C094E09 -:10128000207030682378834208D902F0BFF83368B1 -:1012900005440133B5F5C84F3360F2D370BD00BFCC -:1012A000DC220020B022002002F04CB900F10060E6 -:1012B000920000F5C84002F0F1B80000054B1A6832 -:1012C000054B1B789B1A834202D9104402F09EB84A -:1012D00000207047B0220020DC22002038B50446F0 -:1012E000064D2868204402F097F828B92868204461 -:1012F000BDE8384002F0A2B838BD00BFB0220020DF -:10130000064991F8243033B100230822086A81F895 -:101310002430FFF7CBBF0120704700BFB42200206C -:10132000022802BF4FF48012014B1A61704700BFC0 -:1013300000080140002310B5934203D0CC5CC45494 -:101340000133F9E710BD000002460346981A13F96D -:10135000011B0029FAD1704703460244934202D090 -:1013600003F8011BFAE770472DE9F047234C0546C7 -:1013700094F824308846174683BB2E46DFF87C90CD -:10138000C7B394F824302BB92022FF2148462662A7 -:10139000FFF7E2FF94F824004146C0F10805BD4282 -:1013A00028BF3D465FFA85FAAD002A4604EB80006F -:1013B000FFF7C0FF94F82430A7EB0A079A445FFABE -:1013C0008AFABAF1080F2E44A844FFB284F824A088 -:1013D000D6D1FFF795FF0028D2D108E0266A06EBA8 -:1013E0008306B042CAD0FFF78BFF0028C5D100208A -:1013F000BDE8F0870120BDE8F08700BFB4220020DF -:101400000FB4002004B070470FB44FF0FF3004B0A9 -:1014100070470000FEE70000EFF30983EFF3058358 -:10142000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE76F -:1014300000ED00E0EFF30983EFF30583044B9A6BB3 -:101440009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFDF -:1014500000ED00E0EFF30983EFF30583034B5A6BD4 -:101460009A6A9A6A9A6A9A6A9B6AFEE700ED00E0B5 -:1014700002F0A0B802F07AB830B5084D0A449142A3 -:101480000BD0092411F8013B5840013CF7D040F340 -:1014900000032B4083EA5000F7E730BD2083B8ED0E -:1014A0000246006848B1036811891360D38801338C -:1014B0009BB29942D38038BF1381704770B5044600 -:1014C0000D4688B0202200216846FFF745FF2046E0 -:1014D0000495FFF7E5FF054658B16B46044608AE94 -:1014E0001A4603CAB24220606160134604F1080440 -:1014F000F6D1284608B070BD2DE9F04130B940F270 -:10150000C531264B264A274802F0C4FA0B7C23B982 -:10151000254B234A40F2C631F5E7C66986B9C16159 -:10152000BDE8F081002B29DA930CAB4229D1B442FB -:1015300001D10C60F3E7C8F800100C60BDE8F08141 -:101540004B68B04623F06047BD0C15EA230538BF51 -:101550003D4634464FEAD37EC3F3807C6368BEEBDE -:10156000D37F23F06042DDD1974203D1C3F3807370 -:101570009C450AD1974205E01C46EFE7AA4206D0F7 -:1015800013469D422CBF00230123002BCFD123689B -:10159000A046002BF0D12160BDE8F081F83F0008A3 -:1015A000EC3D0008B0400008D140000808B5034AEF -:1015B000034B40F25E31034802F06CFAC83D00086C -:1015C00070400008B040000808B503680B60C3888D -:1015D000016033B9044B054A4FF4C761044802F077 -:1015E00059FA013BC38008BD404000083C3E00085A -:1015F000B040000870B50C4600F10C05616831B9C7 -:10160000E38A002061F30903E382002170BD0E68C4 -:101610002846FFF7D9FF6660F0E7000008B542688A -:1016200032B10B4B0B4A40F22F410B4802F032FA19 -:10163000C37DC3F38401013161F38603C375C38A9B -:1016400062F30903C3821B0A62F3C713C37508BDA3 -:101650008C400008F83D0008B04000082DE9F04734 -:10166000089E32B91F4B204A40F239511F4802F000 -:1016700011FA4FF47F4901F007054FEAD6082A44D2 -:1016800006F0070600EBD100954201D1BDE8F087D6 -:1016900005F0070E06F0070AD645774638BF5746CD -:1016A000511BC7F108078F4228BF0F46EC08045DA5 -:1016B00008EBD60113F801C004FA0EF429FA07FE6C -:1016C00024FA0AF45FFA8EFE8CEA04044EFA0AFE4B -:1016D00004EA0E048CEA040C03F801C03D443E44C5 -:1016E000D2E700BF0C400008103E0008B0400008E0 -:1016F0002DE9F04106460F4600254FF6FF7441F2F2 -:1017000021082A4630463946FEF72AFD0823C0B292 -:1017100084EA002414F4004F4FEA4404A4B203F115 -:10172000FF3318BF84EA080413F0FF03F2D1083531 -:10173000402DE6D12046BDE8F081000010B541F211 -:1017400021040A44914200D110BD11F8013B80EA06 -:101750000320082310F4004F4FEA400080B203F149 -:10176000FF3318BF604013F0FF03F3D1EAE7000036 -:101770002DE9F04F85B08A468DE80C00BDF83C405D -:10178000814630B940F26E31484B494A494802F02F -:1017900081F911F0604F04D0474B454A40F26F3158 -:1017A000F4E7009B002B7ED024B10E9B002B7AD057 -:1017B000072C28D809F10C00FFF772FE054628B95E -:1017C0006FF00205284605B0BDE8F08F1422002115 -:1017D000FFF7C2FD22460E9905F10800FFF7AAFDAA -:1017E000631C2B74009B2C441B78294603F01F03B9 -:1017F00063F03F0323724AF000436B604846FFF7F3 -:101800007BFE0125DEE74FF000084FF0800B4646D7 -:101810004546019B1B0A029300F10C0303930398B6 -:10182000FFF73EFE07460028CAD014220021FFF72A -:1018300093FDB6BB02229DF804303B729DF8083040 -:101840007B720E9B711E1944B4420AD9B81801323A -:1018500011F801EFD2B20136072A80F808E0B6B2DB -:10186000F2D1B44208BF4FF0400B009BB818197872 -:10187000013201F01F0141EA48114BEA01030372F2 -:101880004AF000437B603A7439464846FFF734FE1D -:101890000135B4422DB288F001084FF0000BBED1E3 -:1018A00090E70022CDE76FF001058BE7F83F0008D5 -:1018B000DC3D0008B04000081C4000082DE9F0475E -:1018C0001E46CB8A9146C3F30902062A80460F467C -:1018D00019D013460021B0B28DB25A1992B2052A1E -:1018E00009D9A84210D8FA8A034463F30902FA829C -:1018F0000120BDE8F087A842F3D919F801403A4425 -:1019000094760131E8E70025FB8A7C68C3F309007F -:101910001C23821FB2FBF3FA03FB1A2A1FFA8AF276 -:101920007CB301212368002B39D1B31F03441C2051 -:10193000B3FBF0F301339BB299420CD2BAF1000F22 -:1019400009D14046FFF7ACFD08B1C0F800A0206007 -:1019500008B3044600224FF0000AB6B2B54230D2B6 -:101960001346691E4944E018013311F801EF9BB298 -:1019700001351C2B80F804E0ADB214D0AE42F2D891 -:10198000ECE74046FFF78CFD044608B100230360F6 -:101990007C60002CDED16FF00200BDE8F0870131E1 -:1019A00089B21C46BEE7AE42D8D94046FFF778FD63 -:1019B00008B1C0F800A020600028ECD00446002246 -:1019C000CCE7FB8AC3F30902164466F30903FB82E2 -:1019D0008EE70000F8B50E4615461F46044628B9A6 -:1019E000144B154A4F21154802F054F824220021C7 -:1019F000FFF7B2FC069B6A096360079B0020236225 -:101A00004FF6FF739A4228BF1A46A7602070A06164 -:101A1000E06197B204F10C05824205D100232B60EE -:101A200027826382A382F8BD2E60013035462036BE -:101A3000F2E700BFF43F0008683D0008B04000082E -:101A400008B528B97321084B084A094802F022F862 -:101A5000037823B94BB2002B01DD017008BD054BA3 -:101A6000024A7D21F1E700BFF83F0008743D0008FD -:101A7000B04000083C3F0008007870472DE9F7436C -:101A80000D9E074619461046BDF828900B9D9DF8FF -:101A90003040BDF8388016B9B8F1000F43D11F2C83 -:101AA00041D83B78D3B9B8F1070F39D839F00303DF -:101AB00039D1424631464FF6FF70FFF73FFE4FEAFD -:101AC000092920F0010009F44079400449EA04643E -:101AD000400C44EA40244FF6FF730DE043EA09232B -:101AE000B8F1070F43EA0464F5D9FFF701FE424657 -:101AF0003146FFF723FE03468DE840012A46214682 -:101B00003846FFF735FE0DB9FFF750FD2B7801334E -:101B1000DBB21F2B88BF00232B7003B0BDE8F0831E -:101B20006FF00300F9E76FF00100F6E72DE9F743E6 -:101B30000E9F81460B9D9DF830009DF83480BDF8C6 -:101B40003C6007B9C6BB1F2836D899F800E0BEF143 -:101B5000000F34D00C0244F080049DF8281044EAB1 -:101B6000C83444EA014444EA0E04072E44EA0064FF -:101B700015D919461046FFF7BBFD32463946FFF727 -:101B8000DDFD0346019600972A4621464846FFF7A9 -:101B9000EFFDB8F1010F0CD125B9FFF707FD4FF6A6 -:101BA000FF73EFE72B780133DBB21F2B88BF0023D5 -:101BB0002B7003B0BDE8F0836FF00100F9E76FF020 -:101BC0000300F6E7C06900B104307047C1690C300A -:101BD0000B680361FFF7F8BC2DE9F84FD0F818A0A7 -:101BE000054616461F4654464FF00009DFF8608050 -:101BF00000F10C0B0CB9BDE8F88FD4E90223B21A3E -:101C000067EB0303994508BF90451FD2AB69214696 -:101C10009C4228460DD1FFF7EDFCAB6921461B68BD -:101C20005846AB61FFF7D0FCAC692346A2461C4680 -:101C3000E0E7FFF7DFFC23682146CAF8003058468A -:101C4000FFF7C2FC5446DAF80030EFE72368EDE70F -:101C500080841E002DE9F04F8BB00D46144607938B -:101C6000DDF850908246002800F06481B9F1000F41 -:101C700000F06081531E3F2B00F25C81012A03D1EA -:101C8000079B002B40F056810023BAF8146008939C -:101C9000F600B542099380F053812B199E420AD277 -:101CA000761B16F0FF0607D140F26751AA4BAB4AEC -:101CB000AB4801F0EFFE2646DAF80C3023B9DAF82B -:101CC0001030002B00F0A5802F2D31D8C5F1300841 -:101CD00046454FF0000334BFB0465FFA88F80093E2 -:101CE000294608AB4246DAF80800FFF7B7FCA6EB36 -:101CF00008074544FFB24FF0300BBAF8143003F137 -:101D00000053063BDB000293DAF80C300593059B89 -:101D1000002B51D087B9DAF81000002861D0002FCD -:101D20005FD0AB4550D98F4B8C4A40F2A651BFE7EC -:101D300037464FF00008DEE7029B23B98A4B874AFB -:101D40004FF4B161B4E7029BE02B28BFE023069378 -:101D50005B44AB4204931DD95B1B9F4226BFDBB2A1 -:101D600003930397AB4504D97E4B7C4A40F29151D3 -:101D70009EE70598CDF8008008ABA5EB0B01039A10 -:101D80000430FFF76BFC039B9844FF1A1D445FFA75 -:101D900088F8FFB2049B9B4504D3744B6F4A40F212 -:101DA0009B5185E7029B069ADDF810B09B1A0293BF -:101DB000059B1B680593AAE7029BBB42ABD26C4B09 -:101DC000664A40F2A15173E7CDF800803A46A5EB90 -:101DD0000B0108ABB8443D44FFF740FC00275FFA15 -:101DE00088F8BAF81430B5EBC30F04D9614B5B4ADD -:101DF00040F2B1515CE7B8F1400F04D95E4B574A4D -:101E000040F2B25154E767B15C4B544A40F2B351CF -:101E10004EE70093324608AB2946DAF80800FFF790 -:101E20001DFC731E3F2B35B201D8A64204DD544B76 -:101E3000544A40F235213BE760070AD00AAB03EB76 -:101E4000D40111F8083C624202F00702134101F884 -:101E5000083C082C21D9102C21D9202C8CBF082318 -:101E60000423079A002A6DD0B4EBC30F6CD0082C62 -:101E700004F1FF3215D89DF8203023FA02F2D10781 -:101E800006D54FF0FF3202FA04F423438DF82030D8 -:101E90009DF8203089F800304EE00123E1E702236D -:101EA000DFE7102C11D8BDF8203023FA02F2D20758 -:101EB00006D54FF0FF3202FA04F42343ADF8203088 -:101EC000BDF82030A9F8003036E0202C0ED8089953 -:101ED00021FA02F2D30705D54FF0FF3303FA04F4D9 -:101EE0000C430894089BC9F8003025E0402C1CD016 -:101EF000DDE9086730463946FEF732F9002100F087 -:101F0000010050EA01030BD0224601200021FEF718 -:101F100033F9404261EB410106430F43CDE90867C5 -:101F2000DDE90823C9E9002306E0174B154A4FF401 -:101F30002071BDE66FF0010528460BB0BDE8F08FBB -:101F40001D46F9E7012CA3D0082CA1D9102CB7D934 -:101F5000202CE5D8C6E700BF483E0008203E000818 -:101F6000B04000086A3E0008573E00088F3E000857 -:101F7000B73E0008DE3E00080C3F0008243F000882 -:101F80003E3F0008A03D00083C3F000830B585B04A -:101F900030B940F2B121234B234A244801F07AFDA5 -:101FA00023B9234B204A40F2B221F6E7402A04D954 -:101FB000204B1D4A40F2B621EFE722B91D4B1A4AC9 -:101FC0004FF42F71E9E70024012A0294039417D1FA -:101FD0001B788DF8083053070AD004AB03EBD2030B -:101FE00013F8084C554205F00705AC4003F8084CBF -:101FF00000910346002102A8FFF730FB05B030BD79 -:10200000082AE5D9102A03D81B88ADF80830E2E782 -:10201000202A02D81B680293DDE7D3E90045CDE909 -:102020000245D8E7783F0008B43D0008B0400008FA -:10203000933F00083C3F000870B50C4600F10C05CA -:10204000E16819B9A1602161A18270BD0E682846BE -:10205000FFF7BAFAE660F3E72DE9F04FD1F8009008 -:1020600091B0C9F3C01604460D46CDE90223002EF7 -:1020700050D0C9F3C03BC9F30626B9F1000F80F276 -:102080009F8119F0C04F40F09B812B7B002B00F00B -:102090009781BBF1020F03D02278B24240F09381C6 -:1020A00009F07F02BBF1020F059236D119F07F0FC4 -:1020B000C9F30F2A01D10AF0030A2B447606059AC8 -:1020C00093F8038046EA0B4646EA82465FEAD81355 -:1020D00046EA0A06069300F09A800022002310A91F -:1020E00061E90823059B6768009352465B462046DA -:1020F000B847002800F08880A7698FB9314604F1FD -:102100000C00FFF7DBF90746D0B96FF0020011B001 -:10211000BDE8F08F4FF0020BAFE7C9F3074ACCE7F9 -:102120003B699E420DD03F68002FF9D1314604F142 -:102130000C00FFF7C3F907460028E6D0A3693B600F -:10214000A761DDE90801FFF7D3FAB882F97D08F04D -:102150001F06C1F38401711A89B20FFA81FEBEF124 -:10216000000FB8BF01F1200EC9F30461D7E90223C3 -:10217000B8BF0FFA8EFE079152EA030100F02F81DB -:10218000DDE90201801A61EB03010B4600210246E2 -:102190009E48994208BF9042C0F02181069B002BC7 -:1021A0003FD0BEF1010F00F31A8118F0400F38D074 -:1021B000DDE90223C7E90223202200210DEB020002 -:1021C000FFF7CAF8DDE90223CDE908232B1D0A93A6 -:1021D0002B7B2046013BDBB2ADF834309DF81C3040 -:1021E000ADF836A08DF83A309DF814308DF838B03F -:1021F0008DF83B308DF83960A36808A998473846B8 -:10220000FFF70CFA002082E76FF00B007FE7A76969 -:1022100017B96FF00C007AE73B699E4296D03F6891 -:10222000F6E7FB7DC8F34012B2EBD31F40F0CE803F -:10223000C3F38403B34240F0CC8006992B7B4FEA72 -:10224000981279B3D2073CD4032B40F2C580DDE964 -:102250000223C7E902232B7BAE1D033BDBB23246D0 -:10226000394604F10C00FFF729FB002808DA39464B -:102270002046FFF7BFF93846FFF7D0F9032046E7BD -:10228000AB883B832A7B033AD2B2B88A3146FFF748 -:1022900055FAFB7DB882DA43C2F3C01262F3C7136A -:1022A000FB75AFE76AB92E1D013BDBB232463946FA -:1022B00004F10C00FFF702FB0028D8DB2A7B013A6F -:1022C000E2E7FA8A013BC2F30902052AD9B250D8E3 -:1022D0000023281D99420AD907EB020E10F801CB02 -:1022E00001320133062A8EF81AC0DBB2F2D18B42DA -:1022F00028BF0023DDE9028907F11A02CDE9088928 -:102300000A927A683CBF04335B190B920C93FB8AE8 -:10231000ADF836A0C3F3090319449DF81C30ADF89D -:1023200034108DF83A309DF814308DF838B08DF8AF -:102330003B3000238DF839607B602A7BB88A013AF4 -:10234000291DFFF7FBF93B8BB882834203D1A368B9 -:1023500008A92046984708A92046FFF76DFE384691 -:10236000FFF75CF9B88A3B8B984214BF112000201C -:10237000CDE6786810B34FF0060E03689BB9A2EB68 -:102380000E021B2A13D80332024405F1040E1F303B -:102390009942ACD91EF801CB013302F801CF90422B -:1023A000DBB2F5D1A3E70EF11C0E1846E5E7184B9A -:1023B000184A40F2B311184801F06CFB034696E747 -:1023C0006FF00900A3E66FF00A00A0E66FF00D00C1 -:1023D0009DE66FF00E009AE66FF00F0097E6FB7D2A -:1023E000394668F386036FF3C713FB752046FFF782 -:1023F00001F9069B002B7FF4D8AEFB7DC3F384026A -:10240000013262F38603FB7503E700BF80841E0080 -:10241000A83F00088C3D0008B04000082DE9F041BD -:102420004E4EB04240F086804D4CDFF838E1E56911 -:1024300045F00075E561E469846AD4F8007207EA42 -:102440000E0747F00107C4F80072D4F8005205EAFD -:102450000E0545F0010545EA0121C4F80012002AE5 -:102460006AD000210F46C4F81C12C4F80412C4F844 -:102470000C12C4F8141204EBC10501310E29C5F881 -:102480004072C5F84472F6D14FF0000E4FF0010CC7 -:10249000964510D1826AB042D2F8003223F001038F -:1024A000C2F8003258D12E4BDA6922F00072DA619C -:1024B000DB69BDE8F0819F781D8817F0010F18BF18 -:1024C000D4F804820CFA05F11CBF41EA0808C4F8EC -:1024D000048217F0020F18BFD4F80C8204EBC50574 -:1024E0001CBF41EA0808C4F80C827F0748BFD4F833 -:1024F000147203F10C0344BF0F43C4F8147253F871 -:10250000087C0EF1010EC5F8407253F8047CC5F842 -:102510004472D4F81C522943C4F81C12B8E70021B5 -:10252000846AC4F81C12C4F80412C4F80C12C4F86B -:102530001412A9E7002AF2D10022836AC3F84022CC -:10254000C3F84422C3F80422C3F814220122C3F8BA -:102550000C22C3F81C229DE7BDE8F081E022002098 -:10256000001002400000FFFF184A08B5916A8B680E -:102570008B6013F0010105D013F00C0F14BF4FF462 -:1025800080310121D80506D513F4406F14BF41F402 -:10259000003141F00201D80306D513F4402F14BFD7 -:1025A00041F4802141F00401D3690BB107489847F9 -:1025B000202383F311880021054800F09DFE0023AD -:1025C00083F31188BDE8084001F086B8E0220020BE -:1025D000E822002038B5124CA36ADD68AA0712D0A1 -:1025E0005A6922F002025A61A36913B101212046FF -:1025F0009847202383F3118800210A4800F07CFECD -:10260000002383F31188EB0606D51021A36AD96055 -:10261000236A0BB102489847BDE8384001F05CB826 -:10262000E0220020F022002038B5124CA36A1D6978 -:10263000AA0712D05A6922F010025A61A36913B195 -:10264000022120469847202383F3118800210A485D -:1026500000F052FE002383F31188EB0606D510210B -:10266000A36A1961236A0BB102489847BDE8384054 -:1026700001F032B8E0220020F022002038B50F4CE3 -:10268000A36A5D682A075D600AD5032222701A6872 -:1026900022F002021A60636A13B1002120469847B3 -:1026A0006B0706D5A36A9969236A13B10904034825 -:1026B0009847BDE8384001F00FB800BFE022002085 -:1026C00010B50F4C204600F03FFA0E4B0B211320A3 -:1026D000A36200F019FA0B21142000F015FA0B2167 -:1026E000152000F011FA0B21162000F00DFA00233E -:1026F0002046BDE810401A460E21FFF78FBE00BFEE -:10270000E0220020006400400F4B10B598420446C0 -:1027100005D10E4BDA6942F00072DA61DB69012201 -:10272000A36A1A60A36A5A68D20707D5626851681B -:102730001268D9611A60064A5A6110BD0121082049 -:1027400000F092FCEEE700BFE02200200010024003 -:102750005B87010003291AD8DFE801F0020A0F1491 -:10276000836A9B6813F0E05F14BF0120002070476C -:10277000836A9868C0F380607047836A9868C0F382 -:10278000C0607047836A9868C0F30070704700208B -:102790007047000010B503291FD8DFE801F0021FC1 -:1027A0002327816A8B68C3F30163183301EB03139A -:1027B000107881061ED55468C0F30011490041EA23 -:1027C000C40141F0040100F00F005860906841F02E -:1027D00001019860D268DA60196010BD836A03F560 -:1027E000C073E5E7836A03F5C873E1E7836A03F51D -:1027F000D073DDE79488C0F30011490041EA4451E9 -:10280000E1E7000001290CD003D3022910D00020F9 -:102810007047836ADA68920701D1186903E00120E2 -:102820007047836AD86810F0030018BF0120704712 -:10283000836AF2E710B539B9836AD96889071BD171 -:102840001B699B0704D110BD012915D0022948D16D -:10285000816AD1F8C031D1F8C401D1F8C8411461FE -:10286000D1F8CC41546120240C610C69A40717D124 -:102870004C6944F0100412E0816AD1F8B031D1F80B -:10288000B401D1F8B8411461D1F8BC41546120249D -:10289000CC60CC68A40703D14C6944F002044C61BD -:1028A00011795C0864F304119C0864F345111171FB -:1028B00089064BBF91681189DB085B0D4CBF63F340 -:1028C0001C0163F30A01137948BF916060F30303AD -:1028D00013714FEA10234FEA104058BF1181137053 -:1028E000508010BD00231A4610B51C495A50CC1810 -:1028F0000833802B6260F9D1194B9A6942F07D024E -:102900009A619B690268174BDA6082685A60426874 -:102910001A60C26803F58063DA6042695A6002692E -:102920001A608269C3F80C24026AC3F80424C269DD -:10293000C3F80024426AC3F80C28C26AC3F804280A -:10294000826AC3F80028026BC3F80C2C826BC3F8B0 -:10295000042C426BC3F8002C10BD00BF0C230020D8 -:102960000010024000080140026843681143016002 -:1029700003B1184770470000024AD36843F0C00310 -:10298000D360704700380140024AD36843F0C00367 -:10299000D3607047004400402DE9F041D0F89C60BE -:1029A0000546F7683368DA059CB20DD5202383F31A -:1029B00011884FF400710430FFF7D6FF6FF4807375 -:1029C0003360002383F31188202383F3118805F1FA -:1029D000040814F02F0333D183F31188380615D57A -:1029E000210613D5202383F3118805F1380000F068 -:1029F0002FFA002846DA0821281DFFF7B5FF4FF609 -:102A00007F733B40F360002383F311887A060ED571 -:102A100063060CD5202383F31188EA6C2B6D9A4250 -:102A200002D12B6C002B2FD1002383F31188D5F812 -:102A3000A420D368002B31D0BDE8F04110691847BD -:102A4000230713D014F0080F0CBF00218021E007EA -:102A500048BF41F02001A20748BF41F04001630791 -:102A600048BF41F480714046FFF77EFFA4067368BB -:102A700005D595F8A0102846194000F089FA346869 -:102A8000A4B2A6E77060BEE727F040073F0410211C -:102A9000281D3F0CFFF768FFF760C5E7BDE8F08130 -:102AA00008B50348FFF778FFBDE8084000F014BE02 -:102AB0008C23002008B50348FFF76EFFBDE80840EF -:102AC00000F00ABE3424002010B5094C094A204603 -:102AD000002100F03DFA084B084AC4F89C30084C2D -:102AE0000021204600F034FA064BC4F89C3010BD9B -:102AF0008C2300207929000800380140892900082A -:102B0000342400200044004000F16043090103F533 -:102B10006143C9B283F80013012300F01F0240098A -:102B2000800000F16040934000F56140C0F88031C2 -:102B300003607047090100F16040C9B200F56D40C3 -:102B400001767047FFF7BCBD01230370002300F13D -:102B500008028260C26000F11002436002614261BB -:102B60008361C361036243627047000010B5202394 -:102B7000044683F31188022341600370FFF7C4FD0C -:102B800003232370002383F3118810BD2DE9F04146 -:102B90001F4604460D461646202383F3118800F194 -:102BA00008082378042B0ED029462046FFF7D2FDD3 -:102BB00048B1204632462946FFF7ECFD002080F35D -:102BC0001188BDE8F0813946404600F079FB0028C5 -:102BD000E7D0002383F31188BDE8F0812DE9F041AF -:102BE0001F4604460D461646202383F3118800F144 -:102BF00010082378042B0ED029462046FFF702FE4A -:102C000048B1204632462946FFF714FE002080F3E3 -:102C10001188BDE8F0813946404600F051FB00289C -:102C2000E7D0002383F31188BDE8F081F8B515469D -:102C300082680B46AA428169066938BF8568761AA0 -:102C4000B542044607D218462A46FEF773FBA3692D -:102C50002B44A3610DE011D932461846FEF76AFBFA -:102C6000AF1B3A46E1683044FEF764FBE2683A4441 -:102C7000A261A36828465B1BA360F8BD18462A46DC -:102C8000FEF758FBE368E4E72DE9F04104461546FA -:102C900083682669934238BF856840690F46361AB3 -:102CA000B54206D22A46FEF745FB63692B446361B1 -:102CB0000DE012D93246A5EB0608FEF73BFB424673 -:102CC000B919E068FEF736FBE26842446261A36826 -:102CD00028465B1BA360BDE8F0812A46FEF72AFB6D -:102CE000E368E4E710B50024C361029B0A44006076 -:102CF00040608460C160816141610261036210BD16 -:102D000008B582694369934201D1826882B98268B9 -:102D1000013282605A1C42611970426903699A4209 -:102D200001D3C3684361002100F0DAFA002008BD36 -:102D30004FF0FF3008BD000070B5202304460E465A -:102D400083F31188A568A5B1A368A269013BA360BC -:102D5000531CA36115782269934224BFE368A361E1 -:102D6000E3690BB120469847002383F31188284676 -:102D700070BD3146204600F0A3FA0028E2DA85F360 -:102D8000118870BD2DE9F74F05460F4690469A46CB -:102D9000D0F81C90202686F311884FF0000B1446C3 -:102DA00064B1224639462846FFF740FF034668B91A -:102DB0005146284600F084FA0028F1D0002383F31E -:102DC0001188A8EB040003B0BDE8F08FB9F1000F43 -:102DD00003D001902846C847019B8BF31188E41A61 -:102DE0001F4486F31188DBE7C361009BC1608161EA -:102DF000416111440060406082600161036270477C -:102E0000F8B504460E461746202383F31188A568BB -:102E1000A5B1A368013BA36063695A1C62611E707F -:102E2000236962699A4224BFE3686361E3690BB175 -:102E300020469847002080F31188F8BD3946204687 -:102E400000F03EFA0028E2DA85F31188F8BD0000B0 -:102E50008369426910B59A4201D182687AB9826861 -:102E6000013282605A1C82611C7803699A4201D344 -:102E7000C3688361002100F033FA204610BD4FF093 -:102E8000FF3010BD2DE9F74F05460F4690469A4694 -:102E9000D0F81C90202686F311884FF0000B1446C2 -:102EA00064B1224639462846FFF7EEFE034668B96C -:102EB0005146284600F004FA0028F1D0002383F39D -:102EC0001188A8EB040003B0BDE8F08FB9F1000F42 -:102ED00003D001902846C847019B8BF31188E41A60 -:102EE0001F4486F31188DBE70268436811430160E1 -:102EF00003B11847704700001430FFF743BF0000CC -:102F00004FF0FF331430FFF73DBF00003830FFF7BC -:102F1000B9BF00004FF0FF333830FFF7B3BF0000F8 -:102F20001430FFF709BF00004FF0FF311430FFF7F6 -:102F300003BF00003830FFF763BF00004FF0FF32DF -:102F40003830FFF75DBF000000207047FFF7BCBDC1 -:102F50000E4B37B50360002343608360C3600123D9 -:102F6000044615460374202200900B4600F15C01D4 -:102F70001430FFF7B7FE00942B46202204F17C01A9 -:102F800004F13800FFF730FF03B030BDEC4000081B -:102F900038B5C36904460D461BB904210844FFF740 -:102FA000A3FF294604F11400FFF7AAFE002806DA61 -:102FB000201D4FF48061BDE83840FFF795BF38BD54 -:102FC0000022024B1B605B609A607047DC2400208B -:102FD000002382680374054B1B6899689142FBD2F9 -:102FE0005A6803604260106058607047DC2400201B -:102FF00008B5202383F31188037C032B05D0042B11 -:103000000DD02BB983F3118808BD002243691A60E3 -:103010004FF0FF334361FFF7DBFF0023F2E790E857 -:103020000C001A6002685360F2E700000023826817 -:103030000374054B1B6899689142FBD85A6803607A -:103040004260106058607047DC240020054B19690D -:1030500008741868026853601A60186101230374C9 -:10306000FDF78EBADC24002030B54B1C87B0054636 -:103070000A4C10D023690A4A01A800F059F92846E1 -:10308000FFF7E4FF049B13B101A800F06BF923697B -:10309000586907B030BDFFF7D9FFF8E7DC240020FE -:1030A000F12F000838B50C4D41612B6981689A6891 -:1030B0000446914203D8BDE83840FFF789BF18465F -:1030C000FFF786FF01232C61014623742046BDE8EB -:1030D0003840FDF755BA00BFDC240020044B1A68C5 -:1030E0001B6990689B68984294BF0020012070473C -:1030F000DC24002010B5084C236820691A6854604D -:103100002260012223611A74FFF790FF01462069B3 -:10311000BDE81040FDF734BADC24002008B5FFF705 -:10312000DDFF18B1BDE80840FFF7E4BF08BD0000AF -:10313000FEE7000010B5174CFFF742FF00F0EAF879 -:1031400080221549204600F06FF8012344F8180C3E -:103150000374124B124AD96821F4E0610904090C86 -:103160000A431049DA60CA6842F08072CA600E49A8 -:103170000A6842F001020A601022DA77202283F8FE -:103180002220002383F3118862B6BDE8104007486F -:1031900000F06CB8042500201441000800ED00E0A8 -:1031A0000003FA05F0ED00E0001000E01C4100080B -:1031B000F8B50F4C226A01322262224652F8141FDF -:1031C0009142154606D020268B68013B8B606369CF -:1031D0009A6802B1F8BD1968DF68DA604D60616114 -:1031E00082F311881869B84786F31188EFE700BFAA -:1031F000DC240020EFF3118020B9EFF305832022B7 -:1032000082F311887047000010B558B9EFF30584B8 -:10321000C4F3080414B180F3118810BDFFF77EFFDA -:1032200084F3118810BD0000826002220274002223 -:10323000427470478368A3F13C0243F80C2C026986 -:1032400043F83C2C426943F8382C074A43F81C2CBD -:10325000C268A3F1180043F8102C022203F8082CCE -:10326000002203F8072C70479105000810B52023B1 -:1032700083F31188FFF7DEFF00210446FFF712FFFA -:10328000002383F31188204610BD0000024B1B6908 -:1032900058610F20FFF7DABEDC240020202383F3DF -:1032A0001188FFF7F3BF000008B50146202383F320 -:1032B00011880820FFF7D8FE002383F3118808BD8A -:1032C00049B1064B42681B6918605A60136043603D -:1032D0000420FFF7C9BE4FF0FF307047DC24002008 -:1032E0000368984206D01A68026050605961184617 -:1032F000FFF76EBE7047000038B504460D462068E3 -:10330000844200D138BD036823605C604561FFF7EB -:103310005FFEF4E7054B03F114025A619A614FF026 -:10332000FF32DA6100221A62704700BFDC240020FD -:1033300010B5C2600A4A036153699C68A1420CD867 -:103340005C68036044602060586081609868411A3E -:1033500099604FF0FF33D36110BD091B1B68ECE788 -:10336000DC240020036881689A680A449A604268F5 -:10337000136003685A6000234FF0FF32C360014BB3 -:10338000DA617047DC24002000207047FEE700006F -:10339000704700004FF0FF3070470000BFF34F8FC1 -:1033A000024AD368DB07FCD4704700BF002002400C -:1033B00008B5074B1B7853B9FFF7F0FF054B1A69A7 -:1033C000120641BF044A5A6002F188325A6008BDB1 -:1033D000E0250020002002402301674508B5054B89 -:1033E0001B7833B9FFF7DAFF034A136943F0800310 -:1033F000136108BDE0250020002002407F289ABF0D -:1034000000F5003080020020704700004FF480601B -:1034100070470000802070477F2808B50BD8FFF761 -:10342000EDFF00F580630268013204D1043083426D -:10343000F9D1012008BD002008BD00007F2838B563 -:10344000044624D800F0B6F8124D2860FFF7A6FF16 -:10345000FFF7AEFFF322104B2046DA6002221A611A -:10346000FFF7CCFF58611A6942F040021A61FFF77A -:1034700095FF4FF4806100F0E9F8FFF7AFFF00F02F -:1034800099F828602046BDE83840FFF7C5BF002006 -:1034900038BD00BFE4250020002002402DE9F8439C -:1034A00012F00103144606D040F24B221F4B1A6063 -:1034B0000020BDE8F88385181D4A954204D94FF4D1 -:1034C00014711A4A1160F3E7FFF772FFFFF766FF06 -:1034D0004FF00109DFF86880451A012C05EB010661 -:1034E0000F4604D8FFF77AFF0120BDE8F883C8F83B -:1034F000109031F8023B3380FFF750FF0020C8F8EE -:10350000100033883A889BB29A420DD040F267226D -:10351000064B1A60074B1E60074B1C60074B1F6071 -:10352000FFF75CFFBDE8F883023CD6E7DC2500200E -:10353000FFFF0108D0250020D8250020D425002039 -:1035400000200240084908B50B7828B153B9FFF7AD -:103550002FFF01230B7008BD23B1BDE808400870A0 -:10356000FFF73CBF08BD00BFE025002038B5FFF7DE -:1035700041FE4FF47A730C490C4A0C6A116803FB44 -:1035800004F38B420A49D1E9004504D2003445F1E5 -:103590000105C1E90045E41845F100051360FFF796 -:1035A00033FE2046294638BDDC240020E8250020D3 -:1035B000F025002008B5FFF7D9FF4FF47A720023F9 -:1035C000FCF7E6FD08BD00BF10B5094C0439013A0F -:1035D000D2B2FF2A00D110BD53089800043054F82D -:1035E000233000599BB243EA004341F8043FEEE721 -:1035F000046C004030B50748013AD2B2FF2A00D12E -:1036000030BD0D88540840F82450A3004C88043382 -:103610001C50F1E7046C004007B5012201A900200D -:10362000FFF7D2FF019803B05DF804FB13B5044621 -:10363000FFF7F2FFA04206D002A941F8044D012293 -:103640000020FFF7D7FF02B010BD00007047000058 -:1036500045F25552064B1A6002225A6040F6FF723C -:103660009A604CF6CC421A600122024B1A707047E5 -:1036700000300040F9250020034B1B781BB14AF6AF -:10368000AA22024B1A607047F92500200030004042 -:10369000034B1B689B0042BF0122024B1A7070470C -:1036A00024100240F82500204FF08072014B1A6070 -:1036B000704700BF24100240014B1878704700BFCC -:1036C000F8250020EFF30983203383F309880023D2 -:1036D00083F311887047000010B5202383F311880D -:1036E0000D4B5B6813F4006312D0EFF309844FF0C5 -:1036F000807344F8043CA4F1200383F30988FFF7A6 -:10370000EDFC18B1054B44F8083C10BD044BFAE73A -:1037100083F3118810BD00BF00ED00E0A105000893 -:10372000A405000870470000FEE70000084A094BA6 -:1037300009498B4204D30021084A934205D37047BC -:1037400052F8040F43F8040BF3E743F8041BF4E7C3 -:10375000304200080026002000260020002600201D -:1037600000F030B808B500F063F9FFF7E3FCBDE8FE -:103770000840FFF78DBF0000704700004FF0FF3199 -:103780000E4B1A6919611A6900221A611869D86802 -:10379000D960D968DA60DA68DA6942F08052DA61B1 -:1037A000DA69DA6942F00062DA61054ADB691368B6 -:1037B00043F48073136000F01BB900BF0010024097 -:1037C00000700040194B1A6842F001021A601A6832 -:1037D0009007FCD51A6802F0F9021A6000225A60BC -:1037E0005A6812F00C0FFBD11A6842F480321A604A -:1037F0001A689103FCD55A6842F4E8125A601A68B4 -:1038000042F080721A601A689201FCD51221084AAF -:103810005A60084A11605A6842F002025A605A68B7 -:1038200002F00C02082AFAD1704700BF00100240D3 -:1038300000641D0000200240084A08B55369116861 -:103840000B4003F00103536123B1054A13680BB128 -:1038500050689847BDE80840FFF73EBF00040140AC -:103860000C230020084A08B5536911680B4003F087 -:103870000203536123B1054A93680BB1D06898479E -:10388000BDE80840FFF728BF000401400C230020DA -:10389000084A08B5536911680B4003F004035361EB -:1038A00023B1054A13690BB150699847BDE8084038 -:1038B000FFF712BF000401400C230020084A08B59E -:1038C000536911680B4003F00803536123B1054AA3 -:1038D00093690BB1D0699847BDE80840FFF7FCBE7B -:1038E000000401400C230020084A08B55369116800 -:1038F0000B4003F01003536123B1054A136A0BB167 -:10390000506A9847BDE80840FFF7E6BE0004014052 -:103910000C230020174B10B55C691A68144004F49E -:1039200078725A61A30604D5134A936A0BB1D06A20 -:103930009847600604D5104A136B0BB1506B98473B -:10394000210604D50C4A936B0BB1D06B9847E20566 -:1039500004D5094A136C0BB1506C9847A30504D5E4 -:10396000054A936C0BB1D06C9847BDE81040FFF747 -:10397000B3BE00BF000401400C2300201A4B10B559 -:103980005C691A68144004F47C425A61620504D5EB -:10399000164A136D0BB1506D9847230504D5134A91 -:1039A000936D0BB1D06D9847E00404D50F4A136EA8 -:1039B0000BB1506E9847A10404D50C4A936E0BB11D -:1039C000D06E9847620404D5084A136F0BB1506F4C -:1039D0009847230404D5054A936F0BB1D06F9847DD -:1039E000BDE81040FFF778BE000401400C23002022 -:1039F000062108B50846FFF787F806210720FFF7DC -:103A000083F806210820FFF77FF806210920FFF739 -:103A10007BF806210A20FFF777F806211720FFF729 -:103A200073F8BDE8084006212820FFF76DB80000B4 -:103A300008B5FFF7A3FE0648FEF754FFFFF782F82C -:103A4000FFF784FAFFF798FEBDE8084000F002B8DF -:103A50003C41000800F00EB808B5202383F311881C -:103A6000FFF7A6FB002383F31188BDE80840FFF7AA -:103A700033BE0000054B064A08215A6000229A60B6 -:103A800007220B201A60FFF755B800BF10E000E0D6 -:103A90003F1901001FB51C46094B05461B68D86835 -:103AA00052B1084B8DE80A0002922B462246064985 -:103AB000FDF7AAFC00F042F8044B1A46F2E700BFFB -:103AC0001011002078410008854100086C3C000876 -:103AD00010B501390244904201D1002010BD10F808 -:103AE000013B11F8014FA342F5D0181B10BD000097 -:103AF0002DE9F8430746884691461E468BB10D4690 -:103B0000A8EB0500B54207EB000402D20020BDE897 -:103B1000F883324649462046FFF7DAFF18B1013DE7 -:103B2000EEE7BDE8F8832046BDE8F883034611F8C8 -:103B3000012B03F8012B002AF9D1704708B50620A4 -:103B400000F02CF80120FFF721FC00001F2938B5F8 -:103B500004460D4604D9162303604FF0FF3038BDEC -:103B6000426C12B152F821304BB9204600F030F8C7 -:103B70002A4601462046BDE8384000F017B8012B20 -:103B80000AD0591C03D116230360012038BD00243C -:103B9000284642F825409847002038BD024B014690 -:103BA0001868FFF7D3BF00BF1011002038B50023FD -:103BB000064C0546084611462360FFF7EBFB431C05 -:103BC00002D1236803B12B6038BD00BFFC25002063 -:103BD000FFF7DABB40A2E4F1646891064E6F206102 -:103BE0007070207369670A00426164206677206CF8 -:103BF000656E6774682025750A0042616420626FF3 -:103C00006172645F69642025752073686F756C64E8 -:103C10002062652025750A00426164206677206471 -:103C2000657363726970746F72206C656E67746817 -:103C30002025750A00426164206170702043524360 -:103C4000203078253038783A307825303878203070 -:103C500078253038783A3078253038780A00476F40 -:103C60006F64206669726D776172650A00000000FA -:103C700072656365697665645F756E697175655FA8 -:103C800069645F6C656E203C2055415643414E5F30 -:103C900050524F544F434F4C5F44594E414D49434E -:103CA0005F4E4F44455F49445F414C4C4F43415444 -:103CB000494F4E5F554E495155455F49445F4D410F -:103CC000585F4C454E475448002E2E2F2E2E2F5411 -:103CD0006F6F6C732F41505F426F6F746C6F6164D4 -:103CE00065722F63616E2E63707000616C6C6F6320 -:103CF000617465645F6E6F64655F6964203C3D203C -:103D0000313237006F72672E6172647570696C6F43 -:103D1000742E61705F7065726970685F48574553B3 -:103D200043000000766F69642068616E646C655FB3 -:103D3000616C6C6F636174696F6E5F726573706FD5 -:103D40006E73652843616E617264496E7374616E4F -:103D500063652A2C2043616E6172645278547261EB -:103D60006E736665722A290063616E617264496EC2 -:103D70006974000063616E6172645365744C6F63B3 -:103D8000616C4E6F646549440000000063616E61C0 -:103D9000726448616E646C6552784672616D65004C -:103DA00063616E6172644465636F64655363616CE3 -:103DB0006172000063616E617264456E636F646579 -:103DC0005363616C61720000696E6372656D656E4C -:103DD000745472616E73666572494400656E7175E4 -:103DE00065756554784672616D65730070757368AA -:103DF00054785175657565007072657061726546BD -:103E00006F724E6578745472616E736665720000ED -:103E1000636F7079426974417272617900000000C9 -:103E20006465736361747465725472616E73666500 -:103E3000725061796C6F61640000000066726565A4 -:103E4000426C6F636B0000006269745F6C656E6743 -:103E50007468203E20300072656D61696E696E671E -:103E60005F62697473203E203000696E7075745F04 -:103E70006269745F6F6666736574203E3D20626C94 -:103E80006F636B5F6269745F6F666673657400620F -:103E90006C6F636B5F656E645F6269745F6F6666AB -:103EA000736574203E20626C6F636B5F6269745F40 -:103EB0006F66667365740072656D61696E696E67C1 -:103EC0005F6269745F6C656E677468203C3D207248 -:103ED000656D61696E696E675F6269747300696EB2 -:103EE0007075745F6269745F6F6666736574203C99 -:103EF0003D207472616E736665722D3E7061796CDF -:103F00006F61645F6C656E202A2038006F75747075 -:103F100075745F6269745F6F6666736574203C3D9B -:103F20002036340072656D61696E696E675F626923 -:103F3000745F6C656E677468203D3D2030002872A8 -:103F40006573756C74203E20302920262620287247 -:103F50006573756C74203C3D20363429202626205C -:103F600028726573756C74203C3D206269745F6CC7 -:103F7000656E67746829000064657374696E6174A6 -:103F8000696F6E20213D202828766F6964202A29D8 -:103F900030290076616C756520213D202828766FD8 -:103FA0006964202A293029006F66667365745F771B -:103FB000697468696E5F626C6F636B203C202833A4 -:103FC0003255202D205F5F6275696C74696E5F6F7A -:103FD00066667365746F66202843616E6172644221 -:103FE0007566666572426C6F636B2C2064617461E8 -:103FF000292900006F75745F696E7320213D2028A8 -:1040000028766F6964202A29302900007372635F63 -:104010006C656E203E203055000000002863616E04 -:104020005F6964202620307831464646464646463B -:104030005529203D3D2063616E5F696400000000EA -:10404000616C6C6F6361746F722D3E73746174691F -:1040500073746963732E63757272656E745F7573C2 -:104060006167655F626C6F636B73203E2030000098 -:104070007472616E736665725F696420213D2028E9 -:1040800028766F6964202A293029000073746174CE -:10409000652D3E6275666665725F626C6F636B73F9 -:1040A000203D3D202828766F6964202A2930290088 -:1040B0002E2E2F2E2E2F6D6F64756C65732F6C69ED -:1040C0006263616E6172642F63616E6172642E63FC -:1040D000006974656D2D3E6672616D652E64617454 -:1040E000615F6C656E203E20300000000000000023 -:1040F000152F0008012F00083D2F0008292F000868 -:10410000352F0008212F00080D2F0008F92E000878 -:10411000492F00086D61696E0000000034410008FD -:1041200020250020D02500200100000031310008AA -:104130000000000069646C65000000000C1E0000B7 -:10414000447B4144B4574944010000004244444484 -:10415000444444440000000044444444444444442F -:10416000000000004444444444444444000000002F -:1041700044444444444444442C2066756E6374694A -:104180006F6E3A2000617373657274696F6E2022DE -:10419000257322206661696C65643A2066696C65E6 -:1041A00020222573222C206C696E652025642573DE -:1041B00025730A000CC0FF7F010000000000000012 -:1041C0006400000000000000FE2A0100D20400008C -:1041D000141100200000000000000000000000009A -:1041E00000000000000000000000000000000000CF -:1041F00000000000000000000000000000000000BF -:1042000000000000000000000000000000000000AE -:10421000000000000000000000000000000000009E -:10422000000000000000000000000000000000008E -:04423000000000008A +:10000000000900202D080008A91C0008791C000820 +:10001000951C0008791C00088D1C00082F0800089A +:100020002F0800082F0800082F080008DD370008F7 +:100030002F0800082F0800082F080008F13C0008CE +:100040002F0800082F0800082F0800082F080008B4 +:100050002F0800082F080008213A00084D3A000830 +:10006000793A0008A53A0008D13A00082F0800089C +:100070002F0800082F0800082F0800082F08000884 +:100080002F0800082F0800082F080008A52C0008DA +:10009000112D0008652D0008B92D0008FD3A000853 +:1000A0002F0800082F0800082F0800082F08000854 +:1000B0002F0800082F0800082F0800082F08000844 +:1000C0002F0800082F0800082F0800082F08000834 +:1000D0002F0800082F0800082F0800082F08000824 +:1000E000653B00082F0800082F0800082F080008AB +:1000F0002F0800082F0800082F0800082F08000804 +:100100002F0800082F0800082F0800082F080008F3 +:100110002F0800082F0800082F0800082F080008E3 +:100120002F0800082F0800082F0800082F080008D3 +:100130002F0800082F0800082F0800082F080008C3 +:100140002F0800082F0800082F0800082F080008B3 +:100150002F0800082F0800082F0800082F080008A3 +:100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A +:100170000C0F93EA0C0F6FD01A4480EA010C400276 +:1001800018BF5FEA41211ED04FF0006343EA5010D0 +:1001900043EA5111A0FB01310CF00040B1F5000F12 +:1001A0003EBF490041EAD3715B0040EA010062F1C1 +:1001B0007F02FD2A1DD8B3F1004F40EBC25008BFAB +:1001C00020F00100704790F0000F0CF0004C08BFC9 +:1001D00049024CEA502040EA51207F3AC2BFD2F196 +:1001E000FF0340EAC250704740F400004FF00003A4 +:1001F000013A5DDC12F1190FDCBF00F000407047DE +:10020000C2F10002410021FA02F1C2F1200200FA1B +:1002100002FC5FEA310040F1000053EA4C0308BFE2 +:1002200020EADC70704792F0000F00F0004C02BF33 +:10023000400010F4000F013AF9D040EA0C0093F0AE +:10024000000F01F0004C02BF490011F4000F013B08 +:10025000F9D041EA0C018FE70CEAD15392EA0C0F76 +:1002600018BF93EA0C0F0AD030F0004C18BF31F0E1 +:10027000004CD8D180EA010000F00040704790F0B7 +:10028000000F17BF90F0004F084691F0000F91F05B +:10029000004F14D092EA0C0F01D142020FD193EA21 +:1002A0000C0F03D14B0218BF084608D180EA0100A9 +:1002B00000F0004040F0FE4040F40000704740F085 +:1002C000FE4040F44000704780F0004002E000BF74 +:1002D00081F0004142001FBF5FEA410392EA030F31 +:1002E0007FEA226C7FEA236C6AD04FEA1262D2EB7B +:1002F0001363C1BFD218414048404140B8BF5B4280 +:10030000192B88BF704710F0004F40F4000020F018 +:100310007F4018BF404211F0004F41F4000121F02E +:100320007F4118BF494292EA030F3FD0A2F1010278 +:1003300041FA03FC10EB0C00C3F1200301FA03F1B6 +:1003400000F0004302D5494260EB4000B0F5000FD9 +:1003500013D3B0F1807F06D340084FEA310102F198 +:100360000102FE2A51D2B1F1004F40EBC25008BF4A +:1003700020F0010040EA03007047490040EB000014 +:10038000013A28BFB0F5000FEDD2B0FA80FCACF115 +:10039000080CB2EB0C0200FA0CF0AABF00EBC25042 +:1003A00052421843BCBFD0401843704792F0000F30 +:1003B00081F4000106BF80F400000132013BB5E783 +:1003C0004FEA41037FEA226C18BF7FEA236C21D0F9 +:1003D00092EA030F04D092F0000F08BF084670475E +:1003E00090EA010F1CBF0020704712F07F4F04D12C +:1003F000400028BF40F00040704712F100723CBF3F +:1004000000F50000704700F0004343F0FE4040F468 +:10041000000070477FEA226216BF08467FEA236326 +:100420000146420206BF5FEA412390EA010F40F411 +:10043000800070474FF0000304E000BF10F000435D +:1004400048BF40425FEA000C08BF704743F0964344 +:1004500001464FF000001CE050EA010208BF70475F +:100460004FF000030AE000BF50EA010208BF7047E6 +:1004700011F0004302D5404261EB41015FEA010CFB +:1004800002BF84460146002043F0B64308BFA3F1F3 +:100490008053A3F50003BCFA8CF2083AA3EBC253D5 +:1004A00010DB01FA02FC634400FA02FCC2F12002F4 +:1004B000BCF1004F20FA02F243EB020008BF20F02B +:1004C0000100704702F1200201FA02FCC2F1200291 +:1004D00050EA4C0021FA02F243EB020008BF20EA86 +:1004E000DC70704742000ED2B2F1FE4F0BD34FF0DA +:1004F0009E03B3EB126209D44FEA002343F000439A +:1005000023FA02F070474FF00000704712F1610FBC +:1005100001D1420202D14FF0FF3070474FF000008E +:10052000704700BF53B94AB9002908BF00281CBF53 +:100530004FF0FF314FF0FF3000F076B9ADF1080C0D +:100540006DE904CE00F006F8DDF804E0DDE90223F1 +:1005500004B070472DE9F047089E0D4604468846D2 +:10056000002B4DD18A42944668D9B2FA82F252B138 +:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 +:1005800041EA030894404FEA1C41B8FBF1F71FFA17 +:100590008CFE01FB178807FB0EF0230C43EA08438F +:1005A00098420AD91CEB030307F1FF3580F01E8146 +:1005B000984240F21B81023F63441B1AB3FBF1F0E7 +:1005C00001FB103300FB0EFEA4B244EA0344A6452F +:1005D0000AD91CEB040400F1FF3380F00981A64521 +:1005E00040F20681644402380021A4EB0E0440EA84 +:1005F00007401EB10023D440C6E90043BDE8F087A0 +:100600008B4208D9002E00F0EE800021C6E90005DB +:100610000846BDE8F087B3FA83F100294AD1AB421E +:1006200002D3824200F2FC80841A65EB03030120AE +:100630009846002EE2D0C6E90048DFE702B9FFDEA7 +:10064000B2FA82F2002A40F09180A1EB0C00012165 +:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 +:10066000250C45EA00450EFB03F0A84208D91CEB17 +:10067000050503F1FF3802D2A84200F2CE804346BE +:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 +:1006900044EA0544A64508D91CEB040400F1FF35E3 +:1006A00002D2A64500F2B6802846A4EB0E0440EA2A +:1006B00003409EE7C1F120078B4022FA07FC4CEA79 +:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D +:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 +:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 +:1006F00001F20BD91CEB040408F1FF3A80F088806A +:10070000A04240F28580A8F102086444241AB4FB98 +:10071000F9F009FB104400FB0EFEADB245EA0444BB +:10072000A64508D91CEB040400F1FF356CD2A645A0 +:100730006AD90238644440EA0840A0FB0295A4EB61 +:100740000E04AC42C846AE4656D353D0002E69D0F4 +:10075000B3EB080264EB0E0422FA01F304FA07F784 +:100760001F43CC40C6E90074002147E70CFA02FCA5 +:10077000C2F1200125FA01F34FEA1C4720FA01F1EA +:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 +:10079000280C40EA034001FB0EF3834204FA02F402 +:1007A00008D91CEB000001F1FF382FD283422DD96C +:1007B00002396044C01AB0FBF7F307FB1300ADB277 +:1007C00045EA004503FB0EF0A84208D91CEB0505DD +:1007D00003F1FF3816D2A84214D9023B6544281A07 +:1007E00043EA014138E73146304607E72F46E4E661 +:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 +:100800000138A3E74346EAE7284694E74146D1E7A3 +:10081000D0467BE76444023847E7023B65442FE754 +:10082000084606E73146E9E6704700BF02E000F0FF +:1008300000F8FEE772B6264880F30888254880F362 +:100840000988254825490860022080F31488BFF3F1 +:100850006F8F03F013F803F077F84FF0553020490D +:100860001B4A91423CBF41F8040BFAE71D49194A63 +:1008700091423CBF41F8040BFAE71B491B4A1C4B51 +:100880009A423EBF51F8040B42F8040BF8E70020EF +:100890001849194A91423CBF41F8040BFAE702F0AB +:1008A000F1FF03F053F8154C154DAC4203DA54F840 +:1008B000041B8847F9E700F03FF8124C124DAC4298 +:1008C00003DA54F8041B8847F9E702F0D9BF0000A7 +:1008D00000090020001100200000000808ED00E0E1 +:1008E0000001002000090020003E00080011002047 +:1008F0002411002028110020E025002060010008BC +:100900006001000860010008600100082DE9F04F57 +:10091000C1F80CD0C3689D46BDE8F08F002383F377 +:1009200011882846A047002002F00CFDFEE702F0E7 +:100930007FFC00DFFEE70000F8B500F039FE02F0B2 +:10094000EBFE074602F036FF0546002840D12C4B4F +:100950009F423DD001339F423DD02A4B27F0FF02FA +:100960009A423BD1F8B200F0FFFB2E4642F21074DF +:1009700000F000FC08B10024264601F003F988B31A +:100980000024032000F044F8264635B11E4B9F4258 +:1009900003D0002402F006FF2646002002F0C6FE27 +:1009A0001A4B9B6813F0400322D00EB100F046F8BA +:1009B00000F040FC00F0FEFD01F078F90546CCB1F6 +:1009C00001F074F9401BA04214D900F037F8F3E7A6 +:1009D0002E460024CCE704460126C9E706464FF41C +:1009E0007A74C5E7002CD0D04FF47A740126CCE796 +:1009F0001C46DDE700F0D0FC012002F0A9FCDEE798 +:100A0000010007B0000008B0263A09B0000C014010 +:100A1000084B187003280CD8DFE800F0080502081E +:100A2000022000F023BE022000F018BE0022024B7C +:100A30005A607047281100202C11002038B501F0B1 +:100A4000A1F830B103221F4B1A7000221E4B5A60CE +:100A500038BD1E4B1E4A19680131F9D00433934248 +:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 +:100A70009B6803F1006303F5C8439A42E8D202F091 +:100A800065FE02F077FE002000F0AEFD0220FFF7C9 +:100A9000BFFF124BDA690022DA61D96999699A615C +:100AA0009B6972B64FF0E023C3F8085D3021D4F89B +:100AB0000034D4F8042481F311889D4683F3088818 +:100AC0001047C5E7281100202C1100200064000801 +:100AD000206400080060000800110020001002409F +:100AE00049F26900084A136899B21B0C00FB0133F4 +:100AF00044F250611360054B186882B2000C01FB90 +:100B00000200186080B27047201100201C110020E4 +:100B100010B504460021102200F0C4FD034B03CBA6 +:100B2000206061601868A06010BD00BFE8F7FF1F7B +:100B30002DE9F0410026ADF54E7D6CAC40F275120A +:100B400007460D460EA831460D9600F0ABFD314626 +:100B50004FF4C472204600F0A5FD01F0A7F84FF451 +:100B60007A72B0FBF2F0244B0DF13408186093E870 +:100B70000700022384E807000DF5E9702382FFF7E0 +:100B8000C7FF4EF603031D4906A8238403F0E8F8C7 +:100B900018230DF2E32684F832310DF1300C6B444A +:100BA0001A4603CA624530607160134606F10806B2 +:100BB000F6D141460122204600F0C0FD00230393F8 +:100BC000AB7E80B2029305F1190301930123CDE9B5 +:100BD00004800093384606A3D3E90023E97E01F0A0 +:100BE000ABFB0DF54E7DBDE8F08100BFAFF300809B +:100BF0009E6AC421818A46EE34110020703D0008AF +:100C00002DE9F041264D80462B7A0C46DAB0FBB92F +:100C1000204627A900F0A2FE0746002836D19DF8FD +:100C20009D60C82E32D801464FF4FA72284600F073 +:100C300039FD32460DF19E0105F1090000F020FD5D +:100C40009DF89C302E4477722B720BB9E37E2B7289 +:100C50008122002106AD27A800F024FD01222946AB +:100C600027A800F0B7FE00230393A37E80B202936F +:100C700004F1190301932823CDE904500093404661 +:100C800005A3D3E90023E17E01F056FB5AB0BDE88D +:100C9000F08100BFAFF3008026417272DF25D7B725 +:100CA0007C210020F0B54FF48A750024234EF1B06A +:100CB00005FB006596F8D830D822214685F8DC304F +:100CC00085F8E8403AA800F0EDFC06F1090000F0D4 +:100CD000E1FCD5F8E430C2B206AF8DF8F00006F1C1 +:100CE00009010DF1F100CDE93A3400F0C9FC3946B3 +:100CF00001223AA800F09AFE80B2CDE904700823E0 +:100D00000127CDE9023706F1D80301933023317A68 +:100D100000930B4807A3D3E9002301F00DFBA04289 +:100D200006DD00F0C3FFC5F8E000384671B0F0BD45 +:100D30002046FBE778F6339F93CACD8D7C210020B7 +:100D40004C210020F0B51E4E1E4F1F4D85B0304681 +:100D500001F01EFB044660B310220021684600F03B +:100D6000A1FC4FF00003227B6068A16862F30303DB +:100D70008DF8003002AB03C3019B2268384662F352 +:100D80001C0301939DF800306A4643F020038DF860 +:100D900000300023194602F087F9044620B9304696 +:100DA00001F0FAFA2C70D2E72B78072B03D8013325 +:100DB0002B7005B0F0BD024801F0EEFAF9E700BF74 +:100DC0004C210020A82300207523002070B50D467B +:100DD00014461E4601F00CFA50B9022E10D1012C17 +:100DE0000ED112A3D3E900230120C5E9002307E0B7 +:100DF000282C10D005D8012C09D0052C0FD00020AC +:100E000070BD302CFBD10BA3D3E90023ECE70BA37F +:100E1000D3E90023E8E70BA3D3E90023E4E70BA31E +:100E2000D3E90023E0E700BFAFF30080401DA1201D +:100E300026812A0B78F6339F93CACD8D9E6AC421F2 +:100E4000818A46EE26417272DF25D7B7F017304A05 +:100E500039059E5638B505460E4C0021013500F087 +:100E6000E5FBA4F8F051B4F8F00100F0C7FB78B14D +:100E7000B4F8F00100F0D2FB014648B9B4F8F00133 +:100E800000F0D4FBB4F8F0310133A4F8F031EAE714 +:100E900038BD00BF7C2100202DE9F04F8DB000AFA0 +:100EA00004460D4601F0A4F9002846D12B7E022B02 +:100EB0001AD1EB8A012B17D100F0F8FE0646FFF796 +:100EC0000FFE4FF4C873B0FBF3F202FB1303DFF81D +:100ED00078829BB206F516763344C8F80030EB7E74 +:100EE00033B90022994B1A703437BD46BDE8F08FF4 +:100EF000284607F11C0100F0EFFC0028F4D107F1AF +:100F00000C00FFF705FEBD7F07F10C012A4607F133 +:100F10001F0002F0F5FE0028E3D10F2D08D88B4BFF +:100F20001D70D8F80030A3F51673C8F80030DBE761 +:100F30002046397F01F054F9D6E7EB8A282B6BD095 +:100F400010D8012B63D0052BCED1BFF34F8F804932 +:100F5000804BCA6802F4E0621343CB60BFF34F8F4B +:100F600000BFFDE7302BBFD17B4CEA7E237A9A424B +:100F7000BAD194F8DC206B7E9A42B5D1284604F1B0 +:100F8000EA0100F07FFD06460028ADD1012384F878 +:100F9000E83000F08BFED4F8E030C01A192840F693 +:100FA000B83338BF1920984228BF1846FFF742FAD5 +:100FB0006A49FFF7D5F805462068FFF73BFA68490C +:100FC000FFF7CEF801462846FFF784F9FFF78AFAC3 +:100FD00020604FF48A7194F8D9307B607A68636836 +:100FE00001FB02F5621992F8E80050B1D2F8E40072 +:100FF000E946834215D0002382F8E830C2F8E03099 +:10100000CD466368574A9B0A013313816CE7294632 +:101010002046FFF78DFD67E729462046FFF7F0FDE4 +:1010200062E7B2F8EC803B6008F1030A4FEA9A0AE3 +:101030004FEA8A02D11DC908A9EBC1039D46EB46C0 +:101040000021584600F02EFB05F1EE0142465846BD +:10105000214400F015FB3B6813B9012000F0C4FAED +:1010600094F8D20000F0CAFA054630B9207200F0B8 +:10107000E5FA284600F0B8FAC2E7D4F8D4303BB914 +:1010800094F8D200B4F8F031834201D8FFF7E2FEC1 +:10109000D4F8D43043449D4208D294F8D200B4F836 +:1010A000F0310130834201D8FFF7D4FE5946606821 +:1010B0005FFA8AF200F0FEFA08B9CD4689E7636864 +:1010C00094F8D20043446360D4F8D43008EB030AA8 +:1010D000C4F8D4A000F092FA824509D394F8D23033 +:1010E000D4F8D4000133401B84F8D230C4F8D400C3 +:1010F000B8F1FF0F0FD80025257200F09FFA28469F +:1011000000F072FA00F03EFD164B188108B9FFF7A7 +:1011100095FCCD46E8E64FF48A727B6894F8D900D6 +:1011200002FB0343D3F8E42083F8E86002F5807201 +:10113000C3F8E060C3F8E420FFF7B4FDFFF702FE58 +:1011400084F8D960B9E700BF48210020452100207C +:1011500000ED00E00400FA057C210020CDCCCC3D60 +:101160006666663F34110020014B1870704700BF5F +:101170004011002030B54FF00054254B226885B057 +:101180009A4207D002F020FB0446C0B90024204652 +:1011900005B030BD0025627D1E4B1F481A70237DAF +:1011A000C92203721D49C0F8E450093000F068FA02 +:1011B0002046E022294600F075FA0124E7E7184AA4 +:1011C000184DD36943F00073D361AA6D164B9A4250 +:1011D000DCD12B6E013B7E2BD8D8144A01AB07CA59 +:1011E00083E807001846032100F09CFC6B6D8342E6 +:1011F0004FF00003CAD12A6D8A4203BFAB652A6E45 +:10120000044B1C4601BF1A70EA6D094B1A60BEE719 +:101210009AAD44C5401100207C210020160000201A +:1012200000100240006600405041A0B058660040E7 +:10123000181100202DE9F04385B000F0A3FC022333 +:10124000494C637100230293484B2081D3F800C0BE +:10125000BCF57A7F12D3464F464BB7FBFCF59C4555 +:101260008CBF0A231123B5FBF3F603FB1652591E5C +:10127000C8B2002A3ED002290B46F4D89DF80B30A4 +:101280003D495A1E9DF80A303C48013B1B0443EA85 +:101290000253BDF80820013A13434B6001F0F4FEFD +:1012A00000230193364B374900934FF48052364B5D +:1012B000364800F06BFF364B197811B1334800F017 +:1012C0008FFF00F0F3FC0546FFF70AFC4FF4C873EC +:1012D000B0FBF3F202FB130305F516709BB2184442 +:1012E0002C4B186002F066FA08B10F23238105B079 +:1012F000BDE8F083731EB3F5806FBFD24FF47A75EB +:10130000C0EBC00E0EF103034FEAE30909FB0555DC +:10131000C3F3C703C11AC9B209F101088844B5FB78 +:10132000F8F5B5F5617F08D90EF1FF33C3F3C703B4 +:10133000C11A581E0F28C9B214D84A1E072A8CBFDA +:1013400000220122581800FB0660B7FBF0F7BC45ED +:1013500094D1002A92D0ADF808608DF80A308DF84B +:101360000B108BE71346EDE7341100201811002015 +:10137000005125023F420F0010110020A823002039 +:10138000CD0D000844110020990E00084C210020CA +:1013900040110020482100202DE9F04F80A7D7E917 +:1013A00000670FF20429D9E90089734D93B00DF15C +:1013B000300AFFF7C7FC18220021504600F072F9EE +:1013C000DFF8B8B16E4C002352461946584601F07A +:1013D00093FE014650BB102208A800F063F9E368B1 +:1013E00083F01003E36000F063FC0DF1240C0B4666 +:1013F00012A9024611E903008CE803009DF834109D +:10140000C1F30300890649BF0E99BDF83810C1F336 +:101410001C0141F0004158BFC1F30A018DF82C00B6 +:101420000891284608A901F097F9CCE7284600F072 +:10143000DFFE0446002847D100F038FCDFF844B155 +:10144000DBF8003098423FD300F030FC0790FFF704 +:1014500047FB4FF4C873B0FBF3F101FB1300079A8D +:1014600083B202F516701844CBF80000DFF818B10B +:101470008DF820409BF8001011B901238DF8203021 +:1014800050460791FFF744FB07990DF12100C1F188 +:101490001004E4B2062C28BF06245144224600F072 +:1014A000EFF808AB039318230293384B01340193F0 +:1014B0000123E4B2009332463B462846049400F0F0 +:1014C000DDFE00238BF8003000F0F0FB304A314C99 +:1014D0001368C31AB3F57A7F30D3106000F0E8FBCD +:1014E00002460B46284600F061FF284600F080FEC9 +:1014F00020B3237ADFF8A0B0002B14BF032302230C +:101500008BF8053000F0D2FB4FF47A73B0FBF3F0A8 +:101510000122CBF800005146584600F0B5F91823D7 +:1015200002931E4B80B2019340F25513CDE903A004 +:10153000009342464B46284600F0A0FE237ABBB1FA +:1015400000F0B4FB94F8E83073B9D4F8E03043B15C +:10155000C01A2368FA2B38BFFA230533B0EB430FC8 +:1015600002D30020FFF79EFB237A002B7FF41FAFEE +:1015700013B0BDE8F08F00BF4C210020A82300204D +:10158000000801404821002045210020442100207E +:10159000702300207C2100203411002074230020BF +:1015A000401DA12026812A0BF1C6A7C1D068080FD3 +:1015B0007047000070B501F095FF0024084E094DFA +:1015C000308028683388834208D901F087FF2B6870 +:1015D00004440133B4F5C84F2B60F2D370BD00BF93 +:1015E000A42300207823002002F00AB800F1006054 +:1015F000920000F5C84001F0AFBF0000054B1A682B +:10160000054B1B889B1A834202D9104401F066BF28 +:101610000020704778230020A4230020024B1B6881 +:10162000184401F061BF00BF78230020024B1B6803 +:10163000184401F06BBF00BF78230020064991F8E1 +:10164000243033B100230822086A81F82430FFF7E0 +:10165000CDBF0120704700BF7C230020022802BFBD +:101660001022014B1A61704700080140022802BF96 +:101670004FF48012014B1A61704700BF000801400F +:10168000002310B5934203D0CC5CC4540133F9E776 +:1016900010BD000003460246D01A12F9011B0029B2 +:1016A000FAD1704703460244934202D003F8011B6B +:1016B000FAE770472DE9F8431F4D144695F82420AA +:1016C0000746884652BBDFF870909CB395F82430EB +:1016D0002BB92022FF2148462F62FFF7E3FF95F840 +:1016E00024004146C0F10802A24228BF224605EB71 +:1016F0008000D6B29200FFF7C3FF95F82430A41BF8 +:101700001E44F6B2082E17449044E4B285F82460D3 +:10171000DBD1FFF793FF0028D7D108E02B6A03EB5A +:1017200082038342CFD0FFF789FF0028CBD100206E +:10173000BDE8F8830120FBE77C2300202DE9F0477A +:101740000D46044600219046284640F27912FFF7E4 +:10175000A9FF234620220021284600F09FFF0222F5 +:1017600020212846231D00F099FF0322222128462C +:10177000631D00F093FF032225212846A31D00F0DE +:101780008DFF10222821284604F1080300F086FF6F +:1017900008223821284604F1100300F07FFF0822B8 +:1017A0004021284604F1110300F078FF0822482167 +:1017B000284604F1120300F071FF20225021284630 +:1017C00004F1140300F06AFF40227021284604F15E +:1017D000180300F063FF0822B021284604F120031B +:1017E00000F05CFF0822B821284604F1210300F034 +:1017F00055FFC02604F122073B4631460822284601 +:10180000083600F04BFFB6F5A07F07F10107F3D1D2 +:1018100008223146284604F1320300F03FFF00273A +:1018200004F1330A94F832304FEAC7099F4209F5B0 +:10183000A47615D3B8F1000F08D131460722284607 +:1018400004F5997300F02AFF09F24F16274694F821 +:1018500032213B1B93420CD3F01DC008BDE8F0873A +:101860000AEB070308223146284600F017FF01372C +:10187000D8E7314607F233130822284600F00EFF5E +:1018800008360137E3E7000038B50C46002105466D +:1018900021600346C4F803102046202200F0FEFE1B +:1018A00020462B1D0222202100F0F8FE20466B1D51 +:1018B0000322222100F0F2FE2046AB1D0322252147 +:1018C00000F0ECFE20461022282105F1080300F06C +:1018D000E5FE072038BD00000023F7B50E4605469B +:1018E000047F07220091194600F09AFD731C0093B3 +:1018F000012200230721284600F092FDC4B9B31C41 +:101900000093052223460821284600F089FD0D2476 +:101910003746B278BB1B934211D32B7FE01DC00822 +:10192000AC8ABBB9A04294BF0020012003B0F0BD37 +:10193000AB8A0824DB00083BDB08B370E8E7FB1C3C +:101940002146009308220023284600F069FD083450 +:101950000137DEE7001B18BF0120E7E70023F7B5DA +:101960000E46047F082200911946054600F058FDF6 +:10197000731CC4B90822009311462346284600F080 +:101980004FFD1024012372785F1C013B934211D359 +:101990002B7FE01DC008AC8ABBB9A04294BF0020D9 +:1019A000012003B0F0BDAB8A0824DB00083BDB0854 +:1019B0007370E7E7F31921460093082200232846B5 +:1019C00000F02EFD08343B46DDE7001B18BF012068 +:1019D000E7E70000F8B50E460546144600218122CF +:1019E0003046FFF75FFE2B4608220021304600F00C +:1019F00055FE7CB90722082130466B1C00F04EFED4 +:101A00000F2401236A785F1C013B934204D3E01D3D +:101A1000C008F8BD0824F4E72146EB190822304637 +:101A200000F03CFE08343B46ECE70000F8B50E46FB +:101A3000054614460021CE223046FFF733FE2B46E2 +:101A400028220021304600F029FE7CB908222821F6 +:101A5000304605F1080300F021FE30242F462A7A93 +:101A60007B1B934204D3E01DC008F8BD2824F5E792 +:101A7000214607F109030822304600F00FFE083422 +:101A80000137ECE7F7B5047F0E46009101231022E1 +:101A90000021054600F0C4FCC4B9B31C0093092220 +:101AA00023461021284600F0BBFC192437467288D3 +:101AB000BB1B9A4211D82B7FE01DC008AC8ABBB972 +:101AC000A04294BF0020012003B0F0BDAB8A1024D7 +:101AD000DB00103BDB087380E8E73B1D21460093E9 +:101AE00008220023284600F09BFC08340137DEE77B +:101AF000001B18BF0120E7E730B5094D0A449142A9 +:101B00000DD011F8013B5840082340F30004013B7D +:101B10002C4013F0FF0384EA5000F6D1EFE730BD0C +:101B20002083B8ED4FF0FF33F7B500EB810619467F +:101B3000DFF848C0DFF848E0B0421BD050F8042B73 +:101B400001AF0192042217F8014B81EA04610824D5 +:101B50000D46DB184941013C002DBCBF83EA0C0354 +:101B600081EA0E0114F0FF04F2D1013A12F0FF02F3 +:101B7000E9D1E1E7D843C94303B0F0BD9336EAA900 +:101B8000EBE1F042F7B56B46354A106851686A469A +:101B900003C308233349344802F0C2F8044690BB1B +:101BA0000A256B46314A106851686A4603C3082308 +:101BB0002F492D4802F0B4F80446002847D00369A5 +:101BC000B3F5CE3F43D8B0F86620B2F57A7F3ED168 +:101BD000284A024402F15C018B4238D35C3B224923 +:101BE00000209E1AFFF788FF07463246002004F1C6 +:101BF0006401FFF781FFA3689F4228D1E368984200 +:101C000008BF002523E00369B3F5CE3F26D8428BF9 +:101C1000B2F57A7F20D1174A024402F110018B42BB +:101C200018D3103B104900209D1AFFF765FF0646A8 +:101C30002A46002004F11801FFF75EFFA3689E42C8 +:101C400002D1E368984201D00D25AAE70025284675 +:101C500003B0F0BD1025A4E70C25A2E70B25A0E7F3 +:101C60008C3D0008DC9B010000640008953D0008E5 +:101C7000909B0100089CFFF7EFF30983EFF30583C6 +:101C8000014B9B6BFEE700BF00ED00E008B5FFF7DE +:101C9000F3FF0000EFF30983EFF30583014B5B6B68 +:101CA000FEE700BF00ED00E0FEE7000001F0E2BC4F +:101CB00001F0BABC2DE9F041456A15B94162BDE8B1 +:101CC000F0814B68AC4623F06047C3F38A4616EABE +:101CD000230638BF3E464FEAD37EC3F380782B46B7 +:101CE0005A68BEEBD27F22F060440AD0002A18DA8C +:101CF000A40CB44217D19D420FD10D60DEE713460C +:101D0000EEE7A74207D102F08044C2F38072424559 +:101D10000BD054B1EFE708D2EDE7CCF800100B6020 +:101D2000CDE7B44201D0B442E5D81A689C46002AF7 +:101D3000E5D11960C3E700002DE9F0474FF47F4972 +:101D4000089D01F007044FEAD508224405F0070575 +:101D500000EBD100944201D1BDE8F08704F0070701 +:101D600005F0070A57453E4638BF5646111BC6F1D7 +:101D700008068E4228BF0E46E108415C08EBD50EEE +:101D800013F80EC0B94029FA06F721FA0AF1FFB29A +:101D90008CEA010147FA0AF739408CEA010C03F892 +:101DA0000EC034443544D5E7082341F2210280EACD +:101DB000012001B24000002980B203F1FF33B8BF17 +:101DC000504013F0FF03F4D17047000038B50C46C3 +:101DD0008D18A54200D138BD14F8011BFFF7E4FFB0 +:101DE000F7E700000346406848B1026899895A60E5 +:101DF0005A89013292B291425A8138BF9A81704712 +:101E000070B504460D4688B0202200216846FFF7D1 +:101E100049FC20460495FFF7E5FF024658B16B46A2 +:101E2000054608AE1C4603CCB442286069602346D0 +:101E300005F10805F6D1104608B070BD082817D97D +:101E400009280CD00A280CD00B280CD00C280CD058 +:101E50000D280CD00E2814BF4020302070470C20D5 +:101E600070471020704714207047182070472020BA +:101E700070470000082817D90C280CD910280CD955 +:101E800014280CD918280CD920280CD930288CBF3C +:101E90000F200E207047092070470A2070470B2042 +:101EA00070470C2070470D20704700002DE9F84363 +:101EB000078C0446072F1ED9D0E9029800254FF65B +:101EC000FF73C5F12006A5F1200029FA05F108FAF3 +:101ED00006F628FA00F031430143C9B21846FFF76D +:101EE00063FF0835402D0346EBD13A46E169BDE872 +:101EF000F843FFF76BBF4FF6FF70BDE8F8830000B3 +:101F000010B54B6823B9CA8A63F30902CA8210BDAF +:101F100004691A681C600361C38A013BC3824A607A +:101F2000EFE700002DE9F84F1D46CB8A0F46C3F3BB +:101F300009010529814692460B4630D00020AAB2FD +:101F400007F11A049EB2042E1FFA80F80FD89045AC +:101F500003F1010306D3FB8A0A4462F3090301205B +:101F6000FB821AE01AF800600130E654EAE7904577 +:101F7000F1D21C23A1F1050BBBFBF3F203FB12BB57 +:101F80007C681FFA8BF6002C45D14846FFF72AFFE4 +:101F9000044638B978606FF00200BDE8F88F4FF062 +:101FA0000008E6E70026066078604FF0000BADB24F +:101FB000454510D90AEB0803221D13F8011B08F14F +:101FC00001089155B1B21B291FFA88F82BD045455D +:101FD00006F10106F1D8FB8AC3F30902154465F343 +:101FE0000903BCE71C46013292B22368002BF9D1E9 +:101FF0006B1F0B441C21B3FBF1F301339BB29A42DC +:10200000D3D2BBF1000FD0D14846FFF7EBFE20B989 +:10201000C4F800B0BFE70122E7E7C0F800B05E46B1 +:1020200020600446C1E74545D5D94846FFF7DAFEAA +:1020300008B92060AFE7C0F800B000262060044671 +:10204000B6E700002DE9F74F1C465B690746884656 +:102050000092002B00F09780238C2BB1E269002ABC +:1020600000F09180072B33D807F10C00FFF7BAFE80 +:10207000054628B96FF00205284603B0BDE8F08F89 +:1020800014220021FFF70EFB228CE16905F1080004 +:10209000FFF7F6FA208C48F00041013080B2FFF7DC +:1020A000E9FEFFF7CBFE013880B2208401302874AE +:1020B0006369228C1B782A4403F01F0363F03F03FB +:1020C0001372384669602946FFF7F4FD0125D3E70E +:1020D0004FF000094FF0800A4E464D4600F10C03C8 +:1020E00001930198FFF77EFE83460028C2D0142298 +:1020F0000021FFF7D7FA002E3BD10222009BABF85C +:1021000008300BF1080E1FFA82FC0CF10100BCF143 +:10211000060F218C80B201D88E422CD3FFF7AAFE85 +:10212000FFF78CFE8E4208BF4FF0400A626901380B +:10213000127880B202F01F0242EA49120BEB000152 +:102140004AEA020A013048F0004281F808A08BF800 +:10215000100059463846CBF80420FFF7ABFD238C1E +:102160000135B3424FF0000A2DB289F00109B8D110 +:1021700082E70022C5E7E169895D01360EF80210A9 +:10218000B6B20132BFE76FF0010575E7F8B5044656 +:1021900015460E46302200211F46FFF783FA069BA4 +:1021A000B5F5001F6360079B28BF4FF6FF72A3625F +:1021B0004FF0000338BF6A09A760E66197B204F1E7 +:1021C00010009A4206D800230360A782E38223838B +:1021D000E360F8BD0660013330462036F1E70000C9 +:1021E00003781BB94BB2002BC8BF017070470000C9 +:1021F00000787047F8B50C46C969074611B9238CB9 +:10220000002B37D1257E1F2D34D8387828BB228C5F +:10221000072A2CD8268A36F003032BD14FF6FF70FD +:10222000FFF7D4FD4FF6FF7220F0010036024004A4 +:1022300046EA0565400C45EA4025234629463846CE +:10224000FFF700FF002807DD626913780133DBB276 +:102250001F2B88BF00231370F8BD218A2D0645EA85 +:10226000012505432046FFF721FE0246E5E76FF012 +:102270000300F1E76FF00100EEE7000070B50446DF +:102280001D4616468AB0282200216846FFF70AFA42 +:10229000BDF838306946ADF810300F9B20460593E5 +:1022A0009DF84030CDE902658DF81830119B0793F9 +:1022B000BDF84830ADF82030FFF79CFF0AB070BD84 +:1022C0002DE9F041D36905460C4616460BB9138C2F +:1022D0005BBB377E1F2F28D895F80080B8F1000F20 +:1022E00026D03046FFF7E2FD3378210241EAC331C0 +:1022F00041EA0801338A41EA076141EA03410246A3 +:102300003346284641F08001FFF79CFE00280ADD95 +:102310003378012B07D1726913780133DBB21F2B9D +:1023200088BF00231370BDE8F0816FF00100FAE769 +:102330006FF00300F7E70000F0B504460D461E46B7 +:1023400017468BB0282200216846FFF7ABF99DF8AD +:102350004C3029465A1E534253418DF800309DF8A7 +:1023600040306A46ADF81030119B204605939DF829 +:102370004830CDE902768DF81830149B0793BDF8EC +:102380005430ADF82030FFF79BFF0BB0F0BD0000DC +:10239000406A00B104307047436A1A6842620269B9 +:1023A0001A600361C38A013BC38270472DE9F04183 +:1023B000D0F8208014461D4641460027174E09B923 +:1023C000BDE8F081D1E90223A21A65EB030396422E +:1023D00077EB03031ED2036A8B420DD1FFF790FD0A +:1023E000036A1B68036203690B60C38A0161016AA7 +:1023F000013B8846C382E2E7FFF782FD0B68C8F81D +:10240000003003690B60C38A0161013BC382D8F8C5 +:102410000010D4E788460968D1E700BF80841E0019 +:102420002DE9F04F8BB00D4614469B468046DDF8F3 +:102430005090002800F01A81B9F1000F00F01681C9 +:10244000531E3F2B00F21281012A03D1BBF1000F72 +:1024500040F00C810023CDE90833B8F81430B5EB17 +:10246000C30F4FEAC30703D300200BB0BDE8F08FC2 +:102470002B199F42D8F80C3036BF7F1B2746FFB27E +:102480001BB9D8F81030002B7BD0272D4ED8C5F1C2 +:102490002806B7424FF0000334BF3E46F6B2009321 +:1024A00029463246D8F8080008ABFFF745FCA7EBF1 +:1024B000060A35445FFA8AFA2821B8F8143003F185 +:1024C0000053053BDB000493D8F80C300393039BC7 +:1024D00013B1BAF1000F2CD1D8F8100040B1BAF105 +:1024E000000F05D05246009608AB691AFFF724FC8E +:1024F00038B2002FB8D066070AD00AAB03EBD4017C +:1025000011F8083C624202F00702134101F8083C4E +:10251000082C3DD9102C40F2B680202C40F2B88017 +:10252000BBF1000F00F09D80082335E0BA4600267D +:10253000C2E7049BE02B28BFE02306930B44AB4289 +:10254000059315D95A1B924538BF5246039828BFA8 +:10255000D2B20096691A08AB04300792FFF7ECFB81 +:10256000079A1644AAEB020A1544F6B25FFA8AFAF1 +:10257000049B069A05999B1A0493039B1B6803937B +:10258000A5E700933A462946D8F8080008ABADE71E +:10259000BBF1000F13D00123B4EBC30F6CD0082C98 +:1025A00012D89DF82030621E23FA02F2D50706D514 +:1025B0004FF0FF3202FA04F423438DF820309DF8E7 +:1025C000203089F8003050E7102C12D8BDF82030A8 +:1025D000621E23FA02F2D10706D54FF0FF3202FA4B +:1025E00004F42343ADF82030BDF82030A9F80030C2 +:1025F0003BE7202C0FD80899631E21FA03F3DA0772 +:1026000005D54FF0FF3202FA04F40C430894089BFE +:10261000C9F8003029E7402C2BD0DDE90865611EA0 +:10262000C4F12102A4F1210326FA01F105FA02F214 +:1026300025FA03F311431943CB0712D50122A4F164 +:102640002003C4F1200102FA03F322FA01F1A240AF +:10265000524243EA010363EB430332432B43CDE988 +:102660000823DDE90823C9E90023FEE66FF0010035 +:10267000FBE66FF00800F8E6082CA0D9102CB3D9BF +:10268000202CEED8C3E7BBF1000FADD0022383E7C7 +:10269000BBF1000FBBD004237EE70000012A30B558 +:1026A000144638BF01220025402A28BF402285B0A9 +:1026B000012CCDE9025517D81B788DF80830530747 +:1026C0000AD004AB03EBD20515F8083C544204F0E1 +:1026D0000704A34005F8083C0346009102A8002126 +:1026E000FFF72AFB05B030BD082CE5D9102C03D824 +:1026F0001B88ADF80830E2E7202C02D81B68029353 +:10270000DDE7D3E90045CDE90245D8E710B5CB6850 +:102710001BB98B600B618B8210BD04691A681C6049 +:102720000361C38A013BC382CA60F0E703064CBF62 +:10273000C0F3C0300220704708B50246FFF7F6FF2D +:10274000022806D15306C2F30F2001D100F0030086 +:1027500008BDC2F30740FBE72DE9F04F93B0CDE988 +:1027600003230A6804461046FFF7E0FF02280CBF67 +:102770000026C2F30626002A0D46824680F2F98121 +:1027800012F0C04940F0F581097B002900F0F18189 +:10279000022803D02378B34240F0EE81C2F30463F1 +:1027A0001046069302F07F030593FFF7C5FF059BD4 +:1027B00000224FEA8348002348EA0A48294448EAAD +:1027C0004668CE78CDE90823F309834648EA000835 +:1027D000029367D0059B02460093204653466768E4 +:1027E00008A9B847002800F0CA81276A4FB94146B6 +:1027F00004F10C00FFF704FB074690B96FF00200EC +:1028000054E03B6998450DD03F68002FF9D141460F +:1028100004F10C00FFF7F4FA07460028EED0236A13 +:102820003B60276297F817C006F01F08CCF3840CB2 +:10283000ACEB08001FFA80FE0028B8BF0EF12000A4 +:10284000A8EB0C031FFA83FEB8BF00B2002B07935E +:10285000BEBF0EF120031BB20793D7E9022152EA53 +:10286000010338D04FF0000C039BDFF8F8E19A1A0F +:10287000049B63EB010196457CEB01032BD36B7B3F +:1028800097F81AE0734519D1029B002B78D00128E4 +:1028900021DC7868F8B9DFF8D0C1944570EB01030A +:1028A00016D337E0276A27B96FF00C0013B0BDE8E4 +:1028B000F08F3B699845B5D03F68F4E76A4890428D +:1028C0007CEB010301D30020F0E7029B002BFAD040 +:1028D000079B0F2B17DCFA7DB30002F0030203F015 +:1028E0007C031343FB7539462046FFF709FB6B7BDE +:1028F000BB76029B3BB9FB7DC3F38402013262F3DA +:102900008603FB75D0E76A7BBB7E9A42DBD1029BD4 +:10291000002B35D0B309022B32D0039B1422BB60AD +:10292000049B0021FB600DA8FEF7BCFE039B204624 +:102930000A93049BADF83EB00B932B1D0C932B7B9D +:102940008DF840A0013BDBB2ADF83C30069B8DF822 +:1029500041808DF84230059B0AA98DF8433094F8E8 +:102960002C3083F001038DF84430A3689847FB7D39 +:10297000C3F38403013303F01F039B02FB82A2E72E +:10298000FB7DC6F34012B2EBD31F40F0FB80C3F3D4 +:102990008403434540F0F980029A2B7BB609002A54 +:1029A0004DD0F20762D4032B40F2F280039BAE1DA0 +:1029B000BB60049B3246FB602B7B3946033BDBB29A +:1029C00004F10C00FFF7AEFA00280CDA3946204675 +:1029D000FFF796FAFB7DC3F38403013303F01F0373 +:1029E0009B02FB820AE7AB88DDE908843B834FF654 +:1029F000FF73C9F12000A9F1200228FA09F104FAB5 +:102A000000F0014324FA02F211431846C9B2FFF75D +:102A1000CBF909F10809B9F1400F0346E9D1314674 +:102A2000B8822A7B033AD2B2FFF7D0F9FB7DB88295 +:102A3000DA43C2F3C01262F3C713FB7543E7AEB9C2 +:102A40002E1D013B32463946DBB204F10C00FFF784 +:102A500069FA0028BADB2A7B3146013AB88AD2B239 +:102A6000E2E700BF80841E0040420F00F98A013B6C +:102A7000C1F309010429DAB25DD80023281D07F14A +:102A80001B069A4208D910F801CB013306F801C0A1 +:102A900001310529DBB2F4D1934228BF0023039909 +:102AA00038BF04330A91049938BFDBB20B9107F1A8 +:102AB0001B010C91796838BF5B190D910E93FB8A4D +:102AC000ADF83EB0C3F309031A44069BADF83C20B1 +:102AD0008DF84230059B8DF840A08DF8433094F876 +:102AE0002C308DF8418083F001038DF844300023B1 +:102AF0007B602A7BB88A013A291DFFF767F93B8B77 +:102B0000B882834203D12046A3680AA99847204689 +:102B10000AA9FFF7FBFDFB7DBA8AC3F384030133E7 +:102B200003F01F039B02FB823B8B9A420CBF0020E9 +:102B30006FF01000BAE67B68002BADD0052001E0F5 +:102B400033461C301E68002EFAD1091A081D2E1DAE +:102B5000184401EB090CBCF11B0F5FFA89F39BD8F9 +:102B60009A4299D916F8013B09F1010900F8013B95 +:102B7000EFE76FF0090099E66FF00A0096E66FF054 +:102B80000B0093E66FF00D0090E66FF00E008DE6FF +:102B90006FF00F008AE600BFF0B53F4D3F4FEB6985 +:102BA00043F00073EB61EB693D4B9B6AD3F8006225 +:102BB0003E4046F00106C3F80062D3F800423C40B4 +:102BC00044EA002444F00104C3F80042002955D02F +:102BD00000200646C3F81C02C3F80402C3F80C0226 +:102BE000C3F8140203EBC00401300E28C4F840629D +:102BF000C4F84462F6D100274FF0010C967814888F +:102C000016F0010F18BFD3F804E20CFA04F01CBF51 +:102C100040EA0E0EC3F804E216F0020F18BFD3F814 +:102C20000CE203EBC4041CBF40EA0E0EC3F80CE236 +:102C3000760748BFD3F8146207F1010744BF064383 +:102C4000C3F814625668B942C4F84062966802F14B +:102C50000C02C4F84462D3F81C4240EA0400C3F8F2 +:102C60001C02CBD1D3F8002222F00102C3F80022CB +:102C7000EB6923F00073EB61EB69F0BD0122C3F84F +:102C80004012C3F84412C3F80412C3F81412C3F874 +:102C90000C22C3F81C22E5E7001002400000FFFFF1 +:102CA000A8230020184A08B5916A8B688B6013F03E +:102CB000010104D013F00C0F18BF4FF48031D80578 +:102CC00006D513F4406F14BF41F4003141F0020106 +:102CD000D80306D513F4402F14BF41F4802141F0EE +:102CE0000401D3690BB108489847302383F3118856 +:102CF0000021064800F048FB002383F31188BDE85B +:102D0000084000F099BD00BFA8230020B023002098 +:102D100038B5124CA36ADD68AA0712D05A6922F0AE +:102D200002025A61A36913B101212046984730235A +:102D300083F3118800210A4800F026FB002383F367 +:102D40001188EB0606D51021A36AD960236A0BB15E +:102D500002489847BDE8384000F06EBDA823002027 +:102D6000B823002038B5124CA36A1D69AA0712D0F7 +:102D70005A6922F010025A61A36913B10221204658 +:102D80009847302383F3118800210A4800F0FCFAA9 +:102D9000002383F31188EB0606D51021A36A19617D +:102DA000236A0BB102489847BDE8384000F044BDA3 +:102DB000A8230020B823002038B50F4CA36A5D6813 +:102DC0002A075D600AD5042222701A6822F00202E6 +:102DD0001A60636A13B10021204698476B0706D535 +:102DE000A36A9969236A13B1034809049847BDE8A7 +:102DF000384000F021BD00BFA823002010B50E4CC4 +:102E0000204600F02FF90D4B0B211320A36200F098 +:102E100009F90B21142000F005F90B21152000F011 +:102E200001F90B21162000F0FDF8BDE8104000224A +:102E30000E201146FFF7B0BEA8230020006400401A +:102E40000F4B10B59842044605D10E4BDA6942F09B +:102E50000072DA61DB690122A36A1A60A36A5A6808 +:102E6000D20707D5626851681268D9611A60064AAC +:102E70005A6110BD0121082000F0B0F9EEE700BF53 +:102E8000A8230020001002405B87010003291AD804 +:102E9000DFE801F0020A0F14836A9B6813F0E05F19 +:102EA00014BF012000207047836A9868C0F38060D7 +:102EB0007047836A9868C0F3C0607047836A9868F7 +:102EC000C0F30070704700207047000010B5032960 +:102ED00027D8DFE801F002272B2F836A9968C1F316 +:102EE0000161183103EB01131078840648BF546860 +:102EF000C0F3001158BF94884FEA410148BF41EA2E +:102F0000C40100F00F00586048BF41F00401906810 +:102F100058BF41EA4451D26841F001019860DA603B +:102F2000196010BD836A03F5C073DDE7836A03F59A +:102F3000C873D9E7836A03F5D073D5E701290AD0AE +:102F400002290FD081B9836ADA68920701D1186922 +:102F500003E001207047836AD86810F0030018BFAF +:102F600001207047836AF2E70020704710B539B935 +:102F7000836AD96889071BD11B699C0704D110BDDE +:102F8000012915D00229FAD1816AD1F8C031D1F8CE +:102F9000C441D1F8C8011061D1F8CC0150612020A2 +:102FA00008610869800717D1486940F0100012E0F5 +:102FB000816AD1F8B031D1F8B441D1F8B8011061CB +:102FC000D1F8BC0150612020C860C868800703D1D7 +:102FD000486940F002004861C3F34000C3F3800138 +:102FE000000140EA4111107920F0300001431171D5 +:102FF00089064BBF91681189DB085B0D4CBF63F3F9 +:103000001C0163F30A01137948BF916064F3030361 +:1030100013714FEA14234FEA144458BF11811370FF +:103020005480ACE70122090100F1604303F56143DC +:10303000C9B283F8001300F01F039A4043099B00B4 +:1030400003F1604303F56143C3F880211A607047C0 +:10305000090100F16040C9B200F56D40017670478A +:10306000FFF7CCBE01230370002300F10802C0E982 +:10307000022200F11002C0E90422C0E90633C0E9CF +:10308000083343607047000010B53023044683F3D3 +:103090001188022341600370FFF7D2FE0423002051 +:1030A000237080F3118810BD2DE9F0411F460446BE +:1030B0000D461646302383F3118800F10808237863 +:1030C000052B0DD029462046FFF7E0FE40B12046F3 +:1030D00032462946FFF7FAFE002080F3118808E007 +:1030E0003946404600F040F90028E8D0002383F339 +:1030F0001188BDE8F08100002DE9F0411F4604462B +:103100000D461646302383F3118800F1100823780A +:10311000052B0DD029462046FFF710FF40B1204671 +:1031200032462946FFF722FF002080F3118808E08D +:103130003946404600F018F90028E8D0002383F310 +:103140001188BDE8F08100000023826803750369DF +:103150001B6899689142FBD25A6803604260106014 +:103160005860704700238268037503691B6899687B +:103170009142FBD85A680360426010605860704703 +:1031800008B50846302383F311880B7D032B05D047 +:10319000042B0DD02BB983F3118808BD00228B6955 +:1031A0001A604FF0FF338361FFF7CEFF0023F2E791 +:1031B000D1E9003213605A60F3E70000FFF7C4BFA3 +:1031C000054BD96808751868026853601A600122B7 +:1031D0000275D860FDF79ABBD823002030B50C4BA0 +:1031E0000446DD684B1C87B00FD02B466846094A61 +:1031F00000F0F0F82046FFF7E3FF009B13B16846AC +:1032000000F0F0F8A86907B030BDFFF7D9FFF9E783 +:10321000D823002081310008044B1A68DB689068CD +:103220009B68984294BF002001207047D82300205B +:10323000084B10B51C68D868226853601A600122D8 +:103240002275DC60FFF78EFF01462046BDE8104086 +:10325000FDF75CBBD8230020044B1A68DB6892683A +:103260009B689A4201D9FFF7E3BF7047D82300203B +:1032700038B501230025064C0649074823706560D0 +:1032800000F020FB0223237085F3118838BD00BFB6 +:1032900030250020A43D0008D823002000F0B4B859 +:1032A000EFF3118020B9EFF30583302282F3118808 +:1032B0007047000010B530B9EFF30584C4F308047B +:1032C00014B180F3118810BDFFF7C6FF84F3118895 +:1032D000F9E700008B60022308618B820846704783 +:1032E0008368A3F1440243F8142C026943F8442C88 +:1032F000426943F8402C094A43F8242CC268A3F1E0 +:10330000200043F8182C022203F80C2C002203F8AA +:103310000B2C034A43F8102C704700BF1D0900080E +:10332000D823002008B5FFF7DBFFBDE80840FFF712 +:1033300045BF0000024BDB6898610F20FFF740BFDC +:10334000D8230020302383F31188FFF7F3BF000058 +:1033500008B50146302383F311880820FFF73EFFAC +:10336000002383F3118808BD064BDB6839B142683E +:1033700018605A60136043600420FFF72FBF4FF0BE +:10338000FF307047D823002038B504460D4620682A +:10339000844200D138BD036823605C608561FFF71B +:1033A0000DFFF4E710B50A4C23699A6891420CD8D6 +:1033B0005A6881600360426010609A685860511AD0 +:1033C00099604FF0FF33A36110BD1B68891AECE7C9 +:1033D000D8230020C0E90323002310B410BC4361AC +:1033E000FFF7E0BF036881689A680A449A60426800 +:1033F00013605A6000234FF0FF320360014B9A6163 +:10340000704700BFD823002070B5124D2A46EB69E3 +:103410000133EB6152F8103F934206D030269A6890 +:10342000013A9A602C69A36803B170BDD4E9002108 +:103430000A605160236083F311882046D4E9033188 +:10344000984786F3118861690029EBD02046FFF781 +:10345000A9FFE7E7D823002000207047FEE700001F +:10346000704700004FF0FF3070470000BFF34F8FF0 +:10347000024AD368DB07FCD4704700BF002002403B +:1034800008B5074B1B7853B9FFF7F0FF054B1A69D6 +:10349000120641BF044A5A6002F188325A6008BDE0 +:1034A00048250020002002402301674508B5054B50 +:1034B0001B7833B9FFF7DAFF034A136943F080033F +:1034C000136108BD48250020002002407F289ABFD4 +:1034D00000F5003080020020704700004FF480604B +:1034E00070470000802070477F2808B50BD8FFF791 +:1034F000EDFF00F580630268013204D1043083429D +:10350000F9D1012008BD0020FCE700007F2810B59C +:1035100004461CD8FFF7AAFFFFF7B2FFF3220D4BBA +:103520004FF48061DA6002221A61FFF7CFFF586121 +:103530001A6942F040021A61FFF798FF00F004F99F +:10354000FFF7B4FF2046BDE81040FFF7CDBF0020D5 +:1035500010BD00BF002002402DE9F843054612F0DF +:103560000100144606D040F2F32200201E4B1A60E0 +:10357000BDE8F8831D4BAA189A4204D94FF43E7255 +:10358000194B1A60F4E7FFF77BFF4FF00109FFF7D3 +:103590006DFFDFF85C806D1A012C0F4605EB01060C +:1035A00003D8FFF783FF0120E2E73B88C8F81090BB +:1035B00033800020FFF75AFFC8F81000338831F835 +:1035C000022B9BB29A420CD040F20F32064B1A608B +:1035D000084B1E60084B1C60084B1F60FFF766FF1E +:1035E000C6E7023CD8E700BF4425002000000208DF +:1035F0000020024038250020402500203C250020E6 +:10360000084908B50B7828B11BB9FFF739FF01232A +:103610000B7008BD002BFCD0BDE808400870FFF718 +:1036200045BF00BF4825002070B5FFF739FE4FF4B5 +:103630007A710D4B0D4EDB69326801FB03F3934247 +:1036400037BF0B4A0A495168156836BF4C1CD1E98F +:10365000005454605D1944F100043360FFF72AFE02 +:103660002846214670BD00BFD82300204C250020ED +:103670005025002070B5FFF713FE4FF47A710F4B01 +:103680000F4EDB69326801FB03F3934237BF0D4AEB +:103690000C49516815683ABF4C1C5460D1E900547C +:1036A0005D1944F100043360FFF704FE4FF47A72B1 +:1036B000002328462146FCF735FF70BDD8230020A3 +:1036C0004C2500205025002010B5094C013AD2B2FB +:1036D000FF2A00D110BD500854F82030013054F8B2 +:1036E00020009BB243EA004341F8043BEEE700BFF1 +:1036F000046C004010B50748013AD2B2FF2A00D14D +:1037000010BD0C88530840F823404C88013340F822 +:103710002340F1E7046C004007B50122002001A915 +:10372000FFF7D2FF019803B05DF804FB13B5044620 +:10373000FFF7F2FFA04205D00122002001A9019469 +:10374000FFF7D8FF02B010BD7047000045F2555298 +:10375000064B1A6002225A6040F6FF729A604CF6DD +:10376000CC421A600122024B1A70704700300040B0 +:103770005C250020034B1B781BB14AF6AA22024BA2 +:103780001A6070475C25002000300040044B1A6826 +:103790002AB902F1804202F50432526A1A60704777 +:1037A000582500204FF08072014B5A62704700BFCD +:1037B0000010024008B5FFF7E9FF024B1868C0F39C +:1037C000407008BD5825002008B5FFF7DFFF024B09 +:1037D0001868C0F3007008BD58250020EFF3098376 +:1037E000203383F30988002383F311887047000096 +:1037F000302080F3118862B60C4B0D4AD96821F451 +:10380000E0610904090C0A43DA60D3F8FC20094995 +:1038100042F08072C3F8FC200A6842F001020A609C +:103820002022DA7783F82200704700BF00ED00E025 +:103830000003FA05001000E0302310B583F311886F +:103840000B4B5B6813F400630FD0EFF309844FF068 +:103850008073203CE36184F30988FFF7DDFC10B13D +:10386000044BA36110BD044BFBE783F31188F9E718 +:1038700000ED00E02F090008320900087047000041 +:10388000FEE700000A4B0B480B4A90420BD30B4B50 +:10389000C11EDA1C121A22F003028B4238BF00222A +:1038A0000021FDF7FFBE53F8041B40F8041BECE7B2 +:1038B000243E0008E0250020E0250020E02500202F +:1038C000FEE7000070B5002504461A4B86B058602C +:1038D000856201630E46FFF78BFF04F11003C4E914 +:1038E00004334FF0FF33A361134BE561D9692B46D5 +:1038F0000A462046C4E9082304F134018023C4E9C0 +:1039000000440E4AA560E5622565FFF7E3FC01234C +:103910000B4AE06003750092726868460192B268D3 +:10392000CDE90223074BCDE90435FFF7FBFC06B0D8 +:1039300070BD00BF30250020D8230020B03D000816 +:10394000B53D0008C138000800F030B808B500F0F7 +:1039500063F9FFF78DFCBDE80840FFF717BF0000D3 +:10396000704700004FF0FF310E4B1A6919611A6958 +:1039700000221A611869D868D960D968DA60DA68F3 +:10398000DA6942F08052DA61DA69DA6942F000629B +:10399000DA61054ADB69136843F48073136000F051 +:1039A0001BB900BF0010024000700040194B1A689C +:1039B00042F001021A601A689007FCD51A6802F0FA +:1039C000F9021A6000225A605A6812F00C0FFBD1FB +:1039D0001A6842F480321A601A689103FCD55A685A +:1039E00042F4E8125A601A6842F080721A601A684B +:1039F0009201FCD51221084A5A60084A11605A689F +:103A000042F002025A605A6802F00C02082AFAD107 +:103A1000704700BF0010024000641D0000200240FB +:103A2000084A08B5516913680B4003F0010353615C +:103A300023B1054A13680BB150689847BDE80840A8 +:103A4000FFF7FABE0004014060250020084A08B5CF +:103A5000516913680B4003F00203536123B1054A17 +:103A600093680BB1D0689847BDE80840FFF7E4BE03 +:103A70000004014060250020084A08B55169136818 +:103A80000B4003F00403536123B1054A13690BB1E2 +:103A900050699847BDE80840FFF7CEBE00040140DA +:103AA00060250020084A08B5516913680B4003F0EF +:103AB0000803536123B1054A93690BB1D069984754 +:103AC000BDE80840FFF7B8BE0004014060250020B3 +:103AD000084A08B5516913680B4003F0100353619D +:103AE00023B1054A136A0BB1506A9847BDE80840F4 +:103AF000FFF7A2BE0004014060250020174B10B55F +:103B00005A691C68144004F478725A61A30604D5FB +:103B1000134A936A0BB1D06A9847600604D5104ADD +:103B2000136B0BB1506B9847210604D50C4A936B6D +:103B30000BB1D06B9847E20504D5094A136C0BB161 +:103B4000506C9847A30504D5054A936C0BB1D06C13 +:103B50009847BDE81040FFF76FBE00BF000401406A +:103B6000602500201A4B10B55A691C68144004F4F3 +:103B70007C425A61620504D5164A136D0BB1506D33 +:103B80009847230504D5134A936D0BB1D06D984720 +:103B9000E00404D50F4A136E0BB1506E9847A10490 +:103BA00004D50C4A936E0BB1D06E9847620404D5CD +:103BB000084A136F0BB1506F9847230404D5054A88 +:103BC000936F0BB1D06F9847BDE81040FFF734BE3C +:103BD0000004014060250020062108B50846FFF7D3 +:103BE00021FA06210720FFF71DFA06210820FFF71A +:103BF00019FA06210920FFF715FA06210A20FFF716 +:103C000011FA06211720FFF70DFABDE8084006213A +:103C10002820FFF707BA000008B5FFF7A3FE054804 +:103C200000F00CF8FFF71CFAFFF79AFEBDE8084019 +:103C300000F002B8BC3D000800F042B8002319466D +:103C40001C4A0133102BC2E9001102F10802F8D11D +:103C5000194B9A6942F07D029A619B690268174B81 +:103C6000DA6082685A6042681A60C26803F580634D +:103C7000DA6042695A6002691A608269C3F80C24EA +:103C8000026AC3F80424C269C3F80024426AC3F874 +:103C90000C28C26AC3F80428826AC3F80028026BA1 +:103CA000C3F80C2C826BC3F8042C426BC3F8002CB5 +:103CB000704700BF6025002000100240000801404E +:103CC0004FF0E023044A08215A6100229A6107223A +:103CD0000B201A61FFF7BCB93F19010008B530236A +:103CE00083F31188FFF7DAFA002383F3118808BD04 +:103CF00008B5FFF7F3FFBDE80840FFF79DBD0000E2 +:103D000010B501390244904201D1002005E003784A +:103D100011F8014FA34201D0181B10BD0130F2E78A +:103D20002DE9F0419BB10446C91A1778014403F10B +:103D3000FF3C8C42204601D9002008E00578013480 +:103D4000BD42F6D10CEB0405D618A54201D1BDE861 +:103D5000F08115F8018D16F801EDF045F5D0E8E792 +:103D6000034611F8012B03F8012B002AF9D1704703 +:103D70006F72672E6172647570696C6F742E663134 +:103D800030332D48574553430000000040A2E4F172 +:103D9000646891060041A3E5F2656992070000009E +:103DA00063300000A03D00083024002030250020B2 +:103DB0006D61696E0069646C6500000000180000A8 +:103DC00044444144445449440100000042444444B2 +:103DD00044444444000000004444444444444444B3 +:103DE00000000000444444444444444400000000B3 +:103DF00044444444444444445CC7FF7F0100000001 +:103E0000E803000000000000009C0100000000002A +:103E1000640000000000000040420F00FE2A010084 +:043E2000D2040000C8 :00000001FF diff --git a/Tools/bootloaders/f103-QiotekPeriph_bl.bin b/Tools/bootloaders/f103-QiotekPeriph_bl.bin index c809ad2c0f114a..ffde9e119ef8ff 100755 Binary files a/Tools/bootloaders/f103-QiotekPeriph_bl.bin and b/Tools/bootloaders/f103-QiotekPeriph_bl.bin differ diff --git a/Tools/bootloaders/f103-QiotekPeriph_bl.hex b/Tools/bootloaders/f103-QiotekPeriph_bl.hex index b0e1d4711dfbb4..072f1569b8776f 100644 --- a/Tools/bootloaders/f103-QiotekPeriph_bl.hex +++ b/Tools/bootloaders/f103-QiotekPeriph_bl.hex @@ -1,963 +1,998 @@ :020000040800F2 -:100000000009002069040008C114000865140008F4 -:10001000A514000865140008851400086B04000886 -:100020006B0400086B0400086B0400087D350008B1 -:100030006B0400086B0400086B040008113A000808 -:100040006B0400086B0400086B0400086B040008D4 -:100050006B0400086B0400083D370008693700088E -:1000600095370008C1370008ED3700086B04000819 -:100070006B0400086B0400086B0400086B040008A4 -:100080006B0400086B0400086B040008712400086E -:10009000DD240008312500088525000819380008EE -:1000A0006B0400086B0400086B0400086B04000874 -:1000B0006B0400086B0400086B0400086B04000864 -:1000C0006B0400086B0400086B0400086B04000854 -:1000D0006B04000825290008392900086B04000872 -:1000E000813800086B0400086B0400086B040008EA -:1000F0006B0400086B0400086B0400086B04000824 -:100100006B0400086B0400086B0400086B04000813 -:100110006B0400086B0400086B0400086B04000803 -:100120006B0400086B0400086B0400086B040008F3 -:100130006B0400086B0400086B0400086B040008E3 -:100140006B0400086B0400086B0400086B040008D3 -:100150006B0400086B0400086B0400086B040008C3 -:1001600053B94AB9002908BF00281CBF4FF0FF311E -:100170004FF0FF3000F076B9ADF1080C6DE904CE18 -:1001800000F006F8DDF804E0DDE9022304B0704772 -:100190002DE9F047089E0D4604468846002B4DD1B8 -:1001A0008A42944668D9B2FA82F252B101FA02F355 -:1001B000C2F1200120FA01F10CFA02FC41EA030825 -:1001C00094404FEA1C41B8FBF1F71FFA8CFE01FB8B -:1001D000178807FB0EF0230C43EA084398420AD91C -:1001E0001CEB030307F1FF3580F01E81984240F2BB -:1001F0001B81023F63441B1AB3FBF1F001FB103378 -:1002000000FB0EFEA4B244EA0344A6450AD91CEB47 -:10021000040400F1FF3380F00981A64540F2068115 -:10022000644402380021A4EB0E0440EA07401EB1EA -:100230000023D440C6E90043BDE8F0878B4208D9CB -:10024000002E00F0EE800021C6E900050846BDE85A -:10025000F087B3FA83F100294AD1AB4202D382423C -:1002600000F2FC80841A65EB030301209846002EFF -:10027000E2D0C6E90048DFE702B9FFDEB2FA82F257 -:10028000002A40F09180A1EB0C0001214FEA1C47AD -:100290001FFA8CFEB0FBF7F307FB1300250C45EAB1 -:1002A00000450EFB03F0A84208D91CEB050503F13D -:1002B000FF3802D2A84200F2CE8043462D1AB5FB89 -:1002C000F7F007FB10550EFB00FEA4B244EA05440C -:1002D000A64508D91CEB040400F1FF3502D2A6455F -:1002E00000F2B6802846A4EB0E0440EA03409EE7E5 -:1002F000C1F120078B4022FA07FC4CEA030C25FAD7 -:1003000007FA4FEA1C49BAFBF9F820FA07F309FB90 -:1003100018AA8D401FFA8CFE1D4300FA01F308FB5A -:100320000EF02C0C44EA0A44A04202FA01F20BD966 -:100330001CEB040408F1FF3A80F08880A04240F2F0 -:100340008580A8F102086444241AB4FBF9F009FB83 -:10035000104400FB0EFEADB245EA0444A64508D9A0 -:100360001CEB040400F1FF356CD2A6456AD90238B3 -:10037000644440EA0840A0FB0295A4EB0E04AC42A2 -:10038000C846AE4656D353D0002E69D0B3EB080210 -:1003900064EB0E0422FA01F304FA07F71F43CC4082 -:1003A000C6E90074002147E70CFA02FCC2F1200103 -:1003B00025FA01F34FEA1C4720FA01F195400D435D -:1003C000B3FBF7F107FB11331FFA8CFE280C40EA50 -:1003D000034001FB0EF3834204FA02F408D91CEB3C -:1003E000000001F1FF382FD283422DD90239604439 -:1003F000C01AB0FBF7F307FB1300ADB245EA0045A6 -:1004000003FB0EF0A84208D91CEB050503F1FF38E9 -:1004100016D2A84214D9023B6544281A43EA014186 -:1004200038E73146304607E72F46E4E61846F9E656 -:100430004B45A9D2B9EB020865EB0C0E0138A3E7D6 -:100440004346EAE7284694E74146D1E7D0467BE7B2 -:100450006444023847E7023B65442FE7084606E755 -:100460003146E9E6704700BF02E000F000F8FEE721 -:1004700072B6284880F30888274880F309882748FF -:100480004EF60851CEF200010860022080F3148875 -:10049000BFF36F8F03F0E4F803F0C0F803F0E2F865 -:1004A0004FF055301E491B4A91423CBF41F8040BA6 -:1004B000FAE71C49184A91423CBF41F8040BFAE79D -:1004C00019491A4A1A4B9A423EBF51F8040B42F896 -:1004D000040BF8E700201749174A91423CBF41F846 -:1004E000040BFAE703F09EF803F0BEF8134C144D2A -:1004F000AC4203DA54F8041B8847F9E700F03CF8F3 -:10050000104C114DAC4203DA54F8041B8847F9E74C -:1005100003F086B800090020001100200000000848 -:100520000001002000090020E03B0008001100202D -:100530002411002028110020A025002060010008BF -:100540006001000860010008600100082DE9F04F1B -:10055000C1F80CD0C3689D46BDE8F08F002383F33B -:1005600011882846A047002002F09CFDFEE702F01B -:1005700021FD00DFFEE700002DE9F04102F09CFFC5 -:10058000074602F0E7FF054600283ED12B4B9F426D -:100590003BD001339F423BD0294B27F0FF029A42C8 -:1005A0003AD1F8B200F052FAA84642F2107400F0C4 -:1005B00057FC08B10024A04600F04EFA064678B376 -:1005C00084BB464635B11F4B9F4203D0002402F046 -:1005D000B9FF2646002002F079FF1B4B9B6813F001 -:1005E000400322D00EB100F031F800F097FC00F08B -:1005F00077FE00F067FF0546CCB100F063FF401BBB -:10060000A04214D900F022F8F3E7A8460024CEE770 -:1006100004464FF00108CAE780464FF47A74C6E7F3 -:100620000446CFE74FF47A74CCE71C46DDE700F0D0 -:1006300025FD012002F03CFDDEE700BF010007B010 -:10064000000008B0263A09B0000C014038B51D4A38 -:100650001D4B1968013134D004339342F9D11B4C3E -:10066000194DD4F80424AA422BD3194B9B6803F1EB -:10067000006303F5C8439A4223D202F037FF02F029 -:1006800049FF002000F046FE0220124B187000F0D7 -:100690007DFE114BDA690022DA61D96999699A61A4 -:1006A0009B6972B64FF0E023C3F8085DD4F80034BC -:1006B000D4F80424202181F311889D4683F308880F -:1006C000104738BD2064000800640008006000087E -:1006D00000110020281100200010024049F269009A -:1006E000084A136899B21B0C00FB013344F25061B5 -:1006F0001360054B186882B2000C01FB0200186001 -:1007000080B27047201100201C11002010B5044653 -:100710000021102200F056FE034B03CB20606160E5 -:100720001868A06010BD00BFE8F7FF1F2DE9F04377 -:10073000BBB000F0C7FE40F2ED22204DAB68C31AFB -:10074000934232D906AF2B4628220021A8603846B2 -:1007500001F0C2FB05F10E0000F02CFE002604465D -:100760005FFA80F905F10E08F3B2F100994501F145 -:10077000280107D908EB06030822384601F0ACFB34 -:100780000136F1E708230122CDE902320C4B053492 -:1007900001933023A4B20093CDE9047405A3D3E9F7 -:1007A0000023297B074801F0ADF93BB0BDE8F08399 -:1007B000AFF3008078F6339F93CACD8D702100206F -:1007C0007D2100204421002070B50D4614461E46B0 -:1007D00001F02EF950B9022E10D1012C0ED112A326 -:1007E000D3E900230120C5E9002307E0282C10D01D -:1007F00005D8012C09D0052C0FD0002070BD302C5D -:10080000FBD10BA3D3E90023ECE70BA3D3E900232F -:10081000E8E70BA3D3E90023E4E70BA3D3E9002324 -:10082000E0E700BFAFF30080401DA12026812A0B26 -:1008300078F6339F93CACD8D9E6AC421818A46EE95 -:1008400026417272DF25D7B7F017304A39059E5618 -:1008500038B50D460446034620222846002101F003 -:100860003BFB22792346032A28BF0322284603F8AC -:10087000042F2021022201F02FFB62792346072A50 -:1008800028BF0722284603F8052F2221032201F062 -:1008900023FBA2792346072A28BF0722284603F80C -:1008A000062F2521032201F017FB284610222821BC -:1008B00004F1080301F010FB382038BD2DE9F04F9A -:1008C0000024ADF5017D0EAE40F2751280460F4654 -:1008D00022A82146219400F075FD21464822304689 -:1008E00000F070FD00F0EEFD4FF47A72B0FBF2F014 -:1008F000544B21AD186093E80700012386E80700F8 -:100900000DF15A003382FFF701FF4EF603033384E3 -:1009100006AB18464C4903F0B3F81F222946306451 -:10092000304686F83C20FFF793FF08220446014634 -:1009300012AB284601F0D0FA08222846A1180DF182 -:10094000490301F0C9FA082228460DF14A0304F1CF -:10095000100101F0C1FA2022284613AB04F118015E -:1009600001F0BAFA4022284614AB04F1380101F034 -:10097000B3FA0822284616AB04F1780101F0ACFA6C -:10098000082228460DF1590304F1800101F0A4FA70 -:1009900004F1880A0DF15A0904F5847B4B4651464F -:1009A000082228460AF1080A01F096FAD34509F10F -:1009B0000109F3D10822594628461BAB01F08CFAF5 -:1009C0004FF0000904F5887496F834304B450AD985 -:1009D000B36B21464B440822284601F07DFA0834C7 -:1009E00009F10109F0E74FF0000996F83C3004EBFB -:1009F000C9014B4508D9336C08224B44284601F005 -:100A00006BFA09F10109F0E700230393BB7E07317C -:100A1000029307F1190301930123C1F3CF01CDE93B -:100A200004510093404605A3D3E90023F97E01F069 -:100A300069F80DF5017DBDE8F08F00BF9E6AC42105 -:100A4000818A46EE2C110020903A0008014B187064 -:100A5000704700BF38110020F0B5334B85B01C7BC8 -:100A600034B10E22314B1A810024204605B0F0BD6E -:100A70002F4A02AB1068516803C308232D492E4842 -:100A80000DEB030202F0DCFF054630B90A22274BCA -:100A90002A481A8100F0E2FCE6E70169B1F5CE3F91 -:100AA00006D90B22214B26481A8100F0D7FCDCE73F -:100AB000438BB3F57A7F09D00C211C4A2148118160 -:100AC0004FF47A72194600F0C9FCCEE71E4A024480 -:100AD00002F11003994204D21022144B1B481A81D0 -:100AE000E3E710398E1A2046134900F0EFFC074661 -:100AF0003246204605F1180100F0E8FCAB689F4241 -:100B000002D1EB6898420AD00D22084B1A8100905E -:100B10003B46D5E902120E4800F0A0FCA4E70D48C0 -:100B200000F09CFC0124A0E7702100202C11002083 -:100B3000413B0008DC9B010000640008B03A00085B -:100B4000BC3A0008CE3A0008089CFFF7EC3A0008CF -:100B5000093B0008323B00082DE9F04FADB006AF6D -:100B600080460C4600F064FF0546002859D1237EDC -:100B7000022B1AD1E38A012B17D100F0A3FC064601 -:100B8000FFF7ACFD4FF4C873B0FBF3F202FB1300A8 -:100B9000DFF8B49206F5167680B2E37E0644C9F813 -:100BA000006033B90022A94B1A709C37BD46BDE8DE -:100BB000F08FA38AEEB2013BB34205F101050BD9D8 -:100BC0003B1D1E44E900002308222046009601F048 -:100BD000F80101F043F8ECE707F11400FFF796FD88 -:100BE000324607F11401381D02F01AFF03460028AF -:100BF000D8D10F2E08D8954B1E70D9F80030A3F528 -:100C00001673C9F80030D0E7FA1CF870014600925C -:100C10002046072201F022F84046F97800F000FF54 -:100C2000C3E7E38A282B26D010D8012B1ED0052B32 -:100C3000BBD1BFF34F8F8649864BCA6802F4E0628E -:100C40001343CB60BFF34F8F00BFFDE7302BACD118 -:100C5000637E814D01336A7BDBB29342E94603D167 -:100C6000E27E2B7B9A4265D0CD469EE721464046E8 -:100C7000FFF724FE99E7A38A013B9BB2C92B94D8C6 -:100C8000754D2E7B26BB05F10C03009308223346DD -:100C90003146204600F0E2FF731CF2B2D9001E4636 -:100CA000A38A013B9A4205DA0E322A4400920023BD -:100CB0000822EEE700230022C5E900230023AB60F1 -:100CC00085F8D730C5F8D8302B7B0BB9E37E2B7372 -:100CD000002507F114060822294630463B1DC7E9C6 -:100CE0000155FD6001F0F8F83B7A05F10109AB42CE -:100CF0004FEAC90107D9FB6808222B44304601F0AE -:100D0000EBF84D46F0E70023C1F3CF01E07ECDE9DB -:100D100004610393A37E19340293282301460093B0 -:100D2000404647A3D3E90023019400F0EBFEFFF710 -:100D3000FDFC3AE74FF0000807F11403A7F8148010 -:100D40001022009341460123204600F087FFA68A27 -:100D5000023EB6B2F31C9B109B000733DB08A9EBE5 -:100D6000C3039D460DF1180A1FFA88F34FEAC80124 -:100D7000B34201F110010AD20AEB080300930822E2 -:100D80000023204600F06AFF08F10108ECE795F81F -:100D9000D70000F0C9FAD5F8D83004461BB995F849 -:100DA000D70000F0D1FAD5F8D83033449C4204D2B1 -:100DB00095F8D700013000F0C7FA4FF000084FEA6D -:100DC000960B1FFA88F18B45D5E9003209D90AEB59 -:100DD000880103EB8800012200F0FCFA08F1010809 -:100DE000EFE7F31842F10002C5E90032D5F8D83038 -:100DF00095F8D70006EB0308C5F8D88000F094FA00 -:100E0000804509D395F8D730D5F8D8000133001BB9 -:100E100085F8D730C5F8D800FF2E08D800232B73EB -:100E200000F0A4FAFFF718FE08B1FFF70FFC2B68DB -:100E30000A4A9B0A013313810023AB6014E700BF09 -:100E400026417272DF25D7B7402100203D210020C6 -:100E500000ED00E00400FA05702100202C110020B4 -:100E600030B54FF00054244B226885B09A4207D029 -:100E700002F07AFB0446A8B90024204605B030BD34 -:100E8000627D1E4B1E481A70237DC92203731D49C3 -:100E90000E3000F085FA2046E022002100F092FAA0 -:100EA0000124EAE7184A194DD36943F00073D3616E -:100EB000AA6D174B9A42DFD12B6E013B7E2BDBD8FC -:100EC000144A01AB07CA83E807001846032100F063 -:100ED00013FB6B6D83424FF00003CDD12A6D8A4224 -:100EE00003BFAB652A6E054B1C4601BF1A70EA6D45 -:100EF000094B1A60C1E700BF9AAD44C53811002004 -:100F00007021002016000020001002400066004002 -:100F10005041A0B0586600401811002002232DE96E -:100F2000F0434A4C85B0637100230293484BD3F8D9 -:100F300000C0BCF57A7F12D3464F474BB7FBFCF598 -:100F40009C458CBF0A231123B5FBF3F603FB165215 -:100F5000591EC8B2002A3ED002290B46F4D89DF88B -:100F60000B303E495A1E9DF80A303D48013B1B0498 -:100F700043EA0253BDF80820013A13434B6001F0E5 -:100F800037FD00230193374B374900934FF48052CC -:100F9000364B374800F01CFD364B197811B13448F8 -:100FA00000F03EFD00F08EFA0546FFF797FB4FF488 -:100FB000C873B0FBF3F202FB130305F516709BB286 -:100FC00018442D4B186002F0C5FA08B10F23238195 -:100FD00005B0BDE8F083731EB3F5806FBFD24FF448 -:100FE0007A75C0EBC00E0EF103034FEAE30909FB6B -:100FF0000555C3F3C703C11AC9B209F101088844F2 -:10100000B5FBF8F5B5F5617F08D90EF1FF33C3F3F1 -:10101000C703C11A581E0F28C9B214D84A1E072A7E -:101020008CBF00220122581800FB0660B7FBF0F7C6 -:10103000BC4594D1002A92D0ADF808608DF80A30F2 -:101040008DF80B108BE71346EDE700BF2C11002045 -:1010500018110020005125023F420F0010110020FE -:1010600088220020C90700083C110020590B000805 -:101070004421002038110020402100202DE9F04FAC -:1010800093A7D7E900670FF25029D9E90089854D68 -:1010900093B0DFF814B2854C284600F097FD0DF1AF -:1010A000300A079070B310220021504600F08AF9F0 -:1010B0004FF00002079B197B61F303028DF830208B -:1010C000586899680EAA03C21B680D9A584663F3C4 -:1010D0001C029DF830300D9243F020038DF8303023 -:1010E00000235246194601F093FC079028B9284680 -:1010F00000F070FD079B2370CEE72378072B3CD8C8 -:101100000133237018220021504600F05BF9DFF80C -:1011100098B1674C002352461946584601F0A0FC8E -:10112000014670BB102208A800F04CF9E36883F078 -:101130001003E36000F0C8F90DF1240C0B4612A96E -:10114000024611E903008CE803009DF83410C1F356 -:101150000300890649BF0E99BDF83810C1F31C0180 -:1011600041F0004158BFC1F30A018DF82C000891ED -:10117000284608A900F0F8FECCE7284600F02AFD32 -:10118000C0E7284600F054FC8346002844D100F014 -:1011900099F9484B1A6890423ED300F093F90446FF -:1011A000FFF79CFA4FF4C872B0FBF2F101FB12009A -:1011B0008DF820B0DFF800B13E4B04F5167480B214 -:1011C0009BF8001004441C6011B901238DF82030F5 -:1011D00050460791FFF79AFA07990DF12100C1F1E6 -:1011E0001004E4B2062C28BF06245144224600F025 -:1011F000D7F808AB039318230293304B01340193C3 -:101200000123E4B2009332463B462846049400F0A2 -:1012100011FC00238BF8003000F054F9284A294CC7 -:101220001368C31AB3F57A7F31D3106000F04CF91C -:1012300002460B46284600F0D7FC284600F0F8FB93 -:1012400028B3237BDFF880B0002B14BF03230223D5 -:101250008BF8053000F036F94FF47A73B0FBF3F0F9 -:101260005146CBF800005846FFF7F2FA18230293D4 -:10127000164B0730019340F25513C0F3CF00CDE970 -:1012800003A0009342464B46284600F0D3FB237B45 -:101290002BB1FFF74BFA237B002B7FF4FAAE13B090 -:1012A000BDE8F08F44210020882200205522002034 -:1012B00000080140402100203D2100203C21002069 -:1012C00050220020702100202C11002054220020E8 -:1012D000401DA12026812A0BF1C6A7C1D068080FA6 -:1012E00070B501F0BFFF0024084E094D308028681A -:1012F0003388834208D901F0B1FF2B6804440133DD -:10130000B4F5C84F2B60F2D370BD00BF842200201B -:101310005822002002F044B800F10060920000F56D -:10132000C84001F0DFBF0000054B1A68054B1B8861 -:101330009B1A834202D9104401F090BF00207047ED -:10134000582200208422002038B50446064D286823 -:10135000204401F089FF28B928682044BDE83840BE -:1013600001F094BF38BD00BF58220020064991F813 -:10137000243033B100230822086A81F82430FFF7B3 -:10138000CBBF0120704700BF5C220020022802BFB3 -:101390004FF48012014B1A61704700BF00080140F2 -:1013A000002310B5934203D0CC5CC4540133F9E759 -:1013B00010BD000003460246D01A12F9011B002995 -:1013C000FAD1704703460244934202D003F8011B4E -:1013D000FAE770472DE9F8431F4D144695F824208D -:1013E0000746884652BBDFF870909CB395F82430CE -:1013F0002BB92022FF2148462F62FFF7E3FF95F823 -:1014000024004146C0F10802A24228BF224605EB53 -:101410008000D6B29200FFF7C3FF95F82430A41BDA -:101420001E44F6B2082E17449044E4B285F82460B6 -:10143000DBD1FFF79BFF0028D7D108E02B6A03EB35 -:1014400082038342CFD0FFF791FF0028CBD1002049 -:10145000BDE8F8830120FBE75C2200200FB40020E8 -:1014600004B07047EFF30983EFF30583044B9A6BE5 -:10147000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE72A -:1014800000ED00E0EFF30983EFF30583044B9A6B63 -:101490009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF8F -:1014A00000ED00E0EFF30983EFF30583034B5A6B84 -:1014B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E065 -:1014C000FEE7000001F0A6BF01F07EBF30B5094D78 -:1014D0000A4491420DD011F8013B5840082340F3D3 -:1014E0000004013B2C4013F0FF0384EA5000F6D1C6 -:1014F000EFE730BD2083B8ED4FF0FF33F7B500EBD9 -:1015000081061946DFF848C0DFF848E0B0421BD03A -:1015100050F8042B01AF0192042217F8014B81EA25 -:10152000046108240D46DB184941013C002DBCBF75 -:1015300083EA0C0381EA0E0114F0FF04F2D1013AB0 -:1015400012F0FF02E9D1E1E7D843C94303B0F0BD8F -:101550009336EAA9EBE1F0422DE9F041C56915B9EE -:10156000C161BDE8F0814B68AC4623F06047C3F32E -:101570008A4616EA230638BF3E464FEAD37EC3F3B7 -:1015800080782B465A68BEEBD27F22F060440AD0A6 -:10159000002A18DAA40CB44217D19D420FD10D6075 -:1015A000DEE71346EEE7A74207D102F08044C2F31C -:1015B000807242450BD054B1EFE708D2EDE7CCF88A -:1015C00000100B60CDE7B44201D0B442E5D81A68F0 -:1015D0009C46002AE5D11960C3E700002DE9F047D9 -:1015E0004FF47F49089D01F007044FEAD5082244D3 -:1015F00005F0070500EBD100944201D1BDE8F0876A -:1016000004F0070705F0070A57453E4638BF56461F -:10161000111BC6F108068E4228BF0E46E108415C48 -:1016200008EBD50E13F80EC0B94029FA06F721FAD7 -:101630000AF1FFB28CEA010147FA0AF739408CEA55 -:10164000010C03F80EC034443544D5E7082341F2B9 -:10165000210280EA012001B24000002980B203F19A -:10166000FF33B8BF504013F0FF03F4D170470000C0 -:1016700038B50C468D18A54200D138BD14F8011BB1 -:10168000FFF7E4FFF7E700000346006848B102688F -:1016900019891A60DA88013292B29142DA8038BF31 -:1016A0001A81704770B504460D4688B0202200218B -:1016B0006846FFF787FE20460495FFF7E5FF0246E0 -:1016C00058B16B46054608AE1C4603CCB4422860B0 -:1016D0006960234605F10805F6D1104608B070BDD3 -:1016E000082817D909280CD00A280CD00B280CD0B0 -:1016F0000C280CD00D280CD00E2814BF4020302010 -:1017000070470C2070471020704714207047182035 -:101710007047202070470000082817D90C280CD9E2 -:1017200010280CD914280CD918280CD920280CD929 -:1017300030288CBF0F200E207047092070470A20E8 -:1017400070470B2070470C2070470D207047000039 -:1017500010B54B6823B9CA8A63F30902CA8210BD67 -:10176000C4681A681C60C360438A013B43824A60B4 -:10177000EFE700002DE9F84F1D46CB8A0F46C3F373 -:1017800009010629814692460B4630D00020AAB2B4 -:1017900007F119049EB2052E1FFA80F80FD8904564 -:1017A00003F1010306D3FB8A0A4462F30903012013 -:1017B000FB821AE01AF800600130E654EAE790452F -:1017C000F1D21C23A1F1060BBBFBF3F203FB12BB0E -:1017D0007C681FFA8BF6002C45D14846FFF754FF72 -:1017E000044638B978606FF00200BDE8F88F4FF01A -:1017F0000008E6E70026066078604FF0000BADB207 -:10180000454510D90AEB0803221D13F8011B08F106 -:1018100001089155B1B21B291FFA88F82BD0454514 -:1018200006F10106F1D8FB8AC3F30902154465F3FA -:101830000903BCE71C46013292B22368002BF9D1A0 -:10184000AB1F0B441C21B3FBF1F301339BB29A4253 -:10185000D3D2BBF1000FD0D14846FFF715FF20B916 -:10186000C4F800B0BFE70122E7E7C0F800B05E4669 -:1018700020600446C1E74545D5D94846FFF704FF37 -:1018800008B92060AFE7C0F800B000262060044629 -:10189000B6E700002DE9F04F85B007469146CDE947 -:1018A0000113BDF83C50002A00F08F802DB10E9B33 -:1018B000002B00F08A80072D30D807F10C00FFF7CD -:1018C000E3FE044628B96FF00204204605B0BDE8E7 -:1018D000F08F14220021FFF775FD2A460E9904F1BE -:1018E0000800FFF75DFD681CC0B2FFF715FFFFF7AA -:1018F000F7FE207499F80020431E9BB202F01F02ED -:10190000234462F03F021A72019B384643F00041C3 -:1019100061602146FFF720FE0124D6E74FF0000862 -:101920004FF0800A4646444600F10C0303930398A7 -:10193000FFF7AAFE83460028C5D014220021FFF736 -:1019400041FD002E38D10220029BABF808300E9BDF -:1019500000F10802D2B299195A440130C0B20828E5 -:1019600001D0AE422AD3FFF7D7FEFFF7B9FEAE4251 -:1019700008BF4FF0400A99F80020019B411E02F079 -:101980001F0242EA4812C9B24AEA020A594443F025 -:10199000004281F808A08BF8100059463846CBF871 -:1019A0000420FFF7D9FD0134AE424FF0000A24B203 -:1019B00088F00108BBD188E70020C8E711F801CB07 -:1019C000013602F801CBB6B2C7E76FF001047CE73D -:1019D000F8B5044615460E46282200211F46FFF79B -:1019E000F1FC069BB5F5001F6360079B28BF4FF60F -:1019F000FF7223624FF0000338BF6A09A76004F149 -:101A00000C0097B29A4205D80023036027826382B4 -:101A1000A382F8BD0660013330462036F2E70000AD -:101A200003781BB94BB2002BC8BF01707047000090 -:101A3000007870472DE9F74FDDF83C9080469246DC -:101A40009B46BDF830500D9E9DF83840BDF8407063 -:101A5000B9F1000F01D1002F51D11F2C4FD898F8A8 -:101A60000000B0B9072F47D835F0030347D13A46F5 -:101A700049464FF6FF70FFF7FBFD20F001002D02F5 -:101A8000400445EA0464400C44EA40244FF6FF73E6 -:101A900021E040EA0520072F40EA0464F6D900253A -:101AA0004FF6FF73C5F12000A5F120022AFA05F1D7 -:101AB0000BFA00F001432BFA02F211431846C9B2A7 -:101AC000FFF7C4FD0835402D0346EBD13A464946A1 -:101AD000FFF7CEFD0346324621464046CDE900974A -:101AE000FFF7D8FE33780133DBB21F2B88BF00230A -:101AF000337003B0BDE8F08F6FF00300F9E76FF0CB -:101B00000100F6E72DE9F04F85B0DDF848809246F8 -:101B100006469B460F9D9DF840209DF84490BDF8D9 -:101B20004C70B8F1000F01D1002F48D11F2A46D8C0 -:101B30003378002B46D00C0244EA02649DF838103A -:101B400044EAC93444EA01441C43072F44F08004AA -:101B500032D900234FF6FF72C3F1200CA3F120000D -:101B60002AFA03F10BFA0CFC41EA0C012BFA00F003 -:101B70000143C9B210460393FFF768FD039B024679 -:101B80000833402BE8D13A464146FFF771FD034642 -:101B90002A4621463046CDE90087FFF77BFEB9F1A2 -:101BA000010F06D12B780133DBB21F2B88BF002336 -:101BB0002B7005B0BDE8F08F4FF6FF73E8E76FF0CC -:101BC0000100F6E76FF00300F3E70000C06900B121 -:101BD00004307047C3691A68C261C2681A60C36082 -:101BE000438A013B438270472DE9F041D0F81880C9 -:101BF00014461D4641460027174E09B9BDE8F0813D -:101C0000D1E90223A21A65EB0303964277EB0303A3 -:101C10001ED283698B420DD1FFF79AFD83691B6841 -:101C20008361C3680B60438AC1608169013B884658 -:101C30004382E2E7FFF78CFD0B68C8F80030C36809 -:101C40000B60438AC160013B4382D8F80010D4E79F -:101C500088460968D1E700BF80841E002DE9F04F57 -:101C60008BB00D4614469B468046DDF85090002808 -:101C700000F01A81B9F1000F00F01681531E3F2BBE -:101C800000F21281012A03D1BBF1000F40F00C8158 -:101C90000023CDE90833B8F81430B5EBC30F4FEA91 -:101CA000C30703D300200BB0BDE8F08F2B199F4270 -:101CB000D8F80C3036BF7F1B2746FFB21BB9D8F8C7 -:101CC0001030002B7BD02F2D4ED8C5F13006B742F7 -:101CD0004FF0000334BF3E46F6B200932946324629 -:101CE000D8F8080008ABFFF779FCA7EB060A3544E3 -:101CF0005FFA8AFA3021B8F8143003F10053063B3A -:101D0000DB000493D8F80C300393039B13B1BAF1B2 -:101D1000000F2CD1D8F8100040B1BAF1000F05D057 -:101D20005246009608AB691AFFF758FC38B2002FEC -:101D3000B8D066070AD00AAB03EBD40111F8083C0F -:101D4000624202F00702134101F8083C082C3DD919 -:101D5000102C40F2B680202C40F2B880BBF1000F6E -:101D600000F09D80082335E0BA460026C2E7049BB8 -:101D7000E02B28BFE02306930B44AB42059315D913 -:101D80005A1B924538BF5246039828BFD2B20096DC -:101D9000691A08AB04300792FFF720FC079A164433 -:101DA000AAEB020A1544F6B25FFA8AFA049B069A75 -:101DB00005999B1A0493039B1B680393A5E7009363 -:101DC0003A462946D8F8080008ABADE7BBF1000F4A -:101DD00013D00123B4EBC30F6CD0082C12D89DF89C -:101DE0002030621E23FA02F2D50706D54FF0FF32EB -:101DF00002FA04F423438DF820309DF8203089F84E -:101E0000003050E7102C12D8BDF82030621E23FAA3 -:101E100002F2D10706D54FF0FF3202FA04F4234351 -:101E2000ADF82030BDF82030A9F800303BE7202C79 -:101E30000FD80899631E21FA03F3DA0705D54FF08E -:101E4000FF3202FA04F40C430894089BC9F80030EE -:101E500029E7402C2BD0DDE90865611EC4F1210281 -:101E6000A4F1210326FA01F105FA02F225FA03F39F -:101E700011431943CB0712D50122A4F12003C4F169 -:101E8000200102FA03F322FA01F1A240524243EA8E -:101E9000010363EB430332432B43CDE90823DDE920 -:101EA0000823C9E90023FEE66FF00100FBE66FF0AE -:101EB0000800F8E6082CA0D9102CB3D9202CEED8B5 -:101EC000C3E7BBF1000FADD0022383E7BBF1000FE6 -:101ED000BBD004237EE70000012A30B5144638BF8A -:101EE00001220025402A28BF402285B0012CCDE9DF -:101EF000025517D81B788DF8083053070AD004AB69 -:101F000003EBD20515F8083C544204F00704A34043 -:101F100005F8083C0346009102A80021FFF75EFB8C -:101F200005B030BD082CE5D9102C03D81B88ADF8BE -:101F30000830E2E7202C02D81B680293DDE7D3E9E2 -:101F40000045CDE90245D8E710B5CB681BB98B60D9 -:101F50000B618B8210BDC4681A681C60C360438A21 -:101F6000013B4382CA60F0E72DE9F04FD1F80080D1 -:101F700093B018F0800FCDE90323C8F3C01207BF58 -:101F80004FF0020B1646C8F3C03BC8F30626B8F163 -:101F9000000F04460D4680F2D48118F0C04305932B -:101FA00040F0CF810B7B002B00F0CB81BBF1020F07 -:101FB00003D00178B14240F0C78108F07F0107915A -:101FC0007AB3C8F3074A2B4493F80390760646EA9F -:101FD0000B4608F07F0246EA82465FEAD91346EADA -:101FE0000A06069300F0918000220023CDE90A231F -:101FF00008F07F03009352465B46204667680AA9B3 -:10200000B84700287ED0A7699FB9314604F10C007B -:10201000FFF748FB0746E0B96FF0020013B0BDE8D8 -:10202000F08FC8F30F2A18F07F0F08BF0AF0030AD9 -:10203000C9E73B699E420DD03F68002FF9D1314678 -:1020400004F10C00FFF72EFB07460028E4D0A3693B -:102050003B60A7610026DDE90A234FF6FF70C6F159 -:10206000200E22FA06F103FA0EFEA6F1200C23FA46 -:102070000CFC41EA0E0141EA0C01C9B20836099292 -:102080000893FFF7E3FADDE90832402EE7D1B88282 -:10209000FB7D09F01F06C3F384039B1B98B2002B42 -:1020A000BCBF00F120031BB2D7E9022152EA0100B4 -:1020B000C8F304680FD00398821A049860EB0101FA -:1020C000A74890424FF000028A4104D3069A002AA2 -:1020D0005BD0012B23DDFA7D4FEA890302F0030276 -:1020E00003F07C031343FB7539462046FFF730FBB2 -:1020F000069BA3B9FB7DC3F38402013262F386031E -:10210000FB7504E06FF00B0088E7A76917B96FF063 -:102110000C0083E73B699E42BAD03F68F6E719F0AE -:10212000400F32D0039B1422BB60049B0021FB6054 -:102130000DA8FFF747F9039B20460A93049BADF8CF -:102140003EA00B932B1D0C932B7B8DF840B0013BD5 -:10215000DBB2ADF83C30079B8DF841608DF8433021 -:1021600094F824308DF8428083F001038DF84430D8 -:102170000AA9A3689847FB7DC3F38403013303F0E6 -:102180001F039B02FB82002048E7FB7DC9F340123E -:10219000B2EBD31F40F0DB80C3F38403B34240F0C3 -:1021A000D98006992B7B4FEA9912002934D0D207A7 -:1021B00041D4032B40F2D180039BAE1DBB60049B36 -:1021C0003246FB602B7B3946033BDBB204F10C004B -:1021D000FFF7D0FA00280DDA20463946FFF7B8FAA3 -:1021E000FB7D0320C3F38403013303F01F039B0231 -:1021F000FB8213E7AB883B832A7B033AB88AD2B2CF -:102200003146FFF735FAFB7DB882DA43C2F3C012DC -:1022100062F3C713FB75B6E76AB92E1D013B324660 -:102220003946DBB204F10C00FFF7A4FA0028D3DB37 -:102230002A7B013AE2E7F98A013BC1F3090105294A -:10224000DAB25BD80023281D07F11A0C9A4208D98C -:1022500010F801EB01330CF801E001310629DBB283 -:10226000F4D1934228BF0023039938BF04330A9165 -:10227000049938BFDBB20B9107F11A010C91796810 -:1022800038BF5B190D910E93FB8AADF83EA0C3F3E6 -:1022900009031A44079BADF83C208DF8433094F8AD -:1022A00024308DF840B083F001038DF844300023D2 -:1022B0008DF841608DF842807B602A7BB88A013AB4 -:1022C000291DFFF7D5F93B8BB882834203D1204605 -:1022D000A3680AA9984720460AA9FFF735FEFB7DA7 -:1022E000B88AC3F38403013303F01F039B02FB820C -:1022F0003B8B984214BF112000208FE67B68002B97 -:10230000AFD0062001E063461C30D3F800C0BCF11A -:10231000000FF8D1091A081D05F1040C1844DDF866 -:1023200014E09DF814308E44BEF11B0F99D89A42E8 -:1023300097D91CF8013B00F8013B059B013305933D -:10234000EDE76FF0090069E66FF00A0066E66FF0EE -:102350000D0063E66FF00E0060E66FF00F005DE6C3 -:1023600080841E00F0B53F4D3F4FEB6943F0007392 -:10237000EB61EB693D4B9B6AD3F800623E4046F04F -:102380000106C3F80062D3F800423C4044EA00244E -:1023900044F00104C3F80042002955D0002006464D -:1023A000C3F81C02C3F80402C3F80C02C3F81402F9 -:1023B00003EBC00401300E28C4F84062C4F8446244 -:1023C000F6D100274FF0010C9678148816F0010F13 -:1023D00018BFD3F804E20CFA04F01CBF40EA0E0E5A -:1023E000C3F804E216F0020F18BFD3F80CE203EBB7 -:1023F000C4041CBF40EA0E0EC3F80CE2760748BFC7 -:10240000D3F8146207F1010744BF0643C3F814620E -:102410005668B942C4F84062966802F10C02C4F8EA -:102420004462D3F81C4240EA0400C3F81C02CBD13A -:10243000D3F8002222F00102C3F80022EB6923F056 -:102440000073EB61EB69F0BD0122C3F84012C3F8E1 -:102450004412C3F80412C3F81412C3F80C22C3F8D0 -:102460001C22E5E7001002400000FFFF8822002048 -:10247000184A08B5916A8B688B6013F0010104D08B -:1024800013F00C0F18BF4FF48031D80506D513F4A4 -:10249000406F14BF41F4003141F00201D80306D56A -:1024A00013F4402F14BF41F4802141F00401D3699B -:1024B0000BB108489847202383F311880021064870 -:1024C00000F01EFE002383F31188BDE8084001F0F0 -:1024D00083B800BF882200209022002038B5124C1B -:1024E000A36ADD68AA0712D05A6922F002025A6173 -:1024F000A36913B1012120469847202383F3118853 -:1025000000210A4800F0FCFD002383F31188EB064C -:1025100006D51021A36AD960236A0BB102489847F7 -:10252000BDE8384001F058B88822002098220020E9 -:1025300038B5124CA36A1D69AA0712D05A6922F055 -:1025400010025A61A36913B1022120469847202343 -:1025500083F3118800210A4800F0D2FD002383F3A1 -:102560001188EB0606D51021A36A1961236A0BB105 -:1025700002489847BDE8384001F02EB88822002074 -:102580009822002038B50F4CA36A5D682A075D6069 -:102590000AD5042222701A6822F002021A60636AC5 -:1025A00013B10021204698476B0706D5A36A9969A5 -:1025B000236A13B1034809049847BDE8384001F085 -:1025C0000BB800BF8822002010B50E4C204600F04A -:1025D000FDF90D4B0B211320A36200F0D7F90B215D -:1025E000142000F0D3F90B21152000F0CFF90B21B6 -:1025F000162000F0CBF9BDE8104000220E20114655 -:10260000FFF7B0BE88220020006400400F4B10B5D9 -:102610009842044605D10E4BDA6942F00072DA6145 -:10262000DB690122A36A1A60A36A5A68D20707D538 -:10263000626851681268D9611A60064A5A6110BD11 -:102640000121082000F052FCEEE700BF88220020A4 -:10265000001002405B87010003291AD8DFE801F06F -:10266000020A0F14836A9B6813F0E05F14BF012015 -:1026700000207047836A9868C0F380607047836A5F -:102680009868C0F3C0607047836A9868C0F30070B0 -:10269000704700207047000010B5032927D8DFE8F5 -:1026A00001F002272B2F836A9968C1F30161183169 -:1026B00003EB01131078840648BF5468C0F300117F -:1026C00058BF94884FEA410148BF41EAC40100F075 -:1026D0000F00586048BF41F00401906858BF41EABC -:1026E0004451D26841F001019860DA60196010BD70 -:1026F000836A03F5C073DDE7836A03F5C873D9E71E -:10270000836A03F5D073D5E701290AD002290FD0D7 -:1027100081B9836ADA68920701D1186903E0012060 -:102720007047836AD86810F0030018BF0120704713 -:10273000836AF2E70020704710B539B9836AD96817 -:1027400089071BD11B699C0704D110BD012915D035 -:102750000229FAD1816AD1F8C031D1F8C441D1F847 -:10276000C8011061D1F8CC015061202008610869CE -:10277000800717D1486940F0100012E0816AD1F853 -:10278000B031D1F8B441D1F8B8011061D1F8BC0131 -:1027900050612020C860C868800703D1486940F0B4 -:1027A00002004861C3F34000C3F38001000140EA26 -:1027B0004111107920F030000143117189064BBF9F -:1027C00091681189DB085B0D4CBF63F31C0163F357 -:1027D0000A01137948BF916064F3030313714FEA50 -:1027E00014234FEA144458BF118113705480ACE78E -:1027F000026843680A43026003B11847704700004B -:10280000024AD36843F0C003D360704700380140E8 -:10281000024AD36843F0C003D360704700440040CD -:102820002DE9F041D0F89C600446F7683368DA057A -:102830009DB20DD5202383F311884FF4007104302D -:10284000FFF7D6FF6FF480733360002383F31188A2 -:10285000202383F3118804F1040815F02F033AD1E3 -:1028600083F31188380615D5290613D5202383F361 -:10287000118804F1380000F02FFA00284DDA082101 -:10288000201DFFF7B5FF4FF67F733B40F360002339 -:1028900083F311887A0616D56B0614D5202383F3AB -:1028A0001188D4E913239A420AD1236C43B127F04B -:1028B00040073F041021201D3F0CFFF799FFF760F0 -:1028C000002383F31188D4F8A420D3683BB3BDE878 -:1028D000F041106918472B0713D015F0080F0CBFF3 -:1028E00000218021E80748BF41F02001AA0748BF26 -:1028F00041F040016B07404648BF41F48071FFF74B -:1029000077FFAD06736805D594F8A01020461940EE -:1029100000F082FA3568ADB29FE77060B7E7BDE8B6 -:10292000F081000008B50348FFF77AFFBDE80840D2 -:1029300000F052BEB422002008B50348FFF770FF34 -:10294000BDE8084000F048BE5C23002010B5094CEB -:1029500000212046084A00F03FFA084B0021C4F845 -:102960009C30074C074A204600F036FA064BC4F864 -:102970009C3010BDB422002001280008003801401E -:102980005C230020112800080044004001220901B6 -:1029900000F1604303F56143C9B283F8001300F00E -:1029A0001F039A4043099B0003F1604303F5614311 -:1029B000C3F880211A607047090100F16040C9B274 -:1029C00000F56D4001767047FFF7FEBD01230370EF -:1029D000002300F10802C0E9022200F11002C0E960 -:1029E0000422C0E90633C0E90833436070470000A1 -:1029F00010B52023044683F311880223416003703D -:102A0000FFF704FE04232370002383F3118810BD15 -:102A10002DE9F0411F4604460D461646202383F358 -:102A2000118800F108082378052B0DD0294620468F -:102A3000FFF712FE40B1204632462946FFF72CFE32 -:102A4000002080F3118808E03946404600F03CFB46 -:102A50000028E8D0002383F31188BDE8F08100004E -:102A60002DE9F0411F4604460D461646202383F308 -:102A7000118800F110082378052B0DD02946204637 -:102A8000FFF742FE40B1204632462946FFF754FE8A -:102A9000002080F3118808E03946404600F014FB1E -:102AA0000028E8D0002383F31188BDE8F0810000FE -:102AB000F8B5154682680B46AA428169066938BF97 -:102AC0008568761AB54204460BD218462A46FEF7A8 -:102AD00067FCA3692B44A361A36828465B1BA36022 -:102AE000F8BD0CD918463246FEF75AFCAF1B3A46E1 -:102AF000E1683044FEF754FCE3683B44EBE71846DA -:102B00002A46FEF74DFCE368E5E700002DE9F041B9 -:102B1000154683680446934238BF8568D0E904703F -:102B20003F1ABD420E460BD22A46FEF739FC6369B6 -:102B30002B446361A36828465B1BA360BDE8F0815A -:102B40000CD93A46A5EB0708FEF72AFC4246E06896 -:102B5000F119FEF725FCE3684344EAE72A46FEF74D -:102B60001FFCE368E5E7000010B50024C361029B89 -:102B7000C0E90511C1601144C0E900008460016131 -:102B8000036210BD08B5D0E90532934201D18268D5 -:102B900092B98268013282605A1C42611970D0E990 -:102BA00004329A4228BFC3684FF0000128BF436136 -:102BB00000F09AFA002008BD4FF0FF30FBE700005C -:102BC00070B5202304460D4683F31188A668A6B18C -:102BD000A368A269013BA360531CA3611578226915 -:102BE000934224BFE368A361E3690BB12046984791 -:102BF000002383F31188284607E02946204600F089 -:102C000063FA0028E2DA86F3118870BD2DE9F74FE8 -:102C100004460E4617469846D0F81C904FF0200AFE -:102C20008AF311884FF0000B154665B12A463146EC -:102C30002046FFF73DFF034660B94146204600F0BD -:102C400043FA0028F1D0002383F31188781B03B0E6 -:102C5000BDE8F08FB9F1000F03D001902046C847BE -:102C6000019B8BF31188ED1A1E448AF31188DCE76F -:102C7000C361009BC0E90511C1601144C0E90000B7 -:102C80008260016103627047F8B504460D4616463E -:102C9000202383F31188A768A7B1A368013BA36031 -:102CA00063695A1C62611D70D4E904329A4224BFE0 -:102CB000E3686361E3690BB120469847002080F325 -:102CC000118807E03146204600F0FEF90028E2DADC -:102CD00087F31188F8BD0000D0E905239A4210B5AA -:102CE00001D182687AB982680021013282605A1C5F -:102CF00082611C7803699A4224BFC368836100F033 -:102D0000F3F9204610BD4FF0FF30FBE72DE9F74FF8 -:102D100004460E4617469846D0F81C904FF0200AFD -:102D20008AF311884FF0000B154665B12A463146EB -:102D30002046FFF7EBFE034660B94146204600F00F -:102D4000C3F90028F1D0002383F31188781B03B066 -:102D5000BDE8F08FB9F1000F03D001902046C847BD -:102D6000019B8BF31188ED1A1E448AF31188DCE76E -:102D7000026843680A43026003B1184770470000C5 -:102D80001430FFF743BF00004FF0FF331430FFF75C -:102D90003DBF00003830FFF7B9BF00004FF0FF33F0 -:102DA0003830FFF7B3BF00001430FFF709BF000051 -:102DB0004FF0FF311430FFF703BF00003830FFF74A -:102DC00063BF00004FF0FF323830FFF75DBF0000F7 -:102DD00000207047FFF7BABD37B515460D4A0446C7 -:102DE000026000224260C0E9022201220B46027406 -:102DF00000F15C01009020221430FFF7B5FE2B4655 -:102E00002022009404F17C0104F13800FFF730FF28 -:102E100003B030BD4C3B000838B5C36904460D46CD -:102E20001BB904210844FFF7A3FF294604F114004D -:102E3000FFF7A8FE002806DA201D4FF48061BDE8E8 -:102E40003840FFF795BF38BD0022024BC3E900337D -:102E50009A60704704240020002382680374054BA5 -:102E60001B6899689142FBD25A6803604260106007 -:102E7000586070470424002008B5202383F311888C -:102E8000037C032B05D0042B0DD02BB983F31188C1 -:102E900008BD002243691A604FF0FF334361FFF71A -:102EA000DBFF0023F2E7D0E9003213605A60F3E75A -:102EB000002382680374054B1B6899689142FBD814 -:102EC0005A68036042601060586070470424002014 -:102ED000054B196908741868026853601A60186114 -:102EE00001230374FDF732BB0424002030B54B1CD2 -:102EF00004460B4D87B010D02B690A4A01A800F098 -:102F00001BF92046FFF7E4FF049B13B101A800F072 -:102F10002FF92B69586907B030BDFFF7D9FFF8E7E3 -:102F200004240020792E000838B50C4D41612B692E -:102F300081689A680446914203D8BDE83840FFF79B -:102F40008BBF1846FFF7B4FF01232C6101462374A1 -:102F50002046BDE83840FDF7F9BA00BF0424002040 -:102F6000044B1A681B6990689B68984294BF0020C4 -:102F7000012070470424002010B5084C2368206904 -:102F80001A6854602260012223611A74FFF790FFCF -:102F900001462069BDE81040FDF7D8BA042400209E -:102FA00008B5FFF7DDFF18B1BDE80840FFF7E4BF43 -:102FB00008BD0000FFF7E0BFFEE7000010B50C4CB5 -:102FC000FFF742FF00F0AAF880220A49204600F0ED -:102FD00031F8012344F8180C037400F0D9FA0023E7 -:102FE00083F3118862B6BDE81040034800F042B890 -:102FF0002C240020743B0008843B000800F0CAB871 -:10300000EFF3118020B9EFF30583202282F31188BA -:103010007047000010B530B9EFF30584C4F308041D -:1030200014B180F3118810BDFFF7BAFF84F3118843 -:10303000F9E7000082600222028270478368A3F1F0 -:103040003C0243F80C2C026943F83C2C426943F8DB -:10305000382C074A43F81C2CC268A3F1180043F827 -:10306000102C022203F8082C002203F8072C7047CA -:103070005D05000810B5202383F31188FFF7DEFFFC -:1030800000210446FFF750FF002383F311882046F8 -:1030900010BD0000024B1B6958610F20FFF718BFDD -:1030A00004240020202383F31188FFF7F3BF0000DE -:1030B00008B50146202383F311880820FFF716FF87 -:1030C000002383F3118808BD49B1064B42681B6990 -:1030D00018605A60136043600420FFF707BF4FF089 -:1030E000FF3070470424002003460068834205D067 -:1030F00002681A6053604161FFF7AEBE704700007E -:1031000038B504460D462068844200D138BD0368B6 -:1031100023605C604561FFF79FFEF4E7054B03F118 -:103120001402C3E905224FF0FF32DA6100221A626D -:10313000704700BF0424002010B5C0E903230B4AE8 -:10314000136A53699C68A1420CD85C688160036073 -:103150004460206058609868411A99604FF0FF33CE -:10316000D36110BD1B68091BECE700BF04240020DD -:10317000036881689A680A449A60426813605A60DA -:1031800000234FF0FF32C360014BDA61704700BF8C -:103190000424002038B50F4C2246236A01332362F1 -:1031A00052F8143F934206D020259A68013A9A605B -:1031B00063699A6802B138BDD3E9001001604860C4 -:1031C000D968DA6082F311881869884785F3118815 -:1031D000EEE700BF0424002000207047FEE7000057 -:1031E000704700004FF0FF3070470000BFF34F8F73 -:1031F000024AD368DB07FCD4704700BF00200240BE -:1032000008B5074B1B7853B9FFF7F0FF054B1A6958 -:10321000120641BF044A5A6002F188325A6008BD62 -:1032200008250020002002402301674508B5054B12 -:103230001B7833B9FFF7DAFF034A136943F08003C1 -:10324000136108BD08250020002002407F289ABF96 -:1032500000F5003080020020704700004FF48060CD -:1032600070470000802070477F2808B50BD8FFF713 -:10327000EDFF00F580630268013204D1043083421F -:10328000F9D1012008BD0020FCE700007F2838B5F7 -:10329000044623D8FFF7B4FEFFF7A8FFFFF7B0FFFF -:1032A000F3220F4B0546DA60022220461A61FFF72F -:1032B000CDFF58611A694FF4806142F040021A61F3 -:1032C000FFF794FF00F010F92846FFF7AFFFFFF774 -:1032D000A1FE2046BDE83840FFF7C6BF002038BD3C -:1032E000002002402DE9F047044612F001000E468E -:1032F000154606D040F2BD22234B1A600020BDE8DF -:10330000F087224BA2189A4204D940F2C2221E4BE7 -:103310001A60F4E7FFF774FE4FF0010AFFF770FF41 -:10332000FFF764FFDFF868903146A61B012D884641 -:1033300006EB010705D8FFF779FFFFF76BFE0120C9 -:10334000DDE7B8F80030C9F810A03B800024FFF793 -:103350004DFFC9F810403B8831F8022B9BB29A42CE -:103360000FD040F2D922084B1A600A4B1F600A4B5B -:103370001D600A4BC3F80080FFF758FFFFF74AFEB5 -:10338000BCE7023DD2E700BF042500200000020890 -:1033900000200240F824002000250020FC2400200A -:1033A000084908B50B7828B11BB9FFF729FF01239D -:1033B0000B7008BD002BFCD0BDE808400870FFF77B -:1033C00035BF00BF0825002070B5FFF719FE4FF488 -:1033D0007A710D4B0D4E1B6A326801FB03F3934269 -:1033E00037BF0B4A0A495168156836BF4C1CD1E9F2 -:1033F000005454605D1944F100043360FFF70AFE85 -:103400002846214670BD00BF042400200C25002062 -:103410001025002070B5FFF7F3FD4FF47A710F4BC4 -:103420000F4E1B6A326801FB03F3934237BF0D4A0C -:103430000C49516815683ABF4C1C5460D1E90054DE -:103440005D1944F100043360FFF7E4FD4FF47A7234 -:10345000002328462146FCF783FE70BD042400208B -:103460000C2500201025002010B5094C013AD2B2DD -:10347000FF2A00D110BD500854F82030013054F814 -:1034800020009BB243EA004341F8043BEEE700BF53 -:10349000046C004010B50748013AD2B2FF2A00D1AF -:1034A00010BD0C88530840F823404C88013340F885 -:1034B0002340F1E7046C004007B50122002001A978 -:1034C000FFF7D2FF019803B05DF804FB13B5044683 -:1034D000FFF7F2FFA04205D00122002001A90194CC -:1034E000FFF7D8FF02B010BD7047000045F25552FB -:1034F000064B1A6002225A6040F6FF729A604CF640 -:10350000CC421A600122024B1A7070470030004012 -:103510001C250020034B1B781BB14AF6AA22024B44 -:103520001A6070471C25002000300040044B1A68C8 -:103530002AB902F1804202F50432526A1A607047D9 -:10354000182500204FF08072014B5A62704700BF6F -:103550000010024008B5FFF7E9FF024B1868C0F3FE -:10356000407008BD1825002008B5FFF7DFFF024BAB -:103570001868C0F3007008BD18250020EFF3098318 -:10358000203383F30988002383F3118870470000F8 -:10359000202080F3118862B60C4B0D4AD96821F4C3 -:1035A000E0610904090C0A43DA60D3F8FC200949F8 -:1035B00042F08072C3F8FC200A6842F001020A60FF -:1035C0001022DA7783F82200704700BF00ED00E098 -:1035D0000003FA05001000E0202310B583F31188E2 -:1035E0000B4B5B6813F400630FD0EFF309844FF0CB -:1035F0008073203CE36184F30988FFF7B1FC10B1CC -:10360000044BA36110BD044BFBE783F31188F9E77A -:1036100000ED00E06F05000872050008704700002B -:10362000FEE700000A4B0B480B4A90420BD30B4BB2 -:10363000C11EDA1C121A22F003028B4238BF00228C -:103640000021FDF7BFBE53F8041B40F8041BECE754 -:10365000043C0008A0250020A0250020A025002073 -:103660007047000000F030B808B500F063F9FFF7CC -:10367000A5FCBDE80840FFF759BF000070470000F7 -:103680004FF0FF310E4B1A6919611A6900221A6155 -:103690001869D868D960D968DA60DA68DA6942F0FE -:1036A0008052DA61DA69DA6942F00062DA61054A69 -:1036B000DB69136843F48073136000F01BB900BF2B -:1036C0000010024000700040194B1A6842F00102DD -:1036D0001A601A689007FCD51A6802F0F9021A609D -:1036E00000225A605A6812F00C0FFBD11A6842F49B -:1036F00080321A601A689103FCD55A6842F4E812C5 -:103700005A601A6842F080721A601A689201FCD5F9 -:103710001221084A5A60084A11605A6842F00202AF -:103720005A605A6802F00C02082AFAD1704700BFAA -:103730000010024000641D0000200240084A08B545 -:10374000516913680B4003F00103536123B1054A2B -:1037500013680BB150689847BDE80840FFF73CBFBD -:103760000004014020250020084A08B5516913686B -:103770000B4003F00203536123B1054A93680BB178 -:10378000D0689847BDE80840FFF726BF0004014015 -:1037900020250020084A08B5516913680B4003F042 -:1037A0000403536123B1054A13690BB1506998476B -:1037B000BDE80840FFF710BF0004014020250020AD -:1037C000084A08B5516913680B4003F008035361B8 -:1037D00023B1054A93690BB1D0699847BDE8084009 -:1037E000FFF7FABE0004014020250020084A08B572 -:1037F000516913680B4003F01003536123B1054A6C -:10380000136A0BB1506A9847BDE80840FFF7E4BE61 -:103810000004014020250020174B10B55A691C6890 -:10382000144004F478725A61A30604D5134A936ACB -:103830000BB1D06A9847600604D5104A136B0BB1E0 -:10384000506B9847210604D50C4A936B0BB1D06B93 -:103850009847E20504D5094A136C0BB1506C9847A0 -:10386000A30504D5054A936C0BB1D06C9847BDE80D -:103870001040FFF7B1BE00BF00040140202500202A -:103880001A4B10B55A691C68144004F47C425A6102 -:10389000620504D5164A136D0BB1506D9847230588 -:1038A00004D5134A936D0BB1D06D9847E00404D54D -:1038B0000F4A136E0BB1506E9847A10404D50C4A01 -:1038C000936E0BB1D06E9847620404D5084A136F0B -:1038D0000BB1506F9847230404D5054A936F0BB181 -:1038E000D06F9847BDE81040FFF776BE0004014056 -:1038F00020250020062108B50846FFF747F80621D5 -:103900000720FFF743F806210820FFF73FF80621BC -:103910000920FFF73BF806210A20FFF737F80621B8 -:103920001720FFF733F8BDE8084006212820FFF7ED -:103930002DB8000008B5FFF7A3FE064800F00EF80A -:10394000FFF742F8FFF746FAFFF798FEBDE8084098 -:1039500000F002B89C3B000800F042B80023194672 -:103960001C4A0133102BC2E9001102F10802F8D100 -:10397000194B9A6942F07D029A619B690268174B64 -:10398000DA6082685A6042681A60C26803F5806330 -:10399000DA6042695A6002691A608269C3F80C24CD -:1039A000026AC3F80424C269C3F80024426AC3F857 -:1039B0000C28C26AC3F80428826AC3F80028026B84 -:1039C000C3F80C2C826BC3F8042C426BC3F8002C98 -:1039D000704700BF20250020001002400008014071 -:1039E0004FF0E023044A08215A6100229A6107221D -:1039F0000B201A61FEF7E0BF3F19010008B5202334 -:103A000083F31188FFF7FAFA002383F3118808BDC6 -:103A100008B5FFF7F3FFBDE80840FFF7DDBD000084 -:103A200010B501390244904201D1002005E003782D -:103A300011F8014FA34201D0181B10BD0130F2E76D -:103A40002DE9F0419BB10446C91A1778014403F1EE -:103A5000FF3C8C42204601D9002008E00578013463 -:103A6000BD42F6D10CEB0405D618A54201D1BDE844 -:103A7000F08115F8018D16F801EDF045F5D0E8E775 -:103A8000034611F8012B03F8012B002AF9D17047E6 -:103A90006F72672E6172647570696C6F742E663117 -:103AA000303351696F74656B5F506572697068007F -:103AB0004E6F20617070207369670A004261642054 -:103AC0006677206C656E6774682025750A00426110 -:103AD0006420626F6172645F696420257520736879 -:103AE0006F756C642062652025750A004261642050 -:103AF00066772064657363726970746F72206C6599 -:103B00006E6774682025750A0042616420617070D8 -:103B100020435243203078253038783A30782530A9 -:103B20003878203078253038783A30782530387831 -:103B30000A00476F6F64206669726D776172650A6B -:103B40000040A2E4F164689106000000000000005B -:103B50009D2D0008892D0008C52D0008B12D0008F5 -:103B6000BD2D0008A92D0008952D0008812D000805 -:103B7000D12D00086D61696E0000000069646C65FC -:103B8000000000007C3B000848240020F8240020AE -:103B900001000000B92F0008000000000C1E00000A -:103BA000447B4144B457494401000000424444442A -:103BB00044444444000000004444444444444444D5 -:103BC00000000000444444444444444400000000D5 -:103BD0004444444444444444B8C5FF7F01000000C9 -:103BE000E803000000000000009C0100000000004D -:103BF000640000000000000040420F00FE2A0100A7 -:043C0000D2040000EA +:10000000000900202D080008B11C0008811C000810 +:100010009D1C0008811C0008951C00082F08000882 +:100020002F0800082F0800082F080008E5370008EF +:100030002F0800082F0800082F080008F93C0008C6 +:100040002F0800082F0800082F0800082F080008B4 +:100050002F0800082F080008293A0008553A000820 +:10006000813A0008AD3A0008D93A00082F08000884 +:100070002F0800082F0800082F0800082F08000884 +:100080002F0800082F0800082F080008AD2C0008D2 +:10009000192D00086D2D0008C12D0008053B000832 +:1000A0002F0800082F0800082F0800082F08000854 +:1000B0002F0800082F0800082F0800082F08000844 +:1000C0002F0800082F0800082F0800082F08000834 +:1000D0002F0800082F0800082F0800082F08000824 +:1000E0006D3B00082F0800082F0800082F080008A3 +:1000F0002F0800082F0800082F0800082F08000804 +:100100002F0800082F0800082F0800082F080008F3 +:100110002F0800082F0800082F0800082F080008E3 +:100120002F0800082F0800082F0800082F080008D3 +:100130002F0800082F0800082F0800082F080008C3 +:100140002F0800082F0800082F0800082F080008B3 +:100150002F0800082F0800082F0800082F080008A3 +:100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A +:100170000C0F93EA0C0F6FD01A4480EA010C400276 +:1001800018BF5FEA41211ED04FF0006343EA5010D0 +:1001900043EA5111A0FB01310CF00040B1F5000F12 +:1001A0003EBF490041EAD3715B0040EA010062F1C1 +:1001B0007F02FD2A1DD8B3F1004F40EBC25008BFAB +:1001C00020F00100704790F0000F0CF0004C08BFC9 +:1001D00049024CEA502040EA51207F3AC2BFD2F196 +:1001E000FF0340EAC250704740F400004FF00003A4 +:1001F000013A5DDC12F1190FDCBF00F000407047DE +:10020000C2F10002410021FA02F1C2F1200200FA1B +:1002100002FC5FEA310040F1000053EA4C0308BFE2 +:1002200020EADC70704792F0000F00F0004C02BF33 +:10023000400010F4000F013AF9D040EA0C0093F0AE +:10024000000F01F0004C02BF490011F4000F013B08 +:10025000F9D041EA0C018FE70CEAD15392EA0C0F76 +:1002600018BF93EA0C0F0AD030F0004C18BF31F0E1 +:10027000004CD8D180EA010000F00040704790F0B7 +:10028000000F17BF90F0004F084691F0000F91F05B +:10029000004F14D092EA0C0F01D142020FD193EA21 +:1002A0000C0F03D14B0218BF084608D180EA0100A9 +:1002B00000F0004040F0FE4040F40000704740F085 +:1002C000FE4040F44000704780F0004002E000BF74 +:1002D00081F0004142001FBF5FEA410392EA030F31 +:1002E0007FEA226C7FEA236C6AD04FEA1262D2EB7B +:1002F0001363C1BFD218414048404140B8BF5B4280 +:10030000192B88BF704710F0004F40F4000020F018 +:100310007F4018BF404211F0004F41F4000121F02E +:100320007F4118BF494292EA030F3FD0A2F1010278 +:1003300041FA03FC10EB0C00C3F1200301FA03F1B6 +:1003400000F0004302D5494260EB4000B0F5000FD9 +:1003500013D3B0F1807F06D340084FEA310102F198 +:100360000102FE2A51D2B1F1004F40EBC25008BF4A +:1003700020F0010040EA03007047490040EB000014 +:10038000013A28BFB0F5000FEDD2B0FA80FCACF115 +:10039000080CB2EB0C0200FA0CF0AABF00EBC25042 +:1003A00052421843BCBFD0401843704792F0000F30 +:1003B00081F4000106BF80F400000132013BB5E783 +:1003C0004FEA41037FEA226C18BF7FEA236C21D0F9 +:1003D00092EA030F04D092F0000F08BF084670475E +:1003E00090EA010F1CBF0020704712F07F4F04D12C +:1003F000400028BF40F00040704712F100723CBF3F +:1004000000F50000704700F0004343F0FE4040F468 +:10041000000070477FEA226216BF08467FEA236326 +:100420000146420206BF5FEA412390EA010F40F411 +:10043000800070474FF0000304E000BF10F000435D +:1004400048BF40425FEA000C08BF704743F0964344 +:1004500001464FF000001CE050EA010208BF70475F +:100460004FF000030AE000BF50EA010208BF7047E6 +:1004700011F0004302D5404261EB41015FEA010CFB +:1004800002BF84460146002043F0B64308BFA3F1F3 +:100490008053A3F50003BCFA8CF2083AA3EBC253D5 +:1004A00010DB01FA02FC634400FA02FCC2F12002F4 +:1004B000BCF1004F20FA02F243EB020008BF20F02B +:1004C0000100704702F1200201FA02FCC2F1200291 +:1004D00050EA4C0021FA02F243EB020008BF20EA86 +:1004E000DC70704742000ED2B2F1FE4F0BD34FF0DA +:1004F0009E03B3EB126209D44FEA002343F000439A +:1005000023FA02F070474FF00000704712F1610FBC +:1005100001D1420202D14FF0FF3070474FF000008E +:10052000704700BF53B94AB9002908BF00281CBF53 +:100530004FF0FF314FF0FF3000F076B9ADF1080C0D +:100540006DE904CE00F006F8DDF804E0DDE90223F1 +:1005500004B070472DE9F047089E0D4604468846D2 +:10056000002B4DD18A42944668D9B2FA82F252B138 +:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 +:1005800041EA030894404FEA1C41B8FBF1F71FFA17 +:100590008CFE01FB178807FB0EF0230C43EA08438F +:1005A00098420AD91CEB030307F1FF3580F01E8146 +:1005B000984240F21B81023F63441B1AB3FBF1F0E7 +:1005C00001FB103300FB0EFEA4B244EA0344A6452F +:1005D0000AD91CEB040400F1FF3380F00981A64521 +:1005E00040F20681644402380021A4EB0E0440EA84 +:1005F00007401EB10023D440C6E90043BDE8F087A0 +:100600008B4208D9002E00F0EE800021C6E90005DB +:100610000846BDE8F087B3FA83F100294AD1AB421E +:1006200002D3824200F2FC80841A65EB03030120AE +:100630009846002EE2D0C6E90048DFE702B9FFDEA7 +:10064000B2FA82F2002A40F09180A1EB0C00012165 +:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 +:10066000250C45EA00450EFB03F0A84208D91CEB17 +:10067000050503F1FF3802D2A84200F2CE804346BE +:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 +:1006900044EA0544A64508D91CEB040400F1FF35E3 +:1006A00002D2A64500F2B6802846A4EB0E0440EA2A +:1006B00003409EE7C1F120078B4022FA07FC4CEA79 +:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D +:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 +:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 +:1006F00001F20BD91CEB040408F1FF3A80F088806A +:10070000A04240F28580A8F102086444241AB4FB98 +:10071000F9F009FB104400FB0EFEADB245EA0444BB +:10072000A64508D91CEB040400F1FF356CD2A645A0 +:100730006AD90238644440EA0840A0FB0295A4EB61 +:100740000E04AC42C846AE4656D353D0002E69D0F4 +:10075000B3EB080264EB0E0422FA01F304FA07F784 +:100760001F43CC40C6E90074002147E70CFA02FCA5 +:10077000C2F1200125FA01F34FEA1C4720FA01F1EA +:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 +:10079000280C40EA034001FB0EF3834204FA02F402 +:1007A00008D91CEB000001F1FF382FD283422DD96C +:1007B00002396044C01AB0FBF7F307FB1300ADB277 +:1007C00045EA004503FB0EF0A84208D91CEB0505DD +:1007D00003F1FF3816D2A84214D9023B6544281A07 +:1007E00043EA014138E73146304607E72F46E4E661 +:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 +:100800000138A3E74346EAE7284694E74146D1E7A3 +:10081000D0467BE76444023847E7023B65442FE754 +:10082000084606E73146E9E6704700BF02E000F0FF +:1008300000F8FEE772B6264880F30888254880F362 +:100840000988254825490860022080F31488BFF3F1 +:100850006F8F03F017F803F07BF84FF05530204905 +:100860001B4A91423CBF41F8040BFAE71D49194A63 +:1008700091423CBF41F8040BFAE71B491B4A1C4B51 +:100880009A423EBF51F8040B42F8040BF8E70020EF +:100890001849194A91423CBF41F8040BFAE702F0AB +:1008A000F5FF03F057F8154C154DAC4203DA54F838 +:1008B000041B8847F9E700F03FF8124C124DAC4298 +:1008C00003DA54F8041B8847F9E702F0DDBF0000A3 +:1008D00000090020001100200000000808ED00E0E1 +:1008E0000001002000090020103E00080011002037 +:1008F0002411002028110020E025002060010008BC +:100900006001000860010008600100082DE9F04F57 +:10091000C1F80CD0C3689D46BDE8F08F002383F377 +:1009200011882846A047002002F010FDFEE702F0E3 +:1009300083FC00DFFEE70000F8B500F03DFE02F0AA +:10094000EFFE074602F03AFF0546002840D12C4B47 +:100950009F423DD001339F423DD02A4B27F0FF02FA +:100960009A423BD1F8B200F003FC2E4642F21074DA +:1009700000F004FC08B10024264601F007F988B312 +:100980000024032000F044F8264635B11E4B9F4258 +:1009900003D0002402F00AFF2646002002F0CAFE1F +:1009A0001A4B9B6813F0400322D00EB100F046F8BA +:1009B00000F044FC00F002FE01F07CF90546CCB1E9 +:1009C00001F078F9401BA04214D900F037F8F3E7A2 +:1009D0002E460024CCE704460126C9E706464FF41C +:1009E0007A74C5E7002CD0D04FF47A740126CCE796 +:1009F0001C46DDE700F0D4FC012002F0ADFCDEE790 +:100A0000010007B0000008B0263A09B0000C014010 +:100A1000084B187003280CD8DFE800F0080502081E +:100A2000022000F027BE022000F01CBE0022024B74 +:100A30005A607047281100202C11002038B501F0B1 +:100A4000A5F830B103221F4B1A7000221E4B5A60CA +:100A500038BD1E4B1E4A19680131F9D00433934248 +:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 +:100A70009B6803F1006303F5C8439A42E8D202F091 +:100A800069FE02F07BFE002000F0B2FD0220FFF7BD +:100A9000BFFF124BDA690022DA61D96999699A615C +:100AA0009B6972B64FF0E023C3F8085D3021D4F89B +:100AB0000034D4F8042481F311889D4683F3088818 +:100AC0001047C5E7281100202C1100200064000801 +:100AD000206400080060000800110020001002409F +:100AE00049F26900084A136899B21B0C00FB0133F4 +:100AF00044F250611360054B186882B2000C01FB90 +:100B00000200186080B27047201100201C110020E4 +:100B100010B504460021102200F0C8FD034B03CBA2 +:100B2000206061601868A06010BD00BFE8F7FF1F7B +:100B30002DE9F0410026ADF5507D6EAC40F2751206 +:100B400007460D4610A831460F9600F0AFFD4FF452 +:100B5000C4723146204600F0A9FD01F0ABF84FF415 +:100B60007A72B0FBF2F0264B0DF13C08186093E866 +:100B70000700022384E807000DF5ED702382FFF7DC +:100B8000C7FF4EF603031F4907A8238403F0ECF8C0 +:100B90001F230DF2EB2284F832310DF1340C07AB38 +:100BA0001E4603CE664510605160334602F10802CE +:100BB000F6D130681060B188B37920469180937186 +:100BC0004146012200F0BEFD00230393AB7E80B2BC +:100BD000029305F1190301930123CDE904800093E9 +:100BE000384605A3D3E90023E97E01F0A9FB0DF502 +:100BF000507DBDE8F08100BF9E6AC421818A46EE27 +:100C000034110020783D00082DE9F041264D804642 +:100C10002B7A0C46DAB0FBB9204627A900F0A2FED9 +:100C20000746002836D19DF89D60C82E32D801466F +:100C30004FF4FA72284600F039FD32460DF19E015C +:100C400005F1090000F020FD9DF89C302E447772DC +:100C50002B720BB9E37E2B728122002106AD27A8EF +:100C600000F024FD0122294627A800F0B7FE00234A +:100C70000393A37E80B2029304F119030193282306 +:100C8000CDE904500093404605A3D3E90023E17E5B +:100C900001F056FB5AB0BDE8F08100BFAFF3008011 +:100CA00026417272DF25D7B77C210020F0B54FF4C2 +:100CB0008A750024234EF1B005FB006596F8D83004 +:100CC000D822214685F8DC3085F8E8403AA800F0C3 +:100CD000EDFC06F1090000F0E1FCD5F8E430C2B209 +:100CE00006AF8DF8F00006F109010DF1F100CDE934 +:100CF0003A3400F0C9FC394601223AA800F09AFEC5 +:100D000080B2CDE9047008230127CDE9023706F14E +:100D1000D80301933023317A00930B4807A3D3E91A +:100D2000002301F00DFBA04206DD00F0C3FFC5F873 +:100D3000E000384671B0F0BD2046FBE778F6339FFF +:100D400093CACD8D7C2100204C210020F0B51E4E91 +:100D50001E4F1F4D85B0304601F01EFB044660B3A8 +:100D600010220021684600F0A1FC4FF00003227B16 +:100D70006068A16862F303038DF8003002AB03C31F +:100D8000019B2268384662F31C0301939DF80030F2 +:100D90006A4643F020038DF800300023194602F024 +:100DA00087F9044620B9304601F0FAFA2C70D2E7F0 +:100DB0002B78072B03D801332B7005B0F0BD024808 +:100DC00001F0EEFAF9E700BF4C210020A823002033 +:100DD0007523002070B50D4614461E4601F00CFA2E +:100DE00050B9022E10D1012C0ED112A3D3E9002349 +:100DF0000120C5E9002307E0282C10D005D8012CDC +:100E000009D0052C0FD0002070BD302CFBD10BA3D6 +:100E1000D3E90023ECE70BA3D3E90023E8E70BA316 +:100E2000D3E90023E4E70BA3D3E90023E0E700BF05 +:100E3000AFF30080401DA12026812A0B78F6339F56 +:100E400093CACD8D9E6AC421818A46EE2641727274 +:100E5000DF25D7B7F017304A39059E5638B5054615 +:100E60000E4C0021013500F0E5FBA4F8F051B4F878 +:100E7000F00100F0C7FB78B1B4F8F00100F0D2FB4C +:100E8000014648B9B4F8F00100F0D4FBB4F8F031F1 +:100E90000133A4F8F031EAE738BD00BF7C2100201F +:100EA0002DE9F04F8DB000AF04460D4601F0A4F9D6 +:100EB000002846D12B7E022B1AD1EB8A012B17D1A9 +:100EC00000F0F8FE0646FFF70BFE4FF4C873B0FBC8 +:100ED000F3F202FB1303DFF878829BB206F5167675 +:100EE0003344C8F80030EB7E33B90022994B1A70B6 +:100EF0003437BD46BDE8F08F284607F11C0100F0ED +:100F0000EFFC0028F4D107F10C00FFF701FEBD7FD4 +:100F100007F10C012A4607F11F0002F0F5FE002838 +:100F2000E3D10F2D08D88B4B1D70D8F80030A3F5F6 +:100F30001673C8F80030DBE72046397F01F054F91A +:100F4000D6E7EB8A282B6BD010D8012B63D0052B6A +:100F5000CED1BFF34F8F8049804BCA6802F4E06264 +:100F60001343CB60BFF34F8F00BFFDE7302BBFD1E2 +:100F70007B4CEA7E237A9A42BAD194F8DC206B7ECD +:100F80009A42B5D1284604F1EA0100F07FFD0646F9 +:100F90000028ADD1012384F8E83000F08BFED4F8AE +:100FA000E030C01A192840F6B83338BF19209842EB +:100FB00028BF1846FFF73EFA6A49FFF7D1F8054601 +:100FC0002068FFF737FA6849FFF7CAF80146284654 +:100FD000FFF780F9FFF786FA20604FF48A7194F8E2 +:100FE000D9307B607A68636801FB02F5621992F878 +:100FF000E80050B1D2F8E400E946834215D000235E +:1010000082F8E830C2F8E030CD466368574A9B0A60 +:10101000013313816CE729462046FFF789FD67E716 +:1010200029462046FFF7F0FD62E7B2F8EC803B600E +:1010300008F1030A4FEA9A0A4FEA8A02D11DC90849 +:10104000A9EBC1039D46EB460021584600F02EFB5C +:1010500005F1EE0142465846214400F015FB3B687D +:1010600013B9012000F0C4FA94F8D20000F0CAFAD3 +:10107000054630B9207200F0E5FA284600F0B8FACB +:10108000C2E7D4F8D4303BB994F8D200B4F8F031C8 +:10109000834201D8FFF7E2FED4F8D43043449D42A6 +:1010A00008D294F8D200B4F8F0310130834201D86C +:1010B000FFF7D4FE594660685FFA8AF200F0FEFA44 +:1010C00008B9CD4689E7636894F8D2004344636069 +:1010D000D4F8D43008EB030AC4F8D4A000F092FA94 +:1010E000824509D394F8D230D4F8D4000133401BA0 +:1010F00084F8D230C4F8D400B8F1FF0F0FD800251F +:10110000257200F09FFA284600F072FA00F03EFDCA +:10111000164B188108B9FFF791FCCD46E8E64FF46D +:101120008A727B6894F8D90002FB0343D3F8E42069 +:1011300083F8E86002F58072C3F8E060C3F8E42049 +:10114000FFF7B4FDFFF702FE84F8D960B9E700BFEE +:10115000482100204521002000ED00E00400FA05B0 +:101160007C210020CDCCCC3D6666663F341100204A +:10117000014B1870704700BF4011002030B54FF090 +:101180000054254B226885B09A4207D002F020FB1C +:101190000446C0B90024204605B030BD0025627D5C +:1011A0001E4B1F481A70237DC92203721D49C0F8C7 +:1011B000E450093000F068FA2046E022294600F0A9 +:1011C00075FA0124E7E7184A184DD36943F0007314 +:1011D000D361AA6D164B9A42DCD12B6E013B7E2B5C +:1011E000D8D8144A01AB07CA83E807001846032180 +:1011F00000F09CFC6B6D83424FF00003CAD12A6D56 +:101200008A4203BFAB652A6E044B1C4601BF1A70AD +:10121000EA6D094B1A60BEE79AAD44C54011002043 +:101220007C210020160000200010024000660040D3 +:101230005041A0B058660040181100202DE9F0433D +:1012400085B000F0A3FC0223494C63710023029394 +:10125000484B2081D3F800C0BCF57A7F12D3464FAB +:10126000464BB7FBFCF59C458CBF0A231123B5FB0D +:10127000F3F603FB1652591EC8B2002A3ED00229CB +:101280000B46F4D89DF80B303D495A1E9DF80A30A4 +:101290003C48013B1B0443EA0253BDF80820013AD5 +:1012A00013434B6001F0F4FE00230193364B3749A2 +:1012B00000934FF48052364B364800F06BFF364BAC +:1012C000197811B1334800F08FFF00F0F3FC0546A8 +:1012D000FFF706FC4FF4C873B0FBF3F202FB1303F5 +:1012E00005F516709BB218442C4B186002F066FA94 +:1012F00008B10F23238105B0BDE8F083731EB3F559 +:10130000806FBFD24FF47A75C0EBC00E0EF10303AD +:101310004FEAE30909FB0555C3F3C703C11AC9B274 +:1013200009F101088844B5FBF8F5B5F5617F08D9E6 +:101330000EF1FF33C3F3C703C11A581E0F28C9B2F9 +:1013400014D84A1E072A8CBF00220122581800FB1D +:101350000660B7FBF0F7BC4594D1002A92D0ADF8F7 +:1013600008608DF80A308DF80B108BE71346EDE717 +:101370003411002018110020005125023F420F00B7 +:1013800010110020A8230020D50D000844110020D2 +:10139000A10E00084C21002040110020482100200F +:1013A0002DE9F04F80A7D7E900670FF20429D9E9AA +:1013B0000089734D93B00DF1300AFFF7C7FC182276 +:1013C0000021504600F072F9DFF8B8B16E4C0023EE +:1013D00052461946584601F093FE014650BB102272 +:1013E00008A800F063F9E36883F01003E36000F0FD +:1013F00063FC0DF1240C0B4612A9024611E903000F +:101400008CE803009DF83410C1F30300890649BF3E +:101410000E99BDF83810C1F31C0141F0004158BFCE +:10142000C1F30A018DF82C000891284608A901F0A3 +:1014300097F9CCE7284600F0DFFE0446002847D1A4 +:1014400000F038FCDFF844B1DBF8003098423FD3BD +:1014500000F030FC0790FFF743FB4FF4C873B0FB7C +:10146000F3F101FB1300079A83B202F516701844DA +:10147000CBF80000DFF818B18DF820409BF8001081 +:1014800011B901238DF8203050460791FFF740FB3A +:1014900007990DF12100C1F11004E4B2062C28BF18 +:1014A00006245144224600F0EFF808AB03931823BA +:1014B0000293384B013401930123E4B20093324686 +:1014C0003B462846049400F0DDFE00238BF80030F4 +:1014D00000F0F0FB304A314C1368C31AB3F57A7F41 +:1014E00030D3106000F0E8FB02460B46284600F0BF +:1014F00061FF284600F080FE20B3237ADFF8A0B019 +:10150000002B14BF032302238BF8053000F0D2FB1D +:101510004FF47A73B0FBF3F00122CBF80000514690 +:10152000584600F0B5F9182302931E4B80B2019380 +:1015300040F25513CDE903A0009342464B4628469E +:1015400000F0A0FE237ABBB100F0B4FB94F8E830C1 +:1015500073B9D4F8E03043B1C01A2368FA2B38BF0E +:10156000FA230533B0EB430F02D30020FFF79EFBB5 +:10157000237A002B7FF41FAF13B0BDE8F08F00BFBC +:101580004C210020A8230020000801404821002011 +:101590004521002044210020702300207C210020D0 +:1015A0003411002074230020401DA12026812A0B25 +:1015B000F1C6A7C1D068080F7047000070B501F0F0 +:1015C00095FF0024084E094D3080286833888342F7 +:1015D00008D901F087FF2B6804440133B4F5C84FE4 +:1015E0002B60F2D370BD00BFA4230020782300201D +:1015F00002F00AB800F10060920000F5C84001F066 +:10160000AFBF0000054B1A68054B1B889B1A83422D +:1016100002D9104401F066BF0020704778230020F3 +:10162000A4230020024B1B68184401F061BF00BFD7 +:1016300078230020024B1B68184401F06BBF00BFE9 +:1016400078230020064991F8243033B10023082282 +:10165000086A81F82430FFF7CDBF0120704700BF32 +:101660007C230020022802BF1022014B1A61704720 +:1016700000080140022802BF4FF48012014B1A619A +:10168000704700BF00080140002310B5934203D00B +:10169000CC5CC4540133F9E710BD00000346024698 +:1016A000D01A12F9011B0029FAD1704703460244EF +:1016B000934202D003F8011BFAE770472DE9F84383 +:1016C0001F4D144695F824200746884652BBDFF884 +:1016D00070909CB395F824302BB92022FF21484606 +:1016E0002F62FFF7E3FF95F824004146C0F108029E +:1016F000A24228BF224605EB8000D6B29200FFF737 +:10170000C3FF95F82430A41B1E44F6B2082E1744DC +:101710009044E4B285F82460DBD1FFF793FF002802 +:10172000D7D108E02B6A03EB82038342CFD0FFF7C7 +:1017300089FF0028CBD10020BDE8F8830120FBE71A +:101740007C2300202DE9F0470D46044600219046F9 +:10175000284640F27912FFF7A9FF234620220021F4 +:10176000284600F09FFF022220212846231D00F07A +:1017700099FF032222212846631D00F093FF0322D4 +:1017800025212846A31D00F08DFF10222821284680 +:1017900004F1080300F086FF08223821284604F1EE +:1017A000100300F07FFF08224021284604F11103B6 +:1017B00000F078FF08224821284604F1120300F0C7 +:1017C00071FF20225021284604F1140300F06AFF23 +:1017D00040227021284604F1180300F063FF08221C +:1017E000B021284604F1200300F05CFF0822B82154 +:1017F000284604F1210300F055FFC02604F122071A +:101800003B46314608222846083600F04BFFB6F525 +:10181000A07F07F10107F3D108223146284604F1E1 +:10182000320300F03FFF002704F1330A94F832300E +:101830004FEAC7099F4209F5A47615D3B8F1000F06 +:1018400008D131460722284604F5997300F02AFF93 +:1018500009F24F16274694F832213B1B93420CD3D2 +:10186000F01DC008BDE8F0870AEB070308223146E7 +:10187000284600F017FF0137D8E7314607F2331347 +:101880000822284600F00EFF08360137E3E7000083 +:1018900038B50C460021054621600346C4F8031004 +:1018A0002046202200F0FEFE20462B1D0222202191 +:1018B00000F0F8FE20466B1D0322222100F0F2FE0C +:1018C0002046AB1D0322252100F0ECFE204610220D +:1018D000282105F1080300F0E5FE072038BD0000CF +:1018E0000023F7B50E460546047F072200911946EE +:1018F00000F09AFD731C0093012200230721284663 +:1019000000F092FDC4B9B31C0093052223460821C0 +:10191000284600F089FD0D243746B278BB1B934260 +:1019200011D32B7FE01DC008AC8ABBB9A04294BF85 +:101930000020012003B0F0BDAB8A0824DB00083B87 +:10194000DB08B370E8E7FB1C214600930822002364 +:10195000284600F069FD08340137DEE7001B18BF98 +:101960000120E7E70023F7B50E46047F0822009127 +:101970001946054600F058FD731CC4B908220093AF +:1019800011462346284600F04FFD102401237278AB +:101990005F1C013B934211D32B7FE01DC008AC8A32 +:1019A000BBB9A04294BF0020012003B0F0BDAB8AB8 +:1019B0000824DB00083BDB087370E7E7F3192146D6 +:1019C000009308220023284600F02EFD08343B46F1 +:1019D000DDE7001B18BF0120E7E70000F8B50E4661 +:1019E00005461446002181223046FFF75FFE2B4654 +:1019F00008220021304600F055FE7CB9072208215C +:101A000030466B1C00F04EFE0F2401236A785F1CE9 +:101A1000013B934204D3E01DC008F8BD0824F4E75D +:101A20002146EB190822304600F03CFE08343B46C4 +:101A3000ECE70000F8B50E46054614460021CE221C +:101A40003046FFF733FE2B4628220021304600F0B7 +:101A500029FE7CB908222821304605F1080300F050 +:101A600021FE30242F462A7A7B1B934204D3E01DAB +:101A7000C008F8BD2824F5E7214607F1090308222C +:101A8000304600F00FFE08340137ECE7F7B5047F6D +:101A90000E460091012310220021054600F0C4FCEF +:101AA000C4B9B31C0093092223461021284600F034 +:101AB000BBFC192437467288BB1B9A4211D82B7F76 +:101AC000E01DC008AC8ABBB9A04294BF0020012031 +:101AD00003B0F0BDAB8A1024DB00103BDB08738041 +:101AE000E8E73B1D2146009308220023284600F02A +:101AF0009BFC08340137DEE7001B18BF0120E7E735 +:101B000030B5094D0A4491420DD011F8013B5840BF +:101B1000082340F30004013B2C4013F0FF0384EA48 +:101B20005000F6D1EFE730BD2083B8ED4FF0FF3322 +:101B3000F7B500EB81061946DFF848C0DFF848E04A +:101B4000B0421BD050F8042B01AF0192042217F8C9 +:101B5000014B81EA046108240D46DB184941013C30 +:101B6000002DBCBF83EA0C0381EA0E0114F0FF04D0 +:101B7000F2D1013A12F0FF02E9D1E1E7D843C943BB +:101B800003B0F0BD9336EAA9EBE1F042F7B56B463E +:101B9000354A106851686A4603C3082333493448FC +:101BA00002F0C2F8044690BB0A256B46314A106821 +:101BB00051686A4603C308232F492D4802F0B4F840 +:101BC0000446002847D00369B3F5CE3F43D8B0F8A8 +:101BD0006620B2F57A7F3ED1284A024402F15C01C8 +:101BE0008B4238D35C3B224900209E1AFFF788FFC6 +:101BF00007463246002004F16401FFF781FFA36825 +:101C00009F4228D1E368984208BF002523E003697A +:101C1000B3F5CE3F26D8428BB2F57A7F20D1174A52 +:101C2000024402F110018B4218D3103B10490020EE +:101C30009D1AFFF765FF06462A46002004F11801A9 +:101C4000FFF75EFFA3689E4202D1E368984201D08D +:101C50000D25AAE70025284603B0F0BD1025A4E70E +:101C60000C25A2E70B25A0E7983D0008DC9B0100AE +:101C700000640008A13D0008909B0100089CFFF74C +:101C8000EFF30983EFF30583014B9B6BFEE700BF86 +:101C900000ED00E008B5FFF7F3FF0000EFF3098364 +:101CA000EFF30583014B5B6BFEE700BF00ED00E047 +:101CB000FEE7000001F0E2BC01F0BABC2DE9F04102 +:101CC000456A15B94162BDE8F0814B68AC4623F026 +:101CD0006047C3F38A4616EA230638BF3E464FEAFA +:101CE000D37EC3F380782B465A68BEEBD27F22F0B6 +:101CF00060440AD0002A18DAA40CB44217D19D42DD +:101D00000FD10D60DEE71346EEE7A74207D102F0E0 +:101D10008044C2F3807242450BD054B1EFE708D241 +:101D2000EDE7CCF800100B60CDE7B44201D0B4422F +:101D3000E5D81A689C46002AE5D11960C3E700007F +:101D40002DE9F0474FF47F49089D01F007044FEA61 +:101D5000D508224405F0070500EBD100944201D1DB +:101D6000BDE8F08704F0070705F0070A57453E462F +:101D700038BF5646111BC6F108068E4228BF0E46D4 +:101D8000E108415C08EBD50E13F80EC0B94029FA02 +:101D900006F721FA0AF1FFB28CEA010147FA0AF7C5 +:101DA00039408CEA010C03F80EC034443544D5E7C1 +:101DB000082341F2210280EA012001B240000029FB +:101DC00080B203F1FF33B8BF504013F0FF03F4D1EA +:101DD0007047000038B50C468D18A54200D138BDBB +:101DE00014F8011BFFF7E4FFF7E700000346406823 +:101DF00048B1026899895A605A89013292B2914277 +:101E00005A8138BF9A81704770B504460D4688B034 +:101E1000202200216846FFF749FC20460495FFF781 +:101E2000E5FF024658B16B46054608AE1C4603CC9A +:101E3000B44228606960234605F10805F6D11046D2 +:101E400008B070BD082817D909280CD00A280CD072 +:101E50000B280CD00C280CD00D280CD00E2814BF49 +:101E60004020302070470C2070471020704714200D +:101E7000704718207047202070470000082817D9A5 +:101E80000C280CD910280CD914280CD918280CD9D6 +:101E900020280CD930288CBF0F200E207047092035 +:101EA00070470A2070470B2070470C2070470D20A8 +:101EB000704700002DE9F843078C0446072F1ED910 +:101EC000D0E9029800254FF6FF73C5F12006A5F171 +:101ED000200029FA05F108FA06F628FA00F0314345 +:101EE0000143C9B21846FFF763FF0835402D03468A +:101EF000EBD13A46E169BDE8F843FFF76BBF4FF617 +:101F0000FF70BDE8F883000010B54B6823B9CA8A9A +:101F100063F30902CA8210BD04691A681C60036178 +:101F2000C38A013BC3824A60EFE700002DE9F84F06 +:101F30001D46CB8A0F46C3F3090105298146924607 +:101F40000B4630D00020AAB207F11A049EB2042E2C +:101F50001FFA80F80FD8904503F1010306D3FB8ADE +:101F60000A4462F309030120FB821AE01AF80060B8 +:101F70000130E654EAE79045F1D21C23A1F1050BAC +:101F8000BBFBF3F203FB12BB7C681FFA8BF6002C41 +:101F900045D14846FFF72AFF044638B978606FF00C +:101FA0000200BDE8F88F4FF00008E6E70026066063 +:101FB00078604FF0000BADB2454510D90AEB08032D +:101FC000221D13F8011B08F101089155B1B21B291C +:101FD0001FFA88F82BD0454506F10106F1D8FB8A97 +:101FE000C3F30902154465F30903BCE71C4601323B +:101FF00092B22368002BF9D16B1F0B441C21B3FB59 +:10200000F1F301339BB29A42D3D2BBF1000FD0D18E +:102010004846FFF7EBFE20B9C4F800B0BFE7012245 +:10202000E7E7C0F800B05E4620600446C1E74545DA +:10203000D5D94846FFF7DAFE08B92060AFE7C0F807 +:1020400000B0002620600446B6E700002DE9F74FF7 +:102050001C465B69074688460092002B00F097807B +:10206000238C2BB1E269002A00F09180072B33D832 +:1020700007F10C00FFF7BAFE054628B96FF002051C +:10208000284603B0BDE8F08F14220021FFF70EFBB5 +:10209000228CE16905F10800FFF7F6FA208C48F080 +:1020A0000041013080B2FFF7E9FEFFF7CBFE0138B7 +:1020B00080B22084013028746369228C1B782A4402 +:1020C00003F01F0363F03F0313723846696029462B +:1020D000FFF7F4FD0125D3E74FF000094FF0800A28 +:1020E0004E464D4600F10C0301930198FFF77EFE2A +:1020F00083460028C2D014220021FFF7D7FA002E11 +:102100003BD10222009BABF808300BF1080E1FFAFE +:1021100082FC0CF10100BCF1060F218C80B201D8C9 +:102120008E422CD3FFF7AAFEFFF78CFE8E4208BF2B +:102130004FF0400A62690138127880B202F01F0243 +:1021400042EA49120BEB00014AEA020A013048F068 +:10215000004281F808A08BF8100059463846CBF8A9 +:102160000420FFF7ABFD238C0135B3424FF0000A8A +:102170002DB289F00109B8D182E70022C5E7E169F3 +:10218000895D01360EF80210B6B20132BFE76FF07A +:10219000010575E7F8B5044615460E4630220021C4 +:1021A0001F46FFF783FA069BB5F5001F6360079B88 +:1021B00028BF4FF6FF72A3624FF0000338BF6A09D1 +:1021C000A760E66197B204F110009A4206D8002396 +:1021D0000360A782E3822383E360F8BD06600133D6 +:1021E00030462036F1E7000003781BB94BB2002BD4 +:1021F000C8BF01707047000000787047F8B50C4602 +:10220000C969074611B9238C002B37D1257E1F2DB4 +:1022100034D8387828BB228C072A2CD8268A36F066 +:1022200003032BD14FF6FF70FFF7D4FD4FF6FF727B +:1022300020F001003602400446EA0565400C45EAFC +:102240004025234629463846FFF700FF002807DDD2 +:10225000626913780133DBB21F2B88BF0023137030 +:10226000F8BD218A2D0645EA012505432046FFF7E2 +:1022700021FE0246E5E76FF00300F1E76FF0010091 +:10228000EEE7000070B504461D4616468AB02822C7 +:1022900000216846FFF70AFABDF838306946ADF804 +:1022A00010300F9B204605939DF84030CDE9026524 +:1022B0008DF81830119B0793BDF84830ADF82030E9 +:1022C000FFF79CFF0AB070BD2DE9F041D3690546C8 +:1022D0000C4616460BB9138C5BBB377E1F2F28D8D4 +:1022E00095F80080B8F1000F26D03046FFF7E2FDE8 +:1022F0003378210241EAC33141EA0801338A41EAD5 +:10230000076141EA034102463346284641F0800115 +:10231000FFF79CFE00280ADD3378012B07D1726994 +:1023200013780133DBB21F2B88BF00231370BDE885 +:10233000F0816FF00100FAE76FF00300F7E70000AB +:10234000F0B504460D461E4617468BB028220021E4 +:102350006846FFF7ABF99DF84C3029465A1E5342A8 +:1023600053418DF800309DF840306A46ADF810308A +:10237000119B204605939DF84830CDE902768DF8F3 +:102380001830149B0793BDF85430ADF82030FFF798 +:102390009BFF0BB0F0BD0000406A00B104307047F5 +:1023A000436A1A68426202691A600361C38A013B88 +:1023B000C38270472DE9F041D0F8208014461D46B5 +:1023C00041460027174E09B9BDE8F081D1E9022343 +:1023D000A21A65EB0303964277EB03031ED2036A4E +:1023E0008B420DD1FFF790FD036A1B6803620369FE +:1023F0000B60C38A0161016A013B8846C382E2E740 +:10240000FFF782FD0B68C8F8003003690B60C38AD0 +:102410000161013BC382D8F80010D4E788460968FF +:10242000D1E700BF80841E002DE9F04F8BB00D4630 +:1024300014469B468046DDF85090002800F01A8133 +:10244000B9F1000F00F01681531E3F2B00F21281EC +:10245000012A03D1BBF1000F40F00C810023CDE92C +:102460000833B8F81430B5EBC30F4FEAC30703D3F2 +:1024700000200BB0BDE8F08F2B199F42D8F80C302C +:1024800036BF7F1B2746FFB21BB9D8F81030002B90 +:102490007BD0272D4ED8C5F12806B7424FF0000358 +:1024A00034BF3E46F6B2009329463246D8F80800BB +:1024B00008ABFFF745FCA7EB060A35445FFA8AFA3A +:1024C0002821B8F8143003F10053053BDB000493D6 +:1024D000D8F80C300393039B13B1BAF1000F2CD141 +:1024E000D8F8100040B1BAF1000F05D0524600965E +:1024F00008AB691AFFF724FC38B2002FB8D0660782 +:102500000AD00AAB03EBD40111F8083C624202F096 +:102510000702134101F8083C082C3DD9102C40F269 +:10252000B680202C40F2B880BBF1000F00F09D80F7 +:10253000082335E0BA460026C2E7049BE02B28BFFB +:10254000E02306930B44AB42059315D95A1B9245E1 +:1025500038BF5246039828BFD2B20096691A08AB1A +:1025600004300792FFF7ECFB079A1644AAEB020A25 +:102570001544F6B25FFA8AFA049B069A05999B1AEB +:102580000493039B1B680393A5E700933A462946EF +:10259000D8F8080008ABADE7BBF1000F13D001235A +:1025A000B4EBC30F6CD0082C12D89DF82030621EFB +:1025B00023FA02F2D50706D54FF0FF3202FA04F4EF +:1025C00023438DF820309DF8203089F8003050E703 +:1025D000102C12D8BDF82030621E23FA02F2D10767 +:1025E00006D54FF0FF3202FA04F42343ADF8203051 +:1025F000BDF82030A9F800303BE7202C0FD808990F +:10260000631E21FA03F3DA0705D54FF0FF3202FA11 +:1026100004F40C430894089BC9F8003029E7402CC7 +:102620002BD0DDE90865611EC4F12102A4F121036C +:1026300026FA01F105FA02F225FA03F311431943D0 +:10264000CB0712D50122A4F12003C4F1200102FA24 +:1026500003F322FA01F1A240524243EA010363EB81 +:10266000430332432B43CDE90823DDE90823C9E9BD +:102670000023FEE66FF00100FBE66FF00800F8E6CD +:10268000082CA0D9102CB3D9202CEED8C3E7BBF16D +:10269000000FADD0022383E7BBF1000FBBD00423B2 +:1026A0007EE70000012A30B5144638BF012200251C +:1026B000402A28BF402285B0012CCDE9025517D809 +:1026C0001B788DF8083053070AD004AB03EBD20512 +:1026D00015F8083C544204F00704A34005F8083CF0 +:1026E0000346009102A80021FFF72AFB05B030BD88 +:1026F000082CE5D9102C03D81B88ADF80830E2E788 +:10270000202C02D81B680293DDE7D3E90045CDE910 +:102710000245D8E710B5CB681BB98B600B618B8283 +:1027200010BD04691A681C600361C38A013BC3823F +:10273000CA60F0E703064CBFC0F3C0300220704708 +:1027400008B50246FFF7F6FF022806D15306C2F38A +:102750000F2001D100F0030008BDC2F30740FBE7E2 +:102760002DE9F04F93B0CDE903230A6804461046E3 +:10277000FFF7E0FF02280CBF0026C2F30626002A5E +:102780000D46824680F2F98112F0C04940F0F58191 +:10279000097B002900F0F181022803D02378B3429D +:1027A00040F0EE81C2F304631046069302F07F030B +:1027B0000593FFF7C5FF059B00224FEA83480023DE +:1027C00048EA0A48294448EA4668CE78CDE9082311 +:1027D000F309834648EA0008029367D0059B024646 +:1027E000009320465346676808A9B847002800F0C0 +:1027F000CA81276A4FB9414604F10C00FFF704FB78 +:10280000074690B96FF0020054E03B6998450DD03F +:102810003F68002FF9D1414604F10C00FFF7F4FAAC +:1028200007460028EED0236A3B60276297F817C05E +:1028300006F01F08CCF3840CACEB08001FFA80FEF6 +:102840000028B8BF0EF12000A8EB0C031FFA83FE8E +:10285000B8BF00B2002B0793BEBF0EF120031BB21E +:102860000793D7E9022152EA010338D04FF0000C58 +:10287000039BDFF8F8E19A1A049B63EB010196458C +:102880007CEB01032BD36B7B97F81AE0734519D1CE +:10289000029B002B78D0012821DC7868F8B9DFF89A +:1028A000D0C1944570EB010316D337E0276A27B9EE +:1028B0006FF00C0013B0BDE8F08F3B699845B5D0C0 +:1028C0003F68F4E76A4890427CEB010301D30020A3 +:1028D000F0E7029B002BFAD0079B0F2B17DCFA7D49 +:1028E000B30002F0030203F07C031343FB75394687 +:1028F0002046FFF709FB6B7BBB76029B3BB9FB7D58 +:10290000C3F38402013262F38603FB75D0E76A7B6E +:10291000BB7E9A42DBD1029B002B35D0B309022B40 +:1029200032D0039B1422BB60049B0021FB600DA8E6 +:10293000FEF7BCFE039B20460A93049BADF83EB015 +:102940000B932B1D0C932B7B8DF840A0013BDBB22E +:10295000ADF83C30069B8DF841808DF84230059BE8 +:102960000AA98DF8433094F82C3083F001038DF8D8 +:102970004430A3689847FB7DC3F38403013303F01D +:102980001F039B02FB82A2E7FB7DC6F34012B2EB62 +:10299000D31F40F0FB80C3F38403434540F0F9802C +:1029A000029A2B7BB609002A4DD0F20762D4032B82 +:1029B00040F2F280039BAE1DBB60049B3246FB607D +:1029C0002B7B3946033BDBB204F10C00FFF7AEFA78 +:1029D00000280CDA39462046FFF796FAFB7DC3F350 +:1029E0008403013303F01F039B02FB820AE7AB88D9 +:1029F000DDE908843B834FF6FF73C9F12000A9F19C +:102A0000200228FA09F104FA00F0014324FA02F244 +:102A100011431846C9B2FFF7CBF909F10809B9F11A +:102A2000400F0346E9D13146B8822A7B033AD2B23D +:102A3000FFF7D0F9FB7DB882DA43C2F3C01262F32C +:102A4000C713FB7543E7AEB92E1D013B324639462D +:102A5000DBB204F10C00FFF769FA0028BADB2A7B2D +:102A60003146013AB88AD2B2E2E700BF80841E0044 +:102A700040420F00F98A013BC1F309010429DAB28F +:102A80005DD80023281D07F11B069A4208D910F8CB +:102A900001CB013306F801C001310529DBB2F4D1C5 +:102AA000934228BF0023039938BF04330A91049945 +:102AB00038BFDBB20B9107F11B010C91796838BF6D +:102AC0005B190D910E93FB8AADF83EB0C3F3090379 +:102AD0001A44069BADF83C208DF84230059B8DF8DA +:102AE00040A08DF8433094F82C308DF8418083F06D +:102AF00001038DF8443000237B602A7BB88A013AB9 +:102B0000291DFFF767F93B8BB882834203D120462A +:102B1000A3680AA9984720460AA9FFF7FBFDFB7D99 +:102B2000BA8AC3F38403013303F01F039B02FB82C1 +:102B30003B8B9A420CBF00206FF01000BAE67B6816 +:102B4000002BADD0052001E033461C301E68002E5E +:102B5000FAD1091A081D2E1D184401EB090CBCF10D +:102B60001B0F5FFA89F39BD89A4299D916F8013B5B +:102B700009F1010900F8013BEFE76FF0090099E660 +:102B80006FF00A0096E66FF00B0093E66FF00D0011 +:102B900090E66FF00E008DE66FF00F008AE600BF42 +:102BA000F0B53F4D3F4FEB6943F00073EB61EB69CC +:102BB0003D4B9B6AD3F800623E4046F00106C3F8E5 +:102BC0000062D3F800423C4044EA002444F001048F +:102BD000C3F80042002955D000200646C3F81C0265 +:102BE000C3F80402C3F80C02C3F8140203EBC004D8 +:102BF00001300E28C4F84062C4F84462F6D10027C0 +:102C00004FF0010C9678148816F0010F18BFD3F816 +:102C100004E20CFA04F01CBF40EA0E0EC3F804E212 +:102C200016F0020F18BFD3F80CE203EBC4041CBF6C +:102C300040EA0E0EC3F80CE2760748BFD3F81462E0 +:102C400007F1010744BF0643C3F814625668B9424E +:102C5000C4F84062966802F10C02C4F84462D3F8EA +:102C60001C4240EA0400C3F81C02CBD1D3F8002276 +:102C700022F00102C3F80022EB6923F00073EB613C +:102C8000EB69F0BD0122C3F84012C3F84412C3F847 +:102C90000412C3F81412C3F80C22C3F81C22E5E78F +:102CA000001002400000FFFFA8230020184A08B5CA +:102CB000916A8B688B6013F0010104D013F00C0F44 +:102CC00018BF4FF48031D80506D513F4406F14BFF8 +:102CD00041F4003141F00201D80306D513F4402F2E +:102CE00014BF41F4802141F00401D3690BB10848BD +:102CF0009847302383F311880021064800F048FBF1 +:102D0000002383F31188BDE8084000F099BD00BF9F +:102D1000A8230020B023002038B5124CA36ADD6838 +:102D2000AA0712D05A6922F002025A61A36913B1AC +:102D3000012120469847302383F3118800210A4857 +:102D400000F026FB002383F31188EB0606D5102143 +:102D5000A36AD960236A0BB102489847BDE838409E +:102D600000F06EBDA8230020B823002038B5124C17 +:102D7000A36A1D69AA0712D05A6922F010025A618B +:102D8000A36913B1022120469847302383F31188A9 +:102D900000210A4800F0FCFA002383F31188EB06B7 +:102DA00006D51021A36A1961236A0BB1024898471E +:102DB000BDE8384000F044BDA8230020B82300201F +:102DC00038B50F4CA36A5D682A075D600AD50422F6 +:102DD00022701A6822F002021A60636A13B100219D +:102DE000204698476B0706D5A36A9969236A13B1F1 +:102DF000034809049847BDE8384000F021BD00BFF2 +:102E0000A823002010B50E4C204600F02FF90D4BE2 +:102E10000B211320A36200F009F90B21142000F00C +:102E200005F90B21152000F001F90B21162000F007 +:102E3000FDF8BDE8104000220E201146FFF7B0BE9D +:102E4000A8230020006400400F4B10B598420446B0 +:102E500005D10E4BDA6942F00072DA61DB690122BA +:102E6000A36A1A60A36A5A68D20707D562685168D4 +:102E70001268D9611A60064A5A6110BD0121082002 +:102E800000F0B0F9EEE700BFA823002000100240D8 +:102E90005B87010003291AD8DFE801F0020A0F144A +:102EA000836A9B6813F0E05F14BF01200020704725 +:102EB000836A9868C0F380607047836A9868C0F33B +:102EC000C0607047836A9868C0F300707047002044 +:102ED0007047000010B5032927D8DFE801F002276A +:102EE0002B2F836A9968C1F30161183103EB011339 +:102EF0001078840648BF5468C0F3001158BF948806 +:102F00004FEA410148BF41EAC40100F00F00586098 +:102F100048BF41F00401906858BF41EA4451D2686B +:102F200041F001019860DA60196010BD836A03F511 +:102F3000C073DDE7836A03F5C873D9E7836A03F5D5 +:102F4000D073D5E701290AD002290FD081B9836A4D +:102F5000DA68920701D1186903E001207047836A9B +:102F6000D86810F0030018BF01207047836AF2E7A9 +:102F70000020704710B539B9836AD96889071BD119 +:102F80001B699C0704D110BD012915D00229FAD173 +:102F9000816AD1F8C031D1F8C441D1F8C8011061BB +:102FA000D1F8CC015061202008610869800717D151 +:102FB000486940F0100012E0816AD1F8B031D1F8D0 +:102FC000B441D1F8B8011061D1F8BC0150612020A2 +:102FD000C860C868800703D1486940F002004861B2 +:102FE000C3F34000C3F38001000140EA41111079AE +:102FF00020F030000143117189064BBF916811899F +:10300000DB085B0D4CBF63F31C0163F30A0113790A +:1030100048BF916064F3030313714FEA14234FEA2E +:10302000144458BF118113705480ACE70122090188 +:1030300000F1604303F56143C9B283F8001300F067 +:103040001F039A4043099B0003F1604303F561436A +:10305000C3F880211A607047090100F16040C9B2CD +:1030600000F56D4001767047FFF7CCBE0123037079 +:10307000002300F10802C0E9022200F11002C0E9B9 +:103080000422C0E90633C0E90833436070470000FA +:1030900010B53023044683F3118802234160037086 +:1030A000FFF7D2FE04230020237080F3118810BDA7 +:1030B0002DE9F0411F4604460D461646302383F3A2 +:1030C000118800F108082378052B0DD029462046E9 +:1030D000FFF7E0FE40B1204632462946FFF7FAFEF0 +:1030E000002080F3118808E03946404600F040F99E +:1030F0000028E8D0002383F31188BDE8F0810000A8 +:103100002DE9F0411F4604460D461646302383F351 +:10311000118800F110082378052B0DD02946204690 +:10312000FFF710FF40B1204632462946FFF722FF45 +:10313000002080F3118808E03946404600F018F975 +:103140000028E8D0002383F31188BDE8F081000057 +:1031500000238268037503691B6899689142FBD25A +:103160005A680360426010605860704700238268AC +:10317000037503691B6899689142FBD85A6803601C +:10318000426010605860704708B50846302383F3EA +:1031900011880B7D032B05D0042B0DD02BB983F3A5 +:1031A000118808BD00228B691A604FF0FF338361DC +:1031B000FFF7CEFF0023F2E7D1E9003213605A6037 +:1031C000F3E70000FFF7C4BF054BD968087518681E +:1031D000026853601A6001220275D860FDF796BB41 +:1031E000D823002030B50C4B0446DD684B1C87B05B +:1031F0000FD02B466846094A00F0F0F82046FFF74A +:10320000E3FF009B13B1684600F0F0F8A86907B02F +:1032100030BDFFF7D9FFF9E7D82300208931000836 +:10322000044B1A68DB6890689B68984294BF002042 +:1032300001207047D8230020084B10B51C68D868BF +:10324000226853601A6001222275DC60FFF78EFF4E +:1032500001462046BDE81040FDF758BBD8230020AA +:10326000044B1A68DB6892689B689A4201D9FFF7A1 +:10327000E3BF7047D823002038B501230025064C52 +:10328000064907482370656000F020FB0223237085 +:1032900085F3118838BD00BF30250020B03D0008FF +:1032A000D823002000F0B4B8EFF3118020B9EFF379 +:1032B0000583302282F311887047000010B530B9C1 +:1032C000EFF30584C4F3080414B180F3118810BD32 +:1032D000FFF7C6FF84F31188F9E700008B60022333 +:1032E00008618B82084670478368A3F1440243F863 +:1032F000142C026943F8442C426943F8402C094AD3 +:1033000043F8242CC268A3F1200043F8182C0222B1 +:1033100003F80C2C002203F80B2C034A43F8102C62 +:10332000704700BF1D090008D823002008B5FFF72B +:10333000DBFFBDE80840FFF745BF0000024BDB683C +:1033400098610F20FFF740BFD8230020302383F37C +:103350001188FFF7F3BF000008B50146302383F35F +:1033600011880820FFF73EFF002383F3118808BD72 +:10337000064BDB6839B1426818605A6013604360DD +:103380000420FFF72FBF4FF0FF307047D8230020F5 +:1033900038B504460D462068844200D138BD036824 +:1033A00023605C608561FFF70DFFF4E710B50A4C00 +:1033B00023699A6891420CD85A6881600360426020 +:1033C00010609A685860511A99604FF0FF33A361FA +:1033D00010BD1B68891AECE7D8230020C0E903233D +:1033E000002310B410BC4361FFF7E0BF036881689D +:1033F0009A680A449A60426813605A6000234FF04A +:10340000FF320360014B9A61704700BFD823002050 +:1034100070B5124D2A46EB690133EB6152F8103F4B +:10342000934206D030269A68013A9A602C69A368C4 +:1034300003B170BDD4E900210A605160236083F3B9 +:1034400011882046D4E90331984786F311886169D1 +:103450000029EBD02046FFF7A9FFE7E7D82300209B +:1034600000207047FEE70000704700004FF0FF307B +:1034700070470000BFF34F8F024AD368DB07FCD4CC +:10348000704700BF0020024008B5074B1B7853B9B6 +:10349000FFF7F0FF054B1A69120641BF044A5A6054 +:1034A00002F188325A6008BD482500200020024001 +:1034B0002301674508B5054B1B7833B9FFF7DAFFE1 +:1034C000034A136943F08003136108BD48250020B7 +:1034D000002002407F289ABF00F5003080020020C3 +:1034E000704700004FF480607047000080207047F4 +:1034F0007F2808B50BD8FFF7EDFF00F58063026861 +:10350000013204D104308342F9D1012008BD0020EA +:10351000FCE700007F2810B504461CD8FFF7AAFF7F +:10352000FFF7B2FFF3220D4B4FF48061DA60022205 +:103530001A61FFF7CFFF58611A6942F040021A6121 +:10354000FFF798FF00F004F9FFF7B4FF2046BDE84D +:103550001040FFF7CDBF002010BD00BF002002408B +:103560002DE9F843054612F00100144606D040F25A +:10357000F32200201E4B1A60BDE8F8831D4BAA18E9 +:103580009A4204D94FF43E72194B1A60F4E7FFF7E0 +:103590007BFF4FF00109FFF76DFFDFF85C806D1ACC +:1035A000012C0F4605EB010603D8FFF783FF01202E +:1035B000E2E73B88C8F8109033800020FFF75AFFFD +:1035C000C8F81000338831F8022B9BB29A420CD015 +:1035D00040F20F32064B1A60084B1E60084B1C600D +:1035E000084B1F60FFF766FFC6E7023CD8E700BF45 +:1035F0004425002000000208002002403825002059 +:10360000402500203C250020084908B50B7828B14A +:103610001BB9FFF739FF01230B7008BD002BFCD04D +:10362000BDE808400870FFF745BF00BF48250020EF +:1036300070B5FFF739FE4FF47A710D4B0D4EDB6913 +:10364000326801FB03F3934237BF0B4A0A495168C2 +:10365000156836BF4C1CD1E9005454605D1944F123 +:1036600000043360FFF72AFE2846214670BD00BFE4 +:10367000D82300204C2500205025002070B5FFF7EE +:1036800013FE4FF47A710F4B0F4EDB69326801FB6A +:1036900003F3934237BF0D4A0C49516815683ABF8E +:1036A0004C1C5460D1E900545D1944F100043360AE +:1036B000FFF704FE4FF47A72002328462146FCF7F8 +:1036C00031FF70BDD82300204C250020502500205C +:1036D00010B5094C013AD2B2FF2A00D110BD5008F2 +:1036E00054F82030013054F820009BB243EA0043E4 +:1036F00041F8043BEEE700BF046C004010B50748FA +:10370000013AD2B2FF2A00D110BD0C88530840F80C +:1037100023404C88013340F82340F1E7046C00401B +:1037200007B50122002001A9FFF7D2FF019803B0DD +:103730005DF804FB13B50446FFF7F2FFA04205D085 +:103740000122002001A90194FFF7D8FF02B010BDAB +:103750007047000045F25552064B1A6002225A602B +:1037600040F6FF729A604CF6CC421A600122024B7E +:103770001A707047003000405C250020034B1B7816 +:103780001BB14AF6AA22024B1A6070475C25002042 +:1037900000300040044B1A682AB902F1804202F559 +:1037A0000432526A1A607047582500204FF0807228 +:1037B000014B5A62704700BF0010024008B5FFF786 +:1037C000E9FF024B1868C0F3407008BD582500207F +:1037D00008B5FFF7DFFF024B1868C0F3007008BDA3 +:1037E00058250020EFF30983203383F30988002351 +:1037F00083F3118870470000302080F3118862B68F +:103800000C4B0D4AD96821F4E0610904090C0A4304 +:10381000DA60D3F8FC20094942F08072C3F8FC203A +:103820000A6842F001020A602022DA7783F8220057 +:10383000704700BF00ED00E00003FA05001000E053 +:10384000302310B583F311880B4B5B6813F40063CE +:103850000FD0EFF309844FF08073203CE36184F3D1 +:103860000988FFF7DDFC10B1044BA36110BD044BC8 +:10387000FBE783F31188F9E700ED00E02F0900086A +:103880003209000870470000FEE700000A4B0B48B1 +:103890000B4A90420BD30B4BC11EDA1C121A22F0BA +:1038A00003028B4238BF00220021FDF7FFBE53F810 +:1038B000041B40F8041BECE7343E0008E025002020 +:1038C000E0250020E0250020FEE7000070B500257F +:1038D00004461A4B86B05860856201630E46FFF7B6 +:1038E0008BFF04F11003C4E904334FF0FF33A361ED +:1038F000134BE561D9692B460A462046C4E90823E3 +:1039000004F134018023C4E900440E4AA560E56255 +:103910002565FFF7E3FC01230B4AE0600375009285 +:10392000726868460192B268CDE90223074BCDE97F +:103930000435FFF7FBFC06B070BD00BF302500204A +:10394000D8230020BC3D0008C13D0008C93800084C +:1039500000F030B808B500F063F9FFF78DFCBDE862 +:103960000840FFF717BF0000704700004FF0FF311D +:103970000E4B1A6919611A6900221A611869D86810 +:10398000D960D968DA60DA68DA6942F08052DA61BF +:10399000DA69DA6942F00062DA61054ADB691368C4 +:1039A00043F48073136000F01BB900BF00100240A5 +:1039B00000700040194B1A6842F001021A601A6840 +:1039C0009007FCD51A6802F0F9021A6000225A60CA +:1039D0005A6812F00C0FFBD11A6842F480321A6058 +:1039E0001A689103FCD55A6842F4E8125A601A68C2 +:1039F00042F080721A601A689201FCD51221084ABE +:103A00005A60084A11605A6842F002025A605A68C5 +:103A100002F00C02082AFAD1704700BF00100240E1 +:103A200000641D0000200240084A08B5516913686F +:103A30000B4003F00103536123B1054A13680BB136 +:103A400050689847BDE80840FFF7FABE00040140FF +:103A500060250020084A08B5516913680B4003F03F +:103A60000203536123B1054A93680BB1D0689847AC +:103A7000BDE80840FFF7E4BE0004014060250020D7 +:103A8000084A08B5516913680B4003F004035361F9 +:103A900023B1054A13690BB150699847BDE8084046 +:103AA000FFF7CEBE0004014060250020084A08B59B +:103AB000516913680B4003F00803536123B1054AB1 +:103AC00093690BB1D0699847BDE80840FFF7B8BECD +:103AD0000004014060250020084A08B551691368B8 +:103AE0000B4003F01003536123B1054A136A0BB175 +:103AF000506A9847BDE80840FFF7A2BE00040140A5 +:103B000060250020174B10B55A691C68144004F456 +:103B100078725A61A30604D5134A936A0BB1D06A2E +:103B20009847600604D5104A136B0BB1506B984749 +:103B3000210604D50C4A936B0BB1D06B9847E20574 +:103B400004D5094A136C0BB1506C9847A30504D5F2 +:103B5000054A936C0BB1D06C9847BDE81040FFF755 +:103B60006FBE00BF00040140602500201A4B10B555 +:103B70005A691C68144004F47C425A61620504D5F9 +:103B8000164A136D0BB1506D9847230504D5134A9F +:103B9000936D0BB1D06D9847E00404D50F4A136EB6 +:103BA0000BB1506E9847A10404D50C4A936E0BB12B +:103BB000D06E9847620404D5084A136F0BB1506F5A +:103BC0009847230404D5054A936F0BB1D06F9847EB +:103BD000BDE81040FFF734BE00040140602500201E +:103BE000062108B50846FFF721FA06210720FFF74E +:103BF0001DFA06210820FFF719FA06210920FFF710 +:103C000015FA06210A20FFF711FA06211720FFF7FF +:103C10000DFABDE8084006212820FFF707BA00008A +:103C200008B5FFF7A3FE054800F00CF8FFF71CFAF3 +:103C3000FFF79AFEBDE8084000F002B8C83D000852 +:103C400000F042B8002319461C4A0133102BC2E988 +:103C5000001102F10802F8D1194B9A6942F07D0275 +:103C60009A619B690268174BDA6082685A60426801 +:103C70001A60C26803F58063DA6042695A600269BB +:103C80001A608269C3F80C24026AC3F80424C2696A +:103C9000C3F80024426AC3F80C28C26AC3F8042897 +:103CA000826AC3F80028026BC3F80C2C826BC3F83D +:103CB000042C426BC3F8002C704700BF6025002025 +:103CC00000100240000801404FF0E023044A0821A0 +:103CD0005A6100229A6107220B201A61FFF7BCB9D2 +:103CE0003F19010008B5302383F31188FFF7DAFA92 +:103CF000002383F3118808BD08B5FFF7F3FFBDE883 +:103D00000840FFF79DBD000010B501390244904204 +:103D100001D1002005E0037811F8014FA34201D042 +:103D2000181B10BD0130F2E72DE9F0419BB10446AC +:103D3000C91A1778014403F1FF3C8C42204601D98F +:103D4000002008E005780134BD42F6D10CEB0405F3 +:103D5000D618A54201D1BDE8F08115F8018D16F8FD +:103D600001EDF045F5D0E8E7034611F8012B03F823 +:103D7000012B002AF9D170476F72672E617264754A +:103D800070696C6F742E663130332D51696F7465B4 +:103D90006B5065726970680040A2E4F16468910636 +:103DA0000041A3E5F265699207000000633000005E +:103DB000AC3D000830240020302500206D61696E84 +:103DC0000069646C65000000001800004444414430 +:103DD000445449440100000042444444444444449F +:103DE00000000000444444444444444400000000B3 +:103DF0004444444444444444000000004444444493 +:103E00004444444450C7FF7F01000000000000000C +:103E1000E803000000000000009C0100000000001A +:103E2000640000000000000040420F00FE2A010074 +:043E3000D2040000B8 :00000001FF diff --git a/Tools/bootloaders/f103-RangeFinder_bl.bin b/Tools/bootloaders/f103-RangeFinder_bl.bin index d0d82766beb889..bc59ee7adab86c 100755 Binary files a/Tools/bootloaders/f103-RangeFinder_bl.bin and b/Tools/bootloaders/f103-RangeFinder_bl.bin differ diff --git a/Tools/bootloaders/f103-RangeFinder_bl.elf b/Tools/bootloaders/f103-RangeFinder_bl.elf index 2ecce5147fa7bd..4f85de7a629ca5 100755 Binary files a/Tools/bootloaders/f103-RangeFinder_bl.elf and b/Tools/bootloaders/f103-RangeFinder_bl.elf differ diff --git a/Tools/bootloaders/f103-RangeFinder_bl.hex b/Tools/bootloaders/f103-RangeFinder_bl.hex index 16c84aded7c66c..d9010ef8e65a7a 100644 --- a/Tools/bootloaders/f103-RangeFinder_bl.hex +++ b/Tools/bootloaders/f103-RangeFinder_bl.hex @@ -1,963 +1,998 @@ :020000040800F2 -:100000000009002069040008C114000865140008F4 -:10001000A514000865140008851400086B04000886 -:100020006B0400086B0400086B0400087D350008B1 -:100030006B0400086B0400086B040008113A000808 -:100040006B0400086B0400086B0400086B040008D4 -:100050006B0400086B0400083D370008693700088E -:1000600095370008C1370008ED3700086B04000819 -:100070006B0400086B0400086B0400086B040008A4 -:100080006B0400086B0400086B040008712400086E -:10009000DD240008312500088525000819380008EE -:1000A0006B0400086B0400086B0400086B04000874 -:1000B0006B0400086B0400086B0400086B04000864 -:1000C0006B0400086B0400086B0400086B04000854 -:1000D0006B04000825290008392900086B04000872 -:1000E000813800086B0400086B0400086B040008EA -:1000F0006B0400086B0400086B0400086B04000824 -:100100006B0400086B0400086B0400086B04000813 -:100110006B0400086B0400086B0400086B04000803 -:100120006B0400086B0400086B0400086B040008F3 -:100130006B0400086B0400086B0400086B040008E3 -:100140006B0400086B0400086B0400086B040008D3 -:100150006B0400086B0400086B0400086B040008C3 -:1001600053B94AB9002908BF00281CBF4FF0FF311E -:100170004FF0FF3000F076B9ADF1080C6DE904CE18 -:1001800000F006F8DDF804E0DDE9022304B0704772 -:100190002DE9F047089E0D4604468846002B4DD1B8 -:1001A0008A42944668D9B2FA82F252B101FA02F355 -:1001B000C2F1200120FA01F10CFA02FC41EA030825 -:1001C00094404FEA1C41B8FBF1F71FFA8CFE01FB8B -:1001D000178807FB0EF0230C43EA084398420AD91C -:1001E0001CEB030307F1FF3580F01E81984240F2BB -:1001F0001B81023F63441B1AB3FBF1F001FB103378 -:1002000000FB0EFEA4B244EA0344A6450AD91CEB47 -:10021000040400F1FF3380F00981A64540F2068115 -:10022000644402380021A4EB0E0440EA07401EB1EA -:100230000023D440C6E90043BDE8F0878B4208D9CB -:10024000002E00F0EE800021C6E900050846BDE85A -:10025000F087B3FA83F100294AD1AB4202D382423C -:1002600000F2FC80841A65EB030301209846002EFF -:10027000E2D0C6E90048DFE702B9FFDEB2FA82F257 -:10028000002A40F09180A1EB0C0001214FEA1C47AD -:100290001FFA8CFEB0FBF7F307FB1300250C45EAB1 -:1002A00000450EFB03F0A84208D91CEB050503F13D -:1002B000FF3802D2A84200F2CE8043462D1AB5FB89 -:1002C000F7F007FB10550EFB00FEA4B244EA05440C -:1002D000A64508D91CEB040400F1FF3502D2A6455F -:1002E00000F2B6802846A4EB0E0440EA03409EE7E5 -:1002F000C1F120078B4022FA07FC4CEA030C25FAD7 -:1003000007FA4FEA1C49BAFBF9F820FA07F309FB90 -:1003100018AA8D401FFA8CFE1D4300FA01F308FB5A -:100320000EF02C0C44EA0A44A04202FA01F20BD966 -:100330001CEB040408F1FF3A80F08880A04240F2F0 -:100340008580A8F102086444241AB4FBF9F009FB83 -:10035000104400FB0EFEADB245EA0444A64508D9A0 -:100360001CEB040400F1FF356CD2A6456AD90238B3 -:10037000644440EA0840A0FB0295A4EB0E04AC42A2 -:10038000C846AE4656D353D0002E69D0B3EB080210 -:1003900064EB0E0422FA01F304FA07F71F43CC4082 -:1003A000C6E90074002147E70CFA02FCC2F1200103 -:1003B00025FA01F34FEA1C4720FA01F195400D435D -:1003C000B3FBF7F107FB11331FFA8CFE280C40EA50 -:1003D000034001FB0EF3834204FA02F408D91CEB3C -:1003E000000001F1FF382FD283422DD90239604439 -:1003F000C01AB0FBF7F307FB1300ADB245EA0045A6 -:1004000003FB0EF0A84208D91CEB050503F1FF38E9 -:1004100016D2A84214D9023B6544281A43EA014186 -:1004200038E73146304607E72F46E4E61846F9E656 -:100430004B45A9D2B9EB020865EB0C0E0138A3E7D6 -:100440004346EAE7284694E74146D1E7D0467BE7B2 -:100450006444023847E7023B65442FE7084606E755 -:100460003146E9E6704700BF02E000F000F8FEE721 -:1004700072B6284880F30888274880F309882748FF -:100480004EF60851CEF200010860022080F3148875 -:10049000BFF36F8F03F0E4F803F0C0F803F0E2F865 -:1004A0004FF055301E491B4A91423CBF41F8040BA6 -:1004B000FAE71C49184A91423CBF41F8040BFAE79D -:1004C00019491A4A1A4B9A423EBF51F8040B42F896 -:1004D000040BF8E700201749174A91423CBF41F846 -:1004E000040BFAE703F09EF803F0BEF8134C144D2A -:1004F000AC4203DA54F8041B8847F9E700F03CF8F3 -:10050000104C114DAC4203DA54F8041B8847F9E74C -:1005100003F086B800090020001100200000000848 -:100520000001002000090020E83B00080011002025 -:100530002411002028110020A025002060010008BF -:100540006001000860010008600100082DE9F04F1B -:10055000C1F80CD0C3689D46BDE8F08F002383F33B -:1005600011882846A047002002F09CFDFEE702F01B -:1005700021FD00DFFEE700002DE9F04102F09CFFC5 -:10058000074602F0E7FF054600283ED12B4B9F426D -:100590003BD001339F423BD0294B27F0FF029A42C8 -:1005A0003AD1F8B200F052FAA84642F2107400F0C4 -:1005B00057FC08B10024A04600F04EFA064678B376 -:1005C00084BB464635B11F4B9F4203D0002402F046 -:1005D000B9FF2646002002F079FF1B4B9B6813F001 -:1005E000400322D00EB100F031F800F097FC00F08B -:1005F00077FE00F067FF0546CCB100F063FF401BBB -:10060000A04214D900F022F8F3E7A8460024CEE770 -:1006100004464FF00108CAE780464FF47A74C6E7F3 -:100620000446CFE74FF47A74CCE71C46DDE700F0D0 -:1006300025FD012002F03CFDDEE700BF010007B010 -:10064000000008B0263A09B0000C014038B51D4A38 -:100650001D4B1968013134D004339342F9D11B4C3E -:10066000194DD4F80424AA422BD3194B9B6803F1EB -:10067000006303F5C8439A4223D202F037FF02F029 -:1006800049FF002000F046FE0220124B187000F0D7 -:100690007DFE114BDA690022DA61D96999699A61A4 -:1006A0009B6972B64FF0E023C3F8085DD4F80034BC -:1006B000D4F80424202181F311889D4683F308880F -:1006C000104738BD2064000800640008006000087E -:1006D00000110020281100200010024049F269009A -:1006E000084A136899B21B0C00FB013344F25061B5 -:1006F0001360054B186882B2000C01FB0200186001 -:1007000080B27047201100201C11002010B5044653 -:100710000021102200F056FE034B03CB20606160E5 -:100720001868A06010BD00BFE8F7FF1F2DE9F04377 -:10073000BBB000F0C7FE40F2ED22204DAB68C31AFB -:10074000934232D906AF2B4628220021A8603846B2 -:1007500001F0C2FB05F10E0000F02CFE002604465D -:100760005FFA80F905F10E08F3B2F100994501F145 -:10077000280107D908EB06030822384601F0ACFB34 -:100780000136F1E708230122CDE902320C4B053492 -:1007900001933023A4B20093CDE9047405A3D3E9F7 -:1007A0000023297B074801F0ADF93BB0BDE8F08399 -:1007B000AFF3008078F6339F93CACD8D702100206F -:1007C0007D2100204421002070B50D4614461E46B0 -:1007D00001F02EF950B9022E10D1012C0ED112A326 -:1007E000D3E900230120C5E9002307E0282C10D01D -:1007F00005D8012C09D0052C0FD0002070BD302C5D -:10080000FBD10BA3D3E90023ECE70BA3D3E900232F -:10081000E8E70BA3D3E90023E4E70BA3D3E9002324 -:10082000E0E700BFAFF30080401DA12026812A0B26 -:1008300078F6339F93CACD8D9E6AC421818A46EE95 -:1008400026417272DF25D7B7F017304A39059E5618 -:1008500038B50D460446034620222846002101F003 -:100860003BFB22792346032A28BF0322284603F8AC -:10087000042F2021022201F02FFB62792346072A50 -:1008800028BF0722284603F8052F2221032201F062 -:1008900023FBA2792346072A28BF0722284603F80C -:1008A000062F2521032201F017FB284610222821BC -:1008B00004F1080301F010FB382038BD2DE9F04F9A -:1008C0000024ADF5037D10AE40F2751280460F4650 -:1008D00024A82146239400F075FD21464822304685 -:1008E00000F070FD00F0EEFD4FF47A72B0FBF2F014 -:1008F000544B23AD186093E80700012386E80700F6 -:100900000DF162003382FFF701FF4EF603033384DB -:1009100007AB18464C4903F0B3F82322294630644C -:10092000304686F83C20FFF793FF08220446014634 -:1009300014AB284601F0D0FA08222846A1180DF180 -:10094000510301F0C9FA082228460DF1520304F1BF -:10095000100101F0C1FA2022284615AB04F118015C -:1009600001F0BAFA4022284616AB04F1380101F032 -:10097000B3FA0822284618AB04F1780101F0ACFA6A -:10098000082228460DF1610304F1800101F0A4FA68 -:1009900004F1880A0DF1620904F5847B4B46514647 -:1009A000082228460AF1080A01F096FAD34509F10F -:1009B0000109F3D10822594628461DAB01F08CFAF3 -:1009C0004FF0000904F5887496F834304B450AD985 -:1009D000B36B21464B440822284601F07DFA0834C7 -:1009E00009F10109F0E74FF0000996F83C3004EBFB -:1009F000C9014B4508D9336C08224B44284601F005 -:100A00006BFA09F10109F0E700230393BB7E07317C -:100A1000029307F1190301930123C1F3CF01CDE93B -:100A200004510093404605A3D3E90023F97E01F069 -:100A300069F80DF5037DBDE8F08F00BF9E6AC42103 -:100A4000818A46EE2C110020903A0008014B187064 -:100A5000704700BF38110020F0B5334B85B01C7BC8 -:100A600034B10E22314B1A810024204605B0F0BD6E -:100A70002F4A02AB1068516803C308232D492E4842 -:100A80000DEB030202F0DCFF054630B90A22274BCA -:100A90002A481A8100F0E2FCE6E70169B1F5CE3F91 -:100AA00006D90B22214B26481A8100F0D7FCDCE73F -:100AB000438BB3F57A7F09D00C211C4A2148118160 -:100AC0004FF47A72194600F0C9FCCEE71E4A024480 -:100AD00002F11003994204D21022144B1B481A81D0 -:100AE000E3E710398E1A2046134900F0EFFC074661 -:100AF0003246204605F1180100F0E8FCAB689F4241 -:100B000002D1EB6898420AD00D22084B1A8100905E -:100B10003B46D5E902120E4800F0A0FCA4E70D48C0 -:100B200000F09CFC0124A0E7702100202C11002083 -:100B3000453B0008DC9B010000640008B43A000853 -:100B4000C03A0008D23A0008089CFFF7F03A0008C3 -:100B50000D3B0008363B00082DE9F04FADB006AF65 -:100B600080460C4600F064FF0546002859D1237EDC -:100B7000022B1AD1E38A012B17D100F0A3FC064601 -:100B8000FFF7ACFD4FF4C873B0FBF3F202FB1300A8 -:100B9000DFF8B49206F5167680B2E37E0644C9F813 -:100BA000006033B90022A94B1A709C37BD46BDE8DE -:100BB000F08FA38AEEB2013BB34205F101050BD9D8 -:100BC0003B1D1E44E900002308222046009601F048 -:100BD000F80101F043F8ECE707F11400FFF796FD88 -:100BE000324607F11401381D02F01AFF03460028AF -:100BF000D8D10F2E08D8954B1E70D9F80030A3F528 -:100C00001673C9F80030D0E7FA1CF870014600925C -:100C10002046072201F022F84046F97800F000FF54 -:100C2000C3E7E38A282B26D010D8012B1ED0052B32 -:100C3000BBD1BFF34F8F8649864BCA6802F4E0628E -:100C40001343CB60BFF34F8F00BFFDE7302BACD118 -:100C5000637E814D01336A7BDBB29342E94603D167 -:100C6000E27E2B7B9A4265D0CD469EE721464046E8 -:100C7000FFF724FE99E7A38A013B9BB2C92B94D8C6 -:100C8000754D2E7B26BB05F10C03009308223346DD -:100C90003146204600F0E2FF731CF2B2D9001E4636 -:100CA000A38A013B9A4205DA0E322A4400920023BD -:100CB0000822EEE700230022C5E900230023AB60F1 -:100CC00085F8D730C5F8D8302B7B0BB9E37E2B7372 -:100CD000002507F114060822294630463B1DC7E9C6 -:100CE0000155FD6001F0F8F83B7A05F10109AB42CE -:100CF0004FEAC90107D9FB6808222B44304601F0AE -:100D0000EBF84D46F0E70023C1F3CF01E07ECDE9DB -:100D100004610393A37E19340293282301460093B0 -:100D2000404647A3D3E90023019400F0EBFEFFF710 -:100D3000FDFC3AE74FF0000807F11403A7F8148010 -:100D40001022009341460123204600F087FFA68A27 -:100D5000023EB6B2F31C9B109B000733DB08A9EBE5 -:100D6000C3039D460DF1180A1FFA88F34FEAC80124 -:100D7000B34201F110010AD20AEB080300930822E2 -:100D80000023204600F06AFF08F10108ECE795F81F -:100D9000D70000F0C9FAD5F8D83004461BB995F849 -:100DA000D70000F0D1FAD5F8D83033449C4204D2B1 -:100DB00095F8D700013000F0C7FA4FF000084FEA6D -:100DC000960B1FFA88F18B45D5E9003209D90AEB59 -:100DD000880103EB8800012200F0FCFA08F1010809 -:100DE000EFE7F31842F10002C5E90032D5F8D83038 -:100DF00095F8D70006EB0308C5F8D88000F094FA00 -:100E0000804509D395F8D730D5F8D8000133001BB9 -:100E100085F8D730C5F8D800FF2E08D800232B73EB -:100E200000F0A4FAFFF718FE08B1FFF70FFC2B68DB -:100E30000A4A9B0A013313810023AB6014E700BF09 -:100E400026417272DF25D7B7402100203D210020C6 -:100E500000ED00E00400FA05702100202C110020B4 -:100E600030B54FF00054244B226885B09A4207D029 -:100E700002F07AFB0446A8B90024204605B030BD34 -:100E8000627D1E4B1E481A70237DC92203731D49C3 -:100E90000E3000F085FA2046E022002100F092FAA0 -:100EA0000124EAE7184A194DD36943F00073D3616E -:100EB000AA6D174B9A42DFD12B6E013B7E2BDBD8FC -:100EC000144A01AB07CA83E807001846032100F063 -:100ED00013FB6B6D83424FF00003CDD12A6D8A4224 -:100EE00003BFAB652A6E054B1C4601BF1A70EA6D45 -:100EF000094B1A60C1E700BF9AAD44C53811002004 -:100F00007021002016000020001002400066004002 -:100F10005041A0B0586600401811002002232DE96E -:100F2000F0434A4C85B0637100230293484BD3F8D9 -:100F300000C0BCF57A7F12D3464F474BB7FBFCF598 -:100F40009C458CBF0A231123B5FBF3F603FB165215 -:100F5000591EC8B2002A3ED002290B46F4D89DF88B -:100F60000B303E495A1E9DF80A303D48013B1B0498 -:100F700043EA0253BDF80820013A13434B6001F0E5 -:100F800037FD00230193374B374900934FF48052CC -:100F9000364B374800F01CFD364B197811B13448F8 -:100FA00000F03EFD00F08EFA0546FFF797FB4FF488 -:100FB000C873B0FBF3F202FB130305F516709BB286 -:100FC00018442D4B186002F0C5FA08B10F23238195 -:100FD00005B0BDE8F083731EB3F5806FBFD24FF448 -:100FE0007A75C0EBC00E0EF103034FEAE30909FB6B -:100FF0000555C3F3C703C11AC9B209F101088844F2 -:10100000B5FBF8F5B5F5617F08D90EF1FF33C3F3F1 -:10101000C703C11A581E0F28C9B214D84A1E072A7E -:101020008CBF00220122581800FB0660B7FBF0F7C6 -:10103000BC4594D1002A92D0ADF808608DF80A30F2 -:101040008DF80B108BE71346EDE700BF2C11002045 -:1010500018110020005125023F420F0010110020FE -:1010600088220020C90700083C110020590B000805 -:101070004421002038110020402100202DE9F04FAC -:1010800093A7D7E900670FF25029D9E90089854D68 -:1010900093B0DFF814B2854C284600F097FD0DF1AF -:1010A000300A079070B310220021504600F08AF9F0 -:1010B0004FF00002079B197B61F303028DF830208B -:1010C000586899680EAA03C21B680D9A584663F3C4 -:1010D0001C029DF830300D9243F020038DF8303023 -:1010E00000235246194601F093FC079028B9284680 -:1010F00000F070FD079B2370CEE72378072B3CD8C8 -:101100000133237018220021504600F05BF9DFF80C -:1011100098B1674C002352461946584601F0A0FC8E -:10112000014670BB102208A800F04CF9E36883F078 -:101130001003E36000F0C8F90DF1240C0B4612A96E -:10114000024611E903008CE803009DF83410C1F356 -:101150000300890649BF0E99BDF83810C1F31C0180 -:1011600041F0004158BFC1F30A018DF82C000891ED -:10117000284608A900F0F8FECCE7284600F02AFD32 -:10118000C0E7284600F054FC8346002844D100F014 -:1011900099F9484B1A6890423ED300F093F90446FF -:1011A000FFF79CFA4FF4C872B0FBF2F101FB12009A -:1011B0008DF820B0DFF800B13E4B04F5167480B214 -:1011C0009BF8001004441C6011B901238DF82030F5 -:1011D00050460791FFF79AFA07990DF12100C1F1E6 -:1011E0001004E4B2062C28BF06245144224600F025 -:1011F000D7F808AB039318230293304B01340193C3 -:101200000123E4B2009332463B462846049400F0A2 -:1012100011FC00238BF8003000F054F9284A294CC7 -:101220001368C31AB3F57A7F31D3106000F04CF91C -:1012300002460B46284600F0D7FC284600F0F8FB93 -:1012400028B3237BDFF880B0002B14BF03230223D5 -:101250008BF8053000F036F94FF47A73B0FBF3F0F9 -:101260005146CBF800005846FFF7F2FA18230293D4 -:10127000164B0730019340F25513C0F3CF00CDE970 -:1012800003A0009342464B46284600F0D3FB237B45 -:101290002BB1FFF74BFA237B002B7FF4FAAE13B090 -:1012A000BDE8F08F44210020882200205522002034 -:1012B00000080140402100203D2100203C21002069 -:1012C00050220020702100202C11002054220020E8 -:1012D000401DA12026812A0BF1C6A7C1D068080FA6 -:1012E00070B501F0BFFF0024084E094D308028681A -:1012F0003388834208D901F0B1FF2B6804440133DD -:10130000B4F5C84F2B60F2D370BD00BF842200201B -:101310005822002002F044B800F10060920000F56D -:10132000C84001F0DFBF0000054B1A68054B1B8861 -:101330009B1A834202D9104401F090BF00207047ED -:10134000582200208422002038B50446064D286823 -:10135000204401F089FF28B928682044BDE83840BE -:1013600001F094BF38BD00BF58220020064991F813 -:10137000243033B100230822086A81F82430FFF7B3 -:10138000CBBF0120704700BF5C220020022802BFB3 -:101390004FF48012014B1A61704700BF00080140F2 -:1013A000002310B5934203D0CC5CC4540133F9E759 -:1013B00010BD000003460246D01A12F9011B002995 -:1013C000FAD1704703460244934202D003F8011B4E -:1013D000FAE770472DE9F8431F4D144695F824208D -:1013E0000746884652BBDFF870909CB395F82430CE -:1013F0002BB92022FF2148462F62FFF7E3FF95F823 -:1014000024004146C0F10802A24228BF224605EB53 -:101410008000D6B29200FFF7C3FF95F82430A41BDA -:101420001E44F6B2082E17449044E4B285F82460B6 -:10143000DBD1FFF79BFF0028D7D108E02B6A03EB35 -:1014400082038342CFD0FFF791FF0028CBD1002049 -:10145000BDE8F8830120FBE75C2200200FB40020E8 -:1014600004B07047EFF30983EFF30583044B9A6BE5 -:10147000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE72A -:1014800000ED00E0EFF30983EFF30583044B9A6B63 -:101490009A6A9A6A9A6A9A6A9A6A9B6AFEE700BF8F -:1014A00000ED00E0EFF30983EFF30583034B5A6B84 -:1014B0009A6A9A6A9A6A9A6A9B6AFEE700ED00E065 -:1014C000FEE7000001F0A6BF01F07EBF30B5094D78 -:1014D0000A4491420DD011F8013B5840082340F3D3 -:1014E0000004013B2C4013F0FF0384EA5000F6D1C6 -:1014F000EFE730BD2083B8ED4FF0FF33F7B500EBD9 -:1015000081061946DFF848C0DFF848E0B0421BD03A -:1015100050F8042B01AF0192042217F8014B81EA25 -:10152000046108240D46DB184941013C002DBCBF75 -:1015300083EA0C0381EA0E0114F0FF04F2D1013AB0 -:1015400012F0FF02E9D1E1E7D843C94303B0F0BD8F -:101550009336EAA9EBE1F0422DE9F041C56915B9EE -:10156000C161BDE8F0814B68AC4623F06047C3F32E -:101570008A4616EA230638BF3E464FEAD37EC3F3B7 -:1015800080782B465A68BEEBD27F22F060440AD0A6 -:10159000002A18DAA40CB44217D19D420FD10D6075 -:1015A000DEE71346EEE7A74207D102F08044C2F31C -:1015B000807242450BD054B1EFE708D2EDE7CCF88A -:1015C00000100B60CDE7B44201D0B442E5D81A68F0 -:1015D0009C46002AE5D11960C3E700002DE9F047D9 -:1015E0004FF47F49089D01F007044FEAD5082244D3 -:1015F00005F0070500EBD100944201D1BDE8F0876A -:1016000004F0070705F0070A57453E4638BF56461F -:10161000111BC6F108068E4228BF0E46E108415C48 -:1016200008EBD50E13F80EC0B94029FA06F721FAD7 -:101630000AF1FFB28CEA010147FA0AF739408CEA55 -:10164000010C03F80EC034443544D5E7082341F2B9 -:10165000210280EA012001B24000002980B203F19A -:10166000FF33B8BF504013F0FF03F4D170470000C0 -:1016700038B50C468D18A54200D138BD14F8011BB1 -:10168000FFF7E4FFF7E700000346006848B102688F -:1016900019891A60DA88013292B29142DA8038BF31 -:1016A0001A81704770B504460D4688B0202200218B -:1016B0006846FFF787FE20460495FFF7E5FF0246E0 -:1016C00058B16B46054608AE1C4603CCB4422860B0 -:1016D0006960234605F10805F6D1104608B070BDD3 -:1016E000082817D909280CD00A280CD00B280CD0B0 -:1016F0000C280CD00D280CD00E2814BF4020302010 -:1017000070470C2070471020704714207047182035 -:101710007047202070470000082817D90C280CD9E2 -:1017200010280CD914280CD918280CD920280CD929 -:1017300030288CBF0F200E207047092070470A20E8 -:1017400070470B2070470C2070470D207047000039 -:1017500010B54B6823B9CA8A63F30902CA8210BD67 -:10176000C4681A681C60C360438A013B43824A60B4 -:10177000EFE700002DE9F84F1D46CB8A0F46C3F373 -:1017800009010629814692460B4630D00020AAB2B4 -:1017900007F119049EB2052E1FFA80F80FD8904564 -:1017A00003F1010306D3FB8A0A4462F30903012013 -:1017B000FB821AE01AF800600130E654EAE790452F -:1017C000F1D21C23A1F1060BBBFBF3F203FB12BB0E -:1017D0007C681FFA8BF6002C45D14846FFF754FF72 -:1017E000044638B978606FF00200BDE8F88F4FF01A -:1017F0000008E6E70026066078604FF0000BADB207 -:10180000454510D90AEB0803221D13F8011B08F106 -:1018100001089155B1B21B291FFA88F82BD0454514 -:1018200006F10106F1D8FB8AC3F30902154465F3FA -:101830000903BCE71C46013292B22368002BF9D1A0 -:10184000AB1F0B441C21B3FBF1F301339BB29A4253 -:10185000D3D2BBF1000FD0D14846FFF715FF20B916 -:10186000C4F800B0BFE70122E7E7C0F800B05E4669 -:1018700020600446C1E74545D5D94846FFF704FF37 -:1018800008B92060AFE7C0F800B000262060044629 -:10189000B6E700002DE9F04F85B007469146CDE947 -:1018A0000113BDF83C50002A00F08F802DB10E9B33 -:1018B000002B00F08A80072D30D807F10C00FFF7CD -:1018C000E3FE044628B96FF00204204605B0BDE8E7 -:1018D000F08F14220021FFF775FD2A460E9904F1BE -:1018E0000800FFF75DFD681CC0B2FFF715FFFFF7AA -:1018F000F7FE207499F80020431E9BB202F01F02ED -:10190000234462F03F021A72019B384643F00041C3 -:1019100061602146FFF720FE0124D6E74FF0000862 -:101920004FF0800A4646444600F10C0303930398A7 -:10193000FFF7AAFE83460028C5D014220021FFF736 -:1019400041FD002E38D10220029BABF808300E9BDF -:1019500000F10802D2B299195A440130C0B20828E5 -:1019600001D0AE422AD3FFF7D7FEFFF7B9FEAE4251 -:1019700008BF4FF0400A99F80020019B411E02F079 -:101980001F0242EA4812C9B24AEA020A594443F025 -:10199000004281F808A08BF8100059463846CBF871 -:1019A0000420FFF7D9FD0134AE424FF0000A24B203 -:1019B00088F00108BBD188E70020C8E711F801CB07 -:1019C000013602F801CBB6B2C7E76FF001047CE73D -:1019D000F8B5044615460E46282200211F46FFF79B -:1019E000F1FC069BB5F5001F6360079B28BF4FF60F -:1019F000FF7223624FF0000338BF6A09A76004F149 -:101A00000C0097B29A4205D80023036027826382B4 -:101A1000A382F8BD0660013330462036F2E70000AD -:101A200003781BB94BB2002BC8BF01707047000090 -:101A3000007870472DE9F74FDDF83C9080469246DC -:101A40009B46BDF830500D9E9DF83840BDF8407063 -:101A5000B9F1000F01D1002F51D11F2C4FD898F8A8 -:101A60000000B0B9072F47D835F0030347D13A46F5 -:101A700049464FF6FF70FFF7FBFD20F001002D02F5 -:101A8000400445EA0464400C44EA40244FF6FF73E6 -:101A900021E040EA0520072F40EA0464F6D900253A -:101AA0004FF6FF73C5F12000A5F120022AFA05F1D7 -:101AB0000BFA00F001432BFA02F211431846C9B2A7 -:101AC000FFF7C4FD0835402D0346EBD13A464946A1 -:101AD000FFF7CEFD0346324621464046CDE900974A -:101AE000FFF7D8FE33780133DBB21F2B88BF00230A -:101AF000337003B0BDE8F08F6FF00300F9E76FF0CB -:101B00000100F6E72DE9F04F85B0DDF848809246F8 -:101B100006469B460F9D9DF840209DF84490BDF8D9 -:101B20004C70B8F1000F01D1002F48D11F2A46D8C0 -:101B30003378002B46D00C0244EA02649DF838103A -:101B400044EAC93444EA01441C43072F44F08004AA -:101B500032D900234FF6FF72C3F1200CA3F120000D -:101B60002AFA03F10BFA0CFC41EA0C012BFA00F003 -:101B70000143C9B210460393FFF768FD039B024679 -:101B80000833402BE8D13A464146FFF771FD034642 -:101B90002A4621463046CDE90087FFF77BFEB9F1A2 -:101BA000010F06D12B780133DBB21F2B88BF002336 -:101BB0002B7005B0BDE8F08F4FF6FF73E8E76FF0CC -:101BC0000100F6E76FF00300F3E70000C06900B121 -:101BD00004307047C3691A68C261C2681A60C36082 -:101BE000438A013B438270472DE9F041D0F81880C9 -:101BF00014461D4641460027174E09B9BDE8F0813D -:101C0000D1E90223A21A65EB0303964277EB0303A3 -:101C10001ED283698B420DD1FFF79AFD83691B6841 -:101C20008361C3680B60438AC1608169013B884658 -:101C30004382E2E7FFF78CFD0B68C8F80030C36809 -:101C40000B60438AC160013B4382D8F80010D4E79F -:101C500088460968D1E700BF80841E002DE9F04F57 -:101C60008BB00D4614469B468046DDF85090002808 -:101C700000F01A81B9F1000F00F01681531E3F2BBE -:101C800000F21281012A03D1BBF1000F40F00C8158 -:101C90000023CDE90833B8F81430B5EBC30F4FEA91 -:101CA000C30703D300200BB0BDE8F08F2B199F4270 -:101CB000D8F80C3036BF7F1B2746FFB21BB9D8F8C7 -:101CC0001030002B7BD02F2D4ED8C5F13006B742F7 -:101CD0004FF0000334BF3E46F6B200932946324629 -:101CE000D8F8080008ABFFF779FCA7EB060A3544E3 -:101CF0005FFA8AFA3021B8F8143003F10053063B3A -:101D0000DB000493D8F80C300393039B13B1BAF1B2 -:101D1000000F2CD1D8F8100040B1BAF1000F05D057 -:101D20005246009608AB691AFFF758FC38B2002FEC -:101D3000B8D066070AD00AAB03EBD40111F8083C0F -:101D4000624202F00702134101F8083C082C3DD919 -:101D5000102C40F2B680202C40F2B880BBF1000F6E -:101D600000F09D80082335E0BA460026C2E7049BB8 -:101D7000E02B28BFE02306930B44AB42059315D913 -:101D80005A1B924538BF5246039828BFD2B20096DC -:101D9000691A08AB04300792FFF720FC079A164433 -:101DA000AAEB020A1544F6B25FFA8AFA049B069A75 -:101DB00005999B1A0493039B1B680393A5E7009363 -:101DC0003A462946D8F8080008ABADE7BBF1000F4A -:101DD00013D00123B4EBC30F6CD0082C12D89DF89C -:101DE0002030621E23FA02F2D50706D54FF0FF32EB -:101DF00002FA04F423438DF820309DF8203089F84E -:101E0000003050E7102C12D8BDF82030621E23FAA3 -:101E100002F2D10706D54FF0FF3202FA04F4234351 -:101E2000ADF82030BDF82030A9F800303BE7202C79 -:101E30000FD80899631E21FA03F3DA0705D54FF08E -:101E4000FF3202FA04F40C430894089BC9F80030EE -:101E500029E7402C2BD0DDE90865611EC4F1210281 -:101E6000A4F1210326FA01F105FA02F225FA03F39F -:101E700011431943CB0712D50122A4F12003C4F169 -:101E8000200102FA03F322FA01F1A240524243EA8E -:101E9000010363EB430332432B43CDE90823DDE920 -:101EA0000823C9E90023FEE66FF00100FBE66FF0AE -:101EB0000800F8E6082CA0D9102CB3D9202CEED8B5 -:101EC000C3E7BBF1000FADD0022383E7BBF1000FE6 -:101ED000BBD004237EE70000012A30B5144638BF8A -:101EE00001220025402A28BF402285B0012CCDE9DF -:101EF000025517D81B788DF8083053070AD004AB69 -:101F000003EBD20515F8083C544204F00704A34043 -:101F100005F8083C0346009102A80021FFF75EFB8C -:101F200005B030BD082CE5D9102C03D81B88ADF8BE -:101F30000830E2E7202C02D81B680293DDE7D3E9E2 -:101F40000045CDE90245D8E710B5CB681BB98B60D9 -:101F50000B618B8210BDC4681A681C60C360438A21 -:101F6000013B4382CA60F0E72DE9F04FD1F80080D1 -:101F700093B018F0800FCDE90323C8F3C01207BF58 -:101F80004FF0020B1646C8F3C03BC8F30626B8F163 -:101F9000000F04460D4680F2D48118F0C04305932B -:101FA00040F0CF810B7B002B00F0CB81BBF1020F07 -:101FB00003D00178B14240F0C78108F07F0107915A -:101FC0007AB3C8F3074A2B4493F80390760646EA9F -:101FD0000B4608F07F0246EA82465FEAD91346EADA -:101FE0000A06069300F0918000220023CDE90A231F -:101FF00008F07F03009352465B46204667680AA9B3 -:10200000B84700287ED0A7699FB9314604F10C007B -:10201000FFF748FB0746E0B96FF0020013B0BDE8D8 -:10202000F08FC8F30F2A18F07F0F08BF0AF0030AD9 -:10203000C9E73B699E420DD03F68002FF9D1314678 -:1020400004F10C00FFF72EFB07460028E4D0A3693B -:102050003B60A7610026DDE90A234FF6FF70C6F159 -:10206000200E22FA06F103FA0EFEA6F1200C23FA46 -:102070000CFC41EA0E0141EA0C01C9B20836099292 -:102080000893FFF7E3FADDE90832402EE7D1B88282 -:10209000FB7D09F01F06C3F384039B1B98B2002B42 -:1020A000BCBF00F120031BB2D7E9022152EA0100B4 -:1020B000C8F304680FD00398821A049860EB0101FA -:1020C000A74890424FF000028A4104D3069A002AA2 -:1020D0005BD0012B23DDFA7D4FEA890302F0030276 -:1020E00003F07C031343FB7539462046FFF730FBB2 -:1020F000069BA3B9FB7DC3F38402013262F386031E -:10210000FB7504E06FF00B0088E7A76917B96FF063 -:102110000C0083E73B699E42BAD03F68F6E719F0AE -:10212000400F32D0039B1422BB60049B0021FB6054 -:102130000DA8FFF747F9039B20460A93049BADF8CF -:102140003EA00B932B1D0C932B7B8DF840B0013BD5 -:10215000DBB2ADF83C30079B8DF841608DF8433021 -:1021600094F824308DF8428083F001038DF84430D8 -:102170000AA9A3689847FB7DC3F38403013303F0E6 -:102180001F039B02FB82002048E7FB7DC9F340123E -:10219000B2EBD31F40F0DB80C3F38403B34240F0C3 -:1021A000D98006992B7B4FEA9912002934D0D207A7 -:1021B00041D4032B40F2D180039BAE1DBB60049B36 -:1021C0003246FB602B7B3946033BDBB204F10C004B -:1021D000FFF7D0FA00280DDA20463946FFF7B8FAA3 -:1021E000FB7D0320C3F38403013303F01F039B0231 -:1021F000FB8213E7AB883B832A7B033AB88AD2B2CF -:102200003146FFF735FAFB7DB882DA43C2F3C012DC -:1022100062F3C713FB75B6E76AB92E1D013B324660 -:102220003946DBB204F10C00FFF7A4FA0028D3DB37 -:102230002A7B013AE2E7F98A013BC1F3090105294A -:10224000DAB25BD80023281D07F11A0C9A4208D98C -:1022500010F801EB01330CF801E001310629DBB283 -:10226000F4D1934228BF0023039938BF04330A9165 -:10227000049938BFDBB20B9107F11A010C91796810 -:1022800038BF5B190D910E93FB8AADF83EA0C3F3E6 -:1022900009031A44079BADF83C208DF8433094F8AD -:1022A00024308DF840B083F001038DF844300023D2 -:1022B0008DF841608DF842807B602A7BB88A013AB4 -:1022C000291DFFF7D5F93B8BB882834203D1204605 -:1022D000A3680AA9984720460AA9FFF735FEFB7DA7 -:1022E000B88AC3F38403013303F01F039B02FB820C -:1022F0003B8B984214BF112000208FE67B68002B97 -:10230000AFD0062001E063461C30D3F800C0BCF11A -:10231000000FF8D1091A081D05F1040C1844DDF866 -:1023200014E09DF814308E44BEF11B0F99D89A42E8 -:1023300097D91CF8013B00F8013B059B013305933D -:10234000EDE76FF0090069E66FF00A0066E66FF0EE -:102350000D0063E66FF00E0060E66FF00F005DE6C3 -:1023600080841E00F0B53F4D3F4FEB6943F0007392 -:10237000EB61EB693D4B9B6AD3F800623E4046F04F -:102380000106C3F80062D3F800423C4044EA00244E -:1023900044F00104C3F80042002955D0002006464D -:1023A000C3F81C02C3F80402C3F80C02C3F81402F9 -:1023B00003EBC00401300E28C4F84062C4F8446244 -:1023C000F6D100274FF0010C9678148816F0010F13 -:1023D00018BFD3F804E20CFA04F01CBF40EA0E0E5A -:1023E000C3F804E216F0020F18BFD3F80CE203EBB7 -:1023F000C4041CBF40EA0E0EC3F80CE2760748BFC7 -:10240000D3F8146207F1010744BF0643C3F814620E -:102410005668B942C4F84062966802F10C02C4F8EA -:102420004462D3F81C4240EA0400C3F81C02CBD13A -:10243000D3F8002222F00102C3F80022EB6923F056 -:102440000073EB61EB69F0BD0122C3F84012C3F8E1 -:102450004412C3F80412C3F81412C3F80C22C3F8D0 -:102460001C22E5E7001002400000FFFF8822002048 -:10247000184A08B5916A8B688B6013F0010104D08B -:1024800013F00C0F18BF4FF48031D80506D513F4A4 -:10249000406F14BF41F4003141F00201D80306D56A -:1024A00013F4402F14BF41F4802141F00401D3699B -:1024B0000BB108489847202383F311880021064870 -:1024C00000F01EFE002383F31188BDE8084001F0F0 -:1024D00083B800BF882200209022002038B5124C1B -:1024E000A36ADD68AA0712D05A6922F002025A6173 -:1024F000A36913B1012120469847202383F3118853 -:1025000000210A4800F0FCFD002383F31188EB064C -:1025100006D51021A36AD960236A0BB102489847F7 -:10252000BDE8384001F058B88822002098220020E9 -:1025300038B5124CA36A1D69AA0712D05A6922F055 -:1025400010025A61A36913B1022120469847202343 -:1025500083F3118800210A4800F0D2FD002383F3A1 -:102560001188EB0606D51021A36A1961236A0BB105 -:1025700002489847BDE8384001F02EB88822002074 -:102580009822002038B50F4CA36A5D682A075D6069 -:102590000AD5042222701A6822F002021A60636AC5 -:1025A00013B10021204698476B0706D5A36A9969A5 -:1025B000236A13B1034809049847BDE8384001F085 -:1025C0000BB800BF8822002010B50E4C204600F04A -:1025D000FDF90D4B0B211320A36200F0D7F90B215D -:1025E000142000F0D3F90B21152000F0CFF90B21B6 -:1025F000162000F0CBF9BDE8104000220E20114655 -:10260000FFF7B0BE88220020006400400F4B10B5D9 -:102610009842044605D10E4BDA6942F00072DA6145 -:10262000DB690122A36A1A60A36A5A68D20707D538 -:10263000626851681268D9611A60064A5A6110BD11 -:102640000121082000F052FCEEE700BF88220020A4 -:10265000001002405B87010003291AD8DFE801F06F -:10266000020A0F14836A9B6813F0E05F14BF012015 -:1026700000207047836A9868C0F380607047836A5F -:102680009868C0F3C0607047836A9868C0F30070B0 -:10269000704700207047000010B5032927D8DFE8F5 -:1026A00001F002272B2F836A9968C1F30161183169 -:1026B00003EB01131078840648BF5468C0F300117F -:1026C00058BF94884FEA410148BF41EAC40100F075 -:1026D0000F00586048BF41F00401906858BF41EABC -:1026E0004451D26841F001019860DA60196010BD70 -:1026F000836A03F5C073DDE7836A03F5C873D9E71E -:10270000836A03F5D073D5E701290AD002290FD0D7 -:1027100081B9836ADA68920701D1186903E0012060 -:102720007047836AD86810F0030018BF0120704713 -:10273000836AF2E70020704710B539B9836AD96817 -:1027400089071BD11B699C0704D110BD012915D035 -:102750000229FAD1816AD1F8C031D1F8C441D1F847 -:10276000C8011061D1F8CC015061202008610869CE -:10277000800717D1486940F0100012E0816AD1F853 -:10278000B031D1F8B441D1F8B8011061D1F8BC0131 -:1027900050612020C860C868800703D1486940F0B4 -:1027A00002004861C3F34000C3F38001000140EA26 -:1027B0004111107920F030000143117189064BBF9F -:1027C00091681189DB085B0D4CBF63F31C0163F357 -:1027D0000A01137948BF916064F3030313714FEA50 -:1027E00014234FEA144458BF118113705480ACE78E -:1027F000026843680A43026003B11847704700004B -:10280000024AD36843F0C003D360704700380140E8 -:10281000024AD36843F0C003D360704700440040CD -:102820002DE9F041D0F89C600446F7683368DA057A -:102830009DB20DD5202383F311884FF4007104302D -:10284000FFF7D6FF6FF480733360002383F31188A2 -:10285000202383F3118804F1040815F02F033AD1E3 -:1028600083F31188380615D5290613D5202383F361 -:10287000118804F1380000F02FFA00284DDA082101 -:10288000201DFFF7B5FF4FF67F733B40F360002339 -:1028900083F311887A0616D56B0614D5202383F3AB -:1028A0001188D4E913239A420AD1236C43B127F04B -:1028B00040073F041021201D3F0CFFF799FFF760F0 -:1028C000002383F31188D4F8A420D3683BB3BDE878 -:1028D000F041106918472B0713D015F0080F0CBFF3 -:1028E00000218021E80748BF41F02001AA0748BF26 -:1028F00041F040016B07404648BF41F48071FFF74B -:1029000077FFAD06736805D594F8A01020461940EE -:1029100000F082FA3568ADB29FE77060B7E7BDE8B6 -:10292000F081000008B50348FFF77AFFBDE80840D2 -:1029300000F052BEB422002008B50348FFF770FF34 -:10294000BDE8084000F048BE5C23002010B5094CEB -:1029500000212046084A00F03FFA084B0021C4F845 -:102960009C30074C074A204600F036FA064BC4F864 -:102970009C3010BDB422002001280008003801401E -:102980005C230020112800080044004001220901B6 -:1029900000F1604303F56143C9B283F8001300F00E -:1029A0001F039A4043099B0003F1604303F5614311 -:1029B000C3F880211A607047090100F16040C9B274 -:1029C00000F56D4001767047FFF7FEBD01230370EF -:1029D000002300F10802C0E9022200F11002C0E960 -:1029E0000422C0E90633C0E90833436070470000A1 -:1029F00010B52023044683F311880223416003703D -:102A0000FFF704FE04232370002383F3118810BD15 -:102A10002DE9F0411F4604460D461646202383F358 -:102A2000118800F108082378052B0DD0294620468F -:102A3000FFF712FE40B1204632462946FFF72CFE32 -:102A4000002080F3118808E03946404600F03CFB46 -:102A50000028E8D0002383F31188BDE8F08100004E -:102A60002DE9F0411F4604460D461646202383F308 -:102A7000118800F110082378052B0DD02946204637 -:102A8000FFF742FE40B1204632462946FFF754FE8A -:102A9000002080F3118808E03946404600F014FB1E -:102AA0000028E8D0002383F31188BDE8F0810000FE -:102AB000F8B5154682680B46AA428169066938BF97 -:102AC0008568761AB54204460BD218462A46FEF7A8 -:102AD00067FCA3692B44A361A36828465B1BA36022 -:102AE000F8BD0CD918463246FEF75AFCAF1B3A46E1 -:102AF000E1683044FEF754FCE3683B44EBE71846DA -:102B00002A46FEF74DFCE368E5E700002DE9F041B9 -:102B1000154683680446934238BF8568D0E904703F -:102B20003F1ABD420E460BD22A46FEF739FC6369B6 -:102B30002B446361A36828465B1BA360BDE8F0815A -:102B40000CD93A46A5EB0708FEF72AFC4246E06896 -:102B5000F119FEF725FCE3684344EAE72A46FEF74D -:102B60001FFCE368E5E7000010B50024C361029B89 -:102B7000C0E90511C1601144C0E900008460016131 -:102B8000036210BD08B5D0E90532934201D18268D5 -:102B900092B98268013282605A1C42611970D0E990 -:102BA00004329A4228BFC3684FF0000128BF436136 -:102BB00000F09AFA002008BD4FF0FF30FBE700005C -:102BC00070B5202304460D4683F31188A668A6B18C -:102BD000A368A269013BA360531CA3611578226915 -:102BE000934224BFE368A361E3690BB12046984791 -:102BF000002383F31188284607E02946204600F089 -:102C000063FA0028E2DA86F3118870BD2DE9F74FE8 -:102C100004460E4617469846D0F81C904FF0200AFE -:102C20008AF311884FF0000B154665B12A463146EC -:102C30002046FFF73DFF034660B94146204600F0BD -:102C400043FA0028F1D0002383F31188781B03B0E6 -:102C5000BDE8F08FB9F1000F03D001902046C847BE -:102C6000019B8BF31188ED1A1E448AF31188DCE76F -:102C7000C361009BC0E90511C1601144C0E90000B7 -:102C80008260016103627047F8B504460D4616463E -:102C9000202383F31188A768A7B1A368013BA36031 -:102CA00063695A1C62611D70D4E904329A4224BFE0 -:102CB000E3686361E3690BB120469847002080F325 -:102CC000118807E03146204600F0FEF90028E2DADC -:102CD00087F31188F8BD0000D0E905239A4210B5AA -:102CE00001D182687AB982680021013282605A1C5F -:102CF00082611C7803699A4224BFC368836100F033 -:102D0000F3F9204610BD4FF0FF30FBE72DE9F74FF8 -:102D100004460E4617469846D0F81C904FF0200AFD -:102D20008AF311884FF0000B154665B12A463146EB -:102D30002046FFF7EBFE034660B94146204600F00F -:102D4000C3F90028F1D0002383F31188781B03B066 -:102D5000BDE8F08FB9F1000F03D001902046C847BD -:102D6000019B8BF31188ED1A1E448AF31188DCE76E -:102D7000026843680A43026003B1184770470000C5 -:102D80001430FFF743BF00004FF0FF331430FFF75C -:102D90003DBF00003830FFF7B9BF00004FF0FF33F0 -:102DA0003830FFF7B3BF00001430FFF709BF000051 -:102DB0004FF0FF311430FFF703BF00003830FFF74A -:102DC00063BF00004FF0FF323830FFF75DBF0000F7 -:102DD00000207047FFF7BABD37B515460D4A0446C7 -:102DE000026000224260C0E9022201220B46027406 -:102DF00000F15C01009020221430FFF7B5FE2B4655 -:102E00002022009404F17C0104F13800FFF730FF28 -:102E100003B030BD503B000838B5C36904460D46C9 -:102E20001BB904210844FFF7A3FF294604F114004D -:102E3000FFF7A8FE002806DA201D4FF48061BDE8E8 -:102E40003840FFF795BF38BD0022024BC3E900337D -:102E50009A60704704240020002382680374054BA5 -:102E60001B6899689142FBD25A6803604260106007 -:102E7000586070470424002008B5202383F311888C -:102E8000037C032B05D0042B0DD02BB983F31188C1 -:102E900008BD002243691A604FF0FF334361FFF71A -:102EA000DBFF0023F2E7D0E9003213605A60F3E75A -:102EB000002382680374054B1B6899689142FBD814 -:102EC0005A68036042601060586070470424002014 -:102ED000054B196908741868026853601A60186114 -:102EE00001230374FDF732BB0424002030B54B1CD2 -:102EF00004460B4D87B010D02B690A4A01A800F098 -:102F00001BF92046FFF7E4FF049B13B101A800F072 -:102F10002FF92B69586907B030BDFFF7D9FFF8E7E3 -:102F200004240020792E000838B50C4D41612B692E -:102F300081689A680446914203D8BDE83840FFF79B -:102F40008BBF1846FFF7B4FF01232C6101462374A1 -:102F50002046BDE83840FDF7F9BA00BF0424002040 -:102F6000044B1A681B6990689B68984294BF0020C4 -:102F7000012070470424002010B5084C2368206904 -:102F80001A6854602260012223611A74FFF790FFCF -:102F900001462069BDE81040FDF7D8BA042400209E -:102FA00008B5FFF7DDFF18B1BDE80840FFF7E4BF43 -:102FB00008BD0000FFF7E0BFFEE7000010B50C4CB5 -:102FC000FFF742FF00F0AAF880220A49204600F0ED -:102FD00031F8012344F8180C037400F0D9FA0023E7 -:102FE00083F3118862B6BDE81040034800F042B890 -:102FF0002C240020783B0008883B000800F0CAB869 -:10300000EFF3118020B9EFF30583202282F31188BA -:103010007047000010B530B9EFF30584C4F308041D -:1030200014B180F3118810BDFFF7BAFF84F3118843 -:10303000F9E7000082600222028270478368A3F1F0 -:103040003C0243F80C2C026943F83C2C426943F8DB -:10305000382C074A43F81C2CC268A3F1180043F827 -:10306000102C022203F8082C002203F8072C7047CA -:103070005D05000810B5202383F31188FFF7DEFFFC -:1030800000210446FFF750FF002383F311882046F8 -:1030900010BD0000024B1B6958610F20FFF718BFDD -:1030A00004240020202383F31188FFF7F3BF0000DE -:1030B00008B50146202383F311880820FFF716FF87 -:1030C000002383F3118808BD49B1064B42681B6990 -:1030D00018605A60136043600420FFF707BF4FF089 -:1030E000FF3070470424002003460068834205D067 -:1030F00002681A6053604161FFF7AEBE704700007E -:1031000038B504460D462068844200D138BD0368B6 -:1031100023605C604561FFF79FFEF4E7054B03F118 -:103120001402C3E905224FF0FF32DA6100221A626D -:10313000704700BF0424002010B5C0E903230B4AE8 -:10314000136A53699C68A1420CD85C688160036073 -:103150004460206058609868411A99604FF0FF33CE -:10316000D36110BD1B68091BECE700BF04240020DD -:10317000036881689A680A449A60426813605A60DA -:1031800000234FF0FF32C360014BDA61704700BF8C -:103190000424002038B50F4C2246236A01332362F1 -:1031A00052F8143F934206D020259A68013A9A605B -:1031B00063699A6802B138BDD3E9001001604860C4 -:1031C000D968DA6082F311881869884785F3118815 -:1031D000EEE700BF0424002000207047FEE7000057 -:1031E000704700004FF0FF3070470000BFF34F8F73 -:1031F000024AD368DB07FCD4704700BF00200240BE -:1032000008B5074B1B7853B9FFF7F0FF054B1A6958 -:10321000120641BF044A5A6002F188325A6008BD62 -:1032200008250020002002402301674508B5054B12 -:103230001B7833B9FFF7DAFF034A136943F08003C1 -:10324000136108BD08250020002002407F289ABF96 -:1032500000F5003080020020704700004FF48060CD -:1032600070470000802070477F2808B50BD8FFF713 -:10327000EDFF00F580630268013204D1043083421F -:10328000F9D1012008BD0020FCE700007F2838B5F7 -:10329000044623D8FFF7B4FEFFF7A8FFFFF7B0FFFF -:1032A000F3220F4B0546DA60022220461A61FFF72F -:1032B000CDFF58611A694FF4806142F040021A61F3 -:1032C000FFF794FF00F010F92846FFF7AFFFFFF774 -:1032D000A1FE2046BDE83840FFF7C6BF002038BD3C -:1032E000002002402DE9F047044612F001000E468E -:1032F000154606D040F2BD22234B1A600020BDE8DF -:10330000F087224BA2189A4204D940F2C2221E4BE7 -:103310001A60F4E7FFF774FE4FF0010AFFF770FF41 -:10332000FFF764FFDFF868903146A61B012D884641 -:1033300006EB010705D8FFF779FFFFF76BFE0120C9 -:10334000DDE7B8F80030C9F810A03B800024FFF793 -:103350004DFFC9F810403B8831F8022B9BB29A42CE -:103360000FD040F2D922084B1A600A4B1F600A4B5B -:103370001D600A4BC3F80080FFF758FFFFF74AFEB5 -:10338000BCE7023DD2E700BF042500200000020890 -:1033900000200240F824002000250020FC2400200A -:1033A000084908B50B7828B11BB9FFF729FF01239D -:1033B0000B7008BD002BFCD0BDE808400870FFF77B -:1033C00035BF00BF0825002070B5FFF719FE4FF488 -:1033D0007A710D4B0D4E1B6A326801FB03F3934269 -:1033E00037BF0B4A0A495168156836BF4C1CD1E9F2 -:1033F000005454605D1944F100043360FFF70AFE85 -:103400002846214670BD00BF042400200C25002062 -:103410001025002070B5FFF7F3FD4FF47A710F4BC4 -:103420000F4E1B6A326801FB03F3934237BF0D4A0C -:103430000C49516815683ABF4C1C5460D1E90054DE -:103440005D1944F100043360FFF7E4FD4FF47A7234 -:10345000002328462146FCF783FE70BD042400208B -:103460000C2500201025002010B5094C013AD2B2DD -:10347000FF2A00D110BD500854F82030013054F814 -:1034800020009BB243EA004341F8043BEEE700BF53 -:10349000046C004010B50748013AD2B2FF2A00D1AF -:1034A00010BD0C88530840F823404C88013340F885 -:1034B0002340F1E7046C004007B50122002001A978 -:1034C000FFF7D2FF019803B05DF804FB13B5044683 -:1034D000FFF7F2FFA04205D00122002001A90194CC -:1034E000FFF7D8FF02B010BD7047000045F25552FB -:1034F000064B1A6002225A6040F6FF729A604CF640 -:10350000CC421A600122024B1A7070470030004012 -:103510001C250020034B1B781BB14AF6AA22024B44 -:103520001A6070471C25002000300040044B1A68C8 -:103530002AB902F1804202F50432526A1A607047D9 -:10354000182500204FF08072014B5A62704700BF6F -:103550000010024008B5FFF7E9FF024B1868C0F3FE -:10356000407008BD1825002008B5FFF7DFFF024BAB -:103570001868C0F3007008BD18250020EFF3098318 -:10358000203383F30988002383F3118870470000F8 -:10359000202080F3118862B60C4B0D4AD96821F4C3 -:1035A000E0610904090C0A43DA60D3F8FC200949F8 -:1035B00042F08072C3F8FC200A6842F001020A60FF -:1035C0001022DA7783F82200704700BF00ED00E098 -:1035D0000003FA05001000E0202310B583F31188E2 -:1035E0000B4B5B6813F400630FD0EFF309844FF0CB -:1035F0008073203CE36184F30988FFF7B1FC10B1CC -:10360000044BA36110BD044BFBE783F31188F9E77A -:1036100000ED00E06F05000872050008704700002B -:10362000FEE700000A4B0B480B4A90420BD30B4BB2 -:10363000C11EDA1C121A22F003028B4238BF00228C -:103640000021FDF7BFBE53F8041B40F8041BECE754 -:103650000C3C0008A0250020A0250020A02500206B -:103660007047000000F030B808B500F063F9FFF7CC -:10367000A5FCBDE80840FFF759BF000070470000F7 -:103680004FF0FF310E4B1A6919611A6900221A6155 -:103690001869D868D960D968DA60DA68DA6942F0FE -:1036A0008052DA61DA69DA6942F00062DA61054A69 -:1036B000DB69136843F48073136000F01BB900BF2B -:1036C0000010024000700040194B1A6842F00102DD -:1036D0001A601A689007FCD51A6802F0F9021A609D -:1036E00000225A605A6812F00C0FFBD11A6842F49B -:1036F00080321A601A689103FCD55A6842F4E812C5 -:103700005A601A6842F080721A601A689201FCD5F9 -:103710001221084A5A60084A11605A6842F00202AF -:103720005A605A6802F00C02082AFAD1704700BFAA -:103730000010024000641D0000200240084A08B545 -:10374000516913680B4003F00103536123B1054A2B -:1037500013680BB150689847BDE80840FFF73CBFBD -:103760000004014020250020084A08B5516913686B -:103770000B4003F00203536123B1054A93680BB178 -:10378000D0689847BDE80840FFF726BF0004014015 -:1037900020250020084A08B5516913680B4003F042 -:1037A0000403536123B1054A13690BB1506998476B -:1037B000BDE80840FFF710BF0004014020250020AD -:1037C000084A08B5516913680B4003F008035361B8 -:1037D00023B1054A93690BB1D0699847BDE8084009 -:1037E000FFF7FABE0004014020250020084A08B572 -:1037F000516913680B4003F01003536123B1054A6C -:10380000136A0BB1506A9847BDE80840FFF7E4BE61 -:103810000004014020250020174B10B55A691C6890 -:10382000144004F478725A61A30604D5134A936ACB -:103830000BB1D06A9847600604D5104A136B0BB1E0 -:10384000506B9847210604D50C4A936B0BB1D06B93 -:103850009847E20504D5094A136C0BB1506C9847A0 -:10386000A30504D5054A936C0BB1D06C9847BDE80D -:103870001040FFF7B1BE00BF00040140202500202A -:103880001A4B10B55A691C68144004F47C425A6102 -:10389000620504D5164A136D0BB1506D9847230588 -:1038A00004D5134A936D0BB1D06D9847E00404D54D -:1038B0000F4A136E0BB1506E9847A10404D50C4A01 -:1038C000936E0BB1D06E9847620404D5084A136F0B -:1038D0000BB1506F9847230404D5054A936F0BB181 -:1038E000D06F9847BDE81040FFF776BE0004014056 -:1038F00020250020062108B50846FFF747F80621D5 -:103900000720FFF743F806210820FFF73FF80621BC -:103910000920FFF73BF806210A20FFF737F80621B8 -:103920001720FFF733F8BDE8084006212820FFF7ED -:103930002DB8000008B5FFF7A3FE064800F00EF80A -:10394000FFF742F8FFF746FAFFF798FEBDE8084098 -:1039500000F002B8A03B000800F042B8002319466E -:103960001C4A0133102BC2E9001102F10802F8D100 -:10397000194B9A6942F07D029A619B690268174B64 -:10398000DA6082685A6042681A60C26803F5806330 -:10399000DA6042695A6002691A608269C3F80C24CD -:1039A000026AC3F80424C269C3F80024426AC3F857 -:1039B0000C28C26AC3F80428826AC3F80028026B84 -:1039C000C3F80C2C826BC3F8042C426BC3F8002C98 -:1039D000704700BF20250020001002400008014071 -:1039E0004FF0E023044A08215A6100229A6107221D -:1039F0000B201A61FEF7E0BF3F19010008B5202334 -:103A000083F31188FFF7FAFA002383F3118808BDC6 -:103A100008B5FFF7F3FFBDE80840FFF7DDBD000084 -:103A200010B501390244904201D1002005E003782D -:103A300011F8014FA34201D0181B10BD0130F2E76D -:103A40002DE9F0419BB10446C91A1778014403F1EE -:103A5000FF3C8C42204601D9002008E00578013463 -:103A6000BD42F6D10CEB0405D618A54201D1BDE844 -:103A7000F08115F8018D16F801EDF045F5D0E8E775 -:103A8000034611F8012B03F8012B002AF9D17047E6 -:103A90006F72672E6172647570696C6F742E6170DD -:103AA0005F7065726970685F72616E676566696E86 -:103AB000646572004E6F20617070207369670A0040 -:103AC000426164206677206C656E67746820257596 -:103AD0000A0042616420626F6172645F696420253C -:103AE000752073686F756C642062652025750A0007 -:103AF0004261642066772064657363726970746FD5 -:103B000072206C656E6774682025750A00426164D6 -:103B10002061707020435243203078253038783A45 -:103B2000307825303878203078253038783A307839 -:103B3000253038780A00476F6F64206669726D77A8 -:103B40006172650A0040A2E4F16468910600000019 -:103B5000000000009D2D0008892D0008C52D0008DB -:103B6000B12D0008BD2D0008A92D0008952D0008D5 -:103B7000812D0008D12D00086D61696E00000000E4 -:103B800069646C6500000000803B00084824002048 -:103B9000F824002001000000B92F000800000000F8 -:103BA0000C1E0000447B4144B4574944010000000E -:103BB00042444444444444440000000044444444D7 -:103BC00044444444000000004444444444444444C5 -:103BD000000000004444444444444444B4C5FF7FCE -:103BE0000100000000000000E803000000000000E9 -:103BF000009C0100000000006400000000000000C4 -:0C3C000040420F00FE2A0100D204000028 +:10000000000900202D080008B11C0008811C000810 +:100010009D1C0008811C0008951C00082F08000882 +:100020002F0800082F0800082F080008E5370008EF +:100030002F0800082F0800082F080008F93C0008C6 +:100040002F0800082F0800082F0800082F080008B4 +:100050002F0800082F080008293A0008553A000820 +:10006000813A0008AD3A0008D93A00082F08000884 +:100070002F0800082F0800082F0800082F08000884 +:100080002F0800082F0800082F080008AD2C0008D2 +:10009000192D00086D2D0008C12D0008053B000832 +:1000A0002F0800082F0800082F0800082F08000854 +:1000B0002F0800082F0800082F0800082F08000844 +:1000C0002F0800082F0800082F0800082F08000834 +:1000D0002F0800082F0800082F0800082F08000824 +:1000E0006D3B00082F0800082F0800082F080008A3 +:1000F0002F0800082F0800082F0800082F08000804 +:100100002F0800082F0800082F0800082F080008F3 +:100110002F0800082F0800082F0800082F080008E3 +:100120002F0800082F0800082F0800082F080008D3 +:100130002F0800082F0800082F0800082F080008C3 +:100140002F0800082F0800082F0800082F080008B3 +:100150002F0800082F0800082F0800082F080008A3 +:100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A +:100170000C0F93EA0C0F6FD01A4480EA010C400276 +:1001800018BF5FEA41211ED04FF0006343EA5010D0 +:1001900043EA5111A0FB01310CF00040B1F5000F12 +:1001A0003EBF490041EAD3715B0040EA010062F1C1 +:1001B0007F02FD2A1DD8B3F1004F40EBC25008BFAB +:1001C00020F00100704790F0000F0CF0004C08BFC9 +:1001D00049024CEA502040EA51207F3AC2BFD2F196 +:1001E000FF0340EAC250704740F400004FF00003A4 +:1001F000013A5DDC12F1190FDCBF00F000407047DE +:10020000C2F10002410021FA02F1C2F1200200FA1B +:1002100002FC5FEA310040F1000053EA4C0308BFE2 +:1002200020EADC70704792F0000F00F0004C02BF33 +:10023000400010F4000F013AF9D040EA0C0093F0AE +:10024000000F01F0004C02BF490011F4000F013B08 +:10025000F9D041EA0C018FE70CEAD15392EA0C0F76 +:1002600018BF93EA0C0F0AD030F0004C18BF31F0E1 +:10027000004CD8D180EA010000F00040704790F0B7 +:10028000000F17BF90F0004F084691F0000F91F05B +:10029000004F14D092EA0C0F01D142020FD193EA21 +:1002A0000C0F03D14B0218BF084608D180EA0100A9 +:1002B00000F0004040F0FE4040F40000704740F085 +:1002C000FE4040F44000704780F0004002E000BF74 +:1002D00081F0004142001FBF5FEA410392EA030F31 +:1002E0007FEA226C7FEA236C6AD04FEA1262D2EB7B +:1002F0001363C1BFD218414048404140B8BF5B4280 +:10030000192B88BF704710F0004F40F4000020F018 +:100310007F4018BF404211F0004F41F4000121F02E +:100320007F4118BF494292EA030F3FD0A2F1010278 +:1003300041FA03FC10EB0C00C3F1200301FA03F1B6 +:1003400000F0004302D5494260EB4000B0F5000FD9 +:1003500013D3B0F1807F06D340084FEA310102F198 +:100360000102FE2A51D2B1F1004F40EBC25008BF4A +:1003700020F0010040EA03007047490040EB000014 +:10038000013A28BFB0F5000FEDD2B0FA80FCACF115 +:10039000080CB2EB0C0200FA0CF0AABF00EBC25042 +:1003A00052421843BCBFD0401843704792F0000F30 +:1003B00081F4000106BF80F400000132013BB5E783 +:1003C0004FEA41037FEA226C18BF7FEA236C21D0F9 +:1003D00092EA030F04D092F0000F08BF084670475E +:1003E00090EA010F1CBF0020704712F07F4F04D12C +:1003F000400028BF40F00040704712F100723CBF3F +:1004000000F50000704700F0004343F0FE4040F468 +:10041000000070477FEA226216BF08467FEA236326 +:100420000146420206BF5FEA412390EA010F40F411 +:10043000800070474FF0000304E000BF10F000435D +:1004400048BF40425FEA000C08BF704743F0964344 +:1004500001464FF000001CE050EA010208BF70475F +:100460004FF000030AE000BF50EA010208BF7047E6 +:1004700011F0004302D5404261EB41015FEA010CFB +:1004800002BF84460146002043F0B64308BFA3F1F3 +:100490008053A3F50003BCFA8CF2083AA3EBC253D5 +:1004A00010DB01FA02FC634400FA02FCC2F12002F4 +:1004B000BCF1004F20FA02F243EB020008BF20F02B +:1004C0000100704702F1200201FA02FCC2F1200291 +:1004D00050EA4C0021FA02F243EB020008BF20EA86 +:1004E000DC70704742000ED2B2F1FE4F0BD34FF0DA +:1004F0009E03B3EB126209D44FEA002343F000439A +:1005000023FA02F070474FF00000704712F1610FBC +:1005100001D1420202D14FF0FF3070474FF000008E +:10052000704700BF53B94AB9002908BF00281CBF53 +:100530004FF0FF314FF0FF3000F076B9ADF1080C0D +:100540006DE904CE00F006F8DDF804E0DDE90223F1 +:1005500004B070472DE9F047089E0D4604468846D2 +:10056000002B4DD18A42944668D9B2FA82F252B138 +:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 +:1005800041EA030894404FEA1C41B8FBF1F71FFA17 +:100590008CFE01FB178807FB0EF0230C43EA08438F +:1005A00098420AD91CEB030307F1FF3580F01E8146 +:1005B000984240F21B81023F63441B1AB3FBF1F0E7 +:1005C00001FB103300FB0EFEA4B244EA0344A6452F +:1005D0000AD91CEB040400F1FF3380F00981A64521 +:1005E00040F20681644402380021A4EB0E0440EA84 +:1005F00007401EB10023D440C6E90043BDE8F087A0 +:100600008B4208D9002E00F0EE800021C6E90005DB +:100610000846BDE8F087B3FA83F100294AD1AB421E +:1006200002D3824200F2FC80841A65EB03030120AE +:100630009846002EE2D0C6E90048DFE702B9FFDEA7 +:10064000B2FA82F2002A40F09180A1EB0C00012165 +:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 +:10066000250C45EA00450EFB03F0A84208D91CEB17 +:10067000050503F1FF3802D2A84200F2CE804346BE +:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 +:1006900044EA0544A64508D91CEB040400F1FF35E3 +:1006A00002D2A64500F2B6802846A4EB0E0440EA2A +:1006B00003409EE7C1F120078B4022FA07FC4CEA79 +:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D +:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 +:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 +:1006F00001F20BD91CEB040408F1FF3A80F088806A +:10070000A04240F28580A8F102086444241AB4FB98 +:10071000F9F009FB104400FB0EFEADB245EA0444BB +:10072000A64508D91CEB040400F1FF356CD2A645A0 +:100730006AD90238644440EA0840A0FB0295A4EB61 +:100740000E04AC42C846AE4656D353D0002E69D0F4 +:10075000B3EB080264EB0E0422FA01F304FA07F784 +:100760001F43CC40C6E90074002147E70CFA02FCA5 +:10077000C2F1200125FA01F34FEA1C4720FA01F1EA +:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 +:10079000280C40EA034001FB0EF3834204FA02F402 +:1007A00008D91CEB000001F1FF382FD283422DD96C +:1007B00002396044C01AB0FBF7F307FB1300ADB277 +:1007C00045EA004503FB0EF0A84208D91CEB0505DD +:1007D00003F1FF3816D2A84214D9023B6544281A07 +:1007E00043EA014138E73146304607E72F46E4E661 +:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 +:100800000138A3E74346EAE7284694E74146D1E7A3 +:10081000D0467BE76444023847E7023B65442FE754 +:10082000084606E73146E9E6704700BF02E000F0FF +:1008300000F8FEE772B6264880F30888254880F362 +:100840000988254825490860022080F31488BFF3F1 +:100850006F8F03F017F803F07BF84FF05530204905 +:100860001B4A91423CBF41F8040BFAE71D49194A63 +:1008700091423CBF41F8040BFAE71B491B4A1C4B51 +:100880009A423EBF51F8040B42F8040BF8E70020EF +:100890001849194A91423CBF41F8040BFAE702F0AB +:1008A000F5FF03F057F8154C154DAC4203DA54F838 +:1008B000041B8847F9E700F03FF8124C124DAC4298 +:1008C00003DA54F8041B8847F9E702F0DDBF0000A3 +:1008D00000090020001100200000000808ED00E0E1 +:1008E0000001002000090020103E00080011002037 +:1008F0002411002028110020E025002060010008BC +:100900006001000860010008600100082DE9F04F57 +:10091000C1F80CD0C3689D46BDE8F08F002383F377 +:1009200011882846A047002002F010FDFEE702F0E3 +:1009300083FC00DFFEE70000F8B500F03DFE02F0AA +:10094000EFFE074602F03AFF0546002840D12C4B47 +:100950009F423DD001339F423DD02A4B27F0FF02FA +:100960009A423BD1F8B200F003FC2E4642F21074DA +:1009700000F004FC08B10024264601F007F988B312 +:100980000024032000F044F8264635B11E4B9F4258 +:1009900003D0002402F00AFF2646002002F0CAFE1F +:1009A0001A4B9B6813F0400322D00EB100F046F8BA +:1009B00000F044FC00F002FE01F07CF90546CCB1E9 +:1009C00001F078F9401BA04214D900F037F8F3E7A2 +:1009D0002E460024CCE704460126C9E706464FF41C +:1009E0007A74C5E7002CD0D04FF47A740126CCE796 +:1009F0001C46DDE700F0D4FC012002F0ADFCDEE790 +:100A0000010007B0000008B0263A09B0000C014010 +:100A1000084B187003280CD8DFE800F0080502081E +:100A2000022000F027BE022000F01CBE0022024B74 +:100A30005A607047281100202C11002038B501F0B1 +:100A4000A5F830B103221F4B1A7000221E4B5A60CA +:100A500038BD1E4B1E4A19680131F9D00433934248 +:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 +:100A70009B6803F1006303F5C8439A42E8D202F091 +:100A800069FE02F07BFE002000F0B2FD0220FFF7BD +:100A9000BFFF124BDA690022DA61D96999699A615C +:100AA0009B6972B64FF0E023C3F8085D3021D4F89B +:100AB0000034D4F8042481F311889D4683F3088818 +:100AC0001047C5E7281100202C1100200064000801 +:100AD000206400080060000800110020001002409F +:100AE00049F26900084A136899B21B0C00FB0133F4 +:100AF00044F250611360054B186882B2000C01FB90 +:100B00000200186080B27047201100201C110020E4 +:100B100010B504460021102200F0C8FD034B03CBA2 +:100B2000206061601868A06010BD00BFE8F7FF1F7B +:100B30002DE9F0410026ADF5507D6EAC40F2751206 +:100B400007460D4610A831460F9600F0AFFD4FF452 +:100B5000C4723146204600F0A9FD01F0ABF84FF415 +:100B60007A72B0FBF2F0264B0DF13C08186093E866 +:100B70000700022384E807000DF5ED702382FFF7DC +:100B8000C7FF4EF603031F4907A8238403F0ECF8C0 +:100B90001E230DF2EB2284F832310DF1340C07AB39 +:100BA0001E4603CE664510605160334602F10802CE +:100BB000F6D1306841461060B38820469380012208 +:100BC00000F0C0FD00230393AB7E80B2029305F1D9 +:100BD000190301930123CDE904800093384606A34D +:100BE000D3E90023E97E01F0ABFB0DF5507DBDE8B4 +:100BF000F08100BFAFF300809E6AC421818A46EE77 +:100C000034110020783D00082DE9F041264D804642 +:100C10002B7A0C46DAB0FBB9204627A900F0A2FED9 +:100C20000746002836D19DF89D60C82E32D801466F +:100C30004FF4FA72284600F039FD32460DF19E015C +:100C400005F1090000F020FD9DF89C302E447772DC +:100C50002B720BB9E37E2B728122002106AD27A8EF +:100C600000F024FD0122294627A800F0B7FE00234A +:100C70000393A37E80B2029304F119030193282306 +:100C8000CDE904500093404605A3D3E90023E17E5B +:100C900001F056FB5AB0BDE8F08100BFAFF3008011 +:100CA00026417272DF25D7B77C210020F0B54FF4C2 +:100CB0008A750024234EF1B005FB006596F8D83004 +:100CC000D822214685F8DC3085F8E8403AA800F0C3 +:100CD000EDFC06F1090000F0E1FCD5F8E430C2B209 +:100CE00006AF8DF8F00006F109010DF1F100CDE934 +:100CF0003A3400F0C9FC394601223AA800F09AFEC5 +:100D000080B2CDE9047008230127CDE9023706F14E +:100D1000D80301933023317A00930B4807A3D3E91A +:100D2000002301F00DFBA04206DD00F0C3FFC5F873 +:100D3000E000384671B0F0BD2046FBE778F6339FFF +:100D400093CACD8D7C2100204C210020F0B51E4E91 +:100D50001E4F1F4D85B0304601F01EFB044660B3A8 +:100D600010220021684600F0A1FC4FF00003227B16 +:100D70006068A16862F303038DF8003002AB03C31F +:100D8000019B2268384662F31C0301939DF80030F2 +:100D90006A4643F020038DF800300023194602F024 +:100DA00087F9044620B9304601F0FAFA2C70D2E7F0 +:100DB0002B78072B03D801332B7005B0F0BD024808 +:100DC00001F0EEFAF9E700BF4C210020A823002033 +:100DD0007523002070B50D4614461E4601F00CFA2E +:100DE00050B9022E10D1012C0ED112A3D3E9002349 +:100DF0000120C5E9002307E0282C10D005D8012CDC +:100E000009D0052C0FD0002070BD302CFBD10BA3D6 +:100E1000D3E90023ECE70BA3D3E90023E8E70BA316 +:100E2000D3E90023E4E70BA3D3E90023E0E700BF05 +:100E3000AFF30080401DA12026812A0B78F6339F56 +:100E400093CACD8D9E6AC421818A46EE2641727274 +:100E5000DF25D7B7F017304A39059E5638B5054615 +:100E60000E4C0021013500F0E5FBA4F8F051B4F878 +:100E7000F00100F0C7FB78B1B4F8F00100F0D2FB4C +:100E8000014648B9B4F8F00100F0D4FBB4F8F031F1 +:100E90000133A4F8F031EAE738BD00BF7C2100201F +:100EA0002DE9F04F8DB000AF04460D4601F0A4F9D6 +:100EB000002846D12B7E022B1AD1EB8A012B17D1A9 +:100EC00000F0F8FE0646FFF70BFE4FF4C873B0FBC8 +:100ED000F3F202FB1303DFF878829BB206F5167675 +:100EE0003344C8F80030EB7E33B90022994B1A70B6 +:100EF0003437BD46BDE8F08F284607F11C0100F0ED +:100F0000EFFC0028F4D107F10C00FFF701FEBD7FD4 +:100F100007F10C012A4607F11F0002F0F5FE002838 +:100F2000E3D10F2D08D88B4B1D70D8F80030A3F5F6 +:100F30001673C8F80030DBE72046397F01F054F91A +:100F4000D6E7EB8A282B6BD010D8012B63D0052B6A +:100F5000CED1BFF34F8F8049804BCA6802F4E06264 +:100F60001343CB60BFF34F8F00BFFDE7302BBFD1E2 +:100F70007B4CEA7E237A9A42BAD194F8DC206B7ECD +:100F80009A42B5D1284604F1EA0100F07FFD0646F9 +:100F90000028ADD1012384F8E83000F08BFED4F8AE +:100FA000E030C01A192840F6B83338BF19209842EB +:100FB00028BF1846FFF73EFA6A49FFF7D1F8054601 +:100FC0002068FFF737FA6849FFF7CAF80146284654 +:100FD000FFF780F9FFF786FA20604FF48A7194F8E2 +:100FE000D9307B607A68636801FB02F5621992F878 +:100FF000E80050B1D2F8E400E946834215D000235E +:1010000082F8E830C2F8E030CD466368574A9B0A60 +:10101000013313816CE729462046FFF789FD67E716 +:1010200029462046FFF7F0FD62E7B2F8EC803B600E +:1010300008F1030A4FEA9A0A4FEA8A02D11DC90849 +:10104000A9EBC1039D46EB460021584600F02EFB5C +:1010500005F1EE0142465846214400F015FB3B687D +:1010600013B9012000F0C4FA94F8D20000F0CAFAD3 +:10107000054630B9207200F0E5FA284600F0B8FACB +:10108000C2E7D4F8D4303BB994F8D200B4F8F031C8 +:10109000834201D8FFF7E2FED4F8D43043449D42A6 +:1010A00008D294F8D200B4F8F0310130834201D86C +:1010B000FFF7D4FE594660685FFA8AF200F0FEFA44 +:1010C00008B9CD4689E7636894F8D2004344636069 +:1010D000D4F8D43008EB030AC4F8D4A000F092FA94 +:1010E000824509D394F8D230D4F8D4000133401BA0 +:1010F00084F8D230C4F8D400B8F1FF0F0FD800251F +:10110000257200F09FFA284600F072FA00F03EFDCA +:10111000164B188108B9FFF791FCCD46E8E64FF46D +:101120008A727B6894F8D90002FB0343D3F8E42069 +:1011300083F8E86002F58072C3F8E060C3F8E42049 +:10114000FFF7B4FDFFF702FE84F8D960B9E700BFEE +:10115000482100204521002000ED00E00400FA05B0 +:101160007C210020CDCCCC3D6666663F341100204A +:10117000014B1870704700BF4011002030B54FF090 +:101180000054254B226885B09A4207D002F020FB1C +:101190000446C0B90024204605B030BD0025627D5C +:1011A0001E4B1F481A70237DC92203721D49C0F8C7 +:1011B000E450093000F068FA2046E022294600F0A9 +:1011C00075FA0124E7E7184A184DD36943F0007314 +:1011D000D361AA6D164B9A42DCD12B6E013B7E2B5C +:1011E000D8D8144A01AB07CA83E807001846032180 +:1011F00000F09CFC6B6D83424FF00003CAD12A6D56 +:101200008A4203BFAB652A6E044B1C4601BF1A70AD +:10121000EA6D094B1A60BEE79AAD44C54011002043 +:101220007C210020160000200010024000660040D3 +:101230005041A0B058660040181100202DE9F0433D +:1012400085B000F0A3FC0223494C63710023029394 +:10125000484B2081D3F800C0BCF57A7F12D3464FAB +:10126000464BB7FBFCF59C458CBF0A231123B5FB0D +:10127000F3F603FB1652591EC8B2002A3ED00229CB +:101280000B46F4D89DF80B303D495A1E9DF80A30A4 +:101290003C48013B1B0443EA0253BDF80820013AD5 +:1012A00013434B6001F0F4FE00230193364B3749A2 +:1012B00000934FF48052364B364800F06BFF364BAC +:1012C000197811B1334800F08FFF00F0F3FC0546A8 +:1012D000FFF706FC4FF4C873B0FBF3F202FB1303F5 +:1012E00005F516709BB218442C4B186002F066FA94 +:1012F00008B10F23238105B0BDE8F083731EB3F559 +:10130000806FBFD24FF47A75C0EBC00E0EF10303AD +:101310004FEAE30909FB0555C3F3C703C11AC9B274 +:1013200009F101088844B5FBF8F5B5F5617F08D9E6 +:101330000EF1FF33C3F3C703C11A581E0F28C9B2F9 +:1013400014D84A1E072A8CBF00220122581800FB1D +:101350000660B7FBF0F7BC4594D1002A92D0ADF8F7 +:1013600008608DF80A308DF80B108BE71346EDE717 +:101370003411002018110020005125023F420F00B7 +:1013800010110020A8230020D50D000844110020D2 +:10139000A10E00084C21002040110020482100200F +:1013A0002DE9F04F80A7D7E900670FF20429D9E9AA +:1013B0000089734D93B00DF1300AFFF7C7FC182276 +:1013C0000021504600F072F9DFF8B8B16E4C0023EE +:1013D00052461946584601F093FE014650BB102272 +:1013E00008A800F063F9E36883F01003E36000F0FD +:1013F00063FC0DF1240C0B4612A9024611E903000F +:101400008CE803009DF83410C1F30300890649BF3E +:101410000E99BDF83810C1F31C0141F0004158BFCE +:10142000C1F30A018DF82C000891284608A901F0A3 +:1014300097F9CCE7284600F0DFFE0446002847D1A4 +:1014400000F038FCDFF844B1DBF8003098423FD3BD +:1014500000F030FC0790FFF743FB4FF4C873B0FB7C +:10146000F3F101FB1300079A83B202F516701844DA +:10147000CBF80000DFF818B18DF820409BF8001081 +:1014800011B901238DF8203050460791FFF740FB3A +:1014900007990DF12100C1F11004E4B2062C28BF18 +:1014A00006245144224600F0EFF808AB03931823BA +:1014B0000293384B013401930123E4B20093324686 +:1014C0003B462846049400F0DDFE00238BF80030F4 +:1014D00000F0F0FB304A314C1368C31AB3F57A7F41 +:1014E00030D3106000F0E8FB02460B46284600F0BF +:1014F00061FF284600F080FE20B3237ADFF8A0B019 +:10150000002B14BF032302238BF8053000F0D2FB1D +:101510004FF47A73B0FBF3F00122CBF80000514690 +:10152000584600F0B5F9182302931E4B80B2019380 +:1015300040F25513CDE903A0009342464B4628469E +:1015400000F0A0FE237ABBB100F0B4FB94F8E830C1 +:1015500073B9D4F8E03043B1C01A2368FA2B38BF0E +:10156000FA230533B0EB430F02D30020FFF79EFBB5 +:10157000237A002B7FF41FAF13B0BDE8F08F00BFBC +:101580004C210020A8230020000801404821002011 +:101590004521002044210020702300207C210020D0 +:1015A0003411002074230020401DA12026812A0B25 +:1015B000F1C6A7C1D068080F7047000070B501F0F0 +:1015C00095FF0024084E094D3080286833888342F7 +:1015D00008D901F087FF2B6804440133B4F5C84FE4 +:1015E0002B60F2D370BD00BFA4230020782300201D +:1015F00002F00AB800F10060920000F5C84001F066 +:10160000AFBF0000054B1A68054B1B889B1A83422D +:1016100002D9104401F066BF0020704778230020F3 +:10162000A4230020024B1B68184401F061BF00BFD7 +:1016300078230020024B1B68184401F06BBF00BFE9 +:1016400078230020064991F8243033B10023082282 +:10165000086A81F82430FFF7CDBF0120704700BF32 +:101660007C230020022802BF1022014B1A61704720 +:1016700000080140022802BF4FF48012014B1A619A +:10168000704700BF00080140002310B5934203D00B +:10169000CC5CC4540133F9E710BD00000346024698 +:1016A000D01A12F9011B0029FAD1704703460244EF +:1016B000934202D003F8011BFAE770472DE9F84383 +:1016C0001F4D144695F824200746884652BBDFF884 +:1016D00070909CB395F824302BB92022FF21484606 +:1016E0002F62FFF7E3FF95F824004146C0F108029E +:1016F000A24228BF224605EB8000D6B29200FFF737 +:10170000C3FF95F82430A41B1E44F6B2082E1744DC +:101710009044E4B285F82460DBD1FFF793FF002802 +:10172000D7D108E02B6A03EB82038342CFD0FFF7C7 +:1017300089FF0028CBD10020BDE8F8830120FBE71A +:101740007C2300202DE9F0470D46044600219046F9 +:10175000284640F27912FFF7A9FF234620220021F4 +:10176000284600F09FFF022220212846231D00F07A +:1017700099FF032222212846631D00F093FF0322D4 +:1017800025212846A31D00F08DFF10222821284680 +:1017900004F1080300F086FF08223821284604F1EE +:1017A000100300F07FFF08224021284604F11103B6 +:1017B00000F078FF08224821284604F1120300F0C7 +:1017C00071FF20225021284604F1140300F06AFF23 +:1017D00040227021284604F1180300F063FF08221C +:1017E000B021284604F1200300F05CFF0822B82154 +:1017F000284604F1210300F055FFC02604F122071A +:101800003B46314608222846083600F04BFFB6F525 +:10181000A07F07F10107F3D108223146284604F1E1 +:10182000320300F03FFF002704F1330A94F832300E +:101830004FEAC7099F4209F5A47615D3B8F1000F06 +:1018400008D131460722284604F5997300F02AFF93 +:1018500009F24F16274694F832213B1B93420CD3D2 +:10186000F01DC008BDE8F0870AEB070308223146E7 +:10187000284600F017FF0137D8E7314607F2331347 +:101880000822284600F00EFF08360137E3E7000083 +:1018900038B50C460021054621600346C4F8031004 +:1018A0002046202200F0FEFE20462B1D0222202191 +:1018B00000F0F8FE20466B1D0322222100F0F2FE0C +:1018C0002046AB1D0322252100F0ECFE204610220D +:1018D000282105F1080300F0E5FE072038BD0000CF +:1018E0000023F7B50E460546047F072200911946EE +:1018F00000F09AFD731C0093012200230721284663 +:1019000000F092FDC4B9B31C0093052223460821C0 +:10191000284600F089FD0D243746B278BB1B934260 +:1019200011D32B7FE01DC008AC8ABBB9A04294BF85 +:101930000020012003B0F0BDAB8A0824DB00083B87 +:10194000DB08B370E8E7FB1C214600930822002364 +:10195000284600F069FD08340137DEE7001B18BF98 +:101960000120E7E70023F7B50E46047F0822009127 +:101970001946054600F058FD731CC4B908220093AF +:1019800011462346284600F04FFD102401237278AB +:101990005F1C013B934211D32B7FE01DC008AC8A32 +:1019A000BBB9A04294BF0020012003B0F0BDAB8AB8 +:1019B0000824DB00083BDB087370E7E7F3192146D6 +:1019C000009308220023284600F02EFD08343B46F1 +:1019D000DDE7001B18BF0120E7E70000F8B50E4661 +:1019E00005461446002181223046FFF75FFE2B4654 +:1019F00008220021304600F055FE7CB9072208215C +:101A000030466B1C00F04EFE0F2401236A785F1CE9 +:101A1000013B934204D3E01DC008F8BD0824F4E75D +:101A20002146EB190822304600F03CFE08343B46C4 +:101A3000ECE70000F8B50E46054614460021CE221C +:101A40003046FFF733FE2B4628220021304600F0B7 +:101A500029FE7CB908222821304605F1080300F050 +:101A600021FE30242F462A7A7B1B934204D3E01DAB +:101A7000C008F8BD2824F5E7214607F1090308222C +:101A8000304600F00FFE08340137ECE7F7B5047F6D +:101A90000E460091012310220021054600F0C4FCEF +:101AA000C4B9B31C0093092223461021284600F034 +:101AB000BBFC192437467288BB1B9A4211D82B7F76 +:101AC000E01DC008AC8ABBB9A04294BF0020012031 +:101AD00003B0F0BDAB8A1024DB00103BDB08738041 +:101AE000E8E73B1D2146009308220023284600F02A +:101AF0009BFC08340137DEE7001B18BF0120E7E735 +:101B000030B5094D0A4491420DD011F8013B5840BF +:101B1000082340F30004013B2C4013F0FF0384EA48 +:101B20005000F6D1EFE730BD2083B8ED4FF0FF3322 +:101B3000F7B500EB81061946DFF848C0DFF848E04A +:101B4000B0421BD050F8042B01AF0192042217F8C9 +:101B5000014B81EA046108240D46DB184941013C30 +:101B6000002DBCBF83EA0C0381EA0E0114F0FF04D0 +:101B7000F2D1013A12F0FF02E9D1E1E7D843C943BB +:101B800003B0F0BD9336EAA9EBE1F042F7B56B463E +:101B9000354A106851686A4603C3082333493448FC +:101BA00002F0C2F8044690BB0A256B46314A106821 +:101BB00051686A4603C308232F492D4802F0B4F840 +:101BC0000446002847D00369B3F5CE3F43D8B0F8A8 +:101BD0006620B2F57A7F3ED1284A024402F15C01C8 +:101BE0008B4238D35C3B224900209E1AFFF788FFC6 +:101BF00007463246002004F16401FFF781FFA36825 +:101C00009F4228D1E368984208BF002523E003697A +:101C1000B3F5CE3F26D8428BB2F57A7F20D1174A52 +:101C2000024402F110018B4218D3103B10490020EE +:101C30009D1AFFF765FF06462A46002004F11801A9 +:101C4000FFF75EFFA3689E4202D1E368984201D08D +:101C50000D25AAE70025284603B0F0BD1025A4E70E +:101C60000C25A2E70B25A0E7983D0008DC9B0100AE +:101C700000640008A13D0008909B0100089CFFF74C +:101C8000EFF30983EFF30583014B9B6BFEE700BF86 +:101C900000ED00E008B5FFF7F3FF0000EFF3098364 +:101CA000EFF30583014B5B6BFEE700BF00ED00E047 +:101CB000FEE7000001F0E2BC01F0BABC2DE9F04102 +:101CC000456A15B94162BDE8F0814B68AC4623F026 +:101CD0006047C3F38A4616EA230638BF3E464FEAFA +:101CE000D37EC3F380782B465A68BEEBD27F22F0B6 +:101CF00060440AD0002A18DAA40CB44217D19D42DD +:101D00000FD10D60DEE71346EEE7A74207D102F0E0 +:101D10008044C2F3807242450BD054B1EFE708D241 +:101D2000EDE7CCF800100B60CDE7B44201D0B4422F +:101D3000E5D81A689C46002AE5D11960C3E700007F +:101D40002DE9F0474FF47F49089D01F007044FEA61 +:101D5000D508224405F0070500EBD100944201D1DB +:101D6000BDE8F08704F0070705F0070A57453E462F +:101D700038BF5646111BC6F108068E4228BF0E46D4 +:101D8000E108415C08EBD50E13F80EC0B94029FA02 +:101D900006F721FA0AF1FFB28CEA010147FA0AF7C5 +:101DA00039408CEA010C03F80EC034443544D5E7C1 +:101DB000082341F2210280EA012001B240000029FB +:101DC00080B203F1FF33B8BF504013F0FF03F4D1EA +:101DD0007047000038B50C468D18A54200D138BDBB +:101DE00014F8011BFFF7E4FFF7E700000346406823 +:101DF00048B1026899895A605A89013292B2914277 +:101E00005A8138BF9A81704770B504460D4688B034 +:101E1000202200216846FFF749FC20460495FFF781 +:101E2000E5FF024658B16B46054608AE1C4603CC9A +:101E3000B44228606960234605F10805F6D11046D2 +:101E400008B070BD082817D909280CD00A280CD072 +:101E50000B280CD00C280CD00D280CD00E2814BF49 +:101E60004020302070470C2070471020704714200D +:101E7000704718207047202070470000082817D9A5 +:101E80000C280CD910280CD914280CD918280CD9D6 +:101E900020280CD930288CBF0F200E207047092035 +:101EA00070470A2070470B2070470C2070470D20A8 +:101EB000704700002DE9F843078C0446072F1ED910 +:101EC000D0E9029800254FF6FF73C5F12006A5F171 +:101ED000200029FA05F108FA06F628FA00F0314345 +:101EE0000143C9B21846FFF763FF0835402D03468A +:101EF000EBD13A46E169BDE8F843FFF76BBF4FF617 +:101F0000FF70BDE8F883000010B54B6823B9CA8A9A +:101F100063F30902CA8210BD04691A681C60036178 +:101F2000C38A013BC3824A60EFE700002DE9F84F06 +:101F30001D46CB8A0F46C3F3090105298146924607 +:101F40000B4630D00020AAB207F11A049EB2042E2C +:101F50001FFA80F80FD8904503F1010306D3FB8ADE +:101F60000A4462F309030120FB821AE01AF80060B8 +:101F70000130E654EAE79045F1D21C23A1F1050BAC +:101F8000BBFBF3F203FB12BB7C681FFA8BF6002C41 +:101F900045D14846FFF72AFF044638B978606FF00C +:101FA0000200BDE8F88F4FF00008E6E70026066063 +:101FB00078604FF0000BADB2454510D90AEB08032D +:101FC000221D13F8011B08F101089155B1B21B291C +:101FD0001FFA88F82BD0454506F10106F1D8FB8A97 +:101FE000C3F30902154465F30903BCE71C4601323B +:101FF00092B22368002BF9D16B1F0B441C21B3FB59 +:10200000F1F301339BB29A42D3D2BBF1000FD0D18E +:102010004846FFF7EBFE20B9C4F800B0BFE7012245 +:10202000E7E7C0F800B05E4620600446C1E74545DA +:10203000D5D94846FFF7DAFE08B92060AFE7C0F807 +:1020400000B0002620600446B6E700002DE9F74FF7 +:102050001C465B69074688460092002B00F097807B +:10206000238C2BB1E269002A00F09180072B33D832 +:1020700007F10C00FFF7BAFE054628B96FF002051C +:10208000284603B0BDE8F08F14220021FFF70EFBB5 +:10209000228CE16905F10800FFF7F6FA208C48F080 +:1020A0000041013080B2FFF7E9FEFFF7CBFE0138B7 +:1020B00080B22084013028746369228C1B782A4402 +:1020C00003F01F0363F03F0313723846696029462B +:1020D000FFF7F4FD0125D3E74FF000094FF0800A28 +:1020E0004E464D4600F10C0301930198FFF77EFE2A +:1020F00083460028C2D014220021FFF7D7FA002E11 +:102100003BD10222009BABF808300BF1080E1FFAFE +:1021100082FC0CF10100BCF1060F218C80B201D8C9 +:102120008E422CD3FFF7AAFEFFF78CFE8E4208BF2B +:102130004FF0400A62690138127880B202F01F0243 +:1021400042EA49120BEB00014AEA020A013048F068 +:10215000004281F808A08BF8100059463846CBF8A9 +:102160000420FFF7ABFD238C0135B3424FF0000A8A +:102170002DB289F00109B8D182E70022C5E7E169F3 +:10218000895D01360EF80210B6B20132BFE76FF07A +:10219000010575E7F8B5044615460E4630220021C4 +:1021A0001F46FFF783FA069BB5F5001F6360079B88 +:1021B00028BF4FF6FF72A3624FF0000338BF6A09D1 +:1021C000A760E66197B204F110009A4206D8002396 +:1021D0000360A782E3822383E360F8BD06600133D6 +:1021E00030462036F1E7000003781BB94BB2002BD4 +:1021F000C8BF01707047000000787047F8B50C4602 +:10220000C969074611B9238C002B37D1257E1F2DB4 +:1022100034D8387828BB228C072A2CD8268A36F066 +:1022200003032BD14FF6FF70FFF7D4FD4FF6FF727B +:1022300020F001003602400446EA0565400C45EAFC +:102240004025234629463846FFF700FF002807DDD2 +:10225000626913780133DBB21F2B88BF0023137030 +:10226000F8BD218A2D0645EA012505432046FFF7E2 +:1022700021FE0246E5E76FF00300F1E76FF0010091 +:10228000EEE7000070B504461D4616468AB02822C7 +:1022900000216846FFF70AFABDF838306946ADF804 +:1022A00010300F9B204605939DF84030CDE9026524 +:1022B0008DF81830119B0793BDF84830ADF82030E9 +:1022C000FFF79CFF0AB070BD2DE9F041D3690546C8 +:1022D0000C4616460BB9138C5BBB377E1F2F28D8D4 +:1022E00095F80080B8F1000F26D03046FFF7E2FDE8 +:1022F0003378210241EAC33141EA0801338A41EAD5 +:10230000076141EA034102463346284641F0800115 +:10231000FFF79CFE00280ADD3378012B07D1726994 +:1023200013780133DBB21F2B88BF00231370BDE885 +:10233000F0816FF00100FAE76FF00300F7E70000AB +:10234000F0B504460D461E4617468BB028220021E4 +:102350006846FFF7ABF99DF84C3029465A1E5342A8 +:1023600053418DF800309DF840306A46ADF810308A +:10237000119B204605939DF84830CDE902768DF8F3 +:102380001830149B0793BDF85430ADF82030FFF798 +:102390009BFF0BB0F0BD0000406A00B104307047F5 +:1023A000436A1A68426202691A600361C38A013B88 +:1023B000C38270472DE9F041D0F8208014461D46B5 +:1023C00041460027174E09B9BDE8F081D1E9022343 +:1023D000A21A65EB0303964277EB03031ED2036A4E +:1023E0008B420DD1FFF790FD036A1B6803620369FE +:1023F0000B60C38A0161016A013B8846C382E2E740 +:10240000FFF782FD0B68C8F8003003690B60C38AD0 +:102410000161013BC382D8F80010D4E788460968FF +:10242000D1E700BF80841E002DE9F04F8BB00D4630 +:1024300014469B468046DDF85090002800F01A8133 +:10244000B9F1000F00F01681531E3F2B00F21281EC +:10245000012A03D1BBF1000F40F00C810023CDE92C +:102460000833B8F81430B5EBC30F4FEAC30703D3F2 +:1024700000200BB0BDE8F08F2B199F42D8F80C302C +:1024800036BF7F1B2746FFB21BB9D8F81030002B90 +:102490007BD0272D4ED8C5F12806B7424FF0000358 +:1024A00034BF3E46F6B2009329463246D8F80800BB +:1024B00008ABFFF745FCA7EB060A35445FFA8AFA3A +:1024C0002821B8F8143003F10053053BDB000493D6 +:1024D000D8F80C300393039B13B1BAF1000F2CD141 +:1024E000D8F8100040B1BAF1000F05D0524600965E +:1024F00008AB691AFFF724FC38B2002FB8D0660782 +:102500000AD00AAB03EBD40111F8083C624202F096 +:102510000702134101F8083C082C3DD9102C40F269 +:10252000B680202C40F2B880BBF1000F00F09D80F7 +:10253000082335E0BA460026C2E7049BE02B28BFFB +:10254000E02306930B44AB42059315D95A1B9245E1 +:1025500038BF5246039828BFD2B20096691A08AB1A +:1025600004300792FFF7ECFB079A1644AAEB020A25 +:102570001544F6B25FFA8AFA049B069A05999B1AEB +:102580000493039B1B680393A5E700933A462946EF +:10259000D8F8080008ABADE7BBF1000F13D001235A +:1025A000B4EBC30F6CD0082C12D89DF82030621EFB +:1025B00023FA02F2D50706D54FF0FF3202FA04F4EF +:1025C00023438DF820309DF8203089F8003050E703 +:1025D000102C12D8BDF82030621E23FA02F2D10767 +:1025E00006D54FF0FF3202FA04F42343ADF8203051 +:1025F000BDF82030A9F800303BE7202C0FD808990F +:10260000631E21FA03F3DA0705D54FF0FF3202FA11 +:1026100004F40C430894089BC9F8003029E7402CC7 +:102620002BD0DDE90865611EC4F12102A4F121036C +:1026300026FA01F105FA02F225FA03F311431943D0 +:10264000CB0712D50122A4F12003C4F1200102FA24 +:1026500003F322FA01F1A240524243EA010363EB81 +:10266000430332432B43CDE90823DDE90823C9E9BD +:102670000023FEE66FF00100FBE66FF00800F8E6CD +:10268000082CA0D9102CB3D9202CEED8C3E7BBF16D +:10269000000FADD0022383E7BBF1000FBBD00423B2 +:1026A0007EE70000012A30B5144638BF012200251C +:1026B000402A28BF402285B0012CCDE9025517D809 +:1026C0001B788DF8083053070AD004AB03EBD20512 +:1026D00015F8083C544204F00704A34005F8083CF0 +:1026E0000346009102A80021FFF72AFB05B030BD88 +:1026F000082CE5D9102C03D81B88ADF80830E2E788 +:10270000202C02D81B680293DDE7D3E90045CDE910 +:102710000245D8E710B5CB681BB98B600B618B8283 +:1027200010BD04691A681C600361C38A013BC3823F +:10273000CA60F0E703064CBFC0F3C0300220704708 +:1027400008B50246FFF7F6FF022806D15306C2F38A +:102750000F2001D100F0030008BDC2F30740FBE7E2 +:102760002DE9F04F93B0CDE903230A6804461046E3 +:10277000FFF7E0FF02280CBF0026C2F30626002A5E +:102780000D46824680F2F98112F0C04940F0F58191 +:10279000097B002900F0F181022803D02378B3429D +:1027A00040F0EE81C2F304631046069302F07F030B +:1027B0000593FFF7C5FF059B00224FEA83480023DE +:1027C00048EA0A48294448EA4668CE78CDE9082311 +:1027D000F309834648EA0008029367D0059B024646 +:1027E000009320465346676808A9B847002800F0C0 +:1027F000CA81276A4FB9414604F10C00FFF704FB78 +:10280000074690B96FF0020054E03B6998450DD03F +:102810003F68002FF9D1414604F10C00FFF7F4FAAC +:1028200007460028EED0236A3B60276297F817C05E +:1028300006F01F08CCF3840CACEB08001FFA80FEF6 +:102840000028B8BF0EF12000A8EB0C031FFA83FE8E +:10285000B8BF00B2002B0793BEBF0EF120031BB21E +:102860000793D7E9022152EA010338D04FF0000C58 +:10287000039BDFF8F8E19A1A049B63EB010196458C +:102880007CEB01032BD36B7B97F81AE0734519D1CE +:10289000029B002B78D0012821DC7868F8B9DFF89A +:1028A000D0C1944570EB010316D337E0276A27B9EE +:1028B0006FF00C0013B0BDE8F08F3B699845B5D0C0 +:1028C0003F68F4E76A4890427CEB010301D30020A3 +:1028D000F0E7029B002BFAD0079B0F2B17DCFA7D49 +:1028E000B30002F0030203F07C031343FB75394687 +:1028F0002046FFF709FB6B7BBB76029B3BB9FB7D58 +:10290000C3F38402013262F38603FB75D0E76A7B6E +:10291000BB7E9A42DBD1029B002B35D0B309022B40 +:1029200032D0039B1422BB60049B0021FB600DA8E6 +:10293000FEF7BCFE039B20460A93049BADF83EB015 +:102940000B932B1D0C932B7B8DF840A0013BDBB22E +:10295000ADF83C30069B8DF841808DF84230059BE8 +:102960000AA98DF8433094F82C3083F001038DF8D8 +:102970004430A3689847FB7DC3F38403013303F01D +:102980001F039B02FB82A2E7FB7DC6F34012B2EB62 +:10299000D31F40F0FB80C3F38403434540F0F9802C +:1029A000029A2B7BB609002A4DD0F20762D4032B82 +:1029B00040F2F280039BAE1DBB60049B3246FB607D +:1029C0002B7B3946033BDBB204F10C00FFF7AEFA78 +:1029D00000280CDA39462046FFF796FAFB7DC3F350 +:1029E0008403013303F01F039B02FB820AE7AB88D9 +:1029F000DDE908843B834FF6FF73C9F12000A9F19C +:102A0000200228FA09F104FA00F0014324FA02F244 +:102A100011431846C9B2FFF7CBF909F10809B9F11A +:102A2000400F0346E9D13146B8822A7B033AD2B23D +:102A3000FFF7D0F9FB7DB882DA43C2F3C01262F32C +:102A4000C713FB7543E7AEB92E1D013B324639462D +:102A5000DBB204F10C00FFF769FA0028BADB2A7B2D +:102A60003146013AB88AD2B2E2E700BF80841E0044 +:102A700040420F00F98A013BC1F309010429DAB28F +:102A80005DD80023281D07F11B069A4208D910F8CB +:102A900001CB013306F801C001310529DBB2F4D1C5 +:102AA000934228BF0023039938BF04330A91049945 +:102AB00038BFDBB20B9107F11B010C91796838BF6D +:102AC0005B190D910E93FB8AADF83EB0C3F3090379 +:102AD0001A44069BADF83C208DF84230059B8DF8DA +:102AE00040A08DF8433094F82C308DF8418083F06D +:102AF00001038DF8443000237B602A7BB88A013AB9 +:102B0000291DFFF767F93B8BB882834203D120462A +:102B1000A3680AA9984720460AA9FFF7FBFDFB7D99 +:102B2000BA8AC3F38403013303F01F039B02FB82C1 +:102B30003B8B9A420CBF00206FF01000BAE67B6816 +:102B4000002BADD0052001E033461C301E68002E5E +:102B5000FAD1091A081D2E1D184401EB090CBCF10D +:102B60001B0F5FFA89F39BD89A4299D916F8013B5B +:102B700009F1010900F8013BEFE76FF0090099E660 +:102B80006FF00A0096E66FF00B0093E66FF00D0011 +:102B900090E66FF00E008DE66FF00F008AE600BF42 +:102BA000F0B53F4D3F4FEB6943F00073EB61EB69CC +:102BB0003D4B9B6AD3F800623E4046F00106C3F8E5 +:102BC0000062D3F800423C4044EA002444F001048F +:102BD000C3F80042002955D000200646C3F81C0265 +:102BE000C3F80402C3F80C02C3F8140203EBC004D8 +:102BF00001300E28C4F84062C4F84462F6D10027C0 +:102C00004FF0010C9678148816F0010F18BFD3F816 +:102C100004E20CFA04F01CBF40EA0E0EC3F804E212 +:102C200016F0020F18BFD3F80CE203EBC4041CBF6C +:102C300040EA0E0EC3F80CE2760748BFD3F81462E0 +:102C400007F1010744BF0643C3F814625668B9424E +:102C5000C4F84062966802F10C02C4F84462D3F8EA +:102C60001C4240EA0400C3F81C02CBD1D3F8002276 +:102C700022F00102C3F80022EB6923F00073EB613C +:102C8000EB69F0BD0122C3F84012C3F84412C3F847 +:102C90000412C3F81412C3F80C22C3F81C22E5E78F +:102CA000001002400000FFFFA8230020184A08B5CA +:102CB000916A8B688B6013F0010104D013F00C0F44 +:102CC00018BF4FF48031D80506D513F4406F14BFF8 +:102CD00041F4003141F00201D80306D513F4402F2E +:102CE00014BF41F4802141F00401D3690BB10848BD +:102CF0009847302383F311880021064800F048FBF1 +:102D0000002383F31188BDE8084000F099BD00BF9F +:102D1000A8230020B023002038B5124CA36ADD6838 +:102D2000AA0712D05A6922F002025A61A36913B1AC +:102D3000012120469847302383F3118800210A4857 +:102D400000F026FB002383F31188EB0606D5102143 +:102D5000A36AD960236A0BB102489847BDE838409E +:102D600000F06EBDA8230020B823002038B5124C17 +:102D7000A36A1D69AA0712D05A6922F010025A618B +:102D8000A36913B1022120469847302383F31188A9 +:102D900000210A4800F0FCFA002383F31188EB06B7 +:102DA00006D51021A36A1961236A0BB1024898471E +:102DB000BDE8384000F044BDA8230020B82300201F +:102DC00038B50F4CA36A5D682A075D600AD50422F6 +:102DD00022701A6822F002021A60636A13B100219D +:102DE000204698476B0706D5A36A9969236A13B1F1 +:102DF000034809049847BDE8384000F021BD00BFF2 +:102E0000A823002010B50E4C204600F02FF90D4BE2 +:102E10000B211320A36200F009F90B21142000F00C +:102E200005F90B21152000F001F90B21162000F007 +:102E3000FDF8BDE8104000220E201146FFF7B0BE9D +:102E4000A8230020006400400F4B10B598420446B0 +:102E500005D10E4BDA6942F00072DA61DB690122BA +:102E6000A36A1A60A36A5A68D20707D562685168D4 +:102E70001268D9611A60064A5A6110BD0121082002 +:102E800000F0B0F9EEE700BFA823002000100240D8 +:102E90005B87010003291AD8DFE801F0020A0F144A +:102EA000836A9B6813F0E05F14BF01200020704725 +:102EB000836A9868C0F380607047836A9868C0F33B +:102EC000C0607047836A9868C0F300707047002044 +:102ED0007047000010B5032927D8DFE801F002276A +:102EE0002B2F836A9968C1F30161183103EB011339 +:102EF0001078840648BF5468C0F3001158BF948806 +:102F00004FEA410148BF41EAC40100F00F00586098 +:102F100048BF41F00401906858BF41EA4451D2686B +:102F200041F001019860DA60196010BD836A03F511 +:102F3000C073DDE7836A03F5C873D9E7836A03F5D5 +:102F4000D073D5E701290AD002290FD081B9836A4D +:102F5000DA68920701D1186903E001207047836A9B +:102F6000D86810F0030018BF01207047836AF2E7A9 +:102F70000020704710B539B9836AD96889071BD119 +:102F80001B699C0704D110BD012915D00229FAD173 +:102F9000816AD1F8C031D1F8C441D1F8C8011061BB +:102FA000D1F8CC015061202008610869800717D151 +:102FB000486940F0100012E0816AD1F8B031D1F8D0 +:102FC000B441D1F8B8011061D1F8BC0150612020A2 +:102FD000C860C868800703D1486940F002004861B2 +:102FE000C3F34000C3F38001000140EA41111079AE +:102FF00020F030000143117189064BBF916811899F +:10300000DB085B0D4CBF63F31C0163F30A0113790A +:1030100048BF916064F3030313714FEA14234FEA2E +:10302000144458BF118113705480ACE70122090188 +:1030300000F1604303F56143C9B283F8001300F067 +:103040001F039A4043099B0003F1604303F561436A +:10305000C3F880211A607047090100F16040C9B2CD +:1030600000F56D4001767047FFF7CCBE0123037079 +:10307000002300F10802C0E9022200F11002C0E9B9 +:103080000422C0E90633C0E90833436070470000FA +:1030900010B53023044683F3118802234160037086 +:1030A000FFF7D2FE04230020237080F3118810BDA7 +:1030B0002DE9F0411F4604460D461646302383F3A2 +:1030C000118800F108082378052B0DD029462046E9 +:1030D000FFF7E0FE40B1204632462946FFF7FAFEF0 +:1030E000002080F3118808E03946404600F040F99E +:1030F0000028E8D0002383F31188BDE8F0810000A8 +:103100002DE9F0411F4604460D461646302383F351 +:10311000118800F110082378052B0DD02946204690 +:10312000FFF710FF40B1204632462946FFF722FF45 +:10313000002080F3118808E03946404600F018F975 +:103140000028E8D0002383F31188BDE8F081000057 +:1031500000238268037503691B6899689142FBD25A +:103160005A680360426010605860704700238268AC +:10317000037503691B6899689142FBD85A6803601C +:10318000426010605860704708B50846302383F3EA +:1031900011880B7D032B05D0042B0DD02BB983F3A5 +:1031A000118808BD00228B691A604FF0FF338361DC +:1031B000FFF7CEFF0023F2E7D1E9003213605A6037 +:1031C000F3E70000FFF7C4BF054BD968087518681E +:1031D000026853601A6001220275D860FDF796BB41 +:1031E000D823002030B50C4B0446DD684B1C87B05B +:1031F0000FD02B466846094A00F0F0F82046FFF74A +:10320000E3FF009B13B1684600F0F0F8A86907B02F +:1032100030BDFFF7D9FFF9E7D82300208931000836 +:10322000044B1A68DB6890689B68984294BF002042 +:1032300001207047D8230020084B10B51C68D868BF +:10324000226853601A6001222275DC60FFF78EFF4E +:1032500001462046BDE81040FDF758BBD8230020AA +:10326000044B1A68DB6892689B689A4201D9FFF7A1 +:10327000E3BF7047D823002038B501230025064C52 +:10328000064907482370656000F020FB0223237085 +:1032900085F3118838BD00BF30250020B03D0008FF +:1032A000D823002000F0B4B8EFF3118020B9EFF379 +:1032B0000583302282F311887047000010B530B9C1 +:1032C000EFF30584C4F3080414B180F3118810BD32 +:1032D000FFF7C6FF84F31188F9E700008B60022333 +:1032E00008618B82084670478368A3F1440243F863 +:1032F000142C026943F8442C426943F8402C094AD3 +:1033000043F8242CC268A3F1200043F8182C0222B1 +:1033100003F80C2C002203F80B2C034A43F8102C62 +:10332000704700BF1D090008D823002008B5FFF72B +:10333000DBFFBDE80840FFF745BF0000024BDB683C +:1033400098610F20FFF740BFD8230020302383F37C +:103350001188FFF7F3BF000008B50146302383F35F +:1033600011880820FFF73EFF002383F3118808BD72 +:10337000064BDB6839B1426818605A6013604360DD +:103380000420FFF72FBF4FF0FF307047D8230020F5 +:1033900038B504460D462068844200D138BD036824 +:1033A00023605C608561FFF70DFFF4E710B50A4C00 +:1033B00023699A6891420CD85A6881600360426020 +:1033C00010609A685860511A99604FF0FF33A361FA +:1033D00010BD1B68891AECE7D8230020C0E903233D +:1033E000002310B410BC4361FFF7E0BF036881689D +:1033F0009A680A449A60426813605A6000234FF04A +:10340000FF320360014B9A61704700BFD823002050 +:1034100070B5124D2A46EB690133EB6152F8103F4B +:10342000934206D030269A68013A9A602C69A368C4 +:1034300003B170BDD4E900210A605160236083F3B9 +:1034400011882046D4E90331984786F311886169D1 +:103450000029EBD02046FFF7A9FFE7E7D82300209B +:1034600000207047FEE70000704700004FF0FF307B +:1034700070470000BFF34F8F024AD368DB07FCD4CC +:10348000704700BF0020024008B5074B1B7853B9B6 +:10349000FFF7F0FF054B1A69120641BF044A5A6054 +:1034A00002F188325A6008BD482500200020024001 +:1034B0002301674508B5054B1B7833B9FFF7DAFFE1 +:1034C000034A136943F08003136108BD48250020B7 +:1034D000002002407F289ABF00F5003080020020C3 +:1034E000704700004FF480607047000080207047F4 +:1034F0007F2808B50BD8FFF7EDFF00F58063026861 +:10350000013204D104308342F9D1012008BD0020EA +:10351000FCE700007F2810B504461CD8FFF7AAFF7F +:10352000FFF7B2FFF3220D4B4FF48061DA60022205 +:103530001A61FFF7CFFF58611A6942F040021A6121 +:10354000FFF798FF00F004F9FFF7B4FF2046BDE84D +:103550001040FFF7CDBF002010BD00BF002002408B +:103560002DE9F843054612F00100144606D040F25A +:10357000F32200201E4B1A60BDE8F8831D4BAA18E9 +:103580009A4204D94FF43E72194B1A60F4E7FFF7E0 +:103590007BFF4FF00109FFF76DFFDFF85C806D1ACC +:1035A000012C0F4605EB010603D8FFF783FF01202E +:1035B000E2E73B88C8F8109033800020FFF75AFFFD +:1035C000C8F81000338831F8022B9BB29A420CD015 +:1035D00040F20F32064B1A60084B1E60084B1C600D +:1035E000084B1F60FFF766FFC6E7023CD8E700BF45 +:1035F0004425002000000208002002403825002059 +:10360000402500203C250020084908B50B7828B14A +:103610001BB9FFF739FF01230B7008BD002BFCD04D +:10362000BDE808400870FFF745BF00BF48250020EF +:1036300070B5FFF739FE4FF47A710D4B0D4EDB6913 +:10364000326801FB03F3934237BF0B4A0A495168C2 +:10365000156836BF4C1CD1E9005454605D1944F123 +:1036600000043360FFF72AFE2846214670BD00BFE4 +:10367000D82300204C2500205025002070B5FFF7EE +:1036800013FE4FF47A710F4B0F4EDB69326801FB6A +:1036900003F3934237BF0D4A0C49516815683ABF8E +:1036A0004C1C5460D1E900545D1944F100043360AE +:1036B000FFF704FE4FF47A72002328462146FCF7F8 +:1036C00031FF70BDD82300204C250020502500205C +:1036D00010B5094C013AD2B2FF2A00D110BD5008F2 +:1036E00054F82030013054F820009BB243EA0043E4 +:1036F00041F8043BEEE700BF046C004010B50748FA +:10370000013AD2B2FF2A00D110BD0C88530840F80C +:1037100023404C88013340F82340F1E7046C00401B +:1037200007B50122002001A9FFF7D2FF019803B0DD +:103730005DF804FB13B50446FFF7F2FFA04205D085 +:103740000122002001A90194FFF7D8FF02B010BDAB +:103750007047000045F25552064B1A6002225A602B +:1037600040F6FF729A604CF6CC421A600122024B7E +:103770001A707047003000405C250020034B1B7816 +:103780001BB14AF6AA22024B1A6070475C25002042 +:1037900000300040044B1A682AB902F1804202F559 +:1037A0000432526A1A607047582500204FF0807228 +:1037B000014B5A62704700BF0010024008B5FFF786 +:1037C000E9FF024B1868C0F3407008BD582500207F +:1037D00008B5FFF7DFFF024B1868C0F3007008BDA3 +:1037E00058250020EFF30983203383F30988002351 +:1037F00083F3118870470000302080F3118862B68F +:103800000C4B0D4AD96821F4E0610904090C0A4304 +:10381000DA60D3F8FC20094942F08072C3F8FC203A +:103820000A6842F001020A602022DA7783F8220057 +:10383000704700BF00ED00E00003FA05001000E053 +:10384000302310B583F311880B4B5B6813F40063CE +:103850000FD0EFF309844FF08073203CE36184F3D1 +:103860000988FFF7DDFC10B1044BA36110BD044BC8 +:10387000FBE783F31188F9E700ED00E02F0900086A +:103880003209000870470000FEE700000A4B0B48B1 +:103890000B4A90420BD30B4BC11EDA1C121A22F0BA +:1038A00003028B4238BF00220021FDF7FFBE53F810 +:1038B000041B40F8041BECE7343E0008E025002020 +:1038C000E0250020E0250020FEE7000070B500257F +:1038D00004461A4B86B05860856201630E46FFF7B6 +:1038E0008BFF04F11003C4E904334FF0FF33A361ED +:1038F000134BE561D9692B460A462046C4E90823E3 +:1039000004F134018023C4E900440E4AA560E56255 +:103910002565FFF7E3FC01230B4AE0600375009285 +:10392000726868460192B268CDE90223074BCDE97F +:103930000435FFF7FBFC06B070BD00BF302500204A +:10394000D8230020BC3D0008C13D0008C93800084C +:1039500000F030B808B500F063F9FFF78DFCBDE862 +:103960000840FFF717BF0000704700004FF0FF311D +:103970000E4B1A6919611A6900221A611869D86810 +:10398000D960D968DA60DA68DA6942F08052DA61BF +:10399000DA69DA6942F00062DA61054ADB691368C4 +:1039A00043F48073136000F01BB900BF00100240A5 +:1039B00000700040194B1A6842F001021A601A6840 +:1039C0009007FCD51A6802F0F9021A6000225A60CA +:1039D0005A6812F00C0FFBD11A6842F480321A6058 +:1039E0001A689103FCD55A6842F4E8125A601A68C2 +:1039F00042F080721A601A689201FCD51221084ABE +:103A00005A60084A11605A6842F002025A605A68C5 +:103A100002F00C02082AFAD1704700BF00100240E1 +:103A200000641D0000200240084A08B5516913686F +:103A30000B4003F00103536123B1054A13680BB136 +:103A400050689847BDE80840FFF7FABE00040140FF +:103A500060250020084A08B5516913680B4003F03F +:103A60000203536123B1054A93680BB1D0689847AC +:103A7000BDE80840FFF7E4BE0004014060250020D7 +:103A8000084A08B5516913680B4003F004035361F9 +:103A900023B1054A13690BB150699847BDE8084046 +:103AA000FFF7CEBE0004014060250020084A08B59B +:103AB000516913680B4003F00803536123B1054AB1 +:103AC00093690BB1D0699847BDE80840FFF7B8BECD +:103AD0000004014060250020084A08B551691368B8 +:103AE0000B4003F01003536123B1054A136A0BB175 +:103AF000506A9847BDE80840FFF7A2BE00040140A5 +:103B000060250020174B10B55A691C68144004F456 +:103B100078725A61A30604D5134A936A0BB1D06A2E +:103B20009847600604D5104A136B0BB1506B984749 +:103B3000210604D50C4A936B0BB1D06B9847E20574 +:103B400004D5094A136C0BB1506C9847A30504D5F2 +:103B5000054A936C0BB1D06C9847BDE81040FFF755 +:103B60006FBE00BF00040140602500201A4B10B555 +:103B70005A691C68144004F47C425A61620504D5F9 +:103B8000164A136D0BB1506D9847230504D5134A9F +:103B9000936D0BB1D06D9847E00404D50F4A136EB6 +:103BA0000BB1506E9847A10404D50C4A936E0BB12B +:103BB000D06E9847620404D5084A136F0BB1506F5A +:103BC0009847230404D5054A936F0BB1D06F9847EB +:103BD000BDE81040FFF734BE00040140602500201E +:103BE000062108B50846FFF721FA06210720FFF74E +:103BF0001DFA06210820FFF719FA06210920FFF710 +:103C000015FA06210A20FFF711FA06211720FFF7FF +:103C10000DFABDE8084006212820FFF707BA00008A +:103C200008B5FFF7A3FE054800F00CF8FFF71CFAF3 +:103C3000FFF79AFEBDE8084000F002B8C83D000852 +:103C400000F042B8002319461C4A0133102BC2E988 +:103C5000001102F10802F8D1194B9A6942F07D0275 +:103C60009A619B690268174BDA6082685A60426801 +:103C70001A60C26803F58063DA6042695A600269BB +:103C80001A608269C3F80C24026AC3F80424C2696A +:103C9000C3F80024426AC3F80C28C26AC3F8042897 +:103CA000826AC3F80028026BC3F80C2C826BC3F83D +:103CB000042C426BC3F8002C704700BF6025002025 +:103CC00000100240000801404FF0E023044A0821A0 +:103CD0005A6100229A6107220B201A61FFF7BCB9D2 +:103CE0003F19010008B5302383F31188FFF7DAFA92 +:103CF000002383F3118808BD08B5FFF7F3FFBDE883 +:103D00000840FFF79DBD000010B501390244904204 +:103D100001D1002005E0037811F8014FA34201D042 +:103D2000181B10BD0130F2E72DE9F0419BB10446AC +:103D3000C91A1778014403F1FF3C8C42204601D98F +:103D4000002008E005780134BD42F6D10CEB0405F3 +:103D5000D618A54201D1BDE8F08115F8018D16F8FD +:103D600001EDF045F5D0E8E7034611F8012B03F823 +:103D7000012B002AF9D170476F72672E617264754A +:103D800070696C6F742E663130332D52616E6765C9 +:103D900046696E646572000040A2E4F164689106B1 +:103DA0000041A3E5F265699207000000633000005E +:103DB000AC3D000830240020302500206D61696E84 +:103DC0000069646C65000000001800004444414430 +:103DD000445449440100000042444444444444449F +:103DE00000000000444444444444444400000000B3 +:103DF0004444444444444444000000004444444493 +:103E00004444444450C7FF7F01000000000000000C +:103E1000E803000000000000009C0100000000001A +:103E2000640000000000000040420F00FE2A010074 +:043E3000D2040000B8 :00000001FF diff --git a/Tools/bootloaders/f103-Trigger_bl.bin b/Tools/bootloaders/f103-Trigger_bl.bin index ceac350c263a54..a2de5dfcab8091 100755 Binary files a/Tools/bootloaders/f103-Trigger_bl.bin and b/Tools/bootloaders/f103-Trigger_bl.bin differ diff --git a/Tools/bootloaders/f103-Trigger_bl.elf b/Tools/bootloaders/f103-Trigger_bl.elf index ad6e82d8d01e38..dc9a90b5ba556f 100755 Binary files a/Tools/bootloaders/f103-Trigger_bl.elf and b/Tools/bootloaders/f103-Trigger_bl.elf differ diff --git a/Tools/bootloaders/f103-Trigger_bl.hex b/Tools/bootloaders/f103-Trigger_bl.hex index 83fdd87e158c00..fe677d32dd3236 100644 --- a/Tools/bootloaders/f103-Trigger_bl.hex +++ b/Tools/bootloaders/f103-Trigger_bl.hex @@ -1,1062 +1,997 @@ :020000040800F2 -:1000000000090020A10400081514000819140008B4 -:10001000551400081914000835140008A30400083A -:10002000A3040008A3040008A3040008C5360008C0 -:10003000A3040008A3040008A3040008593A000818 -:10004000A3040008A3040008A3040008A3040008F4 -:10005000A3040008A3040008393800086538000824 -:1000600091380008BD380008E9380008A3040008EA -:10007000A3040008A3040008A3040008A3040008C4 -:10008000A3040008A3040008A304000869250008CD -:10009000D5250008292600087D2600081539000806 -:1000A000A3040008A3040008A3040008A304000894 -:1000B000A3040008A3040008A3040008A304000884 -:1000C000A3040008A3040008A3040008A304000874 -:1000D000A3040008A12A0008B52A0008A304000808 -:1000E0007D390008A3040008A3040008A304000845 -:1000F000A3040008A3040008A3040008A304000844 -:10010000A3040008A3040008A3040008A304000833 -:10011000A3040008A3040008A3040008A304000823 -:10012000A3040008A3040008A3040008A304000813 -:10013000A3040008A3040008A3040008A304000803 -:10014000A3040008A3040008A3040008A3040008F3 -:10015000A3040008A3040008A3040008A3040008E3 -:10016000D0400B1CD1409C46203AD3401843524209 -:1001700063469340184370479140031C90409C464F -:10018000203A9340194352426346D3401943704783 -:1001900053B94AB9002908BF00281CBF4FF0FF31EE -:1001A0004FF0FF3000F07AB9ADF1080C6DE904CEE4 -:1001B00000F006F8DDF804E0DDE9022304B0704742 -:1001C0002DE9F0478C460E460446089D002B50D181 -:1001D0008A4217466CD9B2FA82FEBEF1000F0BD0EC -:1001E000CEF1200C01FA0EF620FA0CFC02FA0EF702 -:1001F0004CEA060C00FA0EF43A0CBCFBF2F9BBB266 -:1002000002FB19CC09FB03FA4FEA144848EA0C46F2 -:10021000B2450AD9F61909F1FF3180F02581B245BE -:1002200040F22281A9F102093E44A6EB0A06B6FB80 -:10023000F2F002FB106600FB03F3A4B244EA0644AA -:10024000A34209D9E41900F1FF3280F00B81A342E7 -:1002500040F2088102383C440021E41A40EA094097 -:10026000002D62D0002324FA0EF42C606B60BDE8F0 -:10027000F0878B4207D9002D55D0002185E8410039 -:100280000846BDE8F087B3FA83F1002940F08F807B -:10029000B34202D3824200F2FC80841A66EB03066A -:1002A0000120B446002D40D085E81010BDE8F0874D -:1002B00012B90127B7FBF2F7B7FA87FEBEF1000FBC -:1002C00035D10121F61B4FEA174C1FFA87F8B6FB10 -:1002D000FCF20CFB126608FB02F0230C43EA064614 -:1002E000B04207D9F61902F1FF3302D2B04200F250 -:1002F000D2801A46361AB6FBFCF00CFB106608FBDF -:1003000000F8A3B243EA0644A04507D9E41900F176 -:10031000FF3302D2A04500F2B9801846A4EB0804CE -:1003200040EA02409CE729462846BDE8F08707FAE4 -:100330000EF7CEF1200326FA03F24FEA174CB2FB78 -:10034000FCF11FFA87F80CFB112206FA0EF620FAD0 -:1003500003F301FB08F933431E0C46EA0246B1459C -:1003600000FA0EF409D9F61901F1FF3280F08C8001 -:10037000B14540F2898002393E44A6EB0906B6FB3E -:10038000FCF00CFB106200FB08F99EB246EA024644 -:10039000B14507D9F61900F1FF3371D2B1456FD9D4 -:1003A00002383E44A6EB090640EA01418FE7C1F15D -:1003B000200722FA07F88B4048EA030326FA07F4DD -:1003C0004FEA134EB4FBFEF91FFA83FC0EFB1944EF -:1003D0008E4020FA07F809FB0CFA48EA06084FEAB3 -:1003E000184646EA0444A24502FA01F200FA01F670 -:1003F00008D9E41809F1FF3044D2A24542D9A9F145 -:1004000002091C44A4EB0A04B4FBFEF00EFB1044EA -:1004100000FB0CFC1FFA88F848EA0444A44507D9FD -:10042000E41800F1FF3E29D2A44527D902381C4424 -:1004300040EA0940A0FB0289A4EB0C0CCC45C24663 -:10044000CE4615D312D055B1B6EB0A036CEB0E06AF -:1004500006FA07F7CB401F43CE402F606E600021A5 -:10046000BDE8F0871046F7E68946DEE64645EAD263 -:10047000B8EB020A69EB030E0138E4E77046D7E7F0 -:1004800018468FE78146BDE7114676E702383C44BF -:1004900044E7084606E7023A3E442BE7704700BFB0 -:1004A00002E000F000F8FEE772B6274880F3088803 -:1004B000264880F3098826484EF60851CEF20001FE -:1004C0000860022080F31488BFF36F8F03F02AF9CD -:1004D00003F046F94FF055301E491B4A91423CBF8C -:1004E00041F8040BFAE71C49184A91423CBF41F815 -:1004F000040BFAE719491A4A1A4B9A423EBF51F8BF -:10050000040B42F8040BF8E700201749174A914200 -:100510003CBF41F8040BFAE703F008F903F022F9B5 -:10052000134C144DAC4203DA54F8041B8847F9E726 -:1005300000F03AF8104C114DAC4203DA54F8041BA9 -:100540008847F9E703F0F0B8000900200011002007 -:10055000000000080001002000090020C041000840 -:1005600000110020741100207811002000260020C6 -:1005700060010008600100086001000860010008D7 -:100580002DE9F04FC1F80CD0C3689D46BDE8F08F4F -:10059000002383F311882846A047002002F07EFE46 -:1005A00002F0A8FD00DFFEE76FF01702364B2DE9E1 -:1005B000F0411A70032200245A7001266FF0630282 -:1005C0009C70DC701C715C719C71DC711C725A72C5 -:1005D0009E72DC7203F020F8804603F06DF8054649 -:1005E000D0BB2A4B984539D03344984537D0284B57 -:1005F00028F0FF029A4234D15FFA88F000F04EFAF8 -:100600002E4642F2107400F077FC00F04DFA0746D7 -:1006100058B364BB374635B11E4B984503D0002410 -:1006200003F042F82746002003F000F81A4B9B68BD -:1006300013F040031ED00FB100F030F800F07EFC44 -:1006400000F018FE00F014FF0546ACB900F0CCFC39 -:10065000012002F029FEF8E70646D4E706462C46BC -:10066000D1E706464FF47A74CDE70446D3E74FF45A -:100670007A74D0E71C46E1E700F0FAFE401BA04286 -:10068000E4D900F00BF8DDE778110020010007B095 -:10069000000008B0263A09B0000C014010B51C4B10 -:1006A0001C4953F8042F013200D110BD8B42F8D100 -:1006B000194C1A4B22689A4228D9194B9B6803F1AE -:1006C000006303F5C8439A4220D202F0C1FF02F052 -:1006D000D3FF002000F0E8FD0220124B187000F05C -:1006E0001FFE114BDA690022DA61D96999699A61B2 -:1006F0009B6972B60D4B0E4A202113601B6822685D -:1007000081F311889D4683F30888104710BD00BF10 -:10071000FC6300081C64000804640008FF63000810 -:1007200078110020841100200010024000640008AD -:1007300008ED00E049F2690008490B689AB21B0C09 -:1007400000FB02330B6044F25061054A136898B213 -:100750001B0C01FB0030106080B270470C110020B0 -:100760000811002010B504460021102200F0F4FD0D -:10077000034B03CB206061601868A06010BD00BF10 -:10078000E8F7FF1FF0B5BBB000F072FE1D4CA36888 -:10079000C31AF92B30D906AD2346A06028220021C8 -:1007A000284601F0F3FB04F10E0000F0CDFD00231C -:1007B000C6B2591D5F1CDBB2B3424FEAC10107DA72 -:1007C0000E3323440822284601F0E0FB3B46F0E7C5 -:1007D00001230393082302930B4B207B01933023C7 -:1007E000C1F3CF0105910093014604A3D3E900238F -:1007F0000495064801F09AF93BB0F0BD78F6339FB6 -:1008000093CACD8DC8210020D5210020A021002031 -:1008100070B50D4614461E4601F02EF950B9022E51 -:100820000ED1012C0CD112A3D3E90023C5E900237A -:10083000012070BD052C14D003D8012C09D0002054 -:1008400070BD282C09D0302CF9D10BA3D3E900239B -:10085000ECE70BA3D3E90023E8E70BA3D3E90023DC -:10086000E4E70BA3D3E90023E0E700BFAFF3008088 -:10087000401DA12026812A0B78F6339F93CACD8D87 -:100880009E6AC421818A46EE26417272DF25D7B75F -:10089000F017304A39059E5638B50D4604460346D2 -:1008A00020222846002101F071FB22792346032AE9 -:1008B00028BF0322284603F8042F2021022201F03A -:1008C00065FB62792346072A28BF0722284603F8DA -:1008D000052F2221032201F059FBA2792346072A82 -:1008E00028BF0722284603F8062F2521032201F0FE -:1008F0004DFB284604F108031022282101F046FB95 -:10090000382038BD2DE9F04FADF5017D21AE0EAD9B -:1009100040F2791280460F463046002100F01CFD5F -:1009200048220021284600F017FD00F0A1FD4FF4F9 -:100930007A72B0FBF2F0574B0DF15A09186093E848 -:10094000070001232B74002385E807000DF15A00EE -:100950006B74FFF707FF032385F82030E82385F841 -:10096000213006AB18464C4903F0E0F81F222864FA -:100970003146284685F83C20FFF78EFF12AB04462F -:1009800001460822304601F001FB08220DF149031F -:10099000A118304601F0FAFA0DF14A03082204F1D9 -:1009A0001001304601F0F2FA13AB202204F11801D5 -:1009B000304601F0EBFA14AB402204F13801304626 -:1009C00001F0E4FA16AB082204F17801304601F098 -:1009D000DDFA0DF15903082204F18001304601F0DF -:1009E000D5FA04F1880A04F5847B4B465146082267 -:1009F00030460AF1080A01F0C9FAD34509F10109A4 -:100A0000F3D11BAB08225946304601F0BFFA4FF034 -:100A1000000904F5887495F834304B4510D84FF030 -:100A2000000995F83C304B4515D92B6C21464B44B9 -:100A30000822304601F0AAFA083409F10109F0E76A -:100A4000AB6B21464B440822304601F09FFA083434 -:100A500009F10109DFE7E31DC3F3CF03F97E059335 -:100A6000002304960393BB7E193702930123019759 -:100A70000093404605A3D3E9002301F057F80DF594 -:100A8000017DBDE8F08F00BFAFF300809E6AC421F6 -:100A9000818A46EE88110020043D0008014B187041 -:100AA000704700BF94110020F0B5334B85B01C7B1C -:100AB00034B10E22314B1A810024204605B0F0BD1E -:100AC0002F4A02AB1068516803C308232D490DEB70 -:100AD00003022D4803F00CF8054630B90A22274BD3 -:100AE0002A481A8100F08CFCE6E70169B1F5CE3F97 -:100AF00006D90B22214B26481A8100F081FCDCE745 -:100B0000438BB3F57A7F09D00C211C4A214811810F -:100B10004FF47A72194600F073FCCEE71E4A024485 -:100B200002F11003994204D21022144B1B481A817F -:100B3000E3E710398E1A2046134900F09DFC074662 -:100B4000324605F11801204600F096FCAB689F4242 -:100B500002D1EB6898420AD00D22084B1A8100900E -:100B60003B46EA68A9680E4800F04AFCA4E70D4835 -:100B700000F046FC0124A0E7C821002088110020D5 -:100B8000D43B0008DC9B010000640008DC3B00084B -:100B9000E83B0008FA3B0008089CFFF7183C0008F7 -:100BA000353C00085E3C00082DE9F04FADB006AFC3 -:100BB00080460C4600F060FF054600286AD1237E7F -:100BC000022B18D1E38A012B15D100F051FC81468C -:100BD000FFF7B0FD4FF4C873B0FBF3F202FB130054 -:100BE000BB4E80B209F51679E37E484430608BB97C -:100BF0000022B84B1A709C37BD46BDE8F08F3B1DF4 -:100C00001D440095002308224FEAC901204601F047 -:100C100021F84D46A38A5FFA85F9013BAB420BD917 -:100C200005F10109B9F1110FE9D140F23911AA4BCF -:100C3000AA4AAB4802F02EFF07F11400FFF792FD1D -:100C40002A4607F11401381D02F042FF034600282E -:100C5000CED1B9F1100F07D09E4B83F800903368C6 -:100C6000A3F516733360C6E707F1980202F8950DF5 -:100C7000014600922046072200F0ECFFF9787F2918 -:100C800004DD984B954A4FF4A871D2E7404600F036 -:100C9000D7FEB0E7E38A052B00F0068106D8012BCA -:100CA000A9D121464046FFF72DFEA4E7282B3DD0D1 -:100CB000302BA0D1637E8C4D01336A7BDBB2934233 -:100CC000E94640F0EF80E27E2B7B9A4240F0EA80DA -:100CD000002607F1980323F8846D00931022012366 -:100CE0003146204600F0B6FFB4F81480A8F102089F -:100CF0001FFA88F808F1030323F003030A3323F0F3 -:100D00000703ADEB030D0DF1180A33469BB2B11C7E -:100D100098454FEAC10106F101066CDD534400938A -:100D200008220023204600F095FFEEE7A38A013B4E -:100D30009BB2C92B3FF65FAF6B4E357B4DBB06F1C7 -:100D40000C03009308222B462946204600F082FF20 -:100D5000A38A05F10109013BEDB29D424FEAC901A9 -:100D600009DA0E353544009500230822204600F0AC -:100D700071FF4D46ECE700230022C6E90023002363 -:100D8000B36086F8D730C6F8D830337B0BB9E37E32 -:100D90003373002507F114063B1D0822294630460F -:100DA0007D60BD60FD6001F0F1F83B7A05F101095D -:100DB000AB424FEAC90107D9FB6808222B443046F1 -:100DC00001F0E4F84D46F0E70023C1F3CF01E07EE7 -:100DD000059104960393A37E1934029328230146B8 -:100DE0000093019438A3D3E90023404600F09EFE0F -:100DF000FFF7C8FCFFE695F8D70000F05FFAD5F8DA -:100E0000D83006461BB995F8D70000F067FAD5F838 -:100E1000D83043449E4204D295F8D700013000F008 -:100E20005DFA00244FEA980BA0B2584504F1010482 -:100E300008DA2B6880000AEB00010122184400F058 -:100E400093FAF1E7D5F8D840D5E9002312EB080270 -:100E500043F10003444495F8D700C5E90023C5F8E1 -:100E6000D84000F02BFA844209D395F8D7300133EB -:100E700085F8D730D5F8D8309E1BC5F8D860B8F1C2 -:100E8000FF0F08DC00232B7300F03AFAFFF70CFE8B -:100E900008B1FFF703FC2B68144A9B0A0133138146 -:100EA0000023AB60CD46A6E6BFF34F8F1049114B30 -:100EB000CA6802F4E0621343CB60BFF34F8F00BFF8 -:100EC000FDE700BFAFF3008026417272DF25D7B780 -:100ED0009C21002099210020703C0008243D00083E -:100EE000C93C0008EB3C0008C82100208811002004 -:100EF00000ED00E00400FA0508B54FF000530B4A7E -:100F0000196891420AD1597D094A0A4811701B7D1E -:100F1000C922037308490E3000F00CFABDE80840FE -:100F2000E02200214FF0005000F016BA9AAD44C5FF -:100F300094110020C821002016000020022330B5A3 -:100F40001F4C85B0637104230025ADF808300123E0 -:100F50000722ADF80C501B498DF80C308DF80B3082 -:100F6000194B1A484B608DF80A2001F0FFFD184B11 -:100F7000019500931749184B4FF48052174800F021 -:100F800029FD174B2546197811B1144800F058FD7A -:100F900000F06EFA0446FFF7CDFB4FF4C873B0FBC8 -:100FA000F3F202FB130304F516749BB21C440D4BC1 -:100FB0001C6002F081FB08B10F232B8105B030BD0E -:100FC000881100200011002003000600E02200200C -:100FD0001108000898110020A90B0008A02100208A -:100FE000941100209C2100202DE9F04F96A7D7E90D -:100FF00000670FF25C29D9E900898F4C93B0DFF8C4 -:1010000058B2DFF858A2204600F0DCFD0CAD079086 -:1010100098B310220021284600F09EF94FF00002FC -:10102000079B197B61F3030219468DF8302051F8B4 -:10103000040F0EAA496803C21B680D9A584663F351 -:101040001C029DF830300D9243F020038DF83030B3 -:1010500000232A46194601F099FD079030B9204631 -:1010600000F0B4FD079B8AF80030CCE79AF8003016 -:10107000072B40DC01338AF8003018220021284673 -:1010800000F06AF9DFF8D0B1DFF8D4A100232A46D6 -:101090001946584601F0A2FD014680BB102208A85F -:1010A00000F05AF9DAF80C3083F01003CAF80C306B -:1010B00000F0E0F90DF1240E0B4612A9024611E9E9 -:1010C00003008EE803009DF83410C1F30300890685 -:1010D00049BF0E99BDF83810C1F31C0141F0004121 -:1010E00058BFC1F30A018DF82C000891204608A9C9 -:1010F00000F0B2FFCAE7204600F068FDBDE72046D9 -:1011000000F0BAFC824600284AD100F0B1F9DFF8BD -:1011100054B1DBF80030984242D300F0A9F90790AF -:10112000FFF708FB4FF4C873B0FBF3F101FB1300AA -:10113000079A80B202F516721044CBF80000DFF86F -:1011400028B18DF820A09BF8001011B901238DF86B -:10115000203028460791FFF705FB07990DF1210084 -:10116000C1F1100A5FFA8AFABAF1060F28BF4FF0F0 -:10117000060A2944524600F0DDF80AF101030493FF -:1011800008AB0393182302932C4B3246019301239F -:10119000204600933B4600F071FC00238BF80030A2 -:1011A00000F066F9264ADFF8C4A01368C31AB3F545 -:1011B0007A7F32D3106000F05DF902460B4620467C -:1011C00000F00AFD204600F057FC30B39AF80C30CE -:1011D000DFF89CB0002B14BF032302238BF80530EB -:1011E00000F046F94FF47A73B0FBF3F02946CBF8E0 -:1011F00000005846FFF750FB18230293114B0730AD -:10120000019340F25513C0F3CF000490009303956F -:1012100042464B46204600F031FC9AF80C300BB1A8 -:10122000FFF7B0FA9AF80C30002B7FF4E8AE13B059 -:10123000BDE8F08FAFF30080A021002098210020AE -:10124000A8220020AC220020401DA12026812A0BCC -:10125000F1C6A7C1D068080FE0220020AD2200200F -:10126000000801409C21002099210020C821002075 -:101270008811002070B502F0CDF80025084C094E09 -:10128000207030682378834208D902F0BFF83368B1 -:1012900005440133B5F5C84F3360F2D370BD00BFCC -:1012A000DC220020B022002002F04CB900F10060E6 -:1012B000920000F5C84002F0F1B80000054B1A6832 -:1012C000054B1B789B1A834202D9104402F09EB84A -:1012D00000207047B0220020DC22002038B50446F0 -:1012E000064D2868204402F097F828B92868204461 -:1012F000BDE8384002F0A2B838BD00BFB0220020DF -:10130000064991F8243033B100230822086A81F895 -:101310002430FFF7CBBF0120704700BFB42200206C -:10132000022802BF4FF48012014B1A61704700BFC0 -:1013300000080140002310B5934203D0CC5CC45494 -:101340000133F9E710BD000002460346981A13F96D -:10135000011B0029FAD1704703460244934202D090 -:1013600003F8011BFAE770472DE9F047234C0546C7 -:1013700094F824308846174683BB2E46DFF87C90CD -:10138000C7B394F824302BB92022FF2148462662A7 -:10139000FFF7E2FF94F824004146C0F10805BD4282 -:1013A00028BF3D465FFA85FAAD002A4604EB80006F -:1013B000FFF7C0FF94F82430A7EB0A079A445FFABE -:1013C0008AFABAF1080F2E44A844FFB284F824A088 -:1013D000D6D1FFF795FF0028D2D108E0266A06EBA8 -:1013E0008306B042CAD0FFF78BFF0028C5D100208A -:1013F000BDE8F0870120BDE8F08700BFB4220020DF -:101400000FB4002004B070470FB44FF0FF3004B0A9 -:1014100070470000FEE70000EFF30983EFF3058358 -:10142000034B9A6B9A6A9A6A9A6A9A6A9B6AFEE76F -:1014300000ED00E0EFF30983EFF30583044B9A6BB3 -:101440009A6A9A6A9A6A9A6A9A6A9B6AFEE700BFDF -:1014500000ED00E0EFF30983EFF30583034B5A6BD4 -:101460009A6A9A6A9A6A9A6A9B6AFEE700ED00E0B5 -:1014700002F0A0B802F07AB830B5084D0A449142A3 -:101480000BD0092411F8013B5840013CF7D040F340 -:1014900000032B4083EA5000F7E730BD2083B8ED0E -:1014A0000246006848B1036811891360D38801338C -:1014B0009BB29942D38038BF1381704770B5044600 -:1014C0000D4688B0202200216846FFF745FF2046E0 -:1014D0000495FFF7E5FF054658B16B46044608AE94 -:1014E0001A4603CAB24220606160134604F1080440 -:1014F000F6D1284608B070BD2DE9F04130B940F270 -:10150000C531264B264A274802F0C4FA0B7C23B982 -:10151000254B234A40F2C631F5E7C66986B9C16159 -:10152000BDE8F081002B29DA930CAB4229D1B442FB -:1015300001D10C60F3E7C8F800100C60BDE8F08141 -:101540004B68B04623F06047BD0C15EA230538BF51 -:101550003D4634464FEAD37EC3F3807C6368BEEBDE -:10156000D37F23F06042DDD1974203D1C3F3807370 -:101570009C450AD1974205E01C46EFE7AA4206D0F7 -:1015800013469D422CBF00230123002BCFD123689B -:10159000A046002BF0D12160BDE8F081F83F0008A3 -:1015A000EC3D0008B0400008D140000808B5034AEF -:1015B000034B40F25E31034802F06CFAC83D00086C -:1015C00070400008B040000808B503680B60C3888D -:1015D000016033B9044B054A4FF4C761044802F077 -:1015E00059FA013BC38008BD404000083C3E00085A -:1015F000B040000870B50C4600F10C05616831B9C7 -:10160000E38A002061F30903E382002170BD0E68C4 -:101610002846FFF7D9FF6660F0E7000008B542688A -:1016200032B10B4B0B4A40F22F410B4802F032FA19 -:10163000C37DC3F38401013161F38603C375C38A9B -:1016400062F30903C3821B0A62F3C713C37508BDA3 -:101650008C400008F83D0008B04000082DE9F04734 -:10166000089E32B91F4B204A40F239511F4802F000 -:1016700011FA4FF47F4901F007054FEAD6082A44D2 -:1016800006F0070600EBD100954201D1BDE8F087D6 -:1016900005F0070E06F0070AD645774638BF5746CD -:1016A000511BC7F108078F4228BF0F46EC08045DA5 -:1016B00008EBD60113F801C004FA0EF429FA07FE6C -:1016C00024FA0AF45FFA8EFE8CEA04044EFA0AFE4B -:1016D00004EA0E048CEA040C03F801C03D443E44C5 -:1016E000D2E700BF0C400008103E0008B0400008E0 -:1016F0002DE9F04106460F4600254FF6FF7441F2F2 -:1017000021082A4630463946FEF72AFD0823C0B292 -:1017100084EA002414F4004F4FEA4404A4B203F115 -:10172000FF3318BF84EA080413F0FF03F2D1083531 -:10173000402DE6D12046BDE8F081000010B541F211 -:1017400021040A44914200D110BD11F8013B80EA06 -:101750000320082310F4004F4FEA400080B203F149 -:10176000FF3318BF604013F0FF03F3D1EAE7000036 -:101770002DE9F04F85B08A468DE80C00BDF83C405D -:10178000814630B940F26E31484B494A494802F02F -:1017900081F911F0604F04D0474B454A40F26F3158 -:1017A000F4E7009B002B7ED024B10E9B002B7AD057 -:1017B000072C28D809F10C00FFF772FE054628B95E -:1017C0006FF00205284605B0BDE8F08F1422002115 -:1017D000FFF7C2FD22460E9905F10800FFF7AAFDAA -:1017E000631C2B74009B2C441B78294603F01F03B9 -:1017F00063F03F0323724AF000436B604846FFF7F3 -:101800007BFE0125DEE74FF000084FF0800B4646D7 -:101810004546019B1B0A029300F10C0303930398B6 -:10182000FFF73EFE07460028CAD014220021FFF72A -:1018300093FDB6BB02229DF804303B729DF8083040 -:101840007B720E9B711E1944B4420AD9B81801323A -:1018500011F801EFD2B20136072A80F808E0B6B2DB -:10186000F2D1B44208BF4FF0400B009BB818197872 -:10187000013201F01F0141EA48114BEA01030372F2 -:101880004AF000437B603A7439464846FFF734FE1D -:101890000135B4422DB288F001084FF0000BBED1E3 -:1018A00090E70022CDE76FF001058BE7F83F0008D5 -:1018B000DC3D0008B04000081C4000082DE9F0475E -:1018C0001E46CB8A9146C3F30902062A80460F467C -:1018D00019D013460021B0B28DB25A1992B2052A1E -:1018E00009D9A84210D8FA8A034463F30902FA829C -:1018F0000120BDE8F087A842F3D919F801403A4425 -:1019000094760131E8E70025FB8A7C68C3F309007F -:101910001C23821FB2FBF3FA03FB1A2A1FFA8AF276 -:101920007CB301212368002B39D1B31F03441C2051 -:10193000B3FBF0F301339BB299420CD2BAF1000F22 -:1019400009D14046FFF7ACFD08B1C0F800A0206007 -:1019500008B3044600224FF0000AB6B2B54230D2B6 -:101960001346691E4944E018013311F801EF9BB298 -:1019700001351C2B80F804E0ADB214D0AE42F2D891 -:10198000ECE74046FFF78CFD044608B100230360F6 -:101990007C60002CDED16FF00200BDE8F0870131E1 -:1019A00089B21C46BEE7AE42D8D94046FFF778FD63 -:1019B00008B1C0F800A020600028ECD00446002246 -:1019C000CCE7FB8AC3F30902164466F30903FB82E2 -:1019D0008EE70000F8B50E4615461F46044628B9A6 -:1019E000144B154A4F21154802F054F824220021C7 -:1019F000FFF7B2FC069B6A096360079B0020236225 -:101A00004FF6FF739A4228BF1A46A7602070A06164 -:101A1000E06197B204F10C05824205D100232B60EE -:101A200027826382A382F8BD2E60013035462036BE -:101A3000F2E700BFF43F0008683D0008B04000082E -:101A400008B528B97321084B084A094802F022F862 -:101A5000037823B94BB2002B01DD017008BD054BA3 -:101A6000024A7D21F1E700BFF83F0008743D0008FD -:101A7000B04000083C3F0008007870472DE9F7436C -:101A80000D9E074619461046BDF828900B9D9DF8FF -:101A90003040BDF8388016B9B8F1000F43D11F2C83 -:101AA00041D83B78D3B9B8F1070F39D839F00303DF -:101AB00039D1424631464FF6FF70FFF73FFE4FEAFD -:101AC000092920F0010009F44079400449EA04643E -:101AD000400C44EA40244FF6FF730DE043EA09232B -:101AE000B8F1070F43EA0464F5D9FFF701FE424657 -:101AF0003146FFF723FE03468DE840012A46214682 -:101B00003846FFF735FE0DB9FFF750FD2B7801334E -:101B1000DBB21F2B88BF00232B7003B0BDE8F0831E -:101B20006FF00300F9E76FF00100F6E72DE9F743E6 -:101B30000E9F81460B9D9DF830009DF83480BDF8C6 -:101B40003C6007B9C6BB1F2836D899F800E0BEF143 -:101B5000000F34D00C0244F080049DF8281044EAB1 -:101B6000C83444EA014444EA0E04072E44EA0064FF -:101B700015D919461046FFF7BBFD32463946FFF727 -:101B8000DDFD0346019600972A4621464846FFF7A9 -:101B9000EFFDB8F1010F0CD125B9FFF707FD4FF6A6 -:101BA000FF73EFE72B780133DBB21F2B88BF0023D5 -:101BB0002B7003B0BDE8F0836FF00100F9E76FF020 -:101BC0000300F6E7C06900B104307047C1690C300A -:101BD0000B680361FFF7F8BC2DE9F84FD0F818A0A7 -:101BE000054616461F4654464FF00009DFF8608050 -:101BF00000F10C0B0CB9BDE8F88FD4E90223B21A3E -:101C000067EB0303994508BF90451FD2AB69214696 -:101C10009C4228460DD1FFF7EDFCAB6921461B68BD -:101C20005846AB61FFF7D0FCAC692346A2461C4680 -:101C3000E0E7FFF7DFFC23682146CAF8003058468A -:101C4000FFF7C2FC5446DAF80030EFE72368EDE70F -:101C500080841E002DE9F04F8BB00D46144607938B -:101C6000DDF850908246002800F06481B9F1000F41 -:101C700000F06081531E3F2B00F25C81012A03D1EA -:101C8000079B002B40F056810023BAF8146008939C -:101C9000F600B542099380F053812B199E420AD277 -:101CA000761B16F0FF0607D140F26751AA4BAB4AEC -:101CB000AB4801F0EFFE2646DAF80C3023B9DAF82B -:101CC0001030002B00F0A5802F2D31D8C5F1300841 -:101CD00046454FF0000334BFB0465FFA88F80093E2 -:101CE000294608AB4246DAF80800FFF7B7FCA6EB36 -:101CF00008074544FFB24FF0300BBAF8143003F137 -:101D00000053063BDB000293DAF80C300593059B89 -:101D1000002B51D087B9DAF81000002861D0002FCD -:101D20005FD0AB4550D98F4B8C4A40F2A651BFE7EC -:101D300037464FF00008DEE7029B23B98A4B874AFB -:101D40004FF4B161B4E7029BE02B28BFE023069378 -:101D50005B44AB4204931DD95B1B9F4226BFDBB2A1 -:101D600003930397AB4504D97E4B7C4A40F29151D3 -:101D70009EE70598CDF8008008ABA5EB0B01039A10 -:101D80000430FFF76BFC039B9844FF1A1D445FFA75 -:101D900088F8FFB2049B9B4504D3744B6F4A40F212 -:101DA0009B5185E7029B069ADDF810B09B1A0293BF -:101DB000059B1B680593AAE7029BBB42ABD26C4B09 -:101DC000664A40F2A15173E7CDF800803A46A5EB90 -:101DD0000B0108ABB8443D44FFF740FC00275FFA15 -:101DE00088F8BAF81430B5EBC30F04D9614B5B4ADD -:101DF00040F2B1515CE7B8F1400F04D95E4B574A4D -:101E000040F2B25154E767B15C4B544A40F2B351CF -:101E10004EE70093324608AB2946DAF80800FFF790 -:101E20001DFC731E3F2B35B201D8A64204DD544B76 -:101E3000544A40F235213BE760070AD00AAB03EB76 -:101E4000D40111F8083C624202F00702134101F884 -:101E5000083C082C21D9102C21D9202C8CBF082318 -:101E60000423079A002A6DD0B4EBC30F6CD0082C62 -:101E700004F1FF3215D89DF8203023FA02F2D10781 -:101E800006D54FF0FF3202FA04F423438DF82030D8 -:101E90009DF8203089F800304EE00123E1E702236D -:101EA000DFE7102C11D8BDF8203023FA02F2D20758 -:101EB00006D54FF0FF3202FA04F42343ADF8203088 -:101EC000BDF82030A9F8003036E0202C0ED8089953 -:101ED00021FA02F2D30705D54FF0FF3303FA04F4D9 -:101EE0000C430894089BC9F8003025E0402C1CD016 -:101EF000DDE9086730463946FEF732F9002100F087 -:101F0000010050EA01030BD0224601200021FEF718 -:101F100033F9404261EB410106430F43CDE90867C5 -:101F2000DDE90823C9E9002306E0174B154A4FF401 -:101F30002071BDE66FF0010528460BB0BDE8F08FBB -:101F40001D46F9E7012CA3D0082CA1D9102CB7D934 -:101F5000202CE5D8C6E700BF483E0008203E000818 -:101F6000B04000086A3E0008573E00088F3E000857 -:101F7000B73E0008DE3E00080C3F0008243F000882 -:101F80003E3F0008A03D00083C3F000830B585B04A -:101F900030B940F2B121234B234A244801F07AFDA5 -:101FA00023B9234B204A40F2B221F6E7402A04D954 -:101FB000204B1D4A40F2B621EFE722B91D4B1A4AC9 -:101FC0004FF42F71E9E70024012A0294039417D1FA -:101FD0001B788DF8083053070AD004AB03EBD2030B -:101FE00013F8084C554205F00705AC4003F8084CBF -:101FF00000910346002102A8FFF730FB05B030BD79 -:10200000082AE5D9102A03D81B88ADF80830E2E782 -:10201000202A02D81B680293DDE7D3E90045CDE909 -:102020000245D8E7783F0008B43D0008B0400008FA -:10203000933F00083C3F000870B50C4600F10C05CA -:10204000E16819B9A1602161A18270BD0E682846BE -:10205000FFF7BAFAE660F3E72DE9F04FD1F8009008 -:1020600091B0C9F3C01604460D46CDE90223002EF7 -:1020700050D0C9F3C03BC9F30626B9F1000F80F276 -:102080009F8119F0C04F40F09B812B7B002B00F00B -:102090009781BBF1020F03D02278B24240F09381C6 -:1020A00009F07F02BBF1020F059236D119F07F0FC4 -:1020B000C9F30F2A01D10AF0030A2B447606059AC8 -:1020C00093F8038046EA0B4646EA82465FEAD81355 -:1020D00046EA0A06069300F09A800022002310A91F -:1020E00061E90823059B6768009352465B462046DA -:1020F000B847002800F08880A7698FB9314604F1FD -:102100000C00FFF7DBF90746D0B96FF0020011B001 -:10211000BDE8F08F4FF0020BAFE7C9F3074ACCE7F9 -:102120003B699E420DD03F68002FF9D1314604F142 -:102130000C00FFF7C3F907460028E6D0A3693B600F -:10214000A761DDE90801FFF7D3FAB882F97D08F04D -:102150001F06C1F38401711A89B20FFA81FEBEF124 -:10216000000FB8BF01F1200EC9F30461D7E90223C3 -:10217000B8BF0FFA8EFE079152EA030100F02F81DB -:10218000DDE90201801A61EB03010B4600210246E2 -:102190009E48994208BF9042C0F02181069B002BC7 -:1021A0003FD0BEF1010F00F31A8118F0400F38D074 -:1021B000DDE90223C7E90223202200210DEB020002 -:1021C000FFF7CAF8DDE90223CDE908232B1D0A93A6 -:1021D0002B7B2046013BDBB2ADF834309DF81C3040 -:1021E000ADF836A08DF83A309DF814308DF838B03F -:1021F0008DF83B308DF83960A36808A998473846B8 -:10220000FFF70CFA002082E76FF00B007FE7A76969 -:1022100017B96FF00C007AE73B699E4296D03F6891 -:10222000F6E7FB7DC8F34012B2EBD31F40F0CE803F -:10223000C3F38403B34240F0CC8006992B7B4FEA72 -:10224000981279B3D2073CD4032B40F2C580DDE964 -:102250000223C7E902232B7BAE1D033BDBB23246D0 -:10226000394604F10C00FFF729FB002808DA39464B -:102270002046FFF7BFF93846FFF7D0F9032046E7BD -:10228000AB883B832A7B033AD2B2B88A3146FFF748 -:1022900055FAFB7DB882DA43C2F3C01262F3C7136A -:1022A000FB75AFE76AB92E1D013BDBB232463946FA -:1022B00004F10C00FFF702FB0028D8DB2A7B013A6F -:1022C000E2E7FA8A013BC2F30902052AD9B250D8E3 -:1022D0000023281D99420AD907EB020E10F801CB02 -:1022E00001320133062A8EF81AC0DBB2F2D18B42DA -:1022F00028BF0023DDE9028907F11A02CDE9088928 -:102300000A927A683CBF04335B190B920C93FB8AE8 -:10231000ADF836A0C3F3090319449DF81C30ADF89D -:1023200034108DF83A309DF814308DF838B08DF8AF -:102330003B3000238DF839607B602A7BB88A013AF4 -:10234000291DFFF7FBF93B8BB882834203D1A368B9 -:1023500008A92046984708A92046FFF76DFE384691 -:10236000FFF75CF9B88A3B8B984214BF112000201C -:10237000CDE6786810B34FF0060E03689BB9A2EB68 -:102380000E021B2A13D80332024405F1040E1F303B -:102390009942ACD91EF801CB013302F801CF90422B -:1023A000DBB2F5D1A3E70EF11C0E1846E5E7184B9A -:1023B000184A40F2B311184801F06CFB034696E747 -:1023C0006FF00900A3E66FF00A00A0E66FF00D00C1 -:1023D0009DE66FF00E009AE66FF00F0097E6FB7D2A -:1023E000394668F386036FF3C713FB752046FFF782 -:1023F00001F9069B002B7FF4D8AEFB7DC3F384026A -:10240000013262F38603FB7503E700BF80841E0080 -:10241000A83F00088C3D0008B04000082DE9F041BD -:102420004E4EB04240F086804D4CDFF838E1E56911 -:1024300045F00075E561E469846AD4F8007207EA42 -:102440000E0747F00107C4F80072D4F8005205EAFD -:102450000E0545F0010545EA0121C4F80012002AE5 -:102460006AD000210F46C4F81C12C4F80412C4F844 -:102470000C12C4F8141204EBC10501310E29C5F881 -:102480004072C5F84472F6D14FF0000E4FF0010CC7 -:10249000964510D1826AB042D2F8003223F001038F -:1024A000C2F8003258D12E4BDA6922F00072DA619C -:1024B000DB69BDE8F0819F781D8817F0010F18BF18 -:1024C000D4F804820CFA05F11CBF41EA0808C4F8EC -:1024D000048217F0020F18BFD4F80C8204EBC50574 -:1024E0001CBF41EA0808C4F80C827F0748BFD4F833 -:1024F000147203F10C0344BF0F43C4F8147253F871 -:10250000087C0EF1010EC5F8407253F8047CC5F842 -:102510004472D4F81C522943C4F81C12B8E70021B5 -:10252000846AC4F81C12C4F80412C4F80C12C4F86B -:102530001412A9E7002AF2D10022836AC3F84022CC -:10254000C3F84422C3F80422C3F814220122C3F8BA -:102550000C22C3F81C229DE7BDE8F081E022002098 -:10256000001002400000FFFF184A08B5916A8B680E -:102570008B6013F0010105D013F00C0F14BF4FF462 -:1025800080310121D80506D513F4406F14BF41F402 -:10259000003141F00201D80306D513F4402F14BFD7 -:1025A00041F4802141F00401D3690BB107489847F9 -:1025B000202383F311880021054800F09DFE0023AD -:1025C00083F31188BDE8084001F086B8E0220020BE -:1025D000E822002038B5124CA36ADD68AA0712D0A1 -:1025E0005A6922F002025A61A36913B101212046FF -:1025F0009847202383F3118800210A4800F07CFECD -:10260000002383F31188EB0606D51021A36AD96055 -:10261000236A0BB102489847BDE8384001F05CB826 -:10262000E0220020F022002038B5124CA36A1D6978 -:10263000AA0712D05A6922F010025A61A36913B195 -:10264000022120469847202383F3118800210A485D -:1026500000F052FE002383F31188EB0606D510210B -:10266000A36A1961236A0BB102489847BDE8384054 -:1026700001F032B8E0220020F022002038B50F4CE3 -:10268000A36A5D682A075D600AD5032222701A6872 -:1026900022F002021A60636A13B1002120469847B3 -:1026A0006B0706D5A36A9969236A13B10904034825 -:1026B0009847BDE8384001F00FB800BFE022002085 -:1026C00010B50F4C204600F03FFA0E4B0B211320A3 -:1026D000A36200F019FA0B21142000F015FA0B2167 -:1026E000152000F011FA0B21162000F00DFA00233E -:1026F0002046BDE810401A460E21FFF78FBE00BFEE -:10270000E0220020006400400F4B10B598420446C0 -:1027100005D10E4BDA6942F00072DA61DB69012201 -:10272000A36A1A60A36A5A68D20707D5626851681B -:102730001268D9611A60064A5A6110BD0121082049 -:1027400000F092FCEEE700BFE02200200010024003 -:102750005B87010003291AD8DFE801F0020A0F1491 -:10276000836A9B6813F0E05F14BF0120002070476C -:10277000836A9868C0F380607047836A9868C0F382 -:10278000C0607047836A9868C0F30070704700208B -:102790007047000010B503291FD8DFE801F0021FC1 -:1027A0002327816A8B68C3F30163183301EB03139A -:1027B000107881061ED55468C0F30011490041EA23 -:1027C000C40141F0040100F00F005860906841F02E -:1027D00001019860D268DA60196010BD836A03F560 -:1027E000C073E5E7836A03F5C873E1E7836A03F51D -:1027F000D073DDE79488C0F30011490041EA4451E9 -:10280000E1E7000001290CD003D3022910D00020F9 -:102810007047836ADA68920701D1186903E00120E2 -:102820007047836AD86810F0030018BF0120704712 -:10283000836AF2E710B539B9836AD96889071BD171 -:102840001B699B0704D110BD012915D0022948D16D -:10285000816AD1F8C031D1F8C401D1F8C8411461FE -:10286000D1F8CC41546120240C610C69A40717D124 -:102870004C6944F0100412E0816AD1F8B031D1F80B -:10288000B401D1F8B8411461D1F8BC41546120249D -:10289000CC60CC68A40703D14C6944F002044C61BD -:1028A00011795C0864F304119C0864F345111171FB -:1028B00089064BBF91681189DB085B0D4CBF63F340 -:1028C0001C0163F30A01137948BF916060F30303AD -:1028D00013714FEA10234FEA104058BF1181137053 -:1028E000508010BD00231A4610B51C495A50CC1810 -:1028F0000833802B6260F9D1194B9A6942F07D024E -:102900009A619B690268174BDA6082685A60426874 -:102910001A60C26803F58063DA6042695A6002692E -:102920001A608269C3F80C24026AC3F80424C269DD -:10293000C3F80024426AC3F80C28C26AC3F804280A -:10294000826AC3F80028026BC3F80C2C826BC3F8B0 -:10295000042C426BC3F8002C10BD00BF0C230020D8 -:102960000010024000080140026843681143016002 -:1029700003B1184770470000024AD36843F0C00310 -:10298000D360704700380140024AD36843F0C00367 -:10299000D3607047004400402DE9F041D0F89C60BE -:1029A0000546F7683368DA059CB20DD5202383F31A -:1029B00011884FF400710430FFF7D6FF6FF4807375 -:1029C0003360002383F31188202383F3118805F1FA -:1029D000040814F02F0333D183F31188380615D57A -:1029E000210613D5202383F3118805F1380000F068 -:1029F0002FFA002846DA0821281DFFF7B5FF4FF609 -:102A00007F733B40F360002383F311887A060ED571 -:102A100063060CD5202383F31188EA6C2B6D9A4250 -:102A200002D12B6C002B2FD1002383F31188D5F812 -:102A3000A420D368002B31D0BDE8F04110691847BD -:102A4000230713D014F0080F0CBF00218021E007EA -:102A500048BF41F02001A20748BF41F04001630791 -:102A600048BF41F480714046FFF77EFFA4067368BB -:102A700005D595F8A0102846194000F089FA346869 -:102A8000A4B2A6E77060BEE727F040073F0410211C -:102A9000281D3F0CFFF768FFF760C5E7BDE8F08130 -:102AA00008B50348FFF778FFBDE8084000F014BE02 -:102AB0008C23002008B50348FFF76EFFBDE80840EF -:102AC00000F00ABE3424002010B5094C094A204603 -:102AD000002100F03DFA084B084AC4F89C30084C2D -:102AE0000021204600F034FA064BC4F89C3010BD9B -:102AF0008C2300207929000800380140892900082A -:102B0000342400200044004000F16043090103F533 -:102B10006143C9B283F80013012300F01F0240098A -:102B2000800000F16040934000F56140C0F88031C2 -:102B300003607047090100F16040C9B200F56D40C3 -:102B400001767047FFF7BCBD01230370002300F13D -:102B500008028260C26000F11002436002614261BB -:102B60008361C361036243627047000010B5202394 -:102B7000044683F31188022341600370FFF7C4FD0C -:102B800003232370002383F3118810BD2DE9F04146 -:102B90001F4604460D461646202383F3118800F194 -:102BA00008082378042B0ED029462046FFF7D2FDD3 -:102BB00048B1204632462946FFF7ECFD002080F35D -:102BC0001188BDE8F0813946404600F079FB0028C5 -:102BD000E7D0002383F31188BDE8F0812DE9F041AF -:102BE0001F4604460D461646202383F3118800F144 -:102BF00010082378042B0ED029462046FFF702FE4A -:102C000048B1204632462946FFF714FE002080F3E3 -:102C10001188BDE8F0813946404600F051FB00289C -:102C2000E7D0002383F31188BDE8F081F8B515469D -:102C300082680B46AA428169066938BF8568761AA0 -:102C4000B542044607D218462A46FEF773FBA3692D -:102C50002B44A3610DE011D932461846FEF76AFBFA -:102C6000AF1B3A46E1683044FEF764FBE2683A4441 -:102C7000A261A36828465B1BA360F8BD18462A46DC -:102C8000FEF758FBE368E4E72DE9F04104461546FA -:102C900083682669934238BF856840690F46361AB3 -:102CA000B54206D22A46FEF745FB63692B446361B1 -:102CB0000DE012D93246A5EB0608FEF73BFB424673 -:102CC000B919E068FEF736FBE26842446261A36826 -:102CD00028465B1BA360BDE8F0812A46FEF72AFB6D -:102CE000E368E4E710B50024C361029B0A44006076 -:102CF00040608460C160816141610261036210BD16 -:102D000008B582694369934201D1826882B98268B9 -:102D1000013282605A1C42611970426903699A4209 -:102D200001D3C3684361002100F0DAFA002008BD36 -:102D30004FF0FF3008BD000070B5202304460E465A -:102D400083F31188A568A5B1A368A269013BA360BC -:102D5000531CA36115782269934224BFE368A361E1 -:102D6000E3690BB120469847002383F31188284676 -:102D700070BD3146204600F0A3FA0028E2DA85F360 -:102D8000118870BD2DE9F74F05460F4690469A46CB -:102D9000D0F81C90202686F311884FF0000B1446C3 -:102DA00064B1224639462846FFF740FF034668B91A -:102DB0005146284600F084FA0028F1D0002383F31E -:102DC0001188A8EB040003B0BDE8F08FB9F1000F43 -:102DD00003D001902846C847019B8BF31188E41A61 -:102DE0001F4486F31188DBE7C361009BC1608161EA -:102DF000416111440060406082600161036270477C -:102E0000F8B504460E461746202383F31188A568BB -:102E1000A5B1A368013BA36063695A1C62611E707F -:102E2000236962699A4224BFE3686361E3690BB175 -:102E300020469847002080F31188F8BD3946204687 -:102E400000F03EFA0028E2DA85F31188F8BD0000B0 -:102E50008369426910B59A4201D182687AB9826861 -:102E6000013282605A1C82611C7803699A4201D344 -:102E7000C3688361002100F033FA204610BD4FF093 -:102E8000FF3010BD2DE9F74F05460F4690469A4694 -:102E9000D0F81C90202686F311884FF0000B1446C2 -:102EA00064B1224639462846FFF7EEFE034668B96C -:102EB0005146284600F004FA0028F1D0002383F39D -:102EC0001188A8EB040003B0BDE8F08FB9F1000F42 -:102ED00003D001902846C847019B8BF31188E41A60 -:102EE0001F4486F31188DBE70268436811430160E1 -:102EF00003B11847704700001430FFF743BF0000CC -:102F00004FF0FF331430FFF73DBF00003830FFF7BC -:102F1000B9BF00004FF0FF333830FFF7B3BF0000F8 -:102F20001430FFF709BF00004FF0FF311430FFF7F6 -:102F300003BF00003830FFF763BF00004FF0FF32DF -:102F40003830FFF75DBF000000207047FFF7BCBDC1 -:102F50000E4B37B50360002343608360C3600123D9 -:102F6000044615460374202200900B4600F15C01D4 -:102F70001430FFF7B7FE00942B46202204F17C01A9 -:102F800004F13800FFF730FF03B030BDEC4000081B -:102F900038B5C36904460D461BB904210844FFF740 -:102FA000A3FF294604F11400FFF7AAFE002806DA61 -:102FB000201D4FF48061BDE83840FFF795BF38BD54 -:102FC0000022024B1B605B609A607047DC2400208B -:102FD000002382680374054B1B6899689142FBD2F9 -:102FE0005A6803604260106058607047DC2400201B -:102FF00008B5202383F31188037C032B05D0042B11 -:103000000DD02BB983F3118808BD002243691A60E3 -:103010004FF0FF334361FFF7DBFF0023F2E790E857 -:103020000C001A6002685360F2E700000023826817 -:103030000374054B1B6899689142FBD85A6803607A -:103040004260106058607047DC240020054B19690D -:1030500008741868026853601A60186101230374C9 -:10306000FDF78EBADC24002030B54B1C87B0054636 -:103070000A4C10D023690A4A01A800F059F92846E1 -:10308000FFF7E4FF049B13B101A800F06BF923697B -:10309000586907B030BDFFF7D9FFF8E7DC240020FE -:1030A000F12F000838B50C4D41612B6981689A6891 -:1030B0000446914203D8BDE83840FFF789BF18465F -:1030C000FFF786FF01232C61014623742046BDE8EB -:1030D0003840FDF755BA00BFDC240020044B1A68C5 -:1030E0001B6990689B68984294BF0020012070473C -:1030F000DC24002010B5084C236820691A6854604D -:103100002260012223611A74FFF790FF01462069B3 -:10311000BDE81040FDF734BADC24002008B5FFF705 -:10312000DDFF18B1BDE80840FFF7E4BF08BD0000AF -:10313000FEE7000010B5174CFFF742FF00F0EAF879 -:1031400080221549204600F06FF8012344F8180C3E -:103150000374124B124AD96821F4E0610904090C86 -:103160000A431049DA60CA6842F08072CA600E49A8 -:103170000A6842F001020A601022DA77202283F8FE -:103180002220002383F3118862B6BDE8104007486F -:1031900000F06CB8042500201441000800ED00E0A8 -:1031A0000003FA05F0ED00E0001000E01C4100080B -:1031B000F8B50F4C226A01322262224652F8141FDF -:1031C0009142154606D020268B68013B8B606369CF -:1031D0009A6802B1F8BD1968DF68DA604D60616114 -:1031E00082F311881869B84786F31188EFE700BFAA -:1031F000DC240020EFF3118020B9EFF305832022B7 -:1032000082F311887047000010B558B9EFF30584B8 -:10321000C4F3080414B180F3118810BDFFF77EFFDA -:1032200084F3118810BD0000826002220274002223 -:10323000427470478368A3F13C0243F80C2C026986 -:1032400043F83C2C426943F8382C074A43F81C2CBD -:10325000C268A3F1180043F8102C022203F8082CCE -:10326000002203F8072C70479105000810B52023B1 -:1032700083F31188FFF7DEFF00210446FFF712FFFA -:10328000002383F31188204610BD0000024B1B6908 -:1032900058610F20FFF7DABEDC240020202383F3DF -:1032A0001188FFF7F3BF000008B50146202383F320 -:1032B00011880820FFF7D8FE002383F3118808BD8A -:1032C00049B1064B42681B6918605A60136043603D -:1032D0000420FFF7C9BE4FF0FF307047DC24002008 -:1032E0000368984206D01A68026050605961184617 -:1032F000FFF76EBE7047000038B504460D462068E3 -:10330000844200D138BD036823605C604561FFF7EB -:103310005FFEF4E7054B03F114025A619A614FF026 -:10332000FF32DA6100221A62704700BFDC240020FD -:1033300010B5C2600A4A036153699C68A1420CD867 -:103340005C68036044602060586081609868411A3E -:1033500099604FF0FF33D36110BD091B1B68ECE788 -:10336000DC240020036881689A680A449A604268F5 -:10337000136003685A6000234FF0FF32C360014BB3 -:10338000DA617047DC24002000207047FEE700006F -:10339000704700004FF0FF3070470000BFF34F8FC1 -:1033A000024AD368DB07FCD4704700BF002002400C -:1033B00008B5074B1B7853B9FFF7F0FF054B1A69A7 -:1033C000120641BF044A5A6002F188325A6008BDB1 -:1033D000E0250020002002402301674508B5054B89 -:1033E0001B7833B9FFF7DAFF034A136943F0800310 -:1033F000136108BDE0250020002002407F289ABF0D -:1034000000F5003080020020704700004FF480601B -:1034100070470000802070477F2808B50BD8FFF761 -:10342000EDFF00F580630268013204D1043083426D -:10343000F9D1012008BD002008BD00007F2838B563 -:10344000044624D800F0B6F8124D2860FFF7A6FF16 -:10345000FFF7AEFFF322104B2046DA6002221A611A -:10346000FFF7CCFF58611A6942F040021A61FFF77A -:1034700095FF4FF4806100F0E9F8FFF7AFFF00F02F -:1034800099F828602046BDE83840FFF7C5BF002006 -:1034900038BD00BFE4250020002002402DE9F8439C -:1034A00012F00103144606D040F24B221F4B1A6063 -:1034B0000020BDE8F88385181D4A954204D94FF4D1 -:1034C00014711A4A1160F3E7FFF772FFFFF766FF06 -:1034D0004FF00109DFF86880451A012C05EB010661 -:1034E0000F4604D8FFF77AFF0120BDE8F883C8F83B -:1034F000109031F8023B3380FFF750FF0020C8F8EE -:10350000100033883A889BB29A420DD040F267226D -:10351000064B1A60074B1E60074B1C60074B1F6071 -:10352000FFF75CFFBDE8F883023CD6E7DC2500200E -:10353000FFFF0108D0250020D8250020D425002039 -:1035400000200240084908B50B7828B153B9FFF7AD -:103550002FFF01230B7008BD23B1BDE808400870A0 -:10356000FFF73CBF08BD00BFE025002038B5FFF7DE -:1035700041FE4FF47A730C490C4A0C6A116803FB44 -:1035800004F38B420A49D1E9004504D2003445F1E5 -:103590000105C1E90045E41845F100051360FFF796 -:1035A00033FE2046294638BDDC240020E8250020D3 -:1035B000F025002008B5FFF7D9FF4FF47A720023F9 -:1035C000FCF7E6FD08BD00BF10B5094C0439013A0F -:1035D000D2B2FF2A00D110BD53089800043054F82D -:1035E000233000599BB243EA004341F8043FEEE721 -:1035F000046C004030B50748013AD2B2FF2A00D12E -:1036000030BD0D88540840F82450A3004C88043382 -:103610001C50F1E7046C004007B5012201A900200D -:10362000FFF7D2FF019803B05DF804FB13B5044621 -:10363000FFF7F2FFA04206D002A941F8044D012293 -:103640000020FFF7D7FF02B010BD00007047000058 -:1036500045F25552064B1A6002225A6040F6FF723C -:103660009A604CF6CC421A600122024B1A707047E5 -:1036700000300040F9250020034B1B781BB14AF6AF -:10368000AA22024B1A607047F92500200030004042 -:10369000034B1B689B0042BF0122024B1A7070470C -:1036A00024100240F82500204FF08072014B1A6070 -:1036B000704700BF24100240014B1878704700BFCC -:1036C000F8250020EFF30983203383F309880023D2 -:1036D00083F311887047000010B5202383F311880D -:1036E0000D4B5B6813F4006312D0EFF309844FF0C5 -:1036F000807344F8043CA4F1200383F30988FFF7A6 -:10370000EDFC18B1054B44F8083C10BD044BFAE73A -:1037100083F3118810BD00BF00ED00E0A105000893 -:10372000A405000870470000FEE70000084A094BA6 -:1037300009498B4204D30021084A934205D37047BC -:1037400052F8040F43F8040BF3E743F8041BF4E7C3 -:10375000304200080026002000260020002600201D -:1037600000F030B808B500F063F9FFF7E3FCBDE8FE -:103770000840FFF78DBF0000704700004FF0FF3199 -:103780000E4B1A6919611A6900221A611869D86802 -:10379000D960D968DA60DA68DA6942F08052DA61B1 -:1037A000DA69DA6942F00062DA61054ADB691368B6 -:1037B00043F48073136000F01BB900BF0010024097 -:1037C00000700040194B1A6842F001021A601A6832 -:1037D0009007FCD51A6802F0F9021A6000225A60BC -:1037E0005A6812F00C0FFBD11A6842F480321A604A -:1037F0001A689103FCD55A6842F4E8125A601A68B4 -:1038000042F080721A601A689201FCD51221084AAF -:103810005A60084A11605A6842F002025A605A68B7 -:1038200002F00C02082AFAD1704700BF00100240D3 -:1038300000641D0000200240084A08B55369116861 -:103840000B4003F00103536123B1054A13680BB128 -:1038500050689847BDE80840FFF73EBF00040140AC -:103860000C230020084A08B5536911680B4003F087 -:103870000203536123B1054A93680BB1D06898479E -:10388000BDE80840FFF728BF000401400C230020DA -:10389000084A08B5536911680B4003F004035361EB -:1038A00023B1054A13690BB150699847BDE8084038 -:1038B000FFF712BF000401400C230020084A08B59E -:1038C000536911680B4003F00803536123B1054AA3 -:1038D00093690BB1D0699847BDE80840FFF7FCBE7B -:1038E000000401400C230020084A08B55369116800 -:1038F0000B4003F01003536123B1054A136A0BB167 -:10390000506A9847BDE80840FFF7E6BE0004014052 -:103910000C230020174B10B55C691A68144004F49E -:1039200078725A61A30604D5134A936A0BB1D06A20 -:103930009847600604D5104A136B0BB1506B98473B -:10394000210604D50C4A936B0BB1D06B9847E20566 -:1039500004D5094A136C0BB1506C9847A30504D5E4 -:10396000054A936C0BB1D06C9847BDE81040FFF747 -:10397000B3BE00BF000401400C2300201A4B10B559 -:103980005C691A68144004F47C425A61620504D5EB -:10399000164A136D0BB1506D9847230504D5134A91 -:1039A000936D0BB1D06D9847E00404D50F4A136EA8 -:1039B0000BB1506E9847A10404D50C4A936E0BB11D -:1039C000D06E9847620404D5084A136F0BB1506F4C -:1039D0009847230404D5054A936F0BB1D06F9847DD -:1039E000BDE81040FFF778BE000401400C23002022 -:1039F000062108B50846FFF787F806210720FFF7DC -:103A000083F806210820FFF77FF806210920FFF739 -:103A10007BF806210A20FFF777F806211720FFF729 -:103A200073F8BDE8084006212820FFF76DB80000B4 -:103A300008B5FFF7A3FE0648FEF754FFFFF782F82C -:103A4000FFF784FAFFF798FEBDE8084000F002B8DF -:103A50003C41000800F00EB808B5202383F311881C -:103A6000FFF7A6FB002383F31188BDE80840FFF7AA -:103A700033BE0000054B064A08215A6000229A60B6 -:103A800007220B201A60FFF755B800BF10E000E0D6 -:103A90003F1901001FB51C46094B05461B68D86835 -:103AA00052B1084B8DE80A0002922B462246064985 -:103AB000FDF7AAFC00F042F8044B1A46F2E700BFFB -:103AC0001011002078410008854100086C3C000876 -:103AD00010B501390244904201D1002010BD10F808 -:103AE000013B11F8014FA342F5D0181B10BD000097 -:103AF0002DE9F8430746884691461E468BB10D4690 -:103B0000A8EB0500B54207EB000402D20020BDE897 -:103B1000F883324649462046FFF7DAFF18B1013DE7 -:103B2000EEE7BDE8F8832046BDE8F883034611F8C8 -:103B3000012B03F8012B002AF9D1704708B50620A4 -:103B400000F02CF80120FFF721FC00001F2938B5F8 -:103B500004460D4604D9162303604FF0FF3038BDEC -:103B6000426C12B152F821304BB9204600F030F8C7 -:103B70002A4601462046BDE8384000F017B8012B20 -:103B80000AD0591C03D116230360012038BD00243C -:103B9000284642F825409847002038BD024B014690 -:103BA0001868FFF7D3BF00BF1011002038B50023FD -:103BB000064C0546084611462360FFF7EBFB431C05 -:103BC00002D1236803B12B6038BD00BFFC25002063 -:103BD000FFF7DABB40A2E4F1646891064E6F206102 -:103BE0007070207369670A00426164206677206CF8 -:103BF000656E6774682025750A0042616420626FF3 -:103C00006172645F69642025752073686F756C64E8 -:103C10002062652025750A00426164206677206471 -:103C2000657363726970746F72206C656E67746817 -:103C30002025750A00426164206170702043524360 -:103C4000203078253038783A307825303878203070 -:103C500078253038783A3078253038780A00476F40 -:103C60006F64206669726D776172650A00000000FA -:103C700072656365697665645F756E697175655FA8 -:103C800069645F6C656E203C2055415643414E5F30 -:103C900050524F544F434F4C5F44594E414D49434E -:103CA0005F4E4F44455F49445F414C4C4F43415444 -:103CB000494F4E5F554E495155455F49445F4D410F -:103CC000585F4C454E475448002E2E2F2E2E2F5411 -:103CD0006F6F6C732F41505F426F6F746C6F6164D4 -:103CE00065722F63616E2E63707000616C6C6F6320 -:103CF000617465645F6E6F64655F6964203C3D203C -:103D0000313237006F72672E6172647570696C6F43 -:103D1000742E61705F7065726970685F7472696734 -:103D200067657200766F69642068616E646C655FB8 -:103D3000616C6C6F636174696F6E5F726573706FD5 -:103D40006E73652843616E617264496E7374616E4F -:103D500063652A2C2043616E6172645278547261EB -:103D60006E736665722A290063616E617264496EC2 -:103D70006974000063616E6172645365744C6F63B3 -:103D8000616C4E6F646549440000000063616E61C0 -:103D9000726448616E646C6552784672616D65004C -:103DA00063616E6172644465636F64655363616CE3 -:103DB0006172000063616E617264456E636F646579 -:103DC0005363616C61720000696E6372656D656E4C -:103DD000745472616E73666572494400656E7175E4 -:103DE00065756554784672616D65730070757368AA -:103DF00054785175657565007072657061726546BD -:103E00006F724E6578745472616E736665720000ED -:103E1000636F7079426974417272617900000000C9 -:103E20006465736361747465725472616E73666500 -:103E3000725061796C6F61640000000066726565A4 -:103E4000426C6F636B0000006269745F6C656E6743 -:103E50007468203E20300072656D61696E696E671E -:103E60005F62697473203E203000696E7075745F04 -:103E70006269745F6F6666736574203E3D20626C94 -:103E80006F636B5F6269745F6F666673657400620F -:103E90006C6F636B5F656E645F6269745F6F6666AB -:103EA000736574203E20626C6F636B5F6269745F40 -:103EB0006F66667365740072656D61696E696E67C1 -:103EC0005F6269745F6C656E677468203C3D207248 -:103ED000656D61696E696E675F6269747300696EB2 -:103EE0007075745F6269745F6F6666736574203C99 -:103EF0003D207472616E736665722D3E7061796CDF -:103F00006F61645F6C656E202A2038006F75747075 -:103F100075745F6269745F6F6666736574203C3D9B -:103F20002036340072656D61696E696E675F626923 -:103F3000745F6C656E677468203D3D2030002872A8 -:103F40006573756C74203E20302920262620287247 -:103F50006573756C74203C3D20363429202626205C -:103F600028726573756C74203C3D206269745F6CC7 -:103F7000656E67746829000064657374696E6174A6 -:103F8000696F6E20213D202828766F6964202A29D8 -:103F900030290076616C756520213D202828766FD8 -:103FA0006964202A293029006F66667365745F771B -:103FB000697468696E5F626C6F636B203C202833A4 -:103FC0003255202D205F5F6275696C74696E5F6F7A -:103FD00066667365746F66202843616E6172644221 -:103FE0007566666572426C6F636B2C2064617461E8 -:103FF000292900006F75745F696E7320213D2028A8 -:1040000028766F6964202A29302900007372635F63 -:104010006C656E203E203055000000002863616E04 -:104020005F6964202620307831464646464646463B -:104030005529203D3D2063616E5F696400000000EA -:10404000616C6C6F6361746F722D3E73746174691F -:1040500073746963732E63757272656E745F7573C2 -:104060006167655F626C6F636B73203E2030000098 -:104070007472616E736665725F696420213D2028E9 -:1040800028766F6964202A293029000073746174CE -:10409000652D3E6275666665725F626C6F636B73F9 -:1040A000203D3D202828766F6964202A2930290088 -:1040B0002E2E2F2E2E2F6D6F64756C65732F6C69ED -:1040C0006263616E6172642F63616E6172642E63FC -:1040D000006974656D2D3E6672616D652E64617454 -:1040E000615F6C656E203E20300000000000000023 -:1040F000152F0008012F00083D2F0008292F000868 -:10410000352F0008212F00080D2F0008F92E000878 -:10411000492F00086D61696E0000000034410008FD -:1041200020250020D02500200100000031310008AA -:104130000000000069646C65000000000C1E0000B7 -:10414000447B4144B4574944010000004244444484 -:10415000444444440000000044444444444444442F -:10416000000000004444444444444444000000002F -:1041700044444444444444442C2066756E6374694A -:104180006F6E3A2000617373657274696F6E2022DE -:10419000257322206661696C65643A2066696C65E6 -:1041A00020222573222C206C696E652025642573DE -:1041B00025730A000CC0FF7F010000000000000012 -:1041C0006400000000000000FE2A0100D20400008C -:1041D000141100200000000000000000000000009A -:1041E00000000000000000000000000000000000CF -:1041F00000000000000000000000000000000000BF -:1042000000000000000000000000000000000000AE -:10421000000000000000000000000000000000009E -:10422000000000000000000000000000000000008E -:04423000000000008A +:10000000000900202D080008A91C0008791C000820 +:10001000951C0008791C00088D1C00082F0800089A +:100020002F0800082F0800082F080008DD370008F7 +:100030002F0800082F0800082F080008F13C0008CE +:100040002F0800082F0800082F0800082F080008B4 +:100050002F0800082F080008213A00084D3A000830 +:10006000793A0008A53A0008D13A00082F0800089C +:100070002F0800082F0800082F0800082F08000884 +:100080002F0800082F0800082F080008A52C0008DA +:10009000112D0008652D0008B92D0008FD3A000853 +:1000A0002F0800082F0800082F0800082F08000854 +:1000B0002F0800082F0800082F0800082F08000844 +:1000C0002F0800082F0800082F0800082F08000834 +:1000D0002F0800082F0800082F0800082F08000824 +:1000E000653B00082F0800082F0800082F080008AB +:1000F0002F0800082F0800082F0800082F08000804 +:100100002F0800082F0800082F0800082F080008F3 +:100110002F0800082F0800082F0800082F080008E3 +:100120002F0800082F0800082F0800082F080008D3 +:100130002F0800082F0800082F0800082F080008C3 +:100140002F0800082F0800082F0800082F080008B3 +:100150002F0800082F0800082F0800082F080008A3 +:100160004FF0FF0C1CEAD0521EBF1CEAD15392EA9A +:100170000C0F93EA0C0F6FD01A4480EA010C400276 +:1001800018BF5FEA41211ED04FF0006343EA5010D0 +:1001900043EA5111A0FB01310CF00040B1F5000F12 +:1001A0003EBF490041EAD3715B0040EA010062F1C1 +:1001B0007F02FD2A1DD8B3F1004F40EBC25008BFAB +:1001C00020F00100704790F0000F0CF0004C08BFC9 +:1001D00049024CEA502040EA51207F3AC2BFD2F196 +:1001E000FF0340EAC250704740F400004FF00003A4 +:1001F000013A5DDC12F1190FDCBF00F000407047DE +:10020000C2F10002410021FA02F1C2F1200200FA1B +:1002100002FC5FEA310040F1000053EA4C0308BFE2 +:1002200020EADC70704792F0000F00F0004C02BF33 +:10023000400010F4000F013AF9D040EA0C0093F0AE +:10024000000F01F0004C02BF490011F4000F013B08 +:10025000F9D041EA0C018FE70CEAD15392EA0C0F76 +:1002600018BF93EA0C0F0AD030F0004C18BF31F0E1 +:10027000004CD8D180EA010000F00040704790F0B7 +:10028000000F17BF90F0004F084691F0000F91F05B +:10029000004F14D092EA0C0F01D142020FD193EA21 +:1002A0000C0F03D14B0218BF084608D180EA0100A9 +:1002B00000F0004040F0FE4040F40000704740F085 +:1002C000FE4040F44000704780F0004002E000BF74 +:1002D00081F0004142001FBF5FEA410392EA030F31 +:1002E0007FEA226C7FEA236C6AD04FEA1262D2EB7B +:1002F0001363C1BFD218414048404140B8BF5B4280 +:10030000192B88BF704710F0004F40F4000020F018 +:100310007F4018BF404211F0004F41F4000121F02E +:100320007F4118BF494292EA030F3FD0A2F1010278 +:1003300041FA03FC10EB0C00C3F1200301FA03F1B6 +:1003400000F0004302D5494260EB4000B0F5000FD9 +:1003500013D3B0F1807F06D340084FEA310102F198 +:100360000102FE2A51D2B1F1004F40EBC25008BF4A +:1003700020F0010040EA03007047490040EB000014 +:10038000013A28BFB0F5000FEDD2B0FA80FCACF115 +:10039000080CB2EB0C0200FA0CF0AABF00EBC25042 +:1003A00052421843BCBFD0401843704792F0000F30 +:1003B00081F4000106BF80F400000132013BB5E783 +:1003C0004FEA41037FEA226C18BF7FEA236C21D0F9 +:1003D00092EA030F04D092F0000F08BF084670475E +:1003E00090EA010F1CBF0020704712F07F4F04D12C +:1003F000400028BF40F00040704712F100723CBF3F +:1004000000F50000704700F0004343F0FE4040F468 +:10041000000070477FEA226216BF08467FEA236326 +:100420000146420206BF5FEA412390EA010F40F411 +:10043000800070474FF0000304E000BF10F000435D +:1004400048BF40425FEA000C08BF704743F0964344 +:1004500001464FF000001CE050EA010208BF70475F +:100460004FF000030AE000BF50EA010208BF7047E6 +:1004700011F0004302D5404261EB41015FEA010CFB +:1004800002BF84460146002043F0B64308BFA3F1F3 +:100490008053A3F50003BCFA8CF2083AA3EBC253D5 +:1004A00010DB01FA02FC634400FA02FCC2F12002F4 +:1004B000BCF1004F20FA02F243EB020008BF20F02B +:1004C0000100704702F1200201FA02FCC2F1200291 +:1004D00050EA4C0021FA02F243EB020008BF20EA86 +:1004E000DC70704742000ED2B2F1FE4F0BD34FF0DA +:1004F0009E03B3EB126209D44FEA002343F000439A +:1005000023FA02F070474FF00000704712F1610FBC +:1005100001D1420202D14FF0FF3070474FF000008E +:10052000704700BF53B94AB9002908BF00281CBF53 +:100530004FF0FF314FF0FF3000F076B9ADF1080C0D +:100540006DE904CE00F006F8DDF804E0DDE90223F1 +:1005500004B070472DE9F047089E0D4604468846D2 +:10056000002B4DD18A42944668D9B2FA82F252B138 +:1005700001FA02F3C2F1200120FA01F10CFA02FCA7 +:1005800041EA030894404FEA1C41B8FBF1F71FFA17 +:100590008CFE01FB178807FB0EF0230C43EA08438F +:1005A00098420AD91CEB030307F1FF3580F01E8146 +:1005B000984240F21B81023F63441B1AB3FBF1F0E7 +:1005C00001FB103300FB0EFEA4B244EA0344A6452F +:1005D0000AD91CEB040400F1FF3380F00981A64521 +:1005E00040F20681644402380021A4EB0E0440EA84 +:1005F00007401EB10023D440C6E90043BDE8F087A0 +:100600008B4208D9002E00F0EE800021C6E90005DB +:100610000846BDE8F087B3FA83F100294AD1AB421E +:1006200002D3824200F2FC80841A65EB03030120AE +:100630009846002EE2D0C6E90048DFE702B9FFDEA7 +:10064000B2FA82F2002A40F09180A1EB0C00012165 +:100650004FEA1C471FFA8CFEB0FBF7F307FB1300B1 +:10066000250C45EA00450EFB03F0A84208D91CEB17 +:10067000050503F1FF3802D2A84200F2CE804346BE +:100680002D1AB5FBF7F007FB10550EFB00FEA4B2C8 +:1006900044EA0544A64508D91CEB040400F1FF35E3 +:1006A00002D2A64500F2B6802846A4EB0E0440EA2A +:1006B00003409EE7C1F120078B4022FA07FC4CEA79 +:1006C000030C25FA07FA4FEA1C49BAFBF9F820FA9D +:1006D00007F309FB18AA8D401FFA8CFE1D4300FA90 +:1006E00001F308FB0EF02C0C44EA0A44A04202FA83 +:1006F00001F20BD91CEB040408F1FF3A80F088806A +:10070000A04240F28580A8F102086444241AB4FB98 +:10071000F9F009FB104400FB0EFEADB245EA0444BB +:10072000A64508D91CEB040400F1FF356CD2A645A0 +:100730006AD90238644440EA0840A0FB0295A4EB61 +:100740000E04AC42C846AE4656D353D0002E69D0F4 +:10075000B3EB080264EB0E0422FA01F304FA07F784 +:100760001F43CC40C6E90074002147E70CFA02FCA5 +:10077000C2F1200125FA01F34FEA1C4720FA01F1EA +:1007800095400D43B3FBF7F107FB11331FFA8CFEC5 +:10079000280C40EA034001FB0EF3834204FA02F402 +:1007A00008D91CEB000001F1FF382FD283422DD96C +:1007B00002396044C01AB0FBF7F307FB1300ADB277 +:1007C00045EA004503FB0EF0A84208D91CEB0505DD +:1007D00003F1FF3816D2A84214D9023B6544281A07 +:1007E00043EA014138E73146304607E72F46E4E661 +:1007F0001846F9E64B45A9D2B9EB020865EB0C0E99 +:100800000138A3E74346EAE7284694E74146D1E7A3 +:10081000D0467BE76444023847E7023B65442FE754 +:10082000084606E73146E9E6704700BF02E000F0FF +:1008300000F8FEE772B6264880F30888254880F362 +:100840000988254825490860022080F31488BFF3F1 +:100850006F8F03F013F803F077F84FF0553020490D +:100860001B4A91423CBF41F8040BFAE71D49194A63 +:1008700091423CBF41F8040BFAE71B491B4A1C4B51 +:100880009A423EBF51F8040B42F8040BF8E70020EF +:100890001849194A91423CBF41F8040BFAE702F0AB +:1008A000F1FF03F053F8154C154DAC4203DA54F840 +:1008B000041B8847F9E700F03FF8124C124DAC4298 +:1008C00003DA54F8041B8847F9E702F0D9BF0000A7 +:1008D00000090020001100200000000808ED00E0E1 +:1008E0000001002000090020003E00080011002047 +:1008F0002411002028110020E025002060010008BC +:100900006001000860010008600100082DE9F04F57 +:10091000C1F80CD0C3689D46BDE8F08F002383F377 +:1009200011882846A047002002F00CFDFEE702F0E7 +:100930007FFC00DFFEE70000F8B500F039FE02F0B2 +:10094000EBFE074602F036FF0546002840D12C4B4F +:100950009F423DD001339F423DD02A4B27F0FF02FA +:100960009A423BD1F8B200F0FFFB2E4642F21074DF +:1009700000F000FC08B10024264601F003F988B31A +:100980000024032000F044F8264635B11E4B9F4258 +:1009900003D0002402F006FF2646002002F0C6FE27 +:1009A0001A4B9B6813F0400322D00EB100F046F8BA +:1009B00000F040FC00F0FEFD01F078F90546CCB1F6 +:1009C00001F074F9401BA04214D900F037F8F3E7A6 +:1009D0002E460024CCE704460126C9E706464FF41C +:1009E0007A74C5E7002CD0D04FF47A740126CCE796 +:1009F0001C46DDE700F0D0FC012002F0A9FCDEE798 +:100A0000010007B0000008B0263A09B0000C014010 +:100A1000084B187003280CD8DFE800F0080502081E +:100A2000022000F023BE022000F018BE0022024B7C +:100A30005A607047281100202C11002038B501F0B1 +:100A4000A1F830B103221F4B1A7000221E4B5A60CE +:100A500038BD1E4B1E4A19680131F9D00433934248 +:100A6000F9D11C4C194DD4F80424AA42F0D31A4BE6 +:100A70009B6803F1006303F5C8439A42E8D202F091 +:100A800065FE02F077FE002000F0AEFD0220FFF7C9 +:100A9000BFFF124BDA690022DA61D96999699A615C +:100AA0009B6972B64FF0E023C3F8085D3021D4F89B +:100AB0000034D4F8042481F311889D4683F3088818 +:100AC0001047C5E7281100202C1100200064000801 +:100AD000206400080060000800110020001002409F +:100AE00049F26900084A136899B21B0C00FB0133F4 +:100AF00044F250611360054B186882B2000C01FB90 +:100B00000200186080B27047201100201C110020E4 +:100B100010B504460021102200F0C4FD034B03CBA6 +:100B2000206061601868A06010BD00BFE8F7FF1F7B +:100B30002DE9F0410026ADF54E7D6CAC40F275120A +:100B400007460D460EA831460D9600F0ABFD4FF45A +:100B5000C4723146204600F0A5FD01F0A7F84FF41D +:100B60007A72B0FBF2F0244B0DF13408186093E870 +:100B70000700022384E807000DF5E9702382FFF7E0 +:100B8000C7FF4EF603031D4906A8238403F0E8F8C7 +:100B90001A230DF2E32284F832310DF1300C06AB4A +:100BA0001E4603CE664510605160334602F10802CE +:100BB000F6D13388414613802046012200F0BEFD65 +:100BC00000230393AB7E80B2029305F119030193D6 +:100BD0000123CDE904800093384605A3D3E900231F +:100BE000E97E01F0A9FB0DF54E7DBDE8F08100BF67 +:100BF0009E6AC421818A46EE34110020703D0008AF +:100C00002DE9F041264D80462B7A0C46DAB0FBB92F +:100C1000204627A900F0A2FE0746002836D19DF8FD +:100C20009D60C82E32D801464FF4FA72284600F073 +:100C300039FD32460DF19E0105F1090000F020FD5D +:100C40009DF89C302E4477722B720BB9E37E2B7289 +:100C50008122002106AD27A800F024FD01222946AB +:100C600027A800F0B7FE00230393A37E80B202936F +:100C700004F1190301932823CDE904500093404661 +:100C800005A3D3E90023E17E01F056FB5AB0BDE88D +:100C9000F08100BFAFF3008026417272DF25D7B725 +:100CA0007C210020F0B54FF48A750024234EF1B06A +:100CB00005FB006596F8D830D822214685F8DC304F +:100CC00085F8E8403AA800F0EDFC06F1090000F0D4 +:100CD000E1FCD5F8E430C2B206AF8DF8F00006F1C1 +:100CE00009010DF1F100CDE93A3400F0C9FC3946B3 +:100CF00001223AA800F09AFE80B2CDE904700823E0 +:100D00000127CDE9023706F1D80301933023317A68 +:100D100000930B4807A3D3E9002301F00DFBA04289 +:100D200006DD00F0C3FFC5F8E000384671B0F0BD45 +:100D30002046FBE778F6339F93CACD8D7C210020B7 +:100D40004C210020F0B51E4E1E4F1F4D85B0304681 +:100D500001F01EFB044660B310220021684600F03B +:100D6000A1FC4FF00003227B6068A16862F30303DB +:100D70008DF8003002AB03C3019B2268384662F352 +:100D80001C0301939DF800306A4643F020038DF860 +:100D900000300023194602F087F9044620B9304696 +:100DA00001F0FAFA2C70D2E72B78072B03D8013325 +:100DB0002B7005B0F0BD024801F0EEFAF9E700BF74 +:100DC0004C210020A82300207523002070B50D467B +:100DD00014461E4601F00CFA50B9022E10D1012C17 +:100DE0000ED112A3D3E900230120C5E9002307E0B7 +:100DF000282C10D005D8012C09D0052C0FD00020AC +:100E000070BD302CFBD10BA3D3E90023ECE70BA37F +:100E1000D3E90023E8E70BA3D3E90023E4E70BA31E +:100E2000D3E90023E0E700BFAFF30080401DA1201D +:100E300026812A0B78F6339F93CACD8D9E6AC421F2 +:100E4000818A46EE26417272DF25D7B7F017304A05 +:100E500039059E5638B505460E4C0021013500F087 +:100E6000E5FBA4F8F051B4F8F00100F0C7FB78B14D +:100E7000B4F8F00100F0D2FB014648B9B4F8F00133 +:100E800000F0D4FBB4F8F0310133A4F8F031EAE714 +:100E900038BD00BF7C2100202DE9F04F8DB000AFA0 +:100EA00004460D4601F0A4F9002846D12B7E022B02 +:100EB0001AD1EB8A012B17D100F0F8FE0646FFF796 +:100EC0000FFE4FF4C873B0FBF3F202FB1303DFF81D +:100ED00078829BB206F516763344C8F80030EB7E74 +:100EE00033B90022994B1A703437BD46BDE8F08FF4 +:100EF000284607F11C0100F0EFFC0028F4D107F1AF +:100F00000C00FFF705FEBD7F07F10C012A4607F133 +:100F10001F0002F0F5FE0028E3D10F2D08D88B4BFF +:100F20001D70D8F80030A3F51673C8F80030DBE761 +:100F30002046397F01F054F9D6E7EB8A282B6BD095 +:100F400010D8012B63D0052BCED1BFF34F8F804932 +:100F5000804BCA6802F4E0621343CB60BFF34F8F4B +:100F600000BFFDE7302BBFD17B4CEA7E237A9A424B +:100F7000BAD194F8DC206B7E9A42B5D1284604F1B0 +:100F8000EA0100F07FFD06460028ADD1012384F878 +:100F9000E83000F08BFED4F8E030C01A192840F693 +:100FA000B83338BF1920984228BF1846FFF742FAD5 +:100FB0006A49FFF7D5F805462068FFF73BFA68490C +:100FC000FFF7CEF801462846FFF784F9FFF78AFAC3 +:100FD00020604FF48A7194F8D9307B607A68636836 +:100FE00001FB02F5621992F8E80050B1D2F8E40072 +:100FF000E946834215D0002382F8E830C2F8E03099 +:10100000CD466368574A9B0A013313816CE7294632 +:101010002046FFF78DFD67E729462046FFF7F0FDE4 +:1010200062E7B2F8EC803B6008F1030A4FEA9A0AE3 +:101030004FEA8A02D11DC908A9EBC1039D46EB46C0 +:101040000021584600F02EFB05F1EE0142465846BD +:10105000214400F015FB3B6813B9012000F0C4FAED +:1010600094F8D20000F0CAFA054630B9207200F0B8 +:10107000E5FA284600F0B8FAC2E7D4F8D4303BB914 +:1010800094F8D200B4F8F031834201D8FFF7E2FEC1 +:10109000D4F8D43043449D4208D294F8D200B4F836 +:1010A000F0310130834201D8FFF7D4FE5946606821 +:1010B0005FFA8AF200F0FEFA08B9CD4689E7636864 +:1010C00094F8D20043446360D4F8D43008EB030AA8 +:1010D000C4F8D4A000F092FA824509D394F8D23033 +:1010E000D4F8D4000133401B84F8D230C4F8D400C3 +:1010F000B8F1FF0F0FD80025257200F09FFA28469F +:1011000000F072FA00F03EFD164B188108B9FFF7A7 +:1011100095FCCD46E8E64FF48A727B6894F8D900D6 +:1011200002FB0343D3F8E42083F8E86002F5807201 +:10113000C3F8E060C3F8E420FFF7B4FDFFF702FE58 +:1011400084F8D960B9E700BF48210020452100207C +:1011500000ED00E00400FA057C210020CDCCCC3D60 +:101160006666663F34110020014B1870704700BF5F +:101170004011002030B54FF00054254B226885B057 +:101180009A4207D002F020FB0446C0B90024204652 +:1011900005B030BD0025627D1E4B1F481A70237DAF +:1011A000C92203721D49C0F8E450093000F068FA02 +:1011B0002046E022294600F075FA0124E7E7184AA4 +:1011C000184DD36943F00073D361AA6D164B9A4250 +:1011D000DCD12B6E013B7E2BD8D8144A01AB07CA59 +:1011E00083E807001846032100F09CFC6B6D8342E6 +:1011F0004FF00003CAD12A6D8A4203BFAB652A6E45 +:10120000044B1C4601BF1A70EA6D094B1A60BEE719 +:101210009AAD44C5401100207C210020160000201A +:1012200000100240006600405041A0B058660040E7 +:10123000181100202DE9F04385B000F0A3FC022333 +:10124000494C637100230293484B2081D3F800C0BE +:10125000BCF57A7F12D3464F464BB7FBFCF59C4555 +:101260008CBF0A231123B5FBF3F603FB1652591E5C +:10127000C8B2002A3ED002290B46F4D89DF80B30A4 +:101280003D495A1E9DF80A303C48013B1B0443EA85 +:101290000253BDF80820013A13434B6001F0F4FEFD +:1012A00000230193364B374900934FF48052364B5D +:1012B000364800F06BFF364B197811B1334800F017 +:1012C0008FFF00F0F3FC0546FFF70AFC4FF4C873EC +:1012D000B0FBF3F202FB130305F516709BB2184442 +:1012E0002C4B186002F066FA08B10F23238105B079 +:1012F000BDE8F083731EB3F5806FBFD24FF47A75EB +:10130000C0EBC00E0EF103034FEAE30909FB0555DC +:10131000C3F3C703C11AC9B209F101088844B5FB78 +:10132000F8F5B5F5617F08D90EF1FF33C3F3C703B4 +:10133000C11A581E0F28C9B214D84A1E072A8CBFDA +:1013400000220122581800FB0660B7FBF0F7BC45ED +:1013500094D1002A92D0ADF808608DF80A308DF84B +:101360000B108BE71346EDE7341100201811002015 +:10137000005125023F420F0010110020A823002039 +:10138000CD0D000844110020990E00084C210020CA +:1013900040110020482100202DE9F04F80A7D7E917 +:1013A00000670FF20429D9E90089734D93B00DF15C +:1013B000300AFFF7C7FC18220021504600F072F9EE +:1013C000DFF8B8B16E4C002352461946584601F07A +:1013D00093FE014650BB102208A800F063F9E368B1 +:1013E00083F01003E36000F063FC0DF1240C0B4666 +:1013F00012A9024611E903008CE803009DF834109D +:10140000C1F30300890649BF0E99BDF83810C1F336 +:101410001C0141F0004158BFC1F30A018DF82C00B6 +:101420000891284608A901F097F9CCE7284600F072 +:10143000DFFE0446002847D100F038FCDFF844B155 +:10144000DBF8003098423FD300F030FC0790FFF704 +:1014500047FB4FF4C873B0FBF3F101FB1300079A8D +:1014600083B202F516701844CBF80000DFF818B10B +:101470008DF820409BF8001011B901238DF8203021 +:1014800050460791FFF744FB07990DF12100C1F188 +:101490001004E4B2062C28BF06245144224600F072 +:1014A000EFF808AB039318230293384B01340193F0 +:1014B0000123E4B2009332463B462846049400F0F0 +:1014C000DDFE00238BF8003000F0F0FB304A314C99 +:1014D0001368C31AB3F57A7F30D3106000F0E8FBCD +:1014E00002460B46284600F061FF284600F080FEC9 +:1014F00020B3237ADFF8A0B0002B14BF032302230C +:101500008BF8053000F0D2FB4FF47A73B0FBF3F0A8 +:101510000122CBF800005146584600F0B5F91823D7 +:1015200002931E4B80B2019340F25513CDE903A004 +:10153000009342464B46284600F0A0FE237ABBB1FA +:1015400000F0B4FB94F8E83073B9D4F8E03043B15C +:10155000C01A2368FA2B38BFFA230533B0EB430FC8 +:1015600002D30020FFF79EFB237A002B7FF41FAFEE +:1015700013B0BDE8F08F00BF4C210020A82300204D +:10158000000801404821002045210020442100207E +:10159000702300207C2100203411002074230020BF +:1015A000401DA12026812A0BF1C6A7C1D068080FD3 +:1015B0007047000070B501F095FF0024084E094DFA +:1015C000308028683388834208D901F087FF2B6870 +:1015D00004440133B4F5C84F2B60F2D370BD00BF93 +:1015E000A42300207823002002F00AB800F1006054 +:1015F000920000F5C84001F0AFBF0000054B1A682B +:10160000054B1B889B1A834202D9104401F066BF28 +:101610000020704778230020A4230020024B1B6881 +:10162000184401F061BF00BF78230020024B1B6803 +:10163000184401F06BBF00BF78230020064991F8E1 +:10164000243033B100230822086A81F82430FFF7E0 +:10165000CDBF0120704700BF7C230020022802BFBD +:101660001022014B1A61704700080140022802BF96 +:101670004FF48012014B1A61704700BF000801400F +:10168000002310B5934203D0CC5CC4540133F9E776 +:1016900010BD000003460246D01A12F9011B0029B2 +:1016A000FAD1704703460244934202D003F8011B6B +:1016B000FAE770472DE9F8431F4D144695F82420AA +:1016C0000746884652BBDFF870909CB395F82430EB +:1016D0002BB92022FF2148462F62FFF7E3FF95F840 +:1016E00024004146C0F10802A24228BF224605EB71 +:1016F0008000D6B29200FFF7C3FF95F82430A41BF8 +:101700001E44F6B2082E17449044E4B285F82460D3 +:10171000DBD1FFF793FF0028D7D108E02B6A03EB5A +:1017200082038342CFD0FFF789FF0028CBD100206E +:10173000BDE8F8830120FBE77C2300202DE9F0477A +:101740000D46044600219046284640F27912FFF7E4 +:10175000A9FF234620220021284600F09FFF0222F5 +:1017600020212846231D00F099FF0322222128462C +:10177000631D00F093FF032225212846A31D00F0DE +:101780008DFF10222821284604F1080300F086FF6F +:1017900008223821284604F1100300F07FFF0822B8 +:1017A0004021284604F1110300F078FF0822482167 +:1017B000284604F1120300F071FF20225021284630 +:1017C00004F1140300F06AFF40227021284604F15E +:1017D000180300F063FF0822B021284604F120031B +:1017E00000F05CFF0822B821284604F1210300F034 +:1017F00055FFC02604F122073B4631460822284601 +:10180000083600F04BFFB6F5A07F07F10107F3D1D2 +:1018100008223146284604F1320300F03FFF00273A +:1018200004F1330A94F832304FEAC7099F4209F5B0 +:10183000A47615D3B8F1000F08D131460722284607 +:1018400004F5997300F02AFF09F24F16274694F821 +:1018500032213B1B93420CD3F01DC008BDE8F0873A +:101860000AEB070308223146284600F017FF01372C +:10187000D8E7314607F233130822284600F00EFF5E +:1018800008360137E3E7000038B50C46002105466D +:1018900021600346C4F803102046202200F0FEFE1B +:1018A00020462B1D0222202100F0F8FE20466B1D51 +:1018B0000322222100F0F2FE2046AB1D0322252147 +:1018C00000F0ECFE20461022282105F1080300F06C +:1018D000E5FE072038BD00000023F7B50E4605469B +:1018E000047F07220091194600F09AFD731C0093B3 +:1018F000012200230721284600F092FDC4B9B31C41 +:101900000093052223460821284600F089FD0D2476 +:101910003746B278BB1B934211D32B7FE01DC00822 +:10192000AC8ABBB9A04294BF0020012003B0F0BD37 +:10193000AB8A0824DB00083BDB08B370E8E7FB1C3C +:101940002146009308220023284600F069FD083450 +:101950000137DEE7001B18BF0120E7E70023F7B5DA +:101960000E46047F082200911946054600F058FDF6 +:10197000731CC4B90822009311462346284600F080 +:101980004FFD1024012372785F1C013B934211D359 +:101990002B7FE01DC008AC8ABBB9A04294BF0020D9 +:1019A000012003B0F0BDAB8A0824DB00083BDB0854 +:1019B0007370E7E7F31921460093082200232846B5 +:1019C00000F02EFD08343B46DDE7001B18BF012068 +:1019D000E7E70000F8B50E460546144600218122CF +:1019E0003046FFF75FFE2B4608220021304600F00C +:1019F00055FE7CB90722082130466B1C00F04EFED4 +:101A00000F2401236A785F1C013B934204D3E01D3D +:101A1000C008F8BD0824F4E72146EB190822304637 +:101A200000F03CFE08343B46ECE70000F8B50E46FB +:101A3000054614460021CE223046FFF733FE2B46E2 +:101A400028220021304600F029FE7CB908222821F6 +:101A5000304605F1080300F021FE30242F462A7A93 +:101A60007B1B934204D3E01DC008F8BD2824F5E792 +:101A7000214607F109030822304600F00FFE083422 +:101A80000137ECE7F7B5047F0E46009101231022E1 +:101A90000021054600F0C4FCC4B9B31C0093092220 +:101AA00023461021284600F0BBFC192437467288D3 +:101AB000BB1B9A4211D82B7FE01DC008AC8ABBB972 +:101AC000A04294BF0020012003B0F0BDAB8A1024D7 +:101AD000DB00103BDB087380E8E73B1D21460093E9 +:101AE00008220023284600F09BFC08340137DEE77B +:101AF000001B18BF0120E7E730B5094D0A449142A9 +:101B00000DD011F8013B5840082340F30004013B7D +:101B10002C4013F0FF0384EA5000F6D1EFE730BD0C +:101B20002083B8ED4FF0FF33F7B500EB810619467F +:101B3000DFF848C0DFF848E0B0421BD050F8042B73 +:101B400001AF0192042217F8014B81EA04610824D5 +:101B50000D46DB184941013C002DBCBF83EA0C0354 +:101B600081EA0E0114F0FF04F2D1013A12F0FF02F3 +:101B7000E9D1E1E7D843C94303B0F0BD9336EAA900 +:101B8000EBE1F042F7B56B46354A106851686A469A +:101B900003C308233349344802F0C2F8044690BB1B +:101BA0000A256B46314A106851686A4603C3082308 +:101BB0002F492D4802F0B4F80446002847D00369A5 +:101BC000B3F5CE3F43D8B0F86620B2F57A7F3ED168 +:101BD000284A024402F15C018B4238D35C3B224923 +:101BE00000209E1AFFF788FF07463246002004F1C6 +:101BF0006401FFF781FFA3689F4228D1E368984200 +:101C000008BF002523E00369B3F5CE3F26D8428BF9 +:101C1000B2F57A7F20D1174A024402F110018B42BB +:101C200018D3103B104900209D1AFFF765FF0646A8 +:101C30002A46002004F11801FFF75EFFA3689E42C8 +:101C400002D1E368984201D00D25AAE70025284675 +:101C500003B0F0BD1025A4E70C25A2E70B25A0E7F3 +:101C60008C3D0008DC9B010000640008953D0008E5 +:101C7000909B0100089CFFF7EFF30983EFF30583C6 +:101C8000014B9B6BFEE700BF00ED00E008B5FFF7DE +:101C9000F3FF0000EFF30983EFF30583014B5B6B68 +:101CA000FEE700BF00ED00E0FEE7000001F0E2BC4F +:101CB00001F0BABC2DE9F041456A15B94162BDE8B1 +:101CC000F0814B68AC4623F06047C3F38A4616EABE +:101CD000230638BF3E464FEAD37EC3F380782B46B7 +:101CE0005A68BEEBD27F22F060440AD0002A18DA8C +:101CF000A40CB44217D19D420FD10D60DEE713460C +:101D0000EEE7A74207D102F08044C2F38072424559 +:101D10000BD054B1EFE708D2EDE7CCF800100B6020 +:101D2000CDE7B44201D0B442E5D81A689C46002AF7 +:101D3000E5D11960C3E700002DE9F0474FF47F4972 +:101D4000089D01F007044FEAD508224405F0070575 +:101D500000EBD100944201D1BDE8F08704F0070701 +:101D600005F0070A57453E4638BF5646111BC6F1D7 +:101D700008068E4228BF0E46E108415C08EBD50EEE +:101D800013F80EC0B94029FA06F721FA0AF1FFB29A +:101D90008CEA010147FA0AF739408CEA010C03F892 +:101DA0000EC034443544D5E7082341F2210280EACD +:101DB000012001B24000002980B203F1FF33B8BF17 +:101DC000504013F0FF03F4D17047000038B50C46C3 +:101DD0008D18A54200D138BD14F8011BFFF7E4FFB0 +:101DE000F7E700000346406848B1026899895A60E5 +:101DF0005A89013292B291425A8138BF9A81704712 +:101E000070B504460D4688B0202200216846FFF7D1 +:101E100049FC20460495FFF7E5FF024658B16B46A2 +:101E2000054608AE1C4603CCB442286069602346D0 +:101E300005F10805F6D1104608B070BD082817D97D +:101E400009280CD00A280CD00B280CD00C280CD058 +:101E50000D280CD00E2814BF4020302070470C20D5 +:101E600070471020704714207047182070472020BA +:101E700070470000082817D90C280CD910280CD955 +:101E800014280CD918280CD920280CD930288CBF3C +:101E90000F200E207047092070470A2070470B2042 +:101EA00070470C2070470D20704700002DE9F84363 +:101EB000078C0446072F1ED9D0E9029800254FF65B +:101EC000FF73C5F12006A5F1200029FA05F108FAF3 +:101ED00006F628FA00F031430143C9B21846FFF76D +:101EE00063FF0835402D0346EBD13A46E169BDE872 +:101EF000F843FFF76BBF4FF6FF70BDE8F8830000B3 +:101F000010B54B6823B9CA8A63F30902CA8210BDAF +:101F100004691A681C600361C38A013BC3824A607A +:101F2000EFE700002DE9F84F1D46CB8A0F46C3F3BB +:101F300009010529814692460B4630D00020AAB2FD +:101F400007F11A049EB2042E1FFA80F80FD89045AC +:101F500003F1010306D3FB8A0A4462F3090301205B +:101F6000FB821AE01AF800600130E654EAE7904577 +:101F7000F1D21C23A1F1050BBBFBF3F203FB12BB57 +:101F80007C681FFA8BF6002C45D14846FFF72AFFE4 +:101F9000044638B978606FF00200BDE8F88F4FF062 +:101FA0000008E6E70026066078604FF0000BADB24F +:101FB000454510D90AEB0803221D13F8011B08F14F +:101FC00001089155B1B21B291FFA88F82BD045455D +:101FD00006F10106F1D8FB8AC3F30902154465F343 +:101FE0000903BCE71C46013292B22368002BF9D1E9 +:101FF0006B1F0B441C21B3FBF1F301339BB29A42DC +:10200000D3D2BBF1000FD0D14846FFF7EBFE20B989 +:10201000C4F800B0BFE70122E7E7C0F800B05E46B1 +:1020200020600446C1E74545D5D94846FFF7DAFEAA +:1020300008B92060AFE7C0F800B000262060044671 +:10204000B6E700002DE9F74F1C465B690746884656 +:102050000092002B00F09780238C2BB1E269002ABC +:1020600000F09180072B33D807F10C00FFF7BAFE80 +:10207000054628B96FF00205284603B0BDE8F08F89 +:1020800014220021FFF70EFB228CE16905F1080004 +:10209000FFF7F6FA208C48F00041013080B2FFF7DC +:1020A000E9FEFFF7CBFE013880B2208401302874AE +:1020B0006369228C1B782A4403F01F0363F03F03FB +:1020C0001372384669602946FFF7F4FD0125D3E70E +:1020D0004FF000094FF0800A4E464D4600F10C03C8 +:1020E00001930198FFF77EFE83460028C2D0142298 +:1020F0000021FFF7D7FA002E3BD10222009BABF85C +:1021000008300BF1080E1FFA82FC0CF10100BCF143 +:10211000060F218C80B201D88E422CD3FFF7AAFE85 +:10212000FFF78CFE8E4208BF4FF0400A626901380B +:10213000127880B202F01F0242EA49120BEB000152 +:102140004AEA020A013048F0004281F808A08BF800 +:10215000100059463846CBF80420FFF7ABFD238C1E +:102160000135B3424FF0000A2DB289F00109B8D110 +:1021700082E70022C5E7E169895D01360EF80210A9 +:10218000B6B20132BFE76FF0010575E7F8B5044656 +:1021900015460E46302200211F46FFF783FA069BA4 +:1021A000B5F5001F6360079B28BF4FF6FF72A3625F +:1021B0004FF0000338BF6A09A760E66197B204F1E7 +:1021C00010009A4206D800230360A782E38223838B +:1021D000E360F8BD0660013330462036F1E70000C9 +:1021E00003781BB94BB2002BC8BF017070470000C9 +:1021F00000787047F8B50C46C969074611B9238CB9 +:10220000002B37D1257E1F2D34D8387828BB228C5F +:10221000072A2CD8268A36F003032BD14FF6FF70FD +:10222000FFF7D4FD4FF6FF7220F0010036024004A4 +:1022300046EA0565400C45EA4025234629463846CE +:10224000FFF700FF002807DD626913780133DBB276 +:102250001F2B88BF00231370F8BD218A2D0645EA85 +:10226000012505432046FFF721FE0246E5E76FF012 +:102270000300F1E76FF00100EEE7000070B50446DF +:102280001D4616468AB0282200216846FFF70AFA42 +:10229000BDF838306946ADF810300F9B20460593E5 +:1022A0009DF84030CDE902658DF81830119B0793F9 +:1022B000BDF84830ADF82030FFF79CFF0AB070BD84 +:1022C0002DE9F041D36905460C4616460BB9138C2F +:1022D0005BBB377E1F2F28D895F80080B8F1000F20 +:1022E00026D03046FFF7E2FD3378210241EAC331C0 +:1022F00041EA0801338A41EA076141EA03410246A3 +:102300003346284641F08001FFF79CFE00280ADD95 +:102310003378012B07D1726913780133DBB21F2B9D +:1023200088BF00231370BDE8F0816FF00100FAE769 +:102330006FF00300F7E70000F0B504460D461E46B7 +:1023400017468BB0282200216846FFF7ABF99DF8AD +:102350004C3029465A1E534253418DF800309DF8A7 +:1023600040306A46ADF81030119B204605939DF829 +:102370004830CDE902768DF81830149B0793BDF8EC +:102380005430ADF82030FFF79BFF0BB0F0BD0000DC +:10239000406A00B104307047436A1A6842620269B9 +:1023A0001A600361C38A013BC38270472DE9F04183 +:1023B000D0F8208014461D4641460027174E09B923 +:1023C000BDE8F081D1E90223A21A65EB030396422E +:1023D00077EB03031ED2036A8B420DD1FFF790FD0A +:1023E000036A1B68036203690B60C38A0161016AA7 +:1023F000013B8846C382E2E7FFF782FD0B68C8F81D +:10240000003003690B60C38A0161013BC382D8F8C5 +:102410000010D4E788460968D1E700BF80841E0019 +:102420002DE9F04F8BB00D4614469B468046DDF8F3 +:102430005090002800F01A81B9F1000F00F01681C9 +:10244000531E3F2B00F21281012A03D1BBF1000F72 +:1024500040F00C810023CDE90833B8F81430B5EB17 +:10246000C30F4FEAC30703D300200BB0BDE8F08FC2 +:102470002B199F42D8F80C3036BF7F1B2746FFB27E +:102480001BB9D8F81030002B7BD0272D4ED8C5F1C2 +:102490002806B7424FF0000334BF3E46F6B2009321 +:1024A00029463246D8F8080008ABFFF745FCA7EBF1 +:1024B000060A35445FFA8AFA2821B8F8143003F185 +:1024C0000053053BDB000493D8F80C300393039BC7 +:1024D00013B1BAF1000F2CD1D8F8100040B1BAF105 +:1024E000000F05D05246009608AB691AFFF724FC8E +:1024F00038B2002FB8D066070AD00AAB03EBD4017C +:1025000011F8083C624202F00702134101F8083C4E +:10251000082C3DD9102C40F2B680202C40F2B88017 +:10252000BBF1000F00F09D80082335E0BA4600267D +:10253000C2E7049BE02B28BFE02306930B44AB4289 +:10254000059315D95A1B924538BF5246039828BFA8 +:10255000D2B20096691A08AB04300792FFF7ECFB81 +:10256000079A1644AAEB020A1544F6B25FFA8AFAF1 +:10257000049B069A05999B1A0493039B1B6803937B +:10258000A5E700933A462946D8F8080008ABADE71E +:10259000BBF1000F13D00123B4EBC30F6CD0082C98 +:1025A00012D89DF82030621E23FA02F2D50706D514 +:1025B0004FF0FF3202FA04F423438DF820309DF8E7 +:1025C000203089F8003050E7102C12D8BDF82030A8 +:1025D000621E23FA02F2D10706D54FF0FF3202FA4B +:1025E00004F42343ADF82030BDF82030A9F80030C2 +:1025F0003BE7202C0FD80899631E21FA03F3DA0772 +:1026000005D54FF0FF3202FA04F40C430894089BFE +:10261000C9F8003029E7402C2BD0DDE90865611EA0 +:10262000C4F12102A4F1210326FA01F105FA02F214 +:1026300025FA03F311431943CB0712D50122A4F164 +:102640002003C4F1200102FA03F322FA01F1A240AF +:10265000524243EA010363EB430332432B43CDE988 +:102660000823DDE90823C9E90023FEE66FF0010035 +:10267000FBE66FF00800F8E6082CA0D9102CB3D9BF +:10268000202CEED8C3E7BBF1000FADD0022383E7C7 +:10269000BBF1000FBBD004237EE70000012A30B558 +:1026A000144638BF01220025402A28BF402285B0A9 +:1026B000012CCDE9025517D81B788DF80830530747 +:1026C0000AD004AB03EBD20515F8083C544204F0E1 +:1026D0000704A34005F8083C0346009102A8002126 +:1026E000FFF72AFB05B030BD082CE5D9102C03D824 +:1026F0001B88ADF80830E2E7202C02D81B68029353 +:10270000DDE7D3E90045CDE90245D8E710B5CB6850 +:102710001BB98B600B618B8210BD04691A681C6049 +:102720000361C38A013BC382CA60F0E703064CBF62 +:10273000C0F3C0300220704708B50246FFF7F6FF2D +:10274000022806D15306C2F30F2001D100F0030086 +:1027500008BDC2F30740FBE72DE9F04F93B0CDE988 +:1027600003230A6804461046FFF7E0FF02280CBF67 +:102770000026C2F30626002A0D46824680F2F98121 +:1027800012F0C04940F0F581097B002900F0F18189 +:10279000022803D02378B34240F0EE81C2F30463F1 +:1027A0001046069302F07F030593FFF7C5FF059BD4 +:1027B00000224FEA8348002348EA0A48294448EAAD +:1027C0004668CE78CDE90823F309834648EA000835 +:1027D000029367D0059B02460093204653466768E4 +:1027E00008A9B847002800F0CA81276A4FB94146B6 +:1027F00004F10C00FFF704FB074690B96FF00200EC +:1028000054E03B6998450DD03F68002FF9D141460F +:1028100004F10C00FFF7F4FA07460028EED0236A13 +:102820003B60276297F817C006F01F08CCF3840CB2 +:10283000ACEB08001FFA80FE0028B8BF0EF12000A4 +:10284000A8EB0C031FFA83FEB8BF00B2002B07935E +:10285000BEBF0EF120031BB20793D7E9022152EA53 +:10286000010338D04FF0000C039BDFF8F8E19A1A0F +:10287000049B63EB010196457CEB01032BD36B7B3F +:1028800097F81AE0734519D1029B002B78D00128E4 +:1028900021DC7868F8B9DFF8D0C1944570EB01030A +:1028A00016D337E0276A27B96FF00C0013B0BDE8E4 +:1028B000F08F3B699845B5D03F68F4E76A4890428D +:1028C0007CEB010301D30020F0E7029B002BFAD040 +:1028D000079B0F2B17DCFA7DB30002F0030203F015 +:1028E0007C031343FB7539462046FFF709FB6B7BDE +:1028F000BB76029B3BB9FB7DC3F38402013262F3DA +:102900008603FB75D0E76A7BBB7E9A42DBD1029BD4 +:10291000002B35D0B309022B32D0039B1422BB60AD +:10292000049B0021FB600DA8FEF7BCFE039B204624 +:102930000A93049BADF83EB00B932B1D0C932B7B9D +:102940008DF840A0013BDBB2ADF83C30069B8DF822 +:1029500041808DF84230059B0AA98DF8433094F8E8 +:102960002C3083F001038DF84430A3689847FB7D39 +:10297000C3F38403013303F01F039B02FB82A2E72E +:10298000FB7DC6F34012B2EBD31F40F0FB80C3F3D4 +:102990008403434540F0F980029A2B7BB609002A54 +:1029A0004DD0F20762D4032B40F2F280039BAE1DA0 +:1029B000BB60049B3246FB602B7B3946033BDBB29A +:1029C00004F10C00FFF7AEFA00280CDA3946204675 +:1029D000FFF796FAFB7DC3F38403013303F01F0373 +:1029E0009B02FB820AE7AB88DDE908843B834FF654 +:1029F000FF73C9F12000A9F1200228FA09F104FAB5 +:102A000000F0014324FA02F211431846C9B2FFF75D +:102A1000CBF909F10809B9F1400F0346E9D1314674 +:102A2000B8822A7B033AD2B2FFF7D0F9FB7DB88295 +:102A3000DA43C2F3C01262F3C713FB7543E7AEB9C2 +:102A40002E1D013B32463946DBB204F10C00FFF784 +:102A500069FA0028BADB2A7B3146013AB88AD2B239 +:102A6000E2E700BF80841E0040420F00F98A013B6C +:102A7000C1F309010429DAB25DD80023281D07F14A +:102A80001B069A4208D910F801CB013306F801C0A1 +:102A900001310529DBB2F4D1934228BF0023039909 +:102AA00038BF04330A91049938BFDBB20B9107F1A8 +:102AB0001B010C91796838BF5B190D910E93FB8A4D +:102AC000ADF83EB0C3F309031A44069BADF83C20B1 +:102AD0008DF84230059B8DF840A08DF8433094F876 +:102AE0002C308DF8418083F001038DF844300023B1 +:102AF0007B602A7BB88A013A291DFFF767F93B8B77 +:102B0000B882834203D12046A3680AA99847204689 +:102B10000AA9FFF7FBFDFB7DBA8AC3F384030133E7 +:102B200003F01F039B02FB823B8B9A420CBF0020E9 +:102B30006FF01000BAE67B68002BADD0052001E0F5 +:102B400033461C301E68002EFAD1091A081D2E1DAE +:102B5000184401EB090CBCF11B0F5FFA89F39BD8F9 +:102B60009A4299D916F8013B09F1010900F8013B95 +:102B7000EFE76FF0090099E66FF00A0096E66FF054 +:102B80000B0093E66FF00D0090E66FF00E008DE6FF +:102B90006FF00F008AE600BFF0B53F4D3F4FEB6985 +:102BA00043F00073EB61EB693D4B9B6AD3F8006225 +:102BB0003E4046F00106C3F80062D3F800423C40B4 +:102BC00044EA002444F00104C3F80042002955D02F +:102BD00000200646C3F81C02C3F80402C3F80C0226 +:102BE000C3F8140203EBC00401300E28C4F840629D +:102BF000C4F84462F6D100274FF0010C967814888F +:102C000016F0010F18BFD3F804E20CFA04F01CBF51 +:102C100040EA0E0EC3F804E216F0020F18BFD3F814 +:102C20000CE203EBC4041CBF40EA0E0EC3F80CE236 +:102C3000760748BFD3F8146207F1010744BF064383 +:102C4000C3F814625668B942C4F84062966802F14B +:102C50000C02C4F84462D3F81C4240EA0400C3F8F2 +:102C60001C02CBD1D3F8002222F00102C3F80022CB +:102C7000EB6923F00073EB61EB69F0BD0122C3F84F +:102C80004012C3F84412C3F80412C3F81412C3F874 +:102C90000C22C3F81C22E5E7001002400000FFFFF1 +:102CA000A8230020184A08B5916A8B688B6013F03E +:102CB000010104D013F00C0F18BF4FF48031D80578 +:102CC00006D513F4406F14BF41F4003141F0020106 +:102CD000D80306D513F4402F14BF41F4802141F0EE +:102CE0000401D3690BB108489847302383F3118856 +:102CF0000021064800F048FB002383F31188BDE85B +:102D0000084000F099BD00BFA8230020B023002098 +:102D100038B5124CA36ADD68AA0712D05A6922F0AE +:102D200002025A61A36913B101212046984730235A +:102D300083F3118800210A4800F026FB002383F367 +:102D40001188EB0606D51021A36AD960236A0BB15E +:102D500002489847BDE8384000F06EBDA823002027 +:102D6000B823002038B5124CA36A1D69AA0712D0F7 +:102D70005A6922F010025A61A36913B10221204658 +:102D80009847302383F3118800210A4800F0FCFAA9 +:102D9000002383F31188EB0606D51021A36A19617D +:102DA000236A0BB102489847BDE8384000F044BDA3 +:102DB000A8230020B823002038B50F4CA36A5D6813 +:102DC0002A075D600AD5042222701A6822F00202E6 +:102DD0001A60636A13B10021204698476B0706D535 +:102DE000A36A9969236A13B1034809049847BDE8A7 +:102DF000384000F021BD00BFA823002010B50E4CC4 +:102E0000204600F02FF90D4B0B211320A36200F098 +:102E100009F90B21142000F005F90B21152000F011 +:102E200001F90B21162000F0FDF8BDE8104000224A +:102E30000E201146FFF7B0BEA8230020006400401A +:102E40000F4B10B59842044605D10E4BDA6942F09B +:102E50000072DA61DB690122A36A1A60A36A5A6808 +:102E6000D20707D5626851681268D9611A60064AAC +:102E70005A6110BD0121082000F0B0F9EEE700BF53 +:102E8000A8230020001002405B87010003291AD804 +:102E9000DFE801F0020A0F14836A9B6813F0E05F19 +:102EA00014BF012000207047836A9868C0F38060D7 +:102EB0007047836A9868C0F3C0607047836A9868F7 +:102EC000C0F30070704700207047000010B5032960 +:102ED00027D8DFE801F002272B2F836A9968C1F316 +:102EE0000161183103EB01131078840648BF546860 +:102EF000C0F3001158BF94884FEA410148BF41EA2E +:102F0000C40100F00F00586048BF41F00401906810 +:102F100058BF41EA4451D26841F001019860DA603B +:102F2000196010BD836A03F5C073DDE7836A03F59A +:102F3000C873D9E7836A03F5D073D5E701290AD0AE +:102F400002290FD081B9836ADA68920701D1186922 +:102F500003E001207047836AD86810F0030018BFAF +:102F600001207047836AF2E70020704710B539B935 +:102F7000836AD96889071BD11B699C0704D110BDDE +:102F8000012915D00229FAD1816AD1F8C031D1F8CE +:102F9000C441D1F8C8011061D1F8CC0150612020A2 +:102FA00008610869800717D1486940F0100012E0F5 +:102FB000816AD1F8B031D1F8B441D1F8B8011061CB +:102FC000D1F8BC0150612020C860C868800703D1D7 +:102FD000486940F002004861C3F34000C3F3800138 +:102FE000000140EA4111107920F0300001431171D5 +:102FF00089064BBF91681189DB085B0D4CBF63F3F9 +:103000001C0163F30A01137948BF916064F3030361 +:1030100013714FEA14234FEA144458BF11811370FF +:103020005480ACE70122090100F1604303F56143DC +:10303000C9B283F8001300F01F039A4043099B00B4 +:1030400003F1604303F56143C3F880211A607047C0 +:10305000090100F16040C9B200F56D40017670478A +:10306000FFF7CCBE01230370002300F10802C0E982 +:10307000022200F11002C0E90422C0E90633C0E9CF +:10308000083343607047000010B53023044683F3D3 +:103090001188022341600370FFF7D2FE0423002051 +:1030A000237080F3118810BD2DE9F0411F460446BE +:1030B0000D461646302383F3118800F10808237863 +:1030C000052B0DD029462046FFF7E0FE40B12046F3 +:1030D00032462946FFF7FAFE002080F3118808E007 +:1030E0003946404600F040F90028E8D0002383F339 +:1030F0001188BDE8F08100002DE9F0411F4604462B +:103100000D461646302383F3118800F1100823780A +:10311000052B0DD029462046FFF710FF40B1204671 +:1031200032462946FFF722FF002080F3118808E08D +:103130003946404600F018F90028E8D0002383F310 +:103140001188BDE8F08100000023826803750369DF +:103150001B6899689142FBD25A6803604260106014 +:103160005860704700238268037503691B6899687B +:103170009142FBD85A680360426010605860704703 +:1031800008B50846302383F311880B7D032B05D047 +:10319000042B0DD02BB983F3118808BD00228B6955 +:1031A0001A604FF0FF338361FFF7CEFF0023F2E791 +:1031B000D1E9003213605A60F3E70000FFF7C4BFA3 +:1031C000054BD96808751868026853601A600122B7 +:1031D0000275D860FDF79ABBD823002030B50C4BA0 +:1031E0000446DD684B1C87B00FD02B466846094A61 +:1031F00000F0F0F82046FFF7E3FF009B13B16846AC +:1032000000F0F0F8A86907B030BDFFF7D9FFF9E783 +:10321000D823002081310008044B1A68DB689068CD +:103220009B68984294BF002001207047D82300205B +:10323000084B10B51C68D868226853601A600122D8 +:103240002275DC60FFF78EFF01462046BDE8104086 +:10325000FDF75CBBD8230020044B1A68DB6892683A +:103260009B689A4201D9FFF7E3BF7047D82300203B +:1032700038B501230025064C0649074823706560D0 +:1032800000F020FB0223237085F3118838BD00BFB6 +:1032900030250020A43D0008D823002000F0B4B859 +:1032A000EFF3118020B9EFF30583302282F3118808 +:1032B0007047000010B530B9EFF30584C4F308047B +:1032C00014B180F3118810BDFFF7C6FF84F3118895 +:1032D000F9E700008B60022308618B820846704783 +:1032E0008368A3F1440243F8142C026943F8442C88 +:1032F000426943F8402C094A43F8242CC268A3F1E0 +:10330000200043F8182C022203F80C2C002203F8AA +:103310000B2C034A43F8102C704700BF1D0900080E +:10332000D823002008B5FFF7DBFFBDE80840FFF712 +:1033300045BF0000024BDB6898610F20FFF740BFDC +:10334000D8230020302383F31188FFF7F3BF000058 +:1033500008B50146302383F311880820FFF73EFFAC +:10336000002383F3118808BD064BDB6839B142683E +:1033700018605A60136043600420FFF72FBF4FF0BE +:10338000FF307047D823002038B504460D4620682A +:10339000844200D138BD036823605C608561FFF71B +:1033A0000DFFF4E710B50A4C23699A6891420CD8D6 +:1033B0005A6881600360426010609A685860511AD0 +:1033C00099604FF0FF33A36110BD1B68891AECE7C9 +:1033D000D8230020C0E90323002310B410BC4361AC +:1033E000FFF7E0BF036881689A680A449A60426800 +:1033F00013605A6000234FF0FF320360014B9A6163 +:10340000704700BFD823002070B5124D2A46EB69E3 +:103410000133EB6152F8103F934206D030269A6890 +:10342000013A9A602C69A36803B170BDD4E9002108 +:103430000A605160236083F311882046D4E9033188 +:10344000984786F3118861690029EBD02046FFF781 +:10345000A9FFE7E7D823002000207047FEE700001F +:10346000704700004FF0FF3070470000BFF34F8FF0 +:10347000024AD368DB07FCD4704700BF002002403B +:1034800008B5074B1B7853B9FFF7F0FF054B1A69D6 +:10349000120641BF044A5A6002F188325A6008BDE0 +:1034A00048250020002002402301674508B5054B50 +:1034B0001B7833B9FFF7DAFF034A136943F080033F +:1034C000136108BD48250020002002407F289ABFD4 +:1034D00000F5003080020020704700004FF480604B +:1034E00070470000802070477F2808B50BD8FFF791 +:1034F000EDFF00F580630268013204D1043083429D +:10350000F9D1012008BD0020FCE700007F2810B59C +:1035100004461CD8FFF7AAFFFFF7B2FFF3220D4BBA +:103520004FF48061DA6002221A61FFF7CFFF586121 +:103530001A6942F040021A61FFF798FF00F004F99F +:10354000FFF7B4FF2046BDE81040FFF7CDBF0020D5 +:1035500010BD00BF002002402DE9F843054612F0DF +:103560000100144606D040F2F32200201E4B1A60E0 +:10357000BDE8F8831D4BAA189A4204D94FF43E7255 +:10358000194B1A60F4E7FFF77BFF4FF00109FFF7D3 +:103590006DFFDFF85C806D1A012C0F4605EB01060C +:1035A00003D8FFF783FF0120E2E73B88C8F81090BB +:1035B00033800020FFF75AFFC8F81000338831F835 +:1035C000022B9BB29A420CD040F20F32064B1A608B +:1035D000084B1E60084B1C60084B1F60FFF766FF1E +:1035E000C6E7023CD8E700BF4425002000000208DF +:1035F0000020024038250020402500203C250020E6 +:10360000084908B50B7828B11BB9FFF739FF01232A +:103610000B7008BD002BFCD0BDE808400870FFF718 +:1036200045BF00BF4825002070B5FFF739FE4FF4B5 +:103630007A710D4B0D4EDB69326801FB03F3934247 +:1036400037BF0B4A0A495168156836BF4C1CD1E98F +:10365000005454605D1944F100043360FFF72AFE02 +:103660002846214670BD00BFD82300204C250020ED +:103670005025002070B5FFF713FE4FF47A710F4B01 +:103680000F4EDB69326801FB03F3934237BF0D4AEB +:103690000C49516815683ABF4C1C5460D1E900547C +:1036A0005D1944F100043360FFF704FE4FF47A72B1 +:1036B000002328462146FCF735FF70BDD8230020A3 +:1036C0004C2500205025002010B5094C013AD2B2FB +:1036D000FF2A00D110BD500854F82030013054F8B2 +:1036E00020009BB243EA004341F8043BEEE700BFF1 +:1036F000046C004010B50748013AD2B2FF2A00D14D +:1037000010BD0C88530840F823404C88013340F822 +:103710002340F1E7046C004007B50122002001A915 +:10372000FFF7D2FF019803B05DF804FB13B5044620 +:10373000FFF7F2FFA04205D00122002001A9019469 +:10374000FFF7D8FF02B010BD7047000045F2555298 +:10375000064B1A6002225A6040F6FF729A604CF6DD +:10376000CC421A600122024B1A70704700300040B0 +:103770005C250020034B1B781BB14AF6AA22024BA2 +:103780001A6070475C25002000300040044B1A6826 +:103790002AB902F1804202F50432526A1A60704777 +:1037A000582500204FF08072014B5A62704700BFCD +:1037B0000010024008B5FFF7E9FF024B1868C0F39C +:1037C000407008BD5825002008B5FFF7DFFF024B09 +:1037D0001868C0F3007008BD58250020EFF3098376 +:1037E000203383F30988002383F311887047000096 +:1037F000302080F3118862B60C4B0D4AD96821F451 +:10380000E0610904090C0A43DA60D3F8FC20094995 +:1038100042F08072C3F8FC200A6842F001020A609C +:103820002022DA7783F82200704700BF00ED00E025 +:103830000003FA05001000E0302310B583F311886F +:103840000B4B5B6813F400630FD0EFF309844FF068 +:103850008073203CE36184F30988FFF7DDFC10B13D +:10386000044BA36110BD044BFBE783F31188F9E718 +:1038700000ED00E02F090008320900087047000041 +:10388000FEE700000A4B0B480B4A90420BD30B4B50 +:10389000C11EDA1C121A22F003028B4238BF00222A +:1038A0000021FDF7FFBE53F8041B40F8041BECE7B2 +:1038B000243E0008E0250020E0250020E02500202F +:1038C000FEE7000070B5002504461A4B86B058602C +:1038D000856201630E46FFF78BFF04F11003C4E914 +:1038E00004334FF0FF33A361134BE561D9692B46D5 +:1038F0000A462046C4E9082304F134018023C4E9C0 +:1039000000440E4AA560E5622565FFF7E3FC01234C +:103910000B4AE06003750092726868460192B268D3 +:10392000CDE90223074BCDE90435FFF7FBFC06B0D8 +:1039300070BD00BF30250020D8230020B03D000816 +:10394000B53D0008C138000800F030B808B500F0F7 +:1039500063F9FFF78DFCBDE80840FFF717BF0000D3 +:10396000704700004FF0FF310E4B1A6919611A6958 +:1039700000221A611869D868D960D968DA60DA68F3 +:10398000DA6942F08052DA61DA69DA6942F000629B +:10399000DA61054ADB69136843F48073136000F051 +:1039A0001BB900BF0010024000700040194B1A689C +:1039B00042F001021A601A689007FCD51A6802F0FA +:1039C000F9021A6000225A605A6812F00C0FFBD1FB +:1039D0001A6842F480321A601A689103FCD55A685A +:1039E00042F4E8125A601A6842F080721A601A684B +:1039F0009201FCD51221084A5A60084A11605A689F +:103A000042F002025A605A6802F00C02082AFAD107 +:103A1000704700BF0010024000641D0000200240FB +:103A2000084A08B5516913680B4003F0010353615C +:103A300023B1054A13680BB150689847BDE80840A8 +:103A4000FFF7FABE0004014060250020084A08B5CF +:103A5000516913680B4003F00203536123B1054A17 +:103A600093680BB1D0689847BDE80840FFF7E4BE03 +:103A70000004014060250020084A08B55169136818 +:103A80000B4003F00403536123B1054A13690BB1E2 +:103A900050699847BDE80840FFF7CEBE00040140DA +:103AA00060250020084A08B5516913680B4003F0EF +:103AB0000803536123B1054A93690BB1D069984754 +:103AC000BDE80840FFF7B8BE0004014060250020B3 +:103AD000084A08B5516913680B4003F0100353619D +:103AE00023B1054A136A0BB1506A9847BDE80840F4 +:103AF000FFF7A2BE0004014060250020174B10B55F +:103B00005A691C68144004F478725A61A30604D5FB +:103B1000134A936A0BB1D06A9847600604D5104ADD +:103B2000136B0BB1506B9847210604D50C4A936B6D +:103B30000BB1D06B9847E20504D5094A136C0BB161 +:103B4000506C9847A30504D5054A936C0BB1D06C13 +:103B50009847BDE81040FFF76FBE00BF000401406A +:103B6000602500201A4B10B55A691C68144004F4F3 +:103B70007C425A61620504D5164A136D0BB1506D33 +:103B80009847230504D5134A936D0BB1D06D984720 +:103B9000E00404D50F4A136E0BB1506E9847A10490 +:103BA00004D50C4A936E0BB1D06E9847620404D5CD +:103BB000084A136F0BB1506F9847230404D5054A88 +:103BC000936F0BB1D06F9847BDE81040FFF734BE3C +:103BD0000004014060250020062108B50846FFF7D3 +:103BE00021FA06210720FFF71DFA06210820FFF71A +:103BF00019FA06210920FFF715FA06210A20FFF716 +:103C000011FA06211720FFF70DFABDE8084006213A +:103C10002820FFF707BA000008B5FFF7A3FE054804 +:103C200000F00CF8FFF71CFAFFF79AFEBDE8084019 +:103C300000F002B8BC3D000800F042B8002319466D +:103C40001C4A0133102BC2E9001102F10802F8D11D +:103C5000194B9A6942F07D029A619B690268174B81 +:103C6000DA6082685A6042681A60C26803F580634D +:103C7000DA6042695A6002691A608269C3F80C24EA +:103C8000026AC3F80424C269C3F80024426AC3F874 +:103C90000C28C26AC3F80428826AC3F80028026BA1 +:103CA000C3F80C2C826BC3F8042C426BC3F8002CB5 +:103CB000704700BF6025002000100240000801404E +:103CC0004FF0E023044A08215A6100229A6107223A +:103CD0000B201A61FFF7BCB93F19010008B530236A +:103CE00083F31188FFF7DAFA002383F3118808BD04 +:103CF00008B5FFF7F3FFBDE80840FFF79DBD0000E2 +:103D000010B501390244904201D1002005E003784A +:103D100011F8014FA34201D0181B10BD0130F2E78A +:103D20002DE9F0419BB10446C91A1778014403F10B +:103D3000FF3C8C42204601D9002008E00578013480 +:103D4000BD42F6D10CEB0405D618A54201D1BDE861 +:103D5000F08115F8018D16F801EDF045F5D0E8E792 +:103D6000034611F8012B03F8012B002AF9D1704703 +:103D70006F72672E6172647570696C6F742E663134 +:103D800030332D54726967676572000040A2E4F118 +:103D9000646891060041A3E5F2656992070000009E +:103DA00063300000A03D00083024002030250020B2 +:103DB0006D61696E0069646C6500000000180000A8 +:103DC00044444144445449440100000042444444B2 +:103DD00044444444000000004444444444444444B3 +:103DE00000000000444444444444444400000000B3 +:103DF00044444444444444445CC7FF7F0100000001 +:103E0000E803000000000000009C0100000000002A +:103E1000640000000000000040420F00FE2A010084 +:043E2000D2040000C8 :00000001FF diff --git a/Tools/bootloaders/f303-GPS_bl.bin b/Tools/bootloaders/f303-GPS_bl.bin index af275afb736724..52d37cb46e4f8f 100755 Binary files a/Tools/bootloaders/f303-GPS_bl.bin and b/Tools/bootloaders/f303-GPS_bl.bin differ diff --git a/Tools/bootloaders/f303-GPS_bl.hex b/Tools/bootloaders/f303-GPS_bl.hex index ff576ceeaa1c13..8411e72140b114 100644 --- a/Tools/bootloaders/f303-GPS_bl.hex +++ b/Tools/bootloaders/f303-GPS_bl.hex @@ -1,980 +1,1217 @@ :020000040800F2 -:1000000000090020A5040008E1140008611400089C -:10001000B9140008611400088D140008A704000832 -:10002000A7040008A7040008A704000881350008F9 -:10003000A7040008A7040008A7040008B93A0008AC -:10004000A7040008A7040008A7040008A7040008E4 -:10005000A7040008A7040008513800087D380008EC -:10006000A9380008D538000801390008A70400089D -:10007000A7040008A7040008A7040008A7040008B4 -:10008000A7040008A7040008A70400082924000802 -:1000900095240008E92400083D2500082D390008B2 -:1000A000A7040008A7040008A7040008A704000884 -:1000B000A7040008A7040008A7040008A704000874 -:1000C000A7040008A7040008A7040008A704000864 -:1000D000A70400088129000895290008A704000842 -:1000E00095390008A7040008A7040008A704000821 -:1000F000A7040008A7040008A7040008A704000834 -:10010000A7040008A7040008A7040008A704000823 -:10011000A7040008A7040008A7040008A704000813 -:10012000A7040008A7040008A7040008A704000803 -:10013000A7040008A7040008A7040008A7040008F3 -:10014000A7040008A7040008A7040008A7040008E3 -:10015000A7040008A7040008A7040008A7040008D3 -:10016000A7040008A7040008A7040008A7040008C3 -:10017000A7040008A7040008A7040008A7040008B3 -:10018000A7040008A7040008A7040008A7040008A3 -:10019000A7040008A7040008A7040008A704000893 -:1001A00053B94AB9002908BF00281CBF4FF0FF31DE -:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA -:1001C00000F006F8DDF804E0DDE9022304B0704732 -:1001D0002DE9F047089D04468E46002B4DD18A42FA -:1001E000944669D9B2FA82F252B101FA02F3C2F12D -:1001F000200120FA01F10CFA02FC41EA030E9440BE -:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE -:1002100016E341EA034306FB07F199420AD91CEBB6 -:10022000030306F1FF3080F01F81994240F21C81E8 -:10023000023E63445B1AA4B2B3FBF8F008FB103330 -:1002400044EA034400FB07F7A7420AD91CEB040465 -:1002500000F1FF3380F00A81A74240F20781644435 -:10026000023840EA0640E41B00261DB1D4400023BA -:10027000C5E900433146BDE8F0878B4209D9002D1E -:1002800000F0EF800026C5E9000130463146BDE8A8 -:10029000F087B3FA83F6002E4AD18B4202D3824212 -:1002A00000F2F980841A61EB030301209E46002DC1 -:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 -:1002C000002A40F09280A1EB0C014FEA1C471FFA74 -:1002D0008CFE0126200CB1FBF7F307FB131140EA5B -:1002E00001410EFB03F0884208D91CEB010103F128 -:1002F000FF3802D2884200F2CB804346091AA4B2EA -:10030000B1FBF7F007FB101144EA01440EFB00FEBD -:10031000A64508D91CEB040400F1FF3102D2A64522 -:1003200000F2BB800846A4EB0E0440EA03409CE7C1 -:10033000C6F12007B34022FA07FC4CEA030C20FA6E -:1003400007F401FA06F31C43F9404FEA1C4900FA8E -:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B -:1003600040EA014108FB0EF0884202FA06F20BD97E -:100370001CEB010108F1FF3A80F08880884240F2CE -:100380008580A8F102086144091AA4B2B1FBF9F012 -:1003900009FB101144EA014100FB0EFE8E4508D90D -:1003A0001CEB010100F1FF346CD28E456AD9023892 -:1003B000614440EA0840A0FB0294A1EB0E01A14277 -:1003C000C846A64656D353D05DB1B3EB080261EBE5 -:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF -:1003E000007100263146BDE8F087C2F12003D840F5 -:1003F0000CFA02FC21FA03F3914001434FEA1C4737 -:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 -:10041000064300FB0EF69E4204FA02F408D91CEBD8 -:10042000030300F1FF382FD29E422DD902386344D6 -:100430009B1B89B2B3FBF7F607FB163341EA034176 -:1004400006FB0EF38B4208D91CEB010106F1FF38C5 -:1004500016D28B4214D9023E6144C91A46EA0046BC -:1004600038E72E46284605E70646E3E61846F8E64E -:100470004B45A9D2B9EB020864EB0C0E0138A3E797 -:100480004646EAE7204694E74046D1E7D0467BE778 -:10049000023B614432E7304609E76444023842E7F0 -:1004A000704700BF02E000F000F8FEE772B63A487D -:1004B00080F30888394880F3098839484EF6085196 -:1004C000CEF20001086040F20000CCF200004EF6CF -:1004D0003471CEF200010860BFF34F8FBFF36F8F0E -:1004E00040F20000C0F2F0004EF68851CEF200015A -:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 -:10050000100A4EF63C71CEF200010860062080F31E -:100510001488BFF36F8F03F0B3F803F08FF803F084 -:10052000C1F84FF055301F491B4A91423CBF41F87A -:10053000040BFAE71C49194A91423CBF41F8040BED -:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C -:1005500042F8040BF8E700201749184A91423CBFC3 -:1005600041F8040BFAE703F06DF803F0D7F8144CE8 -:10057000144DAC4203DA54F8041B8847F9E700F045 -:1005800041F8114C114DAC4203DA54F8041B884772 -:10059000F9E703F055B80000000900200011002021 -:1005A000000000080001002000090020F83C0008BD -:1005B00000110020201100202011002028260020FA -:1005C000A0010008A0010008A0010008A001000887 -:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F -:1005E000BDEC108ABDE8F08F002383F31188284604 -:1005F000A047002002F04CFDFEE702F0D1FC00DF36 -:10060000FEE700002DE9F04102F062FF074602F02C -:10061000ADFF054600283ED12B4B9F423BD0013316 -:100620009F423BD0294B27F0FF029A423AD1F8B2C1 -:1006300000F054FAA84642F2107400F059FC08B1D8 -:100640000024A04600F050FA064678B384BB464624 -:1006500035B11F4B9F4203D002F080FF0024264695 -:10066000002002F03FFF1B4B1B6913F0400322D018 -:100670000EB100F031F800F05FFC00F031FE00F048 -:1006800031FF0546CCB100F02DFF401BA04214D92C -:1006900000F022F8F3E7A8460024CEE704464FF026 -:1006A0000108CAE780464FF47A74C6E70446CFE7EC -:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 -:1006C00002F0ECFCDEE700BF010007B0000008B05C -:1006D000263A09B00004004838B51D4A1D4B196878 -:1006E000013134D004339342F9D11B4C194DD4F865 -:1006F0000428AA422BD3194B9B6803F1006303F52E -:10070000D0439A4223D202F0FDFE02F00FFF0020F8 -:1007100000F000FE124B0220187000F037FE114B63 -:10072000DA690022DA61D96999699A619B6972B6BE -:100730004FF0E0232021C3F8085DD4F80038D4F846 -:10074000042881F311889D4683F30888104738BD3B -:100750002068000800680008006000080011002000 -:100760002011002000100240094A136849F2690074 -:1007700099B21B0C00FB01331360064B186844F25E -:10078000506182B2000C01FB0200186080B2704719 -:100790001C1100201811002010B500211022044661 -:1007A00000F00EFE034B03CB206061601868A06070 -:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 -:1007C00000F090FEAB6840F2ED22C31A934232D99A -:1007D00006AFA8602B4628220021384601F05EFBB8 -:1007E00005F10E0000F0E4FD002604465FFA80F9F2 -:1007F00005F10E08F3B2F100994501F1280107D97E -:1008000008EB06030822384601F048FB0136F1E701 -:1008100008230122CDE9023205340C4B0193A4B226 -:1008200030230093CDE9047405A3D3E90023297B89 -:10083000074801F04BF93BB0BDE8F083AFF300800F -:1008400078F6339F93CACD8D682100207521002052 -:100850003C21002070B50D4614461E4601F0CCF830 -:1008600050B9022E10D1012C0ED112A3D3E90023CE -:10087000C5E90023012007E0282C10D005D8012C61 -:1008800009D0052C0FD0002070BD302CFBD10BA35C -:10089000D3E90023ECE70BA3D3E90023E8E70BA39C -:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B -:1008B000AFF30080401DA12026812A0B78F6339FDC -:1008C00093CACD8D9E6AC421818A46EE26417272FA -:1008D000DF25D7B7F017304A39059E5613B50446C1 -:1008E0002346084620220021019001F0D7FA227900 -:1008F0000198032A234628BF032203F8042F20214E -:10090000022201F0CBFA62790198072A234628BF18 -:10091000072203F8052F2221032201F0BFFAA27952 -:100920000198072A234628BF072203F8062F25210E -:10093000032201F0B3FA019804F1080310222821E0 -:1009400001F0ACFA382002B010BD00002DE9F04FE4 -:10095000ADF5017D21AD0EAE40F2751280460F4619 -:1009600022A80021296000F02BFD482200213046FA -:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 -:10098000F2F0186093E80700012386E807000DF1F4 -:100990005A003382FFF700FF4EF60343338407AB60 -:1009A00018464D4903F0C2F81B22306429463046F0 -:1009B00086F83C20FFF792FF12AB0446014608225E -:1009C000284601F06BFA0822A1180DF149032846C8 -:1009D00001F064FA0DF14A03082204F110012846DF -:1009E00001F05CFA13AB202204F11801284601F053 -:1009F00055FA14AB402204F13801284601F04EFAB2 -:100A000016AB082204F17801284601F047FA0DF1EF -:100A10005903082204F18001284601F03FFA04F14D -:100A2000880A0DF15A0904F5847B4B465146082289 -:100A300028460AF1080A01F031FAD34509F1010903 -:100A4000F3D11BAB08225946284601F027FA04F5DA -:100A500088744FF0000996F834304B450AD9B36BCF -:100A600021464B440822284601F018FA083409F1BF -:100A70000109F0E74FF0000996F83C304B4504EBD4 -:100A8000C90108D9336C08224B44284601F006FA04 -:100A900009F10109F0E700230393BB7E02930731BC -:100AA00007F119030193C1F3CF010123CDE90451EB -:100AB0000093F97E05A3D3E90023404601F006F830 -:100AC0000DF5017DBDE8F08FAFF300809E6AC42173 -:100AD000818A46EE241100203C3B0008014B18702F -:100AE000704700BF30110020F0B5334B1C7B85B040 -:100AF00034B1324B0E221A810024204605B0F0BDDD -:100B00002F4A1068516802AB03C308232D492E48B1 -:100B10000DEB030202F0E8FF054630B9274B2B48E6 -:100B20000A221A8100F098FCE6E70169B1F5663FF8 -:100B300006D9224B26480B221A8100F08DFCDCE7F7 -:100B4000438BB3F57B7F09D01C4A22480C211181CD -:100B50004FF47B72194600F07FFCCEE71E4A024438 -:100B600002F11003994204D2144B1C4810221A813E -:100B7000E3E710398E1A2046134900F0B7FC3246DD -:100B8000074605F11801204600F0B0FCAB689F4213 -:100B900002D1EB6898420AD0084B0D221A810090CE -:100BA000D5E902123B460E4800F056FCA4E70D487A -:100BB00000F052FC0124A0E768210020241100204D -:100BC000E93B0008DC97030000680008583B000878 -:100BD000643B0008763B00080898FFF7943B000848 -:100BE000B13B0008DA3B00082DE9F04FADB006AF8D -:100BF00080460C4600F000FF054600285AD1237EAF -:100C0000022B1BD1E38A012B18D100F06BFC0646A6 -:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C -:100C2000F0F206F5167602FB103316FA83F3C9F8D4 -:100C30000030E37E33B9A84B00221A709C37BD46C2 -:100C4000BDE8F08FA38AEEB2013BB34205F1010586 -:100C50000BD93B1D1E44E90000960023082201F039 -:100C6000F801204600F0DEFFECE707F11400FFF783 -:100C700093FD324607F11401381D02F025FF0028CC -:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 -:100C90001673C9F80030D1E7FB1CF87001460093C9 -:100CA00007220346204600F0BDFFF978404600F0D9 -:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 -:100CC000052BBBD1BFF34F8F8449854BCA6802F413 -:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 -:100CE000ACD1637E7F4D01336A7BDBB29342E94630 -:100CF00003D1E27E2B7B9A4265D0CD469EE721460A -:100D00004046FFF723FE99E7A38A013B9BB2C92B1C -:100D100094D8744D2E7B26BB05F10C03009308225A -:100D200033463146204600F07DFF731CF2B2D900F5 -:100D30001E46A38A013B9A4205DA0E322A440092EB -:100D400000230822EEE700230022C5E90023002348 -:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 -:100D60002B73002507F114093B1D0822294648462C -:100D7000C7E90155FD6001F091F83B7A05F1010AE0 -:100D8000AB424FEACA0608D9FB6808222B44314619 -:100D9000484601F083F85546EFE7C6F3CF06E17EFB -:100DA000CDE9049600230393A37E029319342823EC -:100DB0000093019446A3D3E90023404600F086FE49 -:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 -:100DD00014801022009341460123204600F022FF98 -:100DE000A68A023EB6B2F31C9B109B000733DB08B9 -:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 -:100E0000C801B34201F110010AD20AEB08030093B2 -:100E100008220023204600F005FF08F10108ECE756 -:100E200095F8D70000F080FAD5F8D83004461BB901 -:100E300095F8D70000F088FAD5F8D83033449C42B2 -:100E400004D295F8D700013000F07EFA4FEA960BF5 -:100E50004FF000081FFA88F18B45D5E9003209D917 -:100E60000AEB880103EB8800012200F0B1FA08F1D7 -:100E70000108EFE7F31842F10002C5E90032D5F8A6 -:100E8000D83095F8D70006EB0308C5F8D88000F0F5 -:100E90004BFA804509D395F8D730D5F8D8000133FF -:100EA000001B85F8D730C5F8D800FF2E08D80023DE -:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D -:100EC0002B68094A9B0A013313810023AB6014E7A6 -:100ED00026417272DF25D7B73521002000ED00E0F2 -:100EE0000400FA0568210020241100203821002088 -:100EF00010B54FF000540C4B22689A4211D10B4BA5 -:100F0000627D1A700A48237D03730A49C9220E3094 -:100F100000F044FAE0220021204600F051FA0120BE -:100F200010BD0020FCE700BF9AAD44C53011002081 -:100F300068210020160000202DE9FF41434C0223C8 -:100F400063710023029324250A23581EB5FBF3F690 -:100F50007343D3F12402C1B23ED002280346F4D138 -:100F60009DF80B303A493B485A1E9DF80A30013B28 -:100F70001B0443EA0253BDF80820013A13434B60B7 -:100F800001F044FD00230193334B3449009334486E -:100F9000344B4FF4805200F001FD334B197811B1FE -:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D -:100FB0004FF4C873B0FBF3F202FB130305F5167090 -:100FC00010FA83F0294B186002F0D0FA08B10F2311 -:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF -:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA -:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F -:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 -:10101000CDB2591E0F2916D86A1E072A8CBF00228E -:101020000122591901FB06601149B1FBF0F1114889 -:10103000814295D1002A93D0ADF808608DF80A302E -:101040008DF80B508CE71346EBE700BF241100200E -:1010500010110020802200205508000834110020C3 -:101060003C210020E90B000830110020382100202D -:101070000051250240420F002DE9F04F90A7D7E91B -:1010800000670FF24429D9E90089874D93B0DFF852 -:1010900040B2864C284600F07DFD0DF1300A0790E5 -:1010A00070B310220021504600F08AF9079B197B8B -:1010B0004FF0000261F303028DF830205868996800 -:1010C0000EAA03C21B680D9A63F31C029DF8303010 -:1010D0000D9243F020038DF830300023524619461C -:1010E000584601F0A3FC079028B9284600F056FDA9 -:1010F000079B2370CEE72378072B3CD8013323705E -:1011000018220021504600F05BF9DFF8C4B100233B -:1011100019465246584601F0B1FC014678BB1022F0 -:1011200008A800F04DF94FF0904209AC536983F0E4 -:101130001003536100F0D8F90B4612A9024611E9D9 -:10114000030084E803009DF83410C1F3030089060E -:101150004CBF0E9CBDF838408DF82C0046BFC4F340 -:101160001C0444F00044C4F30A0408A92846089467 -:1011700000F0DCFECBE7284600F010FDC0E7284673 -:1011800000F03AFC0446002848D1DFF848B100F0EE -:10119000A9F9DBF80030984240D300F0A3F907909A -:1011A000FFF7E2FA079A8DF8204003464FF4C87023 -:1011B00002F51672B3FBF0F101FB103312FA83F360 -:1011C000CBF80030DFF810B19BF8001011B9012303 -:1011D0008DF8203050460791FFF7DEFA0799C1F1EC -:1011E0001004E4B2062C28BF0624224651440DF117 -:1011F000210000F0D3F808AB0393182302930134C5 -:101200002B4B0193E4B20123009304943B463246F6 -:10121000284600F0F3FB00238BF8003000F062F961 -:10122000244A254C1368C31AB3F57A7F31D3106072 -:1012300000F05AF902460B46284600F0B9FC284651 -:1012400000F0DAFB28B3237BDFF890B0002B14BF4B -:10125000032302238BF8053000F044F94FF47A732E -:101260005146B0FBF3F0CBF800005846FFF736FBD1 -:10127000182307300293114B0193C0F3CF0040F2C3 -:101280005513CDE903A0009342464B46284600F093 -:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 -:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 -:1012B0003421002048220020682100204C220020F8 -:1012C000401DA12026812A0BF1C6A7C1D068080FB6 -:1012D0008022002038210020352100202411002008 -:1012E00070B501F0B5FF094E094D30800024286823 -:1012F0003388834208D901F0A7FF2B6804440133E7 -:10130000B4F5D04F2B60F2D370BD00BF7C2200201B -:101310005022002002F03AB800F10060920000F57F -:10132000D04001F0D5BF0000054B1A68054B1B8863 -:101330009B1A834202D9104401F086BF00207047F7 -:10134000502200207C22002038B5074D0446286832 -:10135000204401F07FFF28B928682044BDE83840C8 -:1013600001F08ABF38BD00BF50220020064991F825 -:10137000243033B10023086A81F824300822FFF7B3 -:10138000CBBF0120704700BF54220020022802BFBB -:101390004FF090434FF480129A61704710B50023CC -:1013A000934203D0CC5CC4540133F9E710BD000074 -:1013B00003460246D01A12F9011B0029FAD17047E0 -:1013C00002440346934202D003F8011BFAE7704738 -:1013D0002DE9F8431F4D144695F82420074688460A -:1013E00052BBDFF870909CB395F824302BB92022C3 -:1013F000FF2148462F62FFF7E3FF95F82400C0F174 -:101400000802A24228BF2246D6B24146920005EB0E -:101410008000FFF7C3FF95F82430A41B1E44F6B2EA -:10142000082E17449044E4B285F82460DBD1FFF71E -:101430009DFF0028D7D108E02B6A03EB820383428B -:10144000CFD0FFF793FF0028CBD10020BDE8F88371 -:101450000120FBE7542200200FB4002004B07047A5 -:1014600000B59BB0EFF3098168226846FFF796FF4D -:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E -:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D -:10149000EFF3098168226846FFF780FFEFF30583C9 -:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF -:1014B000FEE700BF00ED00E000B59BB0EFF309814F -:1014C00068226846FFF76AFFEFF30583034B5A6B08 -:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 -:1014E000FEE7000001F08EBF01F064BF30B5094D8A -:1014F0000A4491420DD011F8013B5840082340F3B3 -:101500000004013B2C4013F0FF0384EA5000F6D1A5 -:10151000EFE730BD2083B8ED2DE9F041C56915B97D -:10152000C161BDE8F0814B6823F06047C3F38A4690 -:101530004FEAD37EC3F3807816EA230638BF3E46CF -:10154000AC462B465A68BEEBD27F22F060440AD0EC -:10155000002A18DAA40CB44217D19D420FD10D60B5 -:10156000DEE71346EEE7A74207D102F08044C2F35C -:10157000807242450BD054B1EFE708D2EDE7CCF8CA -:1015800000100B60CDE7B44201D0B442E5D81A6830 -:101590009C46002AE5D11960C3E700002DE9F04719 -:1015A000089D01F007044FEAD508224405F007051D -:1015B00000EBD1004FF47F49944201D1BDE8F087A0 -:1015C00004F0070705F0070A57453E4638BF564660 -:1015D000C6F10806111B8E4228BF0E46E10808EB33 -:1015E000D50E415C13F80EC0B94029FA06F721FA6E -:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 -:10160000010C03F80EC034443544D5E780EA0120CC -:10161000082341F2210201B24000002980B203F107 -:10162000FF33B8BF504013F0FF03F4D17047000000 -:1016300038B50C468D18A54200D138BD14F8011BF1 -:10164000FFF7E4FFF7E7000002684AB113680360A0 -:10165000C388018901339BB29942C38038BF03819B -:101660001046704770B588B0202204460D46684683 -:101670000021FFF7A5FE20460495FFF7E5FF02468F -:1016800058B16B46054608AE1C4603CCB4422860F0 -:101690006960234605F10805F6D1104608B070BD13 -:1016A000082817D909280CD00A280CD00B280CD0F0 -:1016B0000C280CD00D280CD00E2814BF4020302050 -:1016C00070470C2070471020704714207047182076 -:1016D0007047202070470000082817D90C280CD923 -:1016E00010280CD914280CD918280CD920280CD96A -:1016F00030288CBF0F200E207047092070470A2029 -:1017000070470B2070470C2070470D207047000079 -:1017100010B54B6823B9CA8A63F30902CA8210BDA7 -:10172000C4681A681C60C360438A013B43824A60F4 -:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 -:1017400009010629814692460B4630D00020AAB2F4 -:1017500007F119049EB2052E1FFA80F80FD89045A4 -:1017600003F1010306D3FB8A0A4462F30903FB82F7 -:1017700001201AE01AF80060E6540130EAE79045CB -:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 -:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 -:1017A000044638B978606FF00200BDE8F88F4FF05A -:1017B0000008E6E7002606607860ADB24FF0000B47 -:1017C000454510D90AEB0803221D13F8011B91555A -:1017D000B1B208F101081B291FFA88F82BD0454542 -:1017E00006F10106F1D8FB8AC3F30902154465F33B -:1017F0000903BCE7013292B21C462368002BF9D1E1 -:10180000AB1F0B441C21B3FBF1F301339BB29A4293 -:10181000D3D2BBF1000FD0D14846FFF715FF20B956 -:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 -:1018300020600446C1E74545D5D94846FFF704FF77 -:1018400008B92060AFE7C0F800B000262060044669 -:10185000B6E700002DE9F04F2DED028B83B0CDE906 -:101860000013BDF83C5007469146002A00F09280D4 -:101870002DB10E9B002B00F08D80072D32D807F183 -:101880000C00FFF7E1FE044638B96FF00204204671 -:1018900003B0BDEC028BBDE8F08F14220021FFF7EE -:1018A0008FFD0E992A4604F10800FFF777FD681CAA -:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 -:1018C000013814FA80F003F01F0363F03F03037242 -:1018D000009B43F00041616038462146FFF71CFE43 -:1018E0000124D4E700F10C034FF0000808EE103A91 -:1018F0004FF0800A4646444618EE100AFFF7A4FE51 -:1019000083460028C1D014220021FFF759FDC6BB31 -:10191000019BABF8083002200E9B00F108029919D8 -:101920005BFA82F20130C0B2082801D0AE422AD35D -:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E -:1019400002F01F0242EA4812AE4208BF4FF0400ABE -:101950005BFA81F14AEA020A43F0004281F808A0EA -:101960008BF81000CBF8042059463846FFF7D4FD19 -:101970000134AE4224B288F001084FF0000ABBD116 -:1019800085E70020C8E711F801CB02F801CB01364A -:10199000B6B2C7E76FF0010479E70000F8B5154665 -:1019A0000E462822002104461F46FFF709FD069B2C -:1019B0006360B5F5001F079BA76034BF6A094FF647 -:1019C000FF72236204F10C0097B200239A4205D8FB -:1019D0000023036027826382A382F8BD066001337F -:1019E00030462036F2E7000003781BB94BB2002BDB -:1019F000C8BF017070470000007870472DE9F74FAD -:101A0000DDF83C90BDF830500D9E9DF83840BDF893 -:101A10004070804692469B46B9F1000F01D1002FDD -:101A200051D11F2C4FD898F80000B0B9072F47D8D4 -:101A300035F0030347D13A4649464FF6FF70FFF7AA -:101A4000F7FD20F001002D02400445EA0464400C3B -:101A500044EA40244FF6FF7321E040EA0520072FB7 -:101A600040EA0464F6D900254FF6FF73C5F1200063 -:101A7000A5F120022AFA05F10BFA00F001432BFA36 -:101A800002F211431846C9B2FFF7C0FD0835402DD8 -:101A90000346EBD13A464946FFF7CAFD0346CDE976 -:101AA0000097324621464046FFF7D4FE3378013393 -:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B -:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 -:101AD00085B09246DDF848800F9D9DF840209DF826 -:101AE0004490BDF84C7006469B46B8F1000F01D1FA -:101AF000002F48D11F2A46D83378002B46D00C023D -:101B000044EA02649DF8381044EAC93444EA0144C6 -:101B10001C43072F44F0800432D900234FF6FF7294 -:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC -:101B300041EA0C012BFA00F00143C9B210460393AD -:101B4000FFF764FD039B0833402B0246E8D13A4679 -:101B50004146FFF76DFD0346CDE900872A46214641 -:101B60003046FFF777FEB9F1010F06D12B7801332C -:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 -:101B80004FF6FF73E8E76FF00100F6E76FF0030030 -:101B9000F3E70000C06900B104307047C3691A68F8 -:101BA000C261C2681A60C360438A013B43827047C6 -:101BB0002DE9F041D0F81880194E14461D464146D3 -:101BC000002709B9BDE8F081D1E90223A21A65EB2B -:101BD0000303964277EB03031ED283698B420DD138 -:101BE000FFF796FD83691B688361C3680B60438AB6 -:101BF000C1608169013B43828846E2E7FFF788FDC7 -:101C00000B68C8F80030C3680B60438AC160013BB1 -:101C10004382D8F80010D4E788460968D1E700BFAE -:101C200080841E002DE9F04F8BB00D46DDF85090FA -:101C300014469B468046002800F01981B9F1000F38 -:101C400000F01581531E3F2B00F21181012A03D1B0 -:101C5000BBF1000F40F00B810023CDE90833B8F849 -:101C60001430B5EBC30F4FEAC30703D300200BB00A -:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C -:101C8000FFB227461BB9D8F81030002B7AD02F2D81 -:101C90004ED8C5F13006B7424FF000032CBFF6B264 -:101CA0003E4600932946D8F8080008AB3246FFF7B5 -:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 -:101CC00003F10053063BDB000493D8F80C30039378 -:101CD0003021039B13B1BAF1000F2CD1D8F81000BA -:101CE00040B1BAF1000F05D0009608AB5246691A10 -:101CF000FFF754FC38B2002FB8D066070AD00AAB01 -:101D000003EBD401624211F8083C02F007021341D0 -:101D100001F8083C082C3CD9102C40F2B580202C4E -:101D200040F2B780BBF1000F00F09C80082334E044 -:101D3000BA460026C2E7049BE02B28BFE0230693A7 -:101D40000B44AB42059314D95A1B03980096924555 -:101D500034BF5246D2B2691A08AB04300792FFF77B -:101D60001DFC079A1644AAEB020A1544F6B25FFA64 -:101D70008AFA049B069A05999B1A0493039B1B6895 -:101D80000393A6E70093D8F8080008AB3A46294623 -:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F -:101DA000082C12D89DF82030621E23FA02F2D507C3 -:101DB00006D54FF0FF3202FA04F423438DF82030A9 -:101DC0009DF8203089F8003051E7102C12D8BDF86A -:101DD0002030621E23FA02F2D10706D54FF0FF32FF -:101DE00002FA04F42343ADF82030BDF82030A9F8FE -:101DF00000303CE7202C0FD80899631E21FA03F32A -:101E0000DA0705D54FF0FF3202FA04F40C430894C8 -:101E1000089BC9F800302AE7402C2BD0DDE9086583 -:101E2000611EC4F12102A4F1210326FA01F105FA91 -:101E300002F225FA03F311431943CB0712D501220D -:101E4000A4F12003C4F1200102FA03F322FA01F104 -:101E5000A240524243EA010363EB430332432B4364 -:101E6000CDE90823DDE90823C9E90023FFE66FF087 -:101E70000100FCE66FF00800F9E6082CA0D9102C50 -:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD -:101E900083E7BBF1000FBBD004237EE730B5012AF6 -:101EA000144638BF0124402C85B028BF40240025AB -:101EB000012ACDE9025518D81B788DF80830630740 -:101EC0000AD004AB03EBD405624215F8083C02F0DB -:101ED0000702934005F8083C009103462246002182 -:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 -:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D -:101F000000231B680293CDE90223D8E710B5CB6804 -:101F10001BB98B600B618B8210BDC4681A681C6092 -:101F2000C360438A013B4382CA60F0E72DE9F04F6A -:101F3000D1F8008093B018F0800FCDE90323C8F3E7 -:101F4000C01219BFC8F3C03BC8F306264FF0020BFE -:101F50001646B8F1000F04460D4680F2D18118F004 -:101F6000C043059340F0CC810B7B002B00F0C8816F -:101F7000BBF1020F03D00178B14240F0C48108F0F8 -:101F80007F0106916AB3C8F3074A2B44069A93F877 -:101F90000390760646EA0B4646EA82465FEAD91384 -:101FA00046EA0A06079300F0908000220023CDE95C -:101FB0000A23069B009367685B4652460AA920469F -:101FC000B84700287ED0A7699FB9314604F10C00BC -:101FD000FFF748FB0746E0B96FF0020013B0BDE819 -:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A -:101FF000CBE73B699E420DD03F68002FF9D13146B7 -:1020000004F10C00FFF72EFB07460028E4D0A3697B -:102010003B60A761DDE90A2300264FF6FF70C6F199 -:10202000200E22FA06F103FA0EFEA6F1200C23FA86 -:102030000CFC41EA0E0141EA0C01C9B208360992D2 -:102040000893FFF7E3FA402EDDE90832E7D1B882C2 -:10205000FB7D09F01F06C3F384039B1BD7E9022114 -:1020600098B2002BBCBF00F120031BB252EA010062 -:10207000C8F304680FD00398821A049860EB01013A -:10208000A74890424FF000028A4104D3079A002AE1 -:102090005BD0012B23DDFA7D4FEA890302F00302B6 -:1020A00003F07C031343FB7539462046FFF730FBF2 -:1020B000079BA3B9FB7DC3F38402013262F386035D -:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 -:1020D0000C0083E73B699E42BAD03F68F6E719F0EF -:1020E000400F32D0039BBB60049BFB601422002195 -:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 -:102100000C932B7BADF83EA0013BDBB2ADF83C302D -:10211000069B8DF8433094F824308DF840B083F05E -:1021200001038DF844308DF84160A3688DF842803A -:102130000AA920469847FB7DC3F38403013303F0CB -:102140001F039B02FB82002048E7FB7DC9F340127E -:10215000B2EBD31F40F0DA80C3F38403B34240F004 -:10216000D88007992B7B4FEA9912002934D0D207E7 -:1021700041D4032B40F2D080039BBB60049BFB60E7 -:102180002B7BAE1D033BDBB23246394604F10C001B -:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 -:1021A000FB7DC3F38403013303F01F039B02FB8217 -:1021B000032013E7AB883B832A7B033AB88AD2B269 -:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D -:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C -:1021E0003246394604F10C00FFF7A4FA0028D3DB8D -:1021F0002A7B013AE2E7F98AC1F30901013B05298B -:10220000DAB259D8281D002307F11A0C9A4208D9CE -:1022100010F801EB0CF801E0013101330629DBB2C3 -:10222000F4D103990A9104990B91934207F11A0191 -:102230000C9138BF043379680D9134BF55FA83F39C -:1022400000230E93FB8AADF83EA0C3F309031A44A2 -:10225000069B8DF8433094F82430ADF83C2083F091 -:1022600001038DF8443000238DF840B08DF84160B3 -:102270008DF842807B602A7BB88A013A291DFFF7DE -:10228000D7F93B8BB882834203D1A3680AA92046C1 -:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 -:1022A0008403013303F01F039B02FB823B8B9842A4 -:1022B00014BF1120002091E67B68002BB1D00620CE -:1022C00001E01C306346D3F800C0BCF1000FF8D128 -:1022D000091A081D05F1040C00EB030905989DF887 -:1022E000143001EB000EBEF11B0F9AD89A4298D918 -:1022F0001CF8013B09F8013B059B01330593EDE711 -:102300006FF009006AE66FF00A0067E66FF00D00F3 -:1023100064E66FF00E0061E66FF00F005EE600BF4E -:1023200080841E00F0B53D4D3D4FEB6943F00073D6 -:10233000EB61EB693B4B9B6AD3F800623E4046F091 -:102340000106C3F80062D3F800423C4044EA002092 -:1023500040F00100C3F80002002951D00020C3F86A -:102360001C020646C3F80402C3F80C02C3F81402A8 -:1023700003EBC00401300E28C4F84062C4F8446284 -:10238000F6D100274FF0010C9678148816F0010F53 -:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A -:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 -:1023B0000E0EC3F80CE2760742BFD3F81462064350 -:1023C000C3F8146203EBC4045668C4F8406296680C -:1023D000C4F84462D3F81C4201372043B942C3F821 -:1023E0001C0202F10C02CFD1D3F8002222F001022C -:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 -:102400000122C3F84012C3F84412C3F80412C3F8FF -:102410001412C3F80C22C3F81C22E5E70010024096 -:102420000000FFFF80220020184A916A08B58B68DF -:102430008B6013F0010104D013F00C0F18BF4FF4A0 -:102440008031D80506D513F4406F14BF41F4003134 -:1024500041F00201D80306D513F4402F14BF41F414 -:10246000802141F00401D3690BB10848984720232B -:1024700083F311880648002100F038FE002383F31F -:102480001188BDE8084001F0AFB800BF80220020ED -:102490008822002038B5124CA36ADD68AA0712D042 -:1024A0005A6922F002025A61A36913B10121204640 -:1024B0009847202383F311880A48002100F016FE74 -:1024C000002383F31188EB0606D5A36A1021D96097 -:1024D000236A0BB102489847BDE8384001F084B840 -:1024E000802200209022002038B5124CA36A1D697A -:1024F000AA0712D05A6922F010025A61A36913B1D7 -:10250000022120469847202383F311880A4800219E -:1025100000F0ECFD002383F31188EB0606D5A36AD7 -:1025200010211961236A0BB102489847BDE8384071 -:1025300001F05AB8802200209022002038B50F4CBC -:10254000A36A5D685D602A070AD5042222701A68B2 -:1025500022F002021A60636A13B1002120469847F4 -:102560006B0706D5A36A9969236A13B10348090466 -:102570009847BDE8384001F037B800BF80220020FE -:1025800010B50E4C204600F02FFA0D4BA3620B2124 -:10259000132000F009FA0B21142000F005FA0B219A -:1025A000152000F001FA0B21162000F0FDF90022A1 -:1025B000BDE8104011460E20FFF7B4BE8022002077 -:1025C000006400400F4B984210B5044605D10E4BF5 -:1025D000DA6942F00072DA61DB69A36A01221A60EB -:1025E000A36A5A68D20707D5626851681268D96130 -:1025F0001A60064A5A6110BD0121082000F06CFCE7 -:10260000EEE700BF80220020001002405B8701003F -:1026100003291AD8DFE801F0020A0F14836A9B68C5 -:1026200013F0E05F14BF012000207047836A9868B0 -:10263000C0F380607047836A9868C0F3C0607047D9 -:10264000836A9868C0F300707047002070470000EC -:1026500010B5032925D8DFE801F00225292D836A6A -:102660009968C1F30161183103EB011310788406F6 -:102670004CBF54689488C0F300114FEA410148BF31 -:1026800041EAC40100F00F004CBF41F0040141EAEF -:102690004451586041F001019068D2689860DA6056 -:1026A000196010BD836A03F5C073DFE7836A03F521 -:1026B000C873DBE7836A03F5D073D7E701290AD033 -:1026C00002290FD081B9836ADA68920701D11869AB -:1026D00003E001207047836AD86810F0030018BF38 -:1026E00001207047836AF2E70020704710B539B9BE -:1026F000836AD96889071BD11B699C0704D110BD67 -:10270000012915D00229FAD1816AD1F8C031D1F856 -:10271000C441D1F8C8011061D1F8CC01506120202A -:1027200008610869800717D1486940F0100012E07D -:10273000816AD1F8B031D1F8B441D1F8B801106153 -:10274000D1F8BC0150612020C860C868800703D15F -:10275000486940F002004861C3F34000C3F38001C0 -:10276000000140EA4111107920F03000014311715D -:1027700089064BBF91681189DB085B0D4CBF63F381 -:102780001C0163F30A01137948BF916064F30303EA -:1027900013714FEA14234FEA144458BF1181137088 -:1027A0005480ACE7026843681143016003B11847E5 -:1027B00070470000024A136843F0C003136070477B -:1027C00000380140024A136843F0C00313607047A9 -:1027D0000044004037B51D4C1D4D204600F006FB5F -:1027E000009404F114001B490023202200F0C8F9D2 -:1027F0002022009404F13800174B184900F042FAE7 -:10280000174BC4E91735174C0C21252000F0CCF8E4 -:10281000204600F0EBFA04F1140013490094002361 -:10282000202200F0ADF904F13800104B104900945B -:10283000202200F027FA0F4B0C212620C4E917357F -:1028400003B0BDE8304000F0AFB800BFAC220020BC -:102850000051250284230020B5270008C42300204E -:102860000038014018230020A4230020C5270008B9 -:10287000E4230020004400402DE9F047C66D37688E -:10288000F46934622107054618D014F0080118BF16 -:102890008021E20748BF41F02001A30748BF41F073 -:1028A0004001600748BF41F48071202383F3118801 -:1028B000281DFFF777FF002383F31188E2050AD56F -:1028C000202383F311884FF40071281DFFF76AFF5E -:1028D000002383F311884FF020094FF0000A14F011 -:1028E000200838D13B0616D54FF0200905F1380AEB -:1028F000200610D589F31188504600F0F7F900281A -:1029000036DA0821281DFFF74DFF27F080033360DA -:10291000002383F31188790614D5620612D520238B -:1029200083F31188D5E913239A4208D12B6C33B174 -:102930001021281D27F04007FFF734FF37600023E0 -:1029400083F31188E30619D5AA6E1369B3B1BDE804 -:10295000F0475069184789F31188B38C95F86410D3 -:102960002846194000F04EFA8AF31188F469B6E758 -:1029700080B2308588F31188F469B9E7BDE8F08743 -:1029800008B50348FFF778FFBDE8084000F02CBE0B -:10299000AC22002008B50348FFF76EFFBDE80840F1 -:1029A00000F022BE1823002000F1604303F56143CC -:1029B0000901C9B283F80013012200F01F039A40F5 -:1029C00043099B0003F1604303F56143C3F8802191 -:1029D0001A60704700F16040090100F56D40C9B20E -:1029E00001767047FFF7CCBD012300F10802C0E972 -:1029F0000222037000F110020023C0E90422C0E9A2 -:102A00000633C0E9083343607047000010B5202347 -:102A1000044683F31188022303704160FFF7D2FD5F -:102A200004232370002383F3118810BD2DE9F041A6 -:102A30001F4604460D461646202383F3118800F1F5 -:102A400008082378052B0DD029462046FFF7E0FD26 -:102A500040B1204632462946FFF7FAFD002080F3B8 -:102A6000118808E03946404600F024FB0028E8D0F1 -:102A7000002383F31188BDE8F08100002DE9F041C7 -:102A80001F4604460D461646202383F3118800F1A5 -:102A900010082378052B0DD029462046FFF70EFE9F -:102AA00040B1204632462946FFF720FE002080F341 -:102AB000118808E03946404600F0FCFA0028E8D0CA -:102AC000002383F31188BDE8F0810000F8B51546B6 -:102AD00082680669AA420B46816938BF8568761A02 -:102AE000B54204460BD218462A46FEF757FCA369A6 -:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 -:102B000018463246FEF74AFCAF1BE1683A463044AD -:102B1000FEF744FCE3683B44EBE718462A46FEF721 -:102B20003DFCE368E5E7000083689342F7B515468E -:102B3000044638BF8568D0E90460361AB5420BD226 -:102B40002A46FEF72BFC63692B446361A368284681 -:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 -:102B60001DFC0199E068AF1B3A463144FEF716FCA4 -:102B7000E3683B44E9E72A46FEF710FCE368E4E734 -:102B800010B50A440024C361029B8460C0E90000C0 -:102B9000C0E90511C1600261036210BD08B5D0E94A -:102BA0000532934201D1826882B982680132826023 -:102BB0005A1C42611970D0E904329A4224BFC3689A -:102BC0004361002100F086FA002008BD4FF0FF307D -:102BD000FBE7000070B5202304460E4683F31188FE -:102BE000A568A5B1A368A269013BA360531CA361BA -:102BF00015782269934224BFE368A361E3690BB1AE -:102C000020469847002383F31188284607E0314681 -:102C1000204600F04FFA0028E2DA85F3118870BDF3 -:102C20002DE9F74F04460E4617469846D0F81C90FB -:102C30004FF0200A8AF311884FF0000B154665B15A -:102C40002A4631462046FFF741FF034660B9414618 -:102C5000204600F02FFA0028F1D0002383F31188DA -:102C6000781B03B0BDE8F08FB9F1000F03D00190DD -:102C70002046C847019B8BF31188ED1A1E448AF346 -:102C80001188DCE7C0E90511C160C3611144009BF4 -:102C90008260C0E90000016103627047F8B5044634 -:102CA0000D461646202383F31188A768A7B1A368B1 -:102CB000013BA36063695A1C62611D70D4E9043250 -:102CC0009A4224BFE3686361E3690BB120469847E9 -:102CD000002080F3118807E03146204600F0EAF931 -:102CE0000028E2DA87F31188F8BD0000D0E9052357 -:102CF0009A4210B501D182687AB982680132826045 -:102D00005A1C82611C7803699A4224BFC36883619C -:102D1000002100F0DFF9204610BD4FF0FF30FBE747 -:102D20002DE9F74F04460E4617469846D0F81C90FA -:102D30004FF0200A8AF311884FF0000B154665B159 -:102D40002A4631462046FFF7EFFE034660B941466A -:102D5000204600F0AFF90028F1D0002383F311885A -:102D6000781B03B0BDE8F08FB9F1000F03D00190DC -:102D70002046C847019B8BF31188ED1A1E448AF345 -:102D80001188DCE7026843681143016003B118470A -:102D9000704700001430FFF743BF00004FF0FF33CF -:102DA0001430FFF73DBF00003830FFF7B9BF000017 -:102DB0004FF0FF333830FFF7B3BF00001430FFF798 -:102DC00009BF00004FF0FF311430FFF703BF0000D0 -:102DD0003830FFF763BF00004FF0FF323830FFF7A5 -:102DE0005DBF000000207047FFF7F4BC044B036098 -:102DF0000023C0E90233436001230374704700BF1E -:102E0000F43B000838B5C36904460D461BB90421DC -:102E10000844FFF7B7FF294604F11400FFF7BEFE90 -:102E2000002806DA201D4FF48061BDE83840FFF726 -:102E3000A9BF38BD024B0022C3E900339A60704736 -:102E400004240020002303748268054B1B689968E2 -:102E50009142FBD25A68036042601060586070472C -:102E60000424002008B5202383F31188037C032B5E -:102E700005D0042B0DD02BB983F3118808BD43690D -:102E800000221A604FF0FF334361FFF7DBFF00239E -:102E9000F2E7D0E9003213605A60F3E700230374CD -:102EA0008268054B1B6899689142FBD85A68036099 -:102EB000426010605860704704240020054B196977 -:102EC0000874186802681A6053601861012303745B -:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 -:102EE000044610D02B690A4A01A800F01BF92046BD -:102EF000FFF7E4FF049B13B101A800F02FF92B6941 -:102F0000586907B030BDFFF7D9FFF8E70424002067 -:102F1000652E000838B50C4D41612B6981689A68AF -:102F20009142044603D8BDE83840FFF78BBF1846EE -:102F3000FFF7B4FF01232C61014623742046BDE84E -:102F40003840FDF745BB00BF04240020044B1A683D -:102F50001B6990689B68984294BF002001207047CD -:102F60000424002010B5084C236820691A682260E8 -:102F70005460012223611A74FFF790FF0146206913 -:102F8000BDE81040FDF724BB0424002008B5FFF77E -:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 -:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 -:102FB00000F0AAF80A498022204600F031F80123E7 -:102FC00044F8180C037400F0EBFA002383F3118823 -:102FD00062B60448BDE8104000F042B82C2400203E -:102FE0001C3C00082C3C000800F0CAB8EFF311802C -:102FF00020B9EFF30583202282F311887047000087 -:1030000010B530B9EFF30584C4F3080414B180F3AC -:10301000118810BDFFF7BAFF84F31188F9E70000AB -:1030200082600222028270478368A3F17C0243F827 -:103030000C2C026943F83C2C426943F8382C074AAF -:1030400043F81C2CC26843F8102C022203F8082C09 -:10305000002203F8072CA3F118007047E9050008C7 -:1030600010B5202383F31188FFF7DEFF002104460B -:10307000FFF750FF002383F31188204610BD0000A6 -:10308000024B1B6958610F20FFF718BF0424002072 -:10309000202383F31188FFF7F3BF000008B5014632 -:1030A000202383F311880820FFF716FF002383F302 -:1030B000118808BD49B1064B42681B6918605A6007 -:1030C000136043600420FFF707BF4FF0FF307047E5 -:1030D000042400200368984206D01A6802605060F9 -:1030E00059611846FFF7AEBE7047000038B5044678 -:1030F0000D462068844200D138BD036823605C60BF -:103100004561FFF79FFEF4E7054B03F11402C3E9A5 -:1031100005224FF0FF32DA6100221A62704700BFC9 -:103120000424002010B5C0E903230B4A136A536935 -:103130009C68A1420CD85C68816003604460206098 -:1031400058609868411A99604FF0FF33D36110BD01 -:103150001B68091BECE700BF04240020036881689A -:103160009A680A449A60426813605A600023C360F8 -:10317000024B4FF0FF32DA61704700BF0424002099 -:1031800038B50F4C236A22460133236252F8143FAC -:10319000934206D09A68013A9A60202563699A683A -:1031A00002B138BDD3E9001001604860D968DA6027 -:1031B00082F311881869884785F31188EEE700BF0C -:1031C0000424002000207047FEE700007047000044 -:1031D0004FF0FF3070470000BFF34F8F024AD368B3 -:1031E000DB07FCD4704700BF0020024008B5074B46 -:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 -:10320000044A5A6002F188325A6008BD90250020B5 -:10321000002002402301674508B5054B1B7833B9F0 -:10322000FFF7DAFF034A136943F08003136108BD17 -:1032300090250020002002407F289ABF00F58030B2 -:10324000C0020020704700004FF40060704700008B -:10325000802070477F2808B50BD8FFF7EDFF00F5F9 -:1032600000630268013204D104308342F9D10120A5 -:1032700008BD0020FCE700007F2838B5044623D8AD -:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 -:10329000DA6002221A6105462046FFF7CDFF586129 -:1032A0001A6942F040021A614FF40061FFF794FF7F -:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 -:1032C000BDE83840FFF7C6BF002038BD00200240EF -:1032D00012F001032DE9F04704460E46154606D0CC -:1032E000244B40F2BD221A600020BDE8F08781180F -:1032F000214A914204D91F4A40F2C2211160F3E7EA -:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 -:1033100031464FF0010AA61B012D06EB0107884636 -:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E -:103330000030C9F810A03B800024FFF74DFFC9F80A -:1033400010403B8831F8022B9BB29A420FD0094BB8 -:1033500040F2D9221A60094B1F60094B1D60094BCE -:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 -:10337000D2E700BF8C250020000004088025002033 -:10338000882500208425002000200240084908B537 -:103390000B7828B11BB9FFF729FF01230B7008BD7B -:1033A000002BFCD0BDE808400870FFF735BF00BF18 -:1033B0009025002030B583B0FFF718FE0E4B0F4D5F -:1033C0001B6A2A684FF47A7101FB03F3934237BFFB -:1033D0000B4A0B49516814682B602EBFD1E900419C -:1033E000013151601C1941F100010191FFF708FE04 -:1033F0000199204603B030BD04240020942500200C -:103400009825002030B583B0FFF7F0FD114B124D29 -:103410001B6A2A684FF47A7101FB03F3934237BFAA -:103420000E4A0E49516814682B602EBFD1E9004145 -:10343000013151601C1941F100010191FFF7E0FDDC -:1034400001994FF47A7200232046FCF7A9FE03B0DD -:1034500030BD00BF042400209425002098250020C2 -:1034600010B50244064BD2B2904200D110BD441CAC -:1034700000B253F8200041F8040BE0B2F4E700BFBB -:10348000502800400F4B30B51C6A240407D41C6A36 -:1034900044F440741C621C6A44F400441C620A4CEC -:1034A000236843F4807323600244084BD2B29042F5 -:1034B00000D130BD441C00B251F8045B43F82050E9 -:1034C000E0B2F4E7001002400070004050280040D5 -:1034D00007B5012201A90020FFF7C2FF019803B040 -:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 -:1034F000012201A900200194FFF7C4FF02B010BD12 -:1035000070470000074B45F255521A6002225A607C -:1035100040F6FF729A604CF6CC421A60024B0122D0 -:103520001A70704700300040A4250020034B1B7820 -:103530001BB1034B4AF6AA221A607047A42500204B -:1035400000300040044B1A682AB902F1804202F5AB -:103550000432526A1A607047A0250020024B4FF0D7 -:1035600080725A62704700BF0010024008B5FFF732 -:10357000E9FF024B1868C0F3407008BDA025002089 -:10358000EFF3098305494A6B22F001024A6368336D -:1035900083F30988002383F31188704700EF00E06C -:1035A000202080F3118862B60C4B0D4AD96821F4B3 -:1035B000E0610904090C0A43DA60D3F8FC200949E8 -:1035C00042F08072C3F8FC200A6842F001020A60EF -:1035D0001022DA7783F82200704700BF00ED00E088 -:1035E0000003FA05001000E010B5202383F31188D2 -:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 -:103600000984683C4FF08073E361094BDB6B2366F0 -:1036100084F30988FFF79AFC10B1064BA36110BD33 -:10362000054BFBE783F31188F9E700BF00ED00E0ED -:1036300000EF00E0FB050008FE05000870470000F1 -:10364000FEE700000A4B0B480B4A90420BD30B4B92 -:10365000DA1C121AC11E22F003028B4238BF00226C -:103660000021FDF7ADBE53F8041B40F8041BECE746 -:10367000183D0008282600202826002028260020A3 -:10368000704700004B6843608B688360CB68C36001 -:103690000B6943614B6903628B6943620B6803608A -:1036A0007047000008B51B4B9A6A42F4FC029A620C -:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB -:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 -:1036D00002F11C0100F58060FFF7D4FF02F1380110 -:1036E00000F58060FFF7CEFF02F1540100F5806025 -:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D -:1037000002F18C0100F58060FFF7BCFFBDE80840C6 -:1037100000F05AB800100240443C000808B500F020 -:1037200093F9FFF741FCBDE80840FFF70BBF00002D -:103730007047000010B5214CA36A63F4FC03A36238 -:10374000A36A03F4FC03A3624FF0FF32A36A236968 -:1037500022612369002323612169E168E260E26854 -:10376000E360E268E269164942F08052E261E26990 -:103770000A6842F480720A60226A02F44072B2F56A -:10378000407F1EBF4FF4803222622362236A1B04F3 -:1037900007D4236A43F440732362236A43F400434B -:1037A000236200F031F9A369064A43F00103A361E3 -:1037B000A369136843F02003136010BD001002409A -:1037C00000700040000001401E4B1A6842F00102E8 -:1037D0001A601A689007FCD55A6822F003025A60F2 -:1037E0005A6812F00C02FBD1196801F0F901196056 -:1037F0005A601A6842F480321A601A689103FCD544 -:10380000114A5A604FF40452DA6230221A631A687D -:1038100042F080721A601A689201FCD50B4912229C -:103820000A600A6802F00702022AFAD15A6842F0D6 -:1038300002025A605A6802F00C02082AFAD11A6B86 -:103840001A6370470010024000241D00002002404F -:10385000084A08B5516913680B4003F0010353612E -:1038600023B1054A13680BB150689847BDE808407A -:10387000FFF7BABE00040140A8250020084A08B599 -:10388000516913680B4003F00203536123B1054AE9 -:1038900093680BB1D0689847BDE80840FFF7A4BE15 -:1038A00000040140A8250020084A08B551691368A2 -:1038B0000B4003F00403536123B1054A13690BB1B4 -:1038C00050699847BDE80840FFF78EBE00040140EC -:1038D000A8250020084A08B5516913680B4003F079 -:1038E0000803536123B1054A93690BB1D069984726 -:1038F000BDE80840FFF778BE00040140A82500207D -:10390000084A08B5516913680B4003F0100353616E -:1039100023B1054A136A0BB1506A9847BDE80840C5 -:10392000FFF762BE00040140A8250020174B10B528 -:103930005A691C68144004F478725A61A30604D5CD -:10394000134A936A0BB1D06A9847600604D5104AAF -:10395000136B0BB1506B9847210604D50C4A936B3F -:103960000BB1D06B9847E20504D5094A136C0BB133 -:10397000506C9847A30504D5054A936C0BB1D06CE5 -:103980009847BDE81040FFF72FBE00BF000401407C -:10399000A82500201A4B10B55A691C68144004F47D -:1039A0007C425A61620504D5164A136D0BB1506D05 -:1039B0009847230504D5134A936D0BB1D06D9847F2 -:1039C000E00404D50F4A136E0BB1506E9847A10462 -:1039D00004D50C4A936E0BB1D06E9847620404D59F -:1039E000084A136F0BB1506F9847230404D5054A5A -:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F -:103A000000040140A8250020062108B50846FEF75D -:103A1000CBFF06210720FEF7C7FF06210820FEF78F -:103A2000C3FF06210920FEF7BFFF06210A20FEF78B -:103A3000BBFF06211720FEF7B7FFBDE808400621AF -:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 -:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE -:103A6000084000F001B8000000F00EB80023054A3D -:103A700019460133102BC2E9001102F10802F8D1F6 -:103A8000704700BFA82500204FF0E023044A5A6188 -:103A900000229A6107221A6108210B20FEF79ABFC3 -:103AA0003F19010008B5202383F31188FFF79CFA22 -:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 -:103AC0000840FFF791BD000010B501390244904253 -:103AD00001D1002005E0037811F8014FA34201D085 -:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E -:103AF00017780144044603F1FF3C8C42204601D96B -:103B0000002009E00578BD4204F10104F5D10CEB79 -:103B10000405D618A54201D1BDE8F08115F8018D44 -:103B200016F801EDF045F5D0E7E70000034611F87F -:103B3000012B03F8012B002AF9D170476F72672E11 -:103B40006172647570696C6F742E61705F706572FC -:103B50006970685F677073004E6F206170702073CA -:103B600069670A00426164206677206C656E67743D -:103B7000682025750A0042616420626F6172645F8B -:103B800069642025752073686F756C6420626520F8 -:103B900025750A004261642066772064657363724C -:103BA0006970746F72206C656E6774682025750A81 -:103BB00000426164206170702043524320307825B8 -:103BC0003038783A307825303878203078253038D9 -:103BD000783A3078253038780A00476F6F6420666D -:103BE00069726D776172650A0040A2E4F1646891C0 -:103BF0000600000000000000B12D00089D2D000807 -:103C0000D92D0008C52D0008D12D0008BD2D0008B4 -:103C1000A92D0008952D0008E52D00086D61696E3D -:103C20000000000069646C6500000000243C00088E -:103C3000482400208025002001000000A52F000856 -:103C400000000000A001A82A00000000FAAABEAAF5 -:103C500050001424EFFF0000007700007097090067 -:103C60000100000000000000AAAAAAAA01000000AA -:103C7000FFFF000000000000000000000000000046 -:103C800000000000AAAAAAAA00000000FFFF00008E -:103C90000000000000000000000000000000000024 -:103CA000AAAAAAAA00000000FFFF0000000000006E -:103CB000000000000000000000000000AAAAAAAA5C -:103CC00000000000FFFF00000000000000000000F6 -:103CD0000000000000000000AAAAAAAA000000003C -:103CE000FFFF00000000000000000000E4C4FF7FB0 -:103CF0000100000000000000EC03000000000000D4 -:103D000000980300000000006400000000000000B4 -:083D1000FE2A0100D2040000AC +:1000000000090020B5040008D52500088D2500084A +:10001000B52500088D250008AD250008B7040008A7 +:10002000B7040008B7040008B7040008C935000881 +:10003000B7040008B7040008B70400087D430008AF +:10004000B7040008B7040008B7040008B7040008A4 +:10005000B7040008B7040008614000088D4000089C +:10006000B9400008E540000811410008B704000845 +:10007000B7040008B7040008B7040008B704000874 +:10008000B7040008B7040008B704000841250008B9 +:100090006D2500087D250008B70400083D410008D3 +:1000A000B7040008B7040008B7040008B704000844 +:1000B000B7040008B7040008B7040008B704000834 +:1000C000B7040008B7040008B7040008B704000824 +:1000D000B70400086D45000881450008B704000812 +:1000E000A5410008B7040008B7040008B7040008D9 +:1000F000B7040008B7040008B7040008B7040008F4 +:10010000B7040008B7040008B7040008B7040008E3 +:10011000B7040008B7040008B7040008B7040008D3 +:10012000B7040008B7040008B7040008B7040008C3 +:10013000B7040008B7040008B7040008B7040008B3 +:10014000B7040008B7040008B7040008B7040008A3 +:10015000B7040008B7040008B7040008B704000893 +:10016000B7040008B7040008B7040008B704000883 +:10017000B7040008B7040008B7040008B704000873 +:10018000B7040008B7040008B7040008B704000863 +:10019000B7040008B7040008B7040008B704000853 +:1001A000291200080000000000000000000000000C +:1001B00053B94AB9002908BF00281CBF4FF0FF31CE +:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA +:1001D00000F006F8DDF804E0DDE9022304B0704722 +:1001E0002DE9F047089D04468E46002B4DD18A42EA +:1001F000944669D9B2FA82F252B101FA02F3C2F11D +:10020000200120FA01F10CFA02FC41EA030E9440AD +:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE +:1002200016E341EA034306FB07F199420AD91CEBA6 +:10023000030306F1FF3080F01F81994240F21C81D8 +:10024000023E63445B1AA4B2B3FBF8F008FB103320 +:1002500044EA034400FB07F7A7420AD91CEB040455 +:1002600000F1FF3380F00A81A74240F20781644425 +:10027000023840EA0640E41B00261DB1D4400023AA +:10028000C5E900433146BDE8F0878B4209D9002D0E +:1002900000F0EF800026C5E9000130463146BDE898 +:1002A000F087B3FA83F6002E4AD18B4202D3824202 +:1002B00000F2F980841A61EB030301209E46002DB1 +:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 +:1002D000002A40F09280A1EB0C014FEA1C471FFA64 +:1002E0008CFE0126200CB1FBF7F307FB131140EA4B +:1002F00001410EFB03F0884208D91CEB010103F118 +:10030000FF3802D2884200F2CB804346091AA4B2D9 +:10031000B1FBF7F007FB101144EA01440EFB00FEAD +:10032000A64508D91CEB040400F1FF3102D2A64512 +:1003300000F2BB800846A4EB0E0440EA03409CE7B1 +:10034000C6F12007B34022FA07FC4CEA030C20FA5E +:1003500007F401FA06F31C43F9404FEA1C4900FA7E +:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB +:1003700040EA014108FB0EF0884202FA06F20BD96E +:100380001CEB010108F1FF3A80F08880884240F2BE +:100390008580A8F102086144091AA4B2B1FBF9F002 +:1003A00009FB101144EA014100FB0EFE8E4508D9FD +:1003B0001CEB010100F1FF346CD28E456AD9023882 +:1003C000614440EA0840A0FB0294A1EB0E01A14267 +:1003D000C846A64656D353D05DB1B3EB080261EBD5 +:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF +:1003F000007100263146BDE8F087C2F12003D840E5 +:100400000CFA02FC21FA03F3914001434FEA1C4726 +:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 +:10042000064300FB0EF69E4204FA02F408D91CEBC8 +:10043000030300F1FF382FD29E422DD902386344C6 +:100440009B1B89B2B3FBF7F607FB163341EA034166 +:1004500006FB0EF38B4208D91CEB010106F1FF38B5 +:1004600016D28B4214D9023E6144C91A46EA0046AC +:1004700038E72E46284605E70646E3E61846F8E63E +:100480004B45A9D2B9EB020864EB0C0E0138A3E787 +:100490004646EAE7204694E74046D1E7D0467BE768 +:1004A000023B614432E7304609E76444023842E7E0 +:1004B000704700BF02E000F000F8FEE772B6374870 +:1004C00080F30888364880F3098836483649086042 +:1004D00040F20000CCF200004EF63471CEF2000182 +:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 +:1004F000F0004EF68851CEF200010860BFF34F8F36 +:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 +:10051000CEF200010860062080F31488BFF36F8FCD +:1005200003F052FC03F0C6FC4FF055301F491B4A44 +:1005300091423CBF41F8040BFAE71D49184A914229 +:100540003CBF41F8040BFAE71A491B4A1B4B9A427D +:100550003EBF51F8040B42F8040BF8E7002018499D +:10056000184A91423CBF41F8040BFAE703F030FC13 +:1005700003F0DCFC144C154DAC4203DA54F8041BB8 +:100580008847F9E700F042F8114C124DAC4203DA0B +:1005900054F8041B8847F9E703F018BC0009002051 +:1005A000001100200000000808ED00E0000100201C +:1005B00000090020704B0008001100207C11002071 +:1005C00080110020583C0020A0010008A401000870 +:1005D000A4010008A40100082DE9F04F2DED108AB8 +:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 +:1005F000002383F311882846A047002003F06EF9FA +:10060000FEE703F0D1F800DFFEE70000F8B500F0E8 +:100610001DFE03F07DFB074603F0CCFB05460028DA +:1006200040D12C4B9F423DD001339F423DD02A4BBD +:1006300027F0FF029A423BD1F8B200F043FC2E466D +:1006400042F2107400F044FC08B10024264601F088 +:10065000B5F888B3032000F045F80024264635B1EC +:100660001E4B9F4203D003F09DFB00242646002032 +:1006700003F058FB1A4B1B6913F0400322D00EB154 +:1006800000F046F800F056FC00F0E2FD01F0AAFF91 +:100690000546CCB101F0A6FF401BA04214D900F0E2 +:1006A00037F8F3E72E460024CCE704460126C9E7D5 +:1006B00006464FF47A74C5E7002CD0D04FF47A7414 +:1006C0000126CCE71C46DDE700F07CFC012003F0AE +:1006D0000BF9DEE7010007B0000008B0263A09B0C8 +:1006E00000040048084B187003280CD8DFE800F01D +:1006F00008050208022000F007BE022000F0FCBD41 +:10070000024B00225A6070478011002084110020A3 +:1007100038B501F053F830B11F4B03221A701F4B4C +:1007200000225A6038BD1E4B1E4A19680131F9D0AB +:1007300004339342F9D11C4C194DD4F80428AA4231 +:10074000F0D31A4B9B6803F1006303F5D0439A4240 +:10075000E8D203F0FBFA03F00DFB002000F092FD5D +:100760000220FFF7BFFF124BDA690022DA61D96974 +:1007700099699A619B6972B64FF0E0233021C3F802 +:10078000085DD4F80038D4F8042881F311889D4618 +:1007900083F308881047C5E78011002084110020EA +:1007A00000680008206800080060000800110020B0 +:1007B00000100240094A136849F2690099B21B0C03 +:1007C00000FB01331360064B186844F2506182B29B +:1007D000000C01FB0200186080B270471411002069 +:1007E0001011002010B500211022044600F0A6FDD3 +:1007F000034B03CB206061601868A06010BD00BF90 +:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 +:100810006CAC40F2751207460D460EA80021C8F8D0 +:10082000001000F08BFD4FF4C4720021204600F050 +:1008300085FD01F0D7FE274B4FF47A72B0FBF2F042 +:10084000186093E80700022384E807000DF5E970BB +:100850002382FFF7C7FF4EF603431F49238407A8EF +:1008600004F0BAF8162384F832310DF2E32207AB14 +:100870000DF12C0C1E4603CE6645106051603346C8 +:1008800002F10802F6D130681060B38893804146C7 +:100890000122204600F09EFD00230393AB7E0293CD +:1008A00005F11903019380B20123CDE9048000937F +:1008B000E97E06A3D3E90023384602F05BFA0DF582 +:1008C0004E7DBDE8F08100BFAFF300809E6AC42179 +:1008D000818A46EE8C110020E84900082DE9F0419C +:1008E0002C4C237ADAB080460D465BBB27A92846FC +:1008F00000F080FE0746002842D19DF89D60C82E7A +:100900003ED801464FF4A662204600F017FD4FF492 +:100910008073C4F8F8314FF40073C4F80C334FF40B +:100920004073C4F8203432460DF19E0104F10900F1 +:1009300000F0F2FC26449DF89C30777223720BB9CC +:10094000EB7E23728122002106AC27A800F0F6FC82 +:100950000122214627A800F089FE00230393AB7EE5 +:10096000029305F1190380B201932823CDE90440D5 +:100970000093E97E05A3D3E90023404602F0FAF98B +:100980005AB0BDE8F08100BFAFF30080264172721B +:10099000DF25D7B7A8320020F0B5254E4FF48A7571 +:1009A00005FB0065F1B096F8D83085F8DC300024FE +:1009B000D822214685F8E8403AA800F0BFFC06F1AD +:1009C000090000F0B3FCD5F8E4308DF8F000C2B2B5 +:1009D00006AF06F109010DF1F100CDE93A3400F05E +:1009E0009BFC394601223AA800F06CFE80B2CDE9AA +:1009F000047008230127CDE9023706F1D8030193DB +:100A000030230093317A0B4807A3D3E9002302F087 +:100A1000B1F9A04206DD01F0E5FDC5F8E000384679 +:100A200071B0F0BD2046FBE778F6339F93CACD8DB9 +:100A3000A8320020A42100202DE9F0411D4D1E4EBA +:100A40001E4F86B0284602F0C1F9034658B3002471 +:100A5000CDE90344ADF81440027B8DF81420996869 +:100A60004068029403AA03C21B68DFF8548043F075 +:100A70000043029301F0B8FD821941F10003009494 +:100A800002A9384601F07CF8A04205DD284602F0B4 +:100A9000A1F988F80040D5E798F80030072B05D871 +:100AA000013388F8003006B0BDE8F081014802F05B +:100AB00091F9F8E7A421002040420F00D82100203E +:100AC000DD37002070B50D4614461E4602F0AEF824 +:100AD00050B9022E10D1012C0ED112A3D3E900235C +:100AE000C5E90023012007E0282C10D005D8012CEF +:100AF00009D0052C0FD0002070BD302CFBD10BA3EA +:100B0000D3E90023ECE70BA3D3E90023E8E70BA329 +:100B1000D3E90023E4E70BA3D3E90023E0E700BF18 +:100B2000AFF30080401DA12026812A0B78F6339F69 +:100B300093CACD8D9E6AC421818A46EE2641727287 +:100B4000DF25D7B7F017304A39059E5638B5054628 +:100B50000E4C0021013500F0B7FBA4F82C55B4F879 +:100B60002C0500F099FB78B1B4F82C0500F0A4FB3B +:100B7000014648B9B4F82C0500F0A6FBB4F82C35B2 +:100B80000133A4F82C35EAE738BD00BFA8320020B5 +:100B900010B50A4B0A4A1A6003F5805393F8602097 +:100BA0003AB9DC6D2CB1204600F082FE204603F0FD +:100BB00053FEBDE81040034800F07ABED821002063 +:100BC0003C4A0008203200202DE9F04F8FB000AFE2 +:100BD00005460C4602F02AF8002849D1237E022B54 +:100BE0001BD1E38A012B18D101F0FCFC0646FFF76C +:100BF000E1FD03464FF4C870DFF8C482B3FBF0F2A6 +:100C000006F5167602FB103316FA83F3C8F80030A7 +:100C1000E37E33B9A34B00221A703C37BD46BDE8D2 +:100C2000F08F07F12401204600F0A2FC0028F4D147 +:100C300007F11400FFF7D6FD97F8264007F11401DD +:100C4000224607F1270003F051FE0028E2D10F2CC5 +:100C500008D8944B1C70D8F80030A3F51673C8F868 +:100C60000030DAE797F82410284601F0D7FFD4E7E0 +:100C7000E38A282B2BD010D8012B23D0052BCCD1E5 +:100C8000BFF34F8F8849894BCA6802F4E06213436F +:100C9000CB60BFF34F8F00BFFDE7302BBDD1844E3B +:100CA000E17E327A9142B8D1607E3146002291F8DD +:100CB000DC50854200F0A5800132042A01F58A71DA +:100CC000F5D1AAE721462846FFF79CFDA5E7214676 +:100CD0002846FFF703FEA0E7B2F8EC507B6005F171 +:100CE00003094FEA99094FEA8902D11DC908A8EB07 +:100CF000C1039D46EB460021584600F01FFB04F15E +:100D0000EE012A463144584600F006FB7B6813B9D1 +:100D1000012000F0B7FA96F8D20000F0BDFA0446C0 +:100D200030B9307200F0D8FA204600F0ABFAB1E0EA +:100D3000D6F8D4203AB996F8D200B6F82C258242DB +:100D400001D8FFF703FFD6F8D4202A44944208D2F2 +:100D500096F8D200B6F82C250130824201D8FFF770 +:100D6000F5FE70685FFA89F2594600F0EFFA08B9AB +:100D7000C54679E0726896F8D2002A447260D6F8C7 +:100D8000D42005EB0209C6F8D49000F085FA81451D +:100D900009D396F8D220D6F8D4000132001B86F889 +:100DA000D220C6F8D400FF2D0FD80024347200F0F2 +:100DB00093FA204600F066FA00F000FD3D4B1881E2 +:100DC00008B9FFF7A5FCC54627E7BB6896F8D90028 +:100DD0000AFB0362FB68D2F8E41082F8E83001F500 +:100DE0008061C2F8E030C2F8E410FFF7D5FDFFF7EC +:100DF00023FE96F8D920013202F0030286F8D920AA +:100E0000B6E74FF48A7A0AFB02F505F1EA013144AC +:100E1000204600F083FCF86000287FF4FEAE3544E5 +:100E2000012285F8E82001F0DDFBD5F8E020D6EDC1 +:100E3000007ADFED216A801A192838BF192040F6A0 +:100E4000B832904228BF1046B8EE677A07EE900A93 +:100E5000F8EEE77A67EEA67ADFED186AE7EE267A13 +:100E6000FCEEE77AC6ED007A96F8D930BB60BA6836 +:100E700073680AFB02F4321992F8E81059B1D2F8FB +:100E8000E4108B42E8463FF427AF002182F8E810D7 +:100E9000C2F8E010C5467368064A9B0A0133138105 +:100EA000BBE600BF9D21002000ED00E00400FA0534 +:100EB000A83200208C110020CDCCCC3D6666663F68 +:100EC000A0210020014B1870704700BF981100202E +:100ED00038B54FF00054134B22689A4220D1124B80 +:100EE000627D12481A70237D03724FF48073C0F83C +:100EF000F8314FF40073C0F80C3300254FF4407301 +:100F0000C0F820340A49C0F8E450C922093000F082 +:100F100003FAE0222946204600F010FA012038BDED +:100F20000020FCE79AAD44C598110020A8320020AB +:100F30001600002037B500F041FC194D19492881F1 +:100F40000223012218486B7101F0EAF90023019392 +:100F5000164B174900931748174B4FF4805201F076 +:100F600035FE164B197811B1124801F057FE01F009 +:100F700039FB0446FFF71EFC4FF4C873B0FBF3F2D5 +:100F800002FB130304F5167010FA83F00C4B186083 +:100F900002F010FF08B10F232B8103B030BD00BF5A +:100FA0008C11002040420F00D8210020C50A000803 +:100FB0009C110020A4210020C90B000898110020DA +:100FC000A02100202DE9F04F2DED028B8EA7D7E94F +:100FD00000670FF23C29D9E90089864C95B00DAD28 +:100FE0009FED828BFFF728FDDFF82CB200230C93D6 +:100FF000ADF83C300D936B6000230DF125028DEDB3 +:10100000008B4FF0010A09A958468DF825308DF85C +:1010100024A001F035F99DF824200023002A40F097 +:10102000AB80204601F002FE0546002847D1DFF8DC +:10103000ECB101F0D7FADBF8003098423FD301F071 +:10104000D1FA0790FFF7B6FB079A4FF4C873B0FBCD +:10105000F3F101FB130302F5167010FA83F0CBF8DD +:101060000000DFF8BCB19BF800100791002914BF05 +:101070002B46534610A88DF83030FFF7B3FB079985 +:10108000C1F11002D2B2062A10AB28BF06221944C1 +:101090000DF13100079200F03FF9079A0CAB039372 +:1010A000182302930132544BD2B2CDE900A304922B +:1010B0003B463246204601F0FFFD8BF8005001F020 +:1010C00091FA4E4A4E4D1368C31AB3F57A7F32D364 +:1010D000106001F089FA02460B46204601F084FEBA +:1010E000204601F0A3FD30B32B7ADFF838A1002BA6 +:1010F00014BF032302238AF8053001F073FA0DF1BF +:10110000400B4FF47A730122B0FBF3F05946CAF852 +:101110000000504600F004FA18230293394B019363 +:1011200080B240F25513CDE903B0009342464B46DE +:10113000204601F0C1FD2B7ACBB101F053FA4FF0FC +:10114000000A83464FF48A7295F8D900504400F0A3 +:10115000030002FB005393F8E81089B30AF1010A77 +:10116000BAF1040FF0D12B7A002B7FF438AF15B011 +:10117000BDEC028BBDE8F08F4FF0904110A84A699A +:1011800082F010024A611946102200F0D7F80DF1E2 +:1011900026030AAA0CA9584600F0F0FD95E80300C2 +:1011A00011AB83E803009DF83C308DF84C300C9B6C +:1011B000109310A9DDE90A23204601F0E9FF1BE79F +:1011C000D3F8E01049B12B68FA2B38BFFA23ABEB08 +:1011D00001010533B1EB430FC0D3FFF7DDFB4FF443 +:1011E0008A720028BAD1BEE7AFF300800000000089 +:1011F00000000000A42100209C210020D8370020FE +:10120000A8320020DC370020401DA12026812A0BB7 +:10121000F1C6A7C1D068080FD8210020A021002066 +:101220009D2100208C11002008B5054800F040FEEB +:10123000BDE80840034A0449002003F007BB00BF93 +:10124000D821002018380020910B000870470000BA +:1012500070B502F013FC094E094D30800024286857 +:101260003388834208D902F005FC2B68044401331B +:10127000B4F5D04F2B60F2D370BD00BF0C38002006 +:10128000E037002002F086BC00F10060920000F51B +:10129000D04002F02DBC0000054B1A68054B1B889E +:1012A0009B1A834202D9104402F0E4BB002070472D +:1012B000E03700200C380020024B1B68184402F075 +:1012C000DFBB00BFE0370020024B1B68184402F070 +:1012D000E9BB00BFE0370020064991F8243033B164 +:1012E0000023086A81F824300822FFF7CDBF0120CF +:1012F000704700BFE4370020022802BF4FF0904340 +:1013000010229A6170470000022802BF4FF09043FC +:101310004FF480129A61704710B50023934203D0B6 +:10132000CC5CC4540133F9E710BD0000034602460B +:10133000D01A12F9011B0029FAD170470244034662 +:10134000934202D003F8011BFAE770472DE9F843F6 +:101350001F4D144695F824200746884652BBDFF8F7 +:1013600070909CB395F824302BB92022FF21484679 +:101370002F62FFF7E3FF95F82400C0F10802A242B4 +:1013800028BF2246D6B24146920005EB8000FFF707 +:10139000C3FF95F82430A41B1E44F6B2082E174450 +:1013A0009044E4B285F82460DBD1FFF795FF002874 +:1013B000D7D108E02B6A03EB82038342CFD0FFF73B +:1013C0008BFF0028CBD10020BDE8F8830120FBE78C +:1013D000E43700202DE9F0470D46044600219046F1 +:1013E000284640F27912FFF7A9FF23462022002168 +:1013F000284601F06FFE231D02222021284601F01D +:1014000069FE631D03222221284601F063FEA31D0D +:1014100003222521284601F05DFE04F10803102275 +:101420002821284601F056FE04F110030822382135 +:10143000284601F04FFE04F11103082240212846FE +:1014400001F048FE04F1120308224821284601F069 +:1014500041FE04F1140320225021284601F03AFEF7 +:1014600004F1180340227021284601F033FE04F1F4 +:1014700020030822B021284601F02CFE04F12103AC +:101480000822B821284601F025FE04F12207C026D3 +:101490003B46314608222846083601F01BFEB6F5C9 +:1014A000A07F07F10107F3D104F13203082231468E +:1014B000284601F00FFE002704F1330A94F8323079 +:1014C0004FEAC7099F4209F5A47615D3B8F1000F7A +:1014D00008D1314604F599730722284601F0FAFD38 +:1014E00009F24F16274694F832213B1B93420CD346 +:1014F000F01DC008BDE8F0870AEB0703082231465B +:10150000284601F0E7FD0137D8E707F233133146EB +:101510000822284601F0DEFD08360137E3E7000027 +:1015200013B504460846002101602346C0F80310A5 +:101530002022019001F0CEFD0198231D02222021DE +:1015400001F0C8FD0198631D0322222101F0C2FDB4 +:101550000198A31D0322252101F0BCFD019804F18F +:1015600008031022282101F0B5FD072002B010BDAC +:10157000F7B50023047F00910E4607221946054661 +:1015800001F06CFC731C0093012200230721284604 +:1015900001F064FCC4B9B31C009305222346082162 +:1015A000284601F05BFC0D243746B278BB1B934202 +:1015B00011D32B7FA88A0734E408BBB9844294BFB7 +:1015C0000020012003B0F0BDAB8ADB00083BDB0844 +:1015D000B3700824E8E7FB1C00932146002308228F +:1015E000284601F03BFC08340137DEE7201A18BF1B +:1015F0000120E7E7F7B50023047F00910E4608229B +:101600001946054601F02AFC731CC4B90822009350 +:1016100011462346284601F021FC1024012372784C +:101620005F1C013B934211D32B7FA88A0734E40847 +:10163000BBB9844294BF0020012003B0F0BDAB8A47 +:10164000DB00083BDB0873700824E7E7F31900931D +:10165000214600230822284601F000FC08343B46BE +:10166000DDE7201A18BF0120E7E70000F8B50E46B5 +:1016700005461446002181223046FFF75FFE2B46C7 +:1016800008220021304601F025FD7CB96B1C0722A1 +:101690000821304601F01EFD0F2401236A785F1CEB +:1016A000013B934204D3E01DC008F8BD0824F4E7D1 +:1016B000EB1921460822304601F00CFD08343B4668 +:1016C000ECE70000F8B50E46054614460021CE2290 +:1016D0003046FFF733FE2B4628220021304601F02A +:1016E000F9FC7CB905F1080308222821304601F0F5 +:1016F000F1FC30242F462A7A7B1B934204D3E01D51 +:10170000C008F8BD2824F5E707F10903214608229F +:10171000304601F0DFFC08340137ECE7F7B5047F11 +:1017200000910E46012310220021054601F096FB90 +:10173000C4B9B31C0093092223461021284601F0A6 +:101740008DFB192437467288BB1B9A4211D82B7F18 +:10175000A88A0734E408BBB9844294BF0020012062 +:1017600003B0F0BDAB8ADB00103BDB0873801024B4 +:10177000E8E73B1D0093214600230822284601F09C +:101780006DFB08340137DEE7201A18BF0120E7E7B8 +:1017900030B5094D0A4491420DD011F8013B584033 +:1017A000082340F30004013B2C4013F0FF0384EABC +:1017B0005000F6D1EFE730BD2083B8EDF7B5364ADB +:1017C000106851686B4603C36A463449344808239D +:1017D00003F09CF8044690BB0A25324A1068516811 +:1017E0006B4603C36A4630492D48082303F08EF840 +:1017F0000446002847D00369B3F5663F43D8B0F8E4 +:101800006620B2F57B7F3ED1284A024402F15C019A +:101810008B4238D35C3B224900209E1AFFF7B8FF69 +:101820003246074604F164010020FFF7B1FFA368C8 +:101830009F4228D1E368984208BF002523E003694E +:10184000B3F5663F26D8428BB2F57B7F20D1174A8D +:10185000024402F110018B4218D3103B10490020C2 +:101860009D1AFFF795FF2A46064604F1180100204D +:10187000FFF78EFFA3689E4202D1E368984201D031 +:101880000D25AAE70025284603B0F0BD1025A4E7E2 +:101890000C25A2E70B25A0E7004A0008DC9703000F +:1018A00000680008094A0008909703000898FFF7AD +:1018B00010B5037C044613B9006803F00FF8204606 +:1018C00010BD00000023BFF35B8FC360BFF35B8FCD +:1018D000BFF35B8F8360BFF35B8F7047BFF35B8F9A +:1018E0000068BFF35B8F704770B505460C30FFF79B +:1018F000F5FF05F1080604463046FFF7EFFFA0426A +:1019000006D930466D68FFF7E9FF2544281A70BDF7 +:101910003046FFF7E3FF201AF9E7000070B50546EF +:10192000406898B105F10800FFF7D8FF05F10C06F3 +:1019300004463046FFF7D2FF8442304694BF6D68BC +:101940000025FFF7CBFF013C2C44201A70BD00009E +:1019500038B50C460546FFF7C7FFA04210D305F186 +:101960000800FFF7BBFF04446868B4FBF0F100FB1C +:101970001144BFF35B8F0120AC60BFF35B8F38BDB8 +:101980000020FCE72DE9F041144607460D46FFF71D +:10199000C5FF844228BF0446D4B1B84658F80C6B42 +:1019A0004046FFF79BFF3044286040467E68FFF7C3 +:1019B00095FF331A9C4203D86C600120BDE8F0818A +:1019C0006B60A41B3B68AB602044E8600220F5E735 +:1019D0002046F3E738B50C460546FFF79FFFA042C7 +:1019E00010D305F10C00FFF779FF04446868B4FBDD +:1019F000F0F100FB1144BFF35B8F0120EC60BFF3FB +:101A00005B8F38BD0020FCE72DE9FF418846694621 +:101A10000746FFF7B7FF6C4606B204EBC606002583 +:101A2000B44209D06268206808EB0501FFF774FC36 +:101A3000636808341D44F3E729463846FFF7CAFFB8 +:101A4000284604B0BDE8F081F8B505460C300F46D5 +:101A5000FFF744FF05F1080604463046FFF73EFF56 +:101A6000A042304688BF6C68FFF738FF201A386004 +:101A700020B130462C68FFF731FF2044F8BD00004C +:101A800073B5144606460D46FFF72EFF844228BF65 +:101A900004460190DCB101A93046FFF7D5FF019B58 +:101AA00033B93268C5E90233C5E9002401200CE0EE +:101AB0009C4238BF01942860019868608442F5D93F +:101AC0003368AB60241AEC60022002B070BD20467F +:101AD000FBE700002DE9FF410F466946FFF7D0FF05 +:101AE0006C4600B204EBC0050026AC4209D0D4F825 +:101AF000048054F8081BB8194246FFF70DFC464411 +:101B0000F3E7304604B0BDE8F081000038B5054683 +:101B1000FFF7E0FF044601462846FFF719FF20467D +:101B200038BD0000302383F3118862B6704700008F +:101B3000002383F3118862B67047000010B4026876 +:101B400054681A4623465DF8044B18470120704735 +:101B50000020704700207047704700000020704749 +:101B60000E20704700F5805090F8C800C0F3400088 +:101B70007047000000F5805090F9C90070470000E0 +:101B8000F7B50C68BDF8207014F000541E466FD1F4 +:101B90000B7B082B6CD8FFF7C5FF4569AB685B0171 +:101BA0000CD4AB681B0108D4AC6814F080545DD130 +:101BB000FFF7BEFF204603B0F0BD01240B6804F11F +:101BC000180C002BB8BFDB004FEA0C1CB4BF43F06D +:101BD00004035B0545F80C300B680FFA84FC13F026 +:101BE000804F18BF05EB0C1E05EB0C1C1EBFDEF86A +:101BF000803143F00203CEF880310B7BCCF8843186 +:101C000005EB04158B68C5F88C314B68C5F8883135 +:101C1000DCF8803143F00103CCF8803100EB44154F +:101C200041F268031D4403EB44130344C5E9002655 +:101C300008330D4601F10C0C55F804EB43F804EBA6 +:101C40006545F9D184342D881D8000EB441407F0DC +:101C50000303257925F00B052B432371FFF768FF5C +:101C60000097334600F0E0FC0120A4E70224A5E73A +:101C70004FF0FF309FE7000013B500F5805401914D +:101C8000E06DFFF74BFE1F280AD90199E06D202275 +:101C9000FFF7BAFEA0F120035842584102B010BD30 +:101CA0000020FBE708B500F58050FFF73BFFC06D53 +:101CB000FFF708FEBDE80840FFF73ABF00220260C8 +:101CC000828142608260704710B500220023C0E923 +:101CD00000230023044603810C30FFF7EFFF20466A +:101CE00010BD0000F0B5054600F580500C4690F898 +:101CF000C83013F0040FC3F3800108BF114661F32D +:101D0000820304F1840680F8C83005EB461389B0DD +:101D10001B79D8072ED57AB319072DD46846FFF75B +:101D2000D3FF05EB441303F5835303F1180703AA0C +:101D3000103318685968144603C40833BB4222465E +:101D4000F7D1186820609B88A380DDE90E23CDE9D8 +:101D500000230123ADF808302B686946DB6B284669 +:101D6000984705EB46152B791A075CBF43F008032B +:101D70002B7101E0002AF4D109B0F0BD2DE9F04744 +:101D8000074688B007F5805468469A468846FFF7AC +:101D9000C9FE9146FFF798FFE06DFFF7A5FD1F28EC +:101DA00029D9E06D20226946FFF7B0FE202822D114 +:101DB00003AD444605AB2E4603CE9E4220606160D3 +:101DC000354604F10804F6D130682060B388A3805A +:101DD000DDE90023C9E90023BDF80830AAF8003086 +:101DE000FFF7A6FE4A4653464146384608B0BDE8CE +:101DF000F04700F007BCFFF79BFE002008B0BDE8ED +:101E0000F08700002DE9F84F0023C0E90133254B8E +:101E1000044640F8183B0F46FFF750FF04F1280036 +:101E2000FFF752FF04F1480804F58255464608358D +:101E300030462036FFF748FFAE42F9D104F5805511 +:101E40004FF480534FF00009C5E91339C5F84880B5 +:101E50000123EE6504F5875804F58456C5F85490BF +:101E600085F8583085F86030083608F108084FF0DA +:101E7000000A4FF0000B46E908ABA6F11800FFF787 +:101E80001DFF203646F8289C4645F4D185F8C970D8 +:101E900017B1054800F0A0FB044B63612046BDE884 +:101EA000F88F00BF3C4A0008144A00080064004054 +:101EB00010B5044B197804464A1C1A70FFF7A2FFAC +:101EC000204610BD143800202DE9F047002950D0DD +:101ED000294B2A4FB7FBF1F599428CBF0A231123F6 +:101EE000581EB5FBF3FC03FB1C53C4B22BB10228F4 +:101EF0000346F5D80020BDE8F0870CF1FF36B6F5B3 +:101F0000806FF7D2C4EBC40E0EF103034FEAE3096E +:101F1000C3F3C703A4EB030809F1010A4FF47A7570 +:101F20005FFA88F009FB05555AFA88F8B5FBF8F511 +:101F3000B5F5617FC1BF0EF1FF33C3F3C703E01AEC +:101F4000C0B25C1C50FA84F40CFB04F4B7FBF4F44C +:101F5000A142CFD1013BDBB20F2BCBD80138C0B2AD +:101F60000728C7D80021107116809170D370012006 +:101F7000C1E70846BFE700BF3F420F0000512502FE +:101F800070B505460E464FF47A746B695B6803F0D2 +:101F90000103B3424FF0010004D001F0A5FC013C65 +:101FA000F3D1204670BD000030B54269936913F04B +:101FB000700F16D000230B4C936103F1840200EBE9 +:101FC000421211794D0709D5890707D5416954F89F +:101FD00023508D60117941F0040111710133032BFD +:101FE000EBD130BD284A000873B51D46436916463B +:101FF0009A68D207044609D59A6801219960C2F30C +:102000004002CDE900650021FFF76CFE63699A6824 +:10201000D1050BD59A684FF480719960C2F34022C4 +:10202000CDE9006501212046FFF75CFE63699A68EF +:10203000D2030BD59A684FF480319960C2F34042C5 +:10204000CDE9006502212046FFF74CFE204602B094 +:10205000BDE87040FFF7A8BFF8B5044646690029FF +:102060006CD106F10C07386880076AD006EB0115C1 +:102070003868D5F8B00110F0040FD5F8B0011ABFD8 +:10208000C00840F00040400DA061D5F8B0C11CF080 +:10209000020F1CBF40F08040A061D5F8B40106EBF0 +:1020A000011100F00F0084F82400D1F8B801207766 +:1020B000D1F8B801000A6077D1F8B801000CA07718 +:1020C000D1F8B801000EE077D1F8BC0184F8200007 +:1020D000D1F8BC01000A84F82100D1F8BC01000C41 +:1020E00084F82200D1F8BC11090E84F8231038219D +:1020F000396004F1340004F1180104F1240551F8A9 +:10210000046B40F8046BA942F9D109880180C4E945 +:102110000A2321460023238651F8283B2046DB6B07 +:10212000984704F58052204692F8C83043F00403E3 +:1021300082F8C830BDE8F840FFF736BF06F1100757 +:1021400091E7F8BD10B5044600F04EFA02460B4682 +:1021500052EA030102D0013A63F10003044908681E +:1021600020B12146BDE81040FFF776BF10BD00BF8B +:1021700010380020F8B500F583511E46FFF7D2FC59 +:10218000DFF844C00831002404F1840500EB451554 +:102190002B795F070ED4DB060CD5D1E9007397428B +:1021A000B34107D243695CF824709F602B7943F0F8 +:1021B00004032B710134032C01F12001E4D1BDE8AB +:1021C000F840FFF7B5BC00BF284A000808B5FFF784 +:1021D000A9FCFFF7E9FEBDE80840FFF7A9BC000035 +:1021E000F8B543690546986800F0E050B0F1E05F4B +:1021F0000F461FD0E8B1FFF795FC05F58354103466 +:10220000002606F1840305EB43131B791A0706D554 +:102210000136032E04F12004F3D1012007E05B070F +:10222000F6D42146384600F039FA0028F0D1FFF7FD +:102230007FFCF8BD0120FCE700F5805008B5FFF7F2 +:1022400071FCC06DFFF750FBFFF772FC43090CBF38 +:102250000120002008BD0000F8B51D4600231370C2 +:102260000F4606461446FFF7E7FF80F0010038707E +:1022700025B129463046FFF7B3FF2070F8BD0000B6 +:102280002DE9B8410C4615461F46804600F0ACF9D2 +:102290000B462178024609B9287850B14046FFF72D +:1022A00069FFFFF793FF3B462A462146FFF7D4FF1D +:1022B0000120BDE8B881000010B5FFF733FC174BD3 +:1022C000DA6942F00072DA611A6942F000721A614A +:1022D0001A6900F5805422F000721A61FFF728FC99 +:1022E00094F8C830DB0718D4B9B103211320FFF7E5 +:1022F00019FC01F0C7F90321142001F0C3F90321EF +:10230000152001F0BFF994F8C83043F0010384F8B8 +:10231000C830BDE81040FFF70BBC10BD00100240F4 +:102320002DE9F04700F5805588B095F8C930012BAC +:102330000446884616467FD8804F57F823200AB9AE +:1023400047F82300D7F800A0C4F80C802674BAF12F +:10235000000F63D095F8C930012B6FD001212046C2 +:10236000FFF7AAFFFFF7DEFB6269136823F00203A1 +:1023700013606269136843F0010313606369002707 +:102380005F6101212046FFF7D3FBFFF7F9FD00282D +:1023900000F09580E86DFFF795FA04F58359BA4689 +:1023A00009F10809202200216846FEF7C7FF02A8AC +:1023B000FFF784FCCDF818A06A4609EB07030DF17E +:1023C000180E9446BCE80300F44518605960624654 +:1023D00003F10803F5D1DCF80000186020379CF801 +:1023E00004201A71602FDDD195F8C8306FF3820395 +:1023F000002785F8C8306A4641462046ADF800708F +:10240000ADF802708DF80470FFF75EFD636948BB9C +:102410004FF400421A6008B0BDE8F08741F2D000E6 +:1024200002F01CFA814610B15146FFF7EBFCC7F8E9 +:102430000090B9F1000F8DD10020ECE738680368F7 +:102440001B6B98470146002888D13868FFF734FF96 +:102450003868036832465B684146984700287FF435 +:102460007DAFE9E761221A609DF802309DF80320F4 +:102470001B06120402F4702203F040731343BDF8EC +:102480000020C2F3090213439DF804201205022E16 +:1024900002F4E0020CBF4FF00041002113436269D7 +:1024A0000B43D361636913225A616269136823F095 +:1024B0000103136039462046FFF762FD08B96369DE +:1024C000A6E795F8C93093BB6169D1F8002242F0C4 +:1024D0000102C1F800226169D1F8002222F47C5285 +:1024E00022F00E02C1F800226169D1F8002242F404 +:1024F0006062C1F800226269C2F814326269C2F8EF +:102500000432626941F6FF71C2F80C126269C2F8C6 +:1025100040326269C2F8443263690122C3F81C2266 +:102520006269D2F8003223F00103C2F8003295F854 +:10253000C83043F0020385F8C8306CE7103800203B +:1025400008B500F051F850EA0103024602D0421EDD +:1025500061F10001044B186810B10B46FFF744FD10 +:10256000BDE8084001F064B81038002008B500202C +:10257000FFF7E8FDBDE8084001F05AB808B50120B2 +:10258000FFF7E0FDBDE8084001F052B800B59BB090 +:10259000EFF3098168226846FEF7BEFEEFF305837C +:1025A000014B9B6BFEE700BF00ED00E008B5FFF7B5 +:1025B000EDFF000000B59BB0EFF30981682268468B +:1025C000FEF7AAFEEFF30583014B5B6BFEE700BF4E +:1025D00000ED00E0FEE700000FB408B5029801F03E +:1025E00019F9FEE701F02EBB01F004BB13B56C46F0 +:1025F00084E80600031D94E8030083E80500012039 +:1026000002B010BD73B58568019155B11B885B0799 +:1026100007D4D0E900369B6B9847019AC1B2304687 +:10262000A847012002B070BDF0B5866889B00546A4 +:102630000C465EB1BDF838305B070AD4D0E90037EC +:102640009B6B98472246C1B23846B047012009B07B +:10265000F0BD00220023CDE900230023ADF80830AF +:102660000A4603AB01F10806106851681C4603C412 +:102670000832B2422346F7D1106820609288A280C7 +:10268000FFF7B2FF0423ADF808302B68CDE9000155 +:10269000DB6B694628469847D8E7000030B50368E9 +:1026A0000968DD0FB5EBD17F23F0604421F0604273 +:1026B0004FEAD1700BD0002BB8BFA40C0029B8BFD3 +:1026C000920C944202D034BF0120002030BD9442CD +:1026D00005D1C1F38070C3F380738342F6D1944275 +:1026E0002CBF00200120F1E72DE9F041456A15B922 +:1026F0004162BDE8F0814B6823F06047C3F38A462E +:102700004FEAD37EC3F3807816EA230638BF3E46ED +:10271000AC462B465A68BEEBD27F22F060440AD00A +:10272000002A18DAA40CB44217D19D420FD10D60D3 +:10273000DEE71346EEE7A74207D102F08044C2F37A +:10274000807242450BD054B1EFE708D2EDE7CCF8E8 +:1027500000100B60CDE7B44201D0B442E5D81A684E +:102760009C46002AE5D11960C3E700002DE9F04737 +:10277000089D01F007044FEAD508224405F007053B +:1027800000EBD1004FF47F49944201D1BDE8F087BE +:1027900004F0070705F0070A57453E4638BF56467E +:1027A000C6F10806111B8E4228BF0E46E10808EB51 +:1027B000D50E415C13F80EC0B94029FA06F721FA8C +:1027C0000AF1FFB28CEA010147FA0AF739408CEAB4 +:1027D000010C03F80EC034443544D5E780EA0120EB +:1027E000082341F2210201B24000002980B203F126 +:1027F000FF33B8BF504013F0FF03F4D1704700001F +:1028000038B50C468D18A54200D138BD14F8011B0F +:10281000FFF7E4FFF7E7000042684AB1136843603E +:102820004389818901339BB29942438138BF8381B7 +:102830001046704770B588B0202204460D466846A1 +:102840000021FEF77BFD20460495FFF7E5FF0246D9 +:1028500058B16B46054608AE1C4603CCB44228600E +:102860006960234605F10805F6D1104608B070BD31 +:10287000082817D909280CD00A280CD00B280CD00E +:102880000C280CD00D280CD00E2814BF402030206E +:1028900070470C2070471020704714207047182094 +:1028A0007047202070470000082817D90C280CD941 +:1028B00010280CD914280CD918280CD920280CD988 +:1028C00030288CBF0F200E207047092070470A2047 +:1028D00070470B2070470C2070470D207047000098 +:1028E0002DE9F843078C072F04461ED9D0E902983A +:1028F00000254FF6FF73C5F12006A5F1200029FA47 +:1029000005F108FA06F628FA00F031430143C9B28E +:102910001846FFF763FF0835402D0346EBD1E16908 +:102920003A46BDE8F843FFF76BBF4FF6FF70BDE8CE +:10293000F883000010B54B6823B9CA8A63F3090213 +:10294000CA8210BD04691A681C600361C38A013B16 +:10295000C3824A60EFE700002DE9F84F1D46CB8A9D +:102960000F46C3F309010529814692460B4630D034 +:102970000020AAB207F11A049EB2042E1FFA80F8B2 +:102980000FD8904503F1010306D3FB8A0A4462F392 +:102990000903FB8201201AE01AF80060E6540130B6 +:1029A000EAE79045F1D2A1F1050B1C237C68BBFB43 +:1029B000F3F203FB12BB1FFA8BF6002C45D14846FD +:1029C000FFF72AFF044638B978606FF00200BDE8CF +:1029D000F88F4FF00008E6E7002606607860ADB299 +:1029E0004FF0000B454510D90AEB0803221D13F8E0 +:1029F000011B9155B1B208F101081B291FFA88F893 +:102A00002BD0454506F10106F1D8FB8AC3F3090234 +:102A1000154465F30903BCE7013292B21C462368F2 +:102A2000002BF9D16B1F0B441C21B3FBF1F30133D5 +:102A30009BB29A42D3D2BBF1000FD0D14846FFF7E8 +:102A4000EBFE20B9C4F800B0BFE70122E7E7C0F809 +:102A500000B05E4620600446C1E74545D5D94846EA +:102A6000FFF7DAFE08B92060AFE7C0F800B0002633 +:102A700020600446B6E700002DE9F04F2DED028BF3 +:102A80001C4683B05B69019207468846002B00F024 +:102A90009A80238C2BB1E269002A00F09480072BE6 +:102AA00035D807F10C00FFF7B7FE054638B96FF0CF +:102AB0000205284603B0BDEC028BBDE8F08F14225E +:102AC0000021FEF73BFC228CE16905F10800FEF7CE +:102AD00023FC208C013080B2FFF7E6FEFFF7C8FE32 +:102AE000013880B22084013028746369228C1B78FD +:102AF0002A4403F01F0363F03F0348F000411372C0 +:102B0000384669602946FFF7EFFD0125D1E700F15E +:102B10000C034FF0000908EE103A4FF0800A4E46C1 +:102B20004D4618EE100AFFF777FE83460028BED008 +:102B300014220021FEF702FC002E3AD1019BABF8D3 +:102B4000083002220BF1080E1FFA82FC0CF1010082 +:102B5000BCF1060F218C80B201D88E422BD3FFF737 +:102B6000A3FEFFF785FE62691278013802F01F02AA +:102B70008E4208BF4FF0400A42EA49121BFA80F128 +:102B80004AEA020A013048F0004281F808A08BF8B6 +:102B90001000CBF8042059463846FFF7A5FD238CDA +:102BA0000135B3422DB289F001094FF0000AB8D1C6 +:102BB0007FE70022C6E7E169895D0EF80210013661 +:102BC000B6B20132C0E76FF0010572E7F8B51546FD +:102BD0000E463022002104461F46FEF7AFFB069B3F +:102BE0006360B5F5001F079BA76034BF6A094FF605 +:102BF000FF72A36297B2E66104F1100000239A42CB +:102C000006D800230360A782E3822383E360F8BD34 +:102C10000660013330462036F1E7000003781BB927 +:102C20004BB2002BC8BF017070470000007870479E +:102C3000F8B50C46C969074611B9238C002B37D16A +:102C4000257E1F2D34D8387828BB228C072A2CD813 +:102C5000268A36F003032BD14FF6FF70FFF7D0FD25 +:102C600020F001003102400441EA0561400C41EAD4 +:102C700040254FF6FF72234629463846FFF7FCFEF3 +:102C8000002807DD626913780133DBB21F2B88BF90 +:102C900000231370F8BD218A2D0645EA012505435E +:102CA0002046FFF71DFE0246E5E76FF00300F1E75F +:102CB0006FF00100EEE7000070B58AB004461646DA +:102CC0000021282268461D46FEF738FBBDF8383043 +:102CD000ADF810300F9B05939DF840308DF81830FB +:102CE000119B07936946BDF84830ADF82030204667 +:102CF000CDE90265FFF79CFF0AB070BD2DE9F041F8 +:102D0000D36905460C4616460BB9138C5BBB377E60 +:102D10001F2F28D895F80080B8F1000F26D0304634 +:102D2000FFF7DEFD3378210241EAC33141EA0801B1 +:102D3000338A41EA076141EA03410246334641F0E2 +:102D400080012846FFF798FE00280ADD3378012B22 +:102D500007D1726913780133DBB21F2B88BF0023C0 +:102D60001370BDE8F0816FF00100FAE76FF0030027 +:102D7000F7E70000F0B58BB004460D46174600217A +:102D8000282268461E46FEF7D9FA9DF84C305A1E96 +:102D9000534253418DF800309DF84030ADF810306B +:102DA000119B05939DF848308DF81830149B0793BC +:102DB0006A46BDF85430ADF8203029462046CDE9AA +:102DC0000276FFF79BFF0BB0F0BD0000406A00B138 +:102DD00004307047436A1A68426202691A600361EC +:102DE000C38A013BC38270472DE9F041D0F82080AF +:102DF000194E14461D464146002709B9BDE8F08129 +:102E0000D1E90223A21A65EB0303964277EB030391 +:102E10001ED2036A8B420DD1FFF78CFD036A1B683B +:102E2000036203690B60C38A0161016A013BC382CB +:102E30008846E2E7FFF77EFD0B68C8F800300369BB +:102E40000B60C38A0161013BC382D8F80010D4E74C +:102E500088460968D1E700BF80841E002DE9F04F45 +:102E60008BB00D46DDF8509014469B4680460028F6 +:102E700000F01981B9F1000F00F01581531E3F2BAE +:102E800000F21181012A03D1BBF1000F40F00B8148 +:102E90000023CDE90833B8F81430B5EBC30F4FEA7F +:102EA000C30703D300200BB0BDE8F08F2B199F425E +:102EB000D8F80C303ABF7F1BFFB227461BB9D8F8B1 +:102EC0001030002B7AD0272D4ED8C5F12806B742F6 +:102ED0004FF000032CBFF6B23E4600932946D8F8C7 +:102EE000080008AB3246FFF741FCA7EB060A354461 +:102EF0005FFA8AFAB8F8143003F10053053BDB009F +:102F00000493D8F80C3003932821039B13B1BAF132 +:102F1000000F2CD1D8F8100040B1BAF1000F05D045 +:102F2000009608AB5246691AFFF720FC38B2002F12 +:102F3000B8D066070AD00AAB03EBD401624211F89D +:102F4000083C02F00702134101F8083C082C3CD968 +:102F5000102C40F2B580202C40F2B780BBF1000F5E +:102F600000F09C80082334E0BA460026C2E7049BA8 +:102F7000E02B28BFE02306930B44AB42059314D902 +:102F80005A1B03980096924534BF5246D2B2691A32 +:102F900008AB04300792FFF7E9FB079A1644AAEB47 +:102FA000020A1544F6B25FFA8AFA049B069A05995A +:102FB0009B1A0493039B1B680393A6E70093D8F81E +:102FC000080008AB3A462946AEE7BBF1000F13D024 +:102FD0000123B4EBC30F6CD0082C12D89DF820301D +:102FE000621E23FA02F2D50706D54FF0FF3202FA2D +:102FF00004F423438DF820309DF8203089F8003008 +:1030000051E7102C12D8BDF82030621E23FA02F2CC +:10301000D10706D54FF0FF3202FA04F42343ADF88E +:103020002030BDF82030A9F800303CE7202C0FD824 +:103030000899631E21FA03F3DA0705D54FF0FF3232 +:1030400002FA04F40C430894089BC9F800302AE7FC +:10305000402C2BD0DDE90865611EC4F12102A4F1EA +:10306000210326FA01F105FA02F225FA03F31143CE +:103070001943CB0712D50122A4F12003C4F120018A +:1030800002FA03F322FA01F1A240524243EA010399 +:1030900063EB430332432B43CDE90823DDE90823E7 +:1030A000C9E90023FFE66FF00100FCE66FF00800BD +:1030B000F9E6082CA0D9102CB3D9202CEED8C3E700 +:1030C000BBF1000FADD0022383E7BBF1000FBBD0F3 +:1030D00004237EE730B5012A144638BF0124402C72 +:1030E00085B028BF40240025012ACDE9025518D813 +:1030F0001B788DF8083063070AD004AB03EBD405C6 +:10310000624215F8083C02F00702934005F8083CBB +:10311000009103462246002102A8FFF727FB05B0D5 +:1031200030BD082AE4D9102A03D81B88ADF808302E +:10313000E1E7202A8DBFD3E900231B680293CDE984 +:103140000223D8E710B5CB681BB98B600B618B826B +:1031500010BD04691A681C600361C38A013BC38205 +:10316000CA60F0E703064CBFC0F3C03002207047CE +:1031700008B50246FFF7F6FF022806D15306C2F350 +:103180000F2001D100F0030008BDC2F30740FBE7A8 +:103190002DE9F04F93B0CDE903230A6804461046A9 +:1031A000FFF7E0FF022814BFC2F306260026002A1C +:1031B0000D46824680F2F28112F0C04940F0EE8165 +:1031C000097B002900F0EA81022803D02378B3426A +:1031D00040F0E781C2F304630693104602F07F03D8 +:1031E0000593FFF7C5FF059B29444FEA834848EA4A +:1031F0000A4848EA4668CE7800230022CDE9082331 +:10320000F309834648EA0008029367D0059B0093C0 +:1032100002466768534608A92046B847002800F0D0 +:10322000C381276A4FB9414604F10C00FFF702FB46 +:10323000074690B96FF0020054E03B6998450DD005 +:103240003F68002FF9D1414604F10C00FFF7F2FA74 +:1032500007460028EED0236A3B60276297F817C024 +:1032600006F01F08CCF3840CACEB08001FFA80FEBC +:103270000028B8BF0EF12000A8EB0C031FFA83FE54 +:10328000D7E90221B8BF00B2002B0793BEBF0EF1F1 +:1032900020031BB2079352EA010338D0039BDFF8E7 +:1032A00024E39A1A049B4FF0000C63EB010196454E +:1032B0007CEB01032BD36B7B97F81AE0734519D194 +:1032C000029B002B78D0012821DC7868F8B9DFF860 +:1032D000F0C2944570EB010316D337E0276A27B993 +:1032E0006FF00C0013B0BDE8F08F3B699845B5D086 +:1032F0003F68F4E7B24890427CEB010301D3002021 +:10330000F0E7029B002BFAD0079B0F2B17DCFA7D0E +:10331000B30002F0030203F07C031343FB7539464C +:103320002046FFF707FB6B7BBB76029B3BB9FB7D1F +:10333000C3F38402013262F38603FB75D0E76A7B34 +:10334000BB7E9A42DBD1029B002B35D0B309022B06 +:1033500032D0039BBB60049BFB60142200210DA8AC +:10336000FDF7ECFF039B0A93049B0B932B1D0C931F +:103370002B7BADF83EB0013BDBB2ADF83C30069B99 +:103380008DF84230059B8DF8433094F82C308DF841 +:1033900040A083F001038DF844308DF84180A3688C +:1033A0000AA920469847FB7DC3F38403013303F049 +:1033B0001F039B02FB82A2E7FB7DC6F34012B2EB28 +:1033C000D31F40F0F480C3F38403434540F0F28000 +:1033D000029A2B7BB609002A4DD0F2075DD4032B4D +:1033E00040F2EB80039BBB60049BFB602B7BAE1D1C +:1033F000033BDBB23246394604F10C00FFF7ACFA6E +:1034000000280CDA39462046FFF794FAFB7DC3F317 +:103410008403013303F01F039B02FB820AE7DDE90B +:103420000884AB883B834FF6FF73C9F12000A9F1F4 +:10343000200228FA09F104FA00F0014324FA02F20A +:1034400011431846C9B2FFF7C9F909F10809B9F1E2 +:10345000400F0346E9D1B8822A7B033AD2B2314603 +:10346000FFF7CEF9FB7DB882DA43C2F3C01262F3F4 +:10347000C713FB7543E786B92E1D013BDBB232460D +:10348000394604F10C00FFF767FA0028BADB2A7B03 +:10349000B88A013AD2B23146E2E7F98AC1F30901AA +:1034A000013B0429DAB25BD8281D002307F11B0673 +:1034B0009A4208D910F801CB06F801C00131013356 +:1034C0000529DBB2F4D103990A9104990B91934237 +:1034D00007F11B010C9138BF043379680D9134BF9B +:1034E00055FA83F300230E93FB8AADF83EB0C3F385 +:1034F00009031A44069B8DF84230059B8DF8433032 +:1035000094F82C30ADF83C2083F001038DF8443062 +:1035100000238DF840A08DF841807B602A7BB88A1B +:10352000013A291DFFF76CF93B8BB882834203D126 +:10353000A3680AA92046984720460AA9FFF702FE79 +:10354000FB7DBA8AC3F38403013303F01F039B029C +:10355000FB823B8B9A420CBF00206FF01000C1E64B +:103560007B68002BAFD0052001E01C3033461E687D +:10357000002EFAD1091A081D2E1D184401EB090C62 +:10358000BCF11B0F5FFA89F39DD89A429BD916F8BC +:10359000013B00F8013B09F10109EFE76FF0090079 +:1035A000A0E66FF00A009DE66FF00B009AE66FF060 +:1035B0000D0097E66FF00E0094E66FF00F0091E6B5 +:1035C00040420F0080841E00EFF3098305494A6BD7 +:1035D00022F001024A63683383F30988002383F3EE +:1035E0001188704700EF00E0302080F3118862B648 +:1035F0000C4B0D4AD96821F4E0610904090C0A4317 +:10360000DA60D3F8FC20094942F08072C3F8FC204C +:103610000A6842F001020A602022DA7783F8220069 +:10362000704700BF00ED00E00003FA05001000E065 +:1036300010B5302383F311880E4B5B6813F40063DD +:1036400014D0F1EE103AEFF30984683C4FF0807328 +:10365000E361094BDB6B236684F3098800F098F87B +:1036600010B1064BA36110BD054BFBE783F3118836 +:10367000F9E700BF00ED00E000EF00E003060008FE +:103680000606000800F1604303F561430901C9B271 +:1036900083F80013012200F01F039A4043099B00A6 +:1036A00003F1604303F56143C3F880211A6070475A +:1036B00000F16040090100F56D40C9B20176704724 +:1036C00000230375826803691B6899689142FBD2E5 +:1036D0005A680360426010605860704700230375A9 +:1036E000826803691B6899689142FBD85A68036035 +:1036F000426010605860704708B50846302383F375 +:1037000011880B7D032B05D0042B0DD02BB983F32F +:10371000118808BD8B6900221A604FF0FF33836166 +:10372000FFF7CEFF0023F2E7D1E9003213605A60C1 +:10373000F3E70000FFF7C4BF054BD96808751868A8 +:1037400002681A60536001220275D860FCF744BF1A +:103750002038002030B50C4BDD684B1C87B0044688 +:103760000FD02B46094A684600F0FEF82046FFF7C6 +:10377000E3FF009B13B1684600F000F9A86907B0A9 +:1037800030BDFFF7D9FFF9E720380020F9360008EF +:10379000044B1A68DB6890689B68984294BF0020CD +:1037A0000120704720380020084B10B51C68D868ED +:1037B00022681A60536001222275DC60FFF78EFFD9 +:1037C00001462046BDE81040FCF706BF2038002027 +:1037D000044B1A68DB6892689B689A4201D9FFF72C +:1037E000E3BF70472038002038B5074C0749084828 +:1037F000012300252370656000F00AFB022323707B +:1038000085F3118838BD00BF483A0020804A00087F +:103810002038002008B572B6044B186500F0CEF9C8 +:1038200000F092FA024B03221A70FEE720380020C3 +:10383000483A002000F0B4B8EFF3118020B9EFF35C +:103840000583302282F311887047000010B530B92B +:10385000EFF30584C4F3080414B180F3118810BD9C +:10386000FFF7B6FF84F31188F9E700008B600223AD +:1038700008618B82084670478368A3F1840243F88D +:10388000142C026943F8442C426943F8402C094A3D +:1038900043F8242CC26843F8182C022203F80C2C9D +:1038A000002203F80B2C044A43F8102CA3F120004B +:1038B000704700BFF10500082038002008B5FFF769 +:1038C000DBFFBDE80840FFF735BF0000024BDB68B7 +:1038D00098610F20FFF730BF20380020302383F39A +:1038E0001188FFF7F3BF000008B50146302383F3CA +:1038F00011880820FFF72EFF002383F3118808BDED +:10390000064BDB6839B1426818605A601360436047 +:103910000420FFF71FBF4FF0FF3070472038002012 +:103920000368984206D01A68026050609961184690 +:10393000FFF700BF7047000010B50A4C23699A6872 +:1039400091420CD85A6881600360426010609A68A6 +:103950005860511A99604FF0FF33A36110BD1B6886 +:10396000891AECE72038002010B4C0E903230023B3 +:103970005DF8044B4361FFF7DFBF00000368816817 +:103980009A680A449A60426813605A600023036090 +:10399000024B4FF0FF329A61704700BF2038002081 +:1039A00070B5124DEB692A460133EB6152F8103FB6 +:1039B000934206D09A68013A9A6030262C69A3682F +:1039C00003B170BDD4E900210A605160236083F324 +:1039D0001188D4E903312046984786F3118861693C +:1039E0000029EBD02046FFF7A7FFE7E720380020AB +:1039F00000207047FEE70000704700004FF0FF30E6 +:103A000070470000BFF34F8F024AD368DB07FCD436 +:103A1000704700BF0020024008B5074B1B7853B920 +:103A2000FFF7F0FF054B1A69120641BF044A5A60BE +:103A300002F188325A6008BD603A0020002002403E +:103A40002301674508B5054B1B7833B9FFF7DAFF4B +:103A5000034A136943F08003136108BD603A0020F4 +:103A6000002002407F289ABF00F58030C00200206D +:103A7000704700004FF400607047000080207047DE +:103A80007F2808B50BD8FFF7EDFF00F5006302684B +:103A9000013204D104308342F9D1012008BD002055 +:103AA000FCE700007F2810B504461CD8FFF7AAFFEA +:103AB000FFF7B2FF0D4BF322DA6002221A61FFF723 +:103AC000D1FF58611A6942F040021A614FF4006157 +:103AD000FFF798FF00F034F9FFF7B4FF2046BDE888 +:103AE0001040FFF7CDBF002010BD00BF00200240F6 +:103AF0002DE9F84312F00103144606D01F4B40F2A3 +:103B0000F3221A600020BDE8F88385181C4A95420C +:103B100004D91A4A4FF43E711160F3E7FFF77CFFB6 +:103B2000FFF770FFDFF86880451A4FF00109012C9C +:103B300005EB01060F4603D8FFF784FF0120E2E7FB +:103B40003B88C8F8109033800020FFF75BFFC8F86F +:103B50001000338831F8022B9BB29A420CD0074BED +:103B600040F20F321A60074B1E60074B1C60074B78 +:103B70001F60FFF767FFC6E7023CD8E75C3A00200A +:103B800000000408503A0020583A0020543A00201F +:103B900000200240084908B50B7828B11BB9FFF78F +:103BA0003BFF01230B7008BD002BFCD0BDE8084093 +:103BB0000870FFF747BF00BF603A002008B54FF418 +:103BC00020414FF0005000F0BDF8BDE808404FF430 +:103BD00000514FF0805000F0B5B800000846114683 +:103BE00000F05EBE012000F05BBE0000084600F061 +:103BF00075BE000030B583B0FFF71EFE0E4B0F4DB3 +:103C0000DB692A684FF47A7101FB03F3934237BFF3 +:103C10000B4A0B49516814682B602EBFD1E9004153 +:103C2000013151601C1941F100010191FFF70EFEB5 +:103C30000199204603B030BD20380020643A0020AE +:103C4000683A002030B583B0FFF7F6FD114B124DF6 +:103C5000DB692A684FF47A7101FB03F3934237BFA3 +:103C60000E4A0E49516814682B602EBFD1E90041FD +:103C7000013151601C1941F100010191FFF7E6FD8E +:103C800001994FF47A7200232046FCF791FA03B0B1 +:103C900030BD00BF20380020643A0020683A002080 +:103CA00010B50244064BD2B2904200D110BD441C64 +:103CB00000B253F8200041F8040BE0B2F4E700BF73 +:103CC000502800400F4B30B51C6A240407D41C6AEE +:103CD00044F440741C621C6A44F400441C620A4CA4 +:103CE000236843F4807323600244084BD2B29042AD +:103CF00000D130BD441C00B251F8045B43F82050A1 +:103D0000E0B2F4E70010024000700040502800408C +:103D100007B5012201A90020FFF7C2FF019803B0F7 +:103D20005DF804FB13B50446FFF7F2FFA04205D08F +:103D3000012201A900200194FFF7C4FF02B010BDC9 +:103D4000704700007047000070470000074B45F2C5 +:103D500055521A6002225A6040F6FF729A604CF681 +:103D6000CC421A60024B01221A70704700300040AA +:103D7000743A0020034B1B781BB1034B4AF6AA226E +:103D80001A607047743A002000300040044B1A68F3 +:103D90002AB902F1804202F50432526A1A60704771 +:103DA000703A0020024B4FF080725A62704700BF99 +:103DB0000010024008B5FFF7E9FF024B1868C0F396 +:103DC000407008BD703A002070470000FEE7000018 +:103DD0000A4B0B480B4A90420BD30B4BDA1C121ABE +:103DE000C11E22F003028B4238BF00220021FDF7E2 +:103DF000A5BA53F8041B40F8041BECE7EC4B000891 +:103E0000583C0020583C0020583C0020FEE70000B1 +:103E100070B51B4B01630025044686B0586085626F +:103E20000E46FFF7E1FB04F11003C4E904334FF041 +:103E3000FF33A361134BE561D969A5600A462B46A0 +:103E4000C4E9082304F13401C4E900440E4AE562E0 +:103E5000256580232046FFF709FD0123E0600B4A1A +:103E60000375009272680192B268CDE90223084B93 +:103E70006846CDE90435FFF721FD06B070BD00BFEF +:103E8000483A0020203800208C4A0008914A000857 +:103E90000D3E00084B6843608B688360CB68C3604D +:103EA0000B6943614B6903628B6943620B68036072 +:103EB0007047000008B51B4B9A6A42F4FC029A62F4 +:103EC0009A6A22F4FC029A629A6A5A6942F4FC02E3 +:103ED0005A61154A5B6911464FF09040FFF7DAFFCF +:103EE00002F11C0100F58060FFF7D4FF02F13801F8 +:103EF00000F58060FFF7CEFF02F1540100F580600D +:103F0000FFF7C8FF02F1700100F58060FFF7C2FF04 +:103F100002F18C0100F58060FFF7BCFFBDE80840AE +:103F200000F05AB800100240984A000808B500F0A6 +:103F300093F9FFF759FCBDE80840FFF727BF0000E1 +:103F40007047000010B5214CA36A63F4FC03A36220 +:103F5000A36A03F4FC03A3624FF0FF32A36A236950 +:103F600022612369002323612169E168E260E2683C +:103F7000E360E268E269164942F08052E261E26978 +:103F80000A6842F480720A60226A02F44072B2F552 +:103F9000407F1EBF4FF4803222622362236A1B04DB +:103FA00007D4236A43F440732362236A43F4004333 +:103FB000236200F031F9A369064A43F00103A361CB +:103FC000A369136843F02003136010BD0010024082 +:103FD00000700040000001401E4B1A6842F00102D0 +:103FE0001A601A689007FCD55A6822F003025A60DA +:103FF0005A6812F00C02FBD1196801F0F90119603E +:104000005A601A6842F480321A601A689103FCD52B +:10401000114A5A604FF40452DA6230221A631A6865 +:1040200042F080721A601A689201FCD50B49122284 +:104030000A600A6802F00702022AFAD15A6842F0BE +:1040400002025A605A6802F00C02082AFAD11A6B6E +:104050001A6370470010024000241D000020024037 +:10406000084A08B5516913680B4003F00103536116 +:1040700023B1054A13680BB150689847BDE8084062 +:10408000FFF7D6BA00040140783A0020084A08B584 +:10409000516913680B4003F00203536123B1054AD1 +:1040A00093680BB1D0689847BDE80840FFF7C0BAE5 +:1040B00000040140783A0020084A08B551691368A5 +:1040C0000B4003F00403536123B1054A13690BB19C +:1040D00050699847BDE80840FFF7AABA00040140BC +:1040E000783A0020084A08B5516913680B4003F07C +:1040F0000803536123B1054A93690BB1D06998470E +:10410000BDE80840FFF794BA00040140783A002067 +:10411000084A08B5516913680B4003F01003536156 +:1041200023B1054A136A0BB1506A9847BDE80840AD +:10413000FFF77EBA00040140783A0020174B10B513 +:104140005A691C68144004F478725A61A30604D5B5 +:10415000134A936A0BB1D06A9847600604D5104A97 +:10416000136B0BB1506B9847210604D50C4A936B27 +:104170000BB1D06B9847E20504D5094A136C0BB11B +:10418000506C9847A30504D5054A936C0BB1D06CCD +:104190009847BDE81040FFF74BBA00BF000401404C +:1041A000783A00201A4B10B55A691C68144004F480 +:1041B0007C425A61620504D5164A136D0BB1506DED +:1041C0009847230504D5134A936D0BB1D06D9847DA +:1041D000E00404D50F4A136E0BB1506E9847A1044A +:1041E00004D50C4A936E0BB1D06E9847620404D587 +:1041F000084A136F0BB1506F9847230404D5054A42 +:10420000936F0BB1D06F9847BDE81040FFF710BA1D +:1042100000040140783A0020062108B50846FFF75F +:1042200031FA06210720FFF72DFA06210820FFF7B3 +:1042300029FA06210920FFF725FA06210A20FFF7AF +:1042400021FA06211720FFF71DFABDE808400621D4 +:104250002820FFF717BA000008B5FFF773FE00F03B +:1042600067F800F03DF8FFF76BFEBDE8084000F08E +:104270005DB80000026843681143016003B118474C +:1042800070470000143000F02FBA00004FF0FF33E9 +:10429000143000F029BA0000383000F0A5BA000050 +:1042A0004FF0FF33383000F09FBA0000143000F0B8 +:1042B000F5B900004FF0FF31143000F0EFB9000005 +:1042C000383000F04FBA00004FF0FF32383000F0C5 +:1042D00049BA0000012914BF6FF013000020704795 +:1042E00000F06CB8044B03600023C0E90233436064 +:1042F00001230374704700BF404B000838B5C36901 +:1043000004460D461BB904210844FFF7B3FF2946B4 +:1043100004F1140000F0A6F9002806DA201D4FF47D +:104320000061BDE83840FFF7A5BF38BD00F00EB80A +:104330000023054A19460133102BC2E9001102F18E +:104340000802F8D1704700BF783A00204FF0E02310 +:10435000044A5A6100229A6107221A6108210B203F +:10436000FFF7A6B93F19010008B5302383F3118880 +:10437000FFF760FA002383F3118808BD08B5FFF743 +:10438000F3FFBDE80840FFF753B900000268436837 +:104390001143016003B1184770470000024A1368D7 +:1043A00043F0C0031360704700380140024A1368AD +:1043B00043F0C003136070470044004037B51D4C04 +:1043C0001D4D2046FFF78EFF009404F114001B4999 +:1043D0000023202200F038F92022009404F1380054 +:1043E000174B184900F0B2F9174BC4E91735174CB1 +:1043F0000C212520FFF746F92046FFF773FF04F153 +:104400001400134900940023202200F01DF904F148 +:104410003800104B10490094202200F097F90F4B00 +:104420000C212620C4E9173503B0BDE83040FFF762 +:1044300029B900BFF83A002000512502D03B0020E6 +:104440009D430008103C002000380140643B0020E0 +:10445000F03B0020AD430008303C00200044004009 +:104460002DE9F047C66D3768F469346221070546C7 +:1044700019D014F0080118BF4FF48071E20748BF4B +:1044800041F02001A30748BF41F04001600748BF49 +:1044900041F08001302383F31188281DFFF776FF58 +:1044A000002383F31188E2050AD5302383F31188B2 +:1044B0004FF48061281DFFF769FF002383F3118803 +:1044C0004FF030094FF0000A14F0200838D13B06B5 +:1044D00016D54FF0300905F1380A200610D589F3BA +:1044E0001188504600F066F9002836DA0821281DA8 +:1044F000FFF74CFF27F080033360002383F311881C +:10450000790614D5620612D5302383F31188D5E9D4 +:1045100013239A4208D12B6C33B11021281D27F0A8 +:104520004007FFF733FF3760002383F31188E3066A +:1045300019D5AA6E1369B3B1BDE8F04750691847A1 +:1045400089F31188B38C95F8641028461940FFF759 +:10455000D5FE8AF31188F469B6E780B2308588F316 +:104560001188F469B9E7BDE8F087000008B5034891 +:10457000FFF776FFBDE80840FFF75AB8F83A002089 +:1045800008B50348FFF76CFFBDE80840FFF750B8D7 +:10459000643B0020F8B5154682680669AA420B46BE +:1045A000816938BF8568761AB54204460BD2184631 +:1045B0002A46FCF7B1FEA3692B44A361A3685B1BE9 +:1045C000A3602846F8BD0CD918463246FCF7A4FE75 +:1045D000AF1BE1683A463044FCF79EFEE3683B447B +:1045E000EBE718462A46FCF797FEE368E5E700008C +:1045F00083689342F7B51546044638BF8568D0E90D +:104600000460361AB5420BD22A46FCF785FE636970 +:104610002B446361A36828465B1BA36003B0F0BD15 +:104620000DD932460191FCF777FE0199E068AF1B86 +:104630003A463144FCF770FEE3683B44E9E72A461A +:10464000FCF76AFEE368E4E710B50A440024C3619E +:10465000029B8460C0E90000C0E90511C1600261ED +:10466000036210BD08B5D0E90532934201D18268DA +:1046700082B98268013282605A1C42611970D0E9A5 +:1046800004329A4224BFC36843610021FFF748F90E +:10469000002008BD4FF0FF30FBE7000070B530236D +:1046A00004460E4683F31188A568A5B1A368A269E4 +:1046B000013BA360531CA36115782269934224BF78 +:1046C000E368A361E3690BB120469847002383F3B5 +:1046D0001188284607E031462046FFF711F90028E7 +:1046E000E2DA85F3118870BD2DE9F74F04460E46D6 +:1046F00017469846D0F81C904FF0300A8AF311887C +:104700004FF0000B154665B12A4631462046FFF7AB +:1047100041FF034660B941462046FFF7F1F8002803 +:10472000F1D0002383F31188781B03B0BDE8F08F2C +:10473000B9F1000F03D001902046C847019B8BF3CD +:104740001188ED1A1E448AF31188DCE7C0E90511CF +:10475000C160C3611144009B8260C0E90000016137 +:1047600003627047F8B504460D461646302383F3BE +:104770001188A768A7B1A368013BA36063695A1CAD +:1047800062611D70D4E904329A4224BFE368636118 +:10479000E3690BB120469847002080F3118807E0B9 +:1047A00031462046FFF7ACF80028E2DA87F311889B +:1047B000F8BD0000D0E905239A4210B501D1826806 +:1047C0007AB98268013282605A1C82611C7803695E +:1047D0009A4224BFC36883610021FFF7A1F82046F5 +:1047E00010BD4FF0FF30FBE72DE9F74F04460E46B2 +:1047F00017469846D0F81C904FF0300A8AF311887B +:104800004FF0000B154665B12A4631462046FFF7AA +:10481000EFFE034660B941462046FFF771F80028D5 +:10482000F1D0002383F31188781B03B0BDE8F08F2B +:10483000B9F1000F03D001902046C847019B8BF3CC +:104840001188ED1A1E448AF31188DCE70B460146F5 +:10485000184600F02DB8000000F040B8012838BF1D +:10486000012010B50446204600F030F830B900F0C1 +:1048700007F808B900F00CF88047F4E710BD000015 +:10488000024B1868BFF35B8F704700BF503C00209D +:1048900008B5062000F084F80120FFF7ABF800000F +:1048A000024B0A4601461868FFF798B91811002014 +:1048B00010B5054C13462CB10A4601460220AFF351 +:1048C000008010BD2046FCE700000000024B0146BE +:1048D0001868FFF787B900BF18110020024B014686 +:1048E0001868FFF783B900BF1811002010B501390F +:1048F0000244904201D1002005E0037811F8014FF5 +:10490000A34201D0181B10BD0130F2E72DE9F041A0 +:10491000A3B1C91A17780144044603F1FF3C8C4245 +:10492000204601D9002009E00578BD4204F10104C8 +:10493000F5D10CEB0405D618A54201D1BDE8F081F4 +:1049400015F8018D16F801EDF045F5D0E7E7000008 +:104950001F2938B504460D4604D9162303604FF0CD +:10496000FF3038BD426C12B152F821304BB92046AD +:1049700000F030F82A4601462046BDE8384000F0F5 +:1049800017B8012B0AD0591C03D11623036001204C +:10499000E7E7002442F82540284698470020E0E752 +:1049A000024B01461868FFF7D3BF00BF1811002063 +:1049B00038B5074D00230446084611462B60FFF723 +:1049C0001DF8431C02D12B6803B1236038BD00BF22 +:1049D000543C0020FFF70CB8034611F8012B03F8F4 +:1049E000012B002AF9D170476F72672E61726475CE +:1049F00070696C6F742E663330332D47505300004E +:104A000040A2E4F1646891060041A3E5F265699271 +:104A1000070000004261642043414E4966616365BE +:104A200020696E6465782E00800000000080000020 +:104A30000000800000000000000000003D1B000896 +:104A400021230008812200084D1B0008811B00085B +:104A50007D1D0008511B0008611B0008551B000844 +:104A60005D1B0008591B0008A51C0008651B0008F9 +:104A7000ED250008751B0008791C00086330000054 +:104A80007C4A000878380020483A00206D61696E41 +:104A90000069646C65000000A001A82A0000000005 +:104AA000FAAABEAA50001424EFFF0000007700000D +:104AB000709709000100000000000000AAAAAAAA3D +:104AC00001000000FFFF00000000000000000000E7 +:104AD0000000000000000000AAAAAAAA000000002E +:104AE000FFFF0000000000000000000000000000C8 +:104AF00000000000AAAAAAAA00000000FFFF000010 +:104B000000000000000000000000000000000000A5 +:104B1000AAAAAAAA00000000FFFF000000000000EF +:104B2000000000000000000000000000AAAAAAAADD +:104B300000000000FFFF0000000000000000000077 +:104B400000000000A14200088D420008C942000890 +:104B5000B5420008C1420008AD4200089942000871 +:104B600085420008D542000878B6FF7F01000000AA +:104B7000EC030000000000000098030000000000AB +:104B8000FE2A0100D20400001C11002000000000D9 +:104B90000000000000000000000000000000000015 +:104BA0000000000000000000000000000000000005 +:104BB00000000000000000000000000000000000F5 +:104BC00000000000000000000000000000000000E5 +:104BD00000000000000000000000000000000000D5 +:0C4BE000000000000000000000000000C9 :00000001FF diff --git a/Tools/bootloaders/f303-HWESC_bl.bin b/Tools/bootloaders/f303-HWESC_bl.bin index b03410ae096640..39b8393e352121 100755 Binary files a/Tools/bootloaders/f303-HWESC_bl.bin and b/Tools/bootloaders/f303-HWESC_bl.bin differ diff --git a/Tools/bootloaders/f303-HWESC_bl.hex b/Tools/bootloaders/f303-HWESC_bl.hex index 9b0eeda49891ca..e35db883a3e8dc 100644 --- a/Tools/bootloaders/f303-HWESC_bl.hex +++ b/Tools/bootloaders/f303-HWESC_bl.hex @@ -1,980 +1,1217 @@ :020000040800F2 -:1000000000090020A5040008E1140008611400089C -:10001000B9140008611400088D140008A704000832 -:10002000A7040008A7040008A704000881350008F9 -:10003000A7040008A7040008A7040008B93A0008AC -:10004000A7040008A7040008A7040008A7040008E4 -:10005000A7040008A7040008513800087D380008EC -:10006000A9380008D538000801390008A70400089D -:10007000A7040008A7040008A7040008A7040008B4 -:10008000A7040008A7040008A70400082924000802 -:1000900095240008E92400083D2500082D390008B2 -:1000A000A7040008A7040008A7040008A704000884 -:1000B000A7040008A7040008A7040008A704000874 -:1000C000A7040008A7040008A7040008A704000864 -:1000D000A70400088129000895290008A704000842 -:1000E00095390008A7040008A7040008A704000821 -:1000F000A7040008A7040008A7040008A704000834 -:10010000A7040008A7040008A7040008A704000823 -:10011000A7040008A7040008A7040008A704000813 -:10012000A7040008A7040008A7040008A704000803 -:10013000A7040008A7040008A7040008A7040008F3 -:10014000A7040008A7040008A7040008A7040008E3 -:10015000A7040008A7040008A7040008A7040008D3 -:10016000A7040008A7040008A7040008A7040008C3 -:10017000A7040008A7040008A7040008A7040008B3 -:10018000A7040008A7040008A7040008A7040008A3 -:10019000A7040008A7040008A7040008A704000893 -:1001A00053B94AB9002908BF00281CBF4FF0FF31DE -:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA -:1001C00000F006F8DDF804E0DDE9022304B0704732 -:1001D0002DE9F047089D04468E46002B4DD18A42FA -:1001E000944669D9B2FA82F252B101FA02F3C2F12D -:1001F000200120FA01F10CFA02FC41EA030E9440BE -:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE -:1002100016E341EA034306FB07F199420AD91CEBB6 -:10022000030306F1FF3080F01F81994240F21C81E8 -:10023000023E63445B1AA4B2B3FBF8F008FB103330 -:1002400044EA034400FB07F7A7420AD91CEB040465 -:1002500000F1FF3380F00A81A74240F20781644435 -:10026000023840EA0640E41B00261DB1D4400023BA -:10027000C5E900433146BDE8F0878B4209D9002D1E -:1002800000F0EF800026C5E9000130463146BDE8A8 -:10029000F087B3FA83F6002E4AD18B4202D3824212 -:1002A00000F2F980841A61EB030301209E46002DC1 -:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 -:1002C000002A40F09280A1EB0C014FEA1C471FFA74 -:1002D0008CFE0126200CB1FBF7F307FB131140EA5B -:1002E00001410EFB03F0884208D91CEB010103F128 -:1002F000FF3802D2884200F2CB804346091AA4B2EA -:10030000B1FBF7F007FB101144EA01440EFB00FEBD -:10031000A64508D91CEB040400F1FF3102D2A64522 -:1003200000F2BB800846A4EB0E0440EA03409CE7C1 -:10033000C6F12007B34022FA07FC4CEA030C20FA6E -:1003400007F401FA06F31C43F9404FEA1C4900FA8E -:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B -:1003600040EA014108FB0EF0884202FA06F20BD97E -:100370001CEB010108F1FF3A80F08880884240F2CE -:100380008580A8F102086144091AA4B2B1FBF9F012 -:1003900009FB101144EA014100FB0EFE8E4508D90D -:1003A0001CEB010100F1FF346CD28E456AD9023892 -:1003B000614440EA0840A0FB0294A1EB0E01A14277 -:1003C000C846A64656D353D05DB1B3EB080261EBE5 -:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF -:1003E000007100263146BDE8F087C2F12003D840F5 -:1003F0000CFA02FC21FA03F3914001434FEA1C4737 -:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 -:10041000064300FB0EF69E4204FA02F408D91CEBD8 -:10042000030300F1FF382FD29E422DD902386344D6 -:100430009B1B89B2B3FBF7F607FB163341EA034176 -:1004400006FB0EF38B4208D91CEB010106F1FF38C5 -:1004500016D28B4214D9023E6144C91A46EA0046BC -:1004600038E72E46284605E70646E3E61846F8E64E -:100470004B45A9D2B9EB020864EB0C0E0138A3E797 -:100480004646EAE7204694E74046D1E7D0467BE778 -:10049000023B614432E7304609E76444023842E7F0 -:1004A000704700BF02E000F000F8FEE772B63A487D -:1004B00080F30888394880F3098839484EF6085196 -:1004C000CEF20001086040F20000CCF200004EF6CF -:1004D0003471CEF200010860BFF34F8FBFF36F8F0E -:1004E00040F20000C0F2F0004EF68851CEF200015A -:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 -:10050000100A4EF63C71CEF200010860062080F31E -:100510001488BFF36F8F03F0B3F803F08FF803F084 -:10052000C1F84FF055301F491B4A91423CBF41F87A -:10053000040BFAE71C49194A91423CBF41F8040BED -:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C -:1005500042F8040BF8E700201749184A91423CBFC3 -:1005600041F8040BFAE703F06DF803F0D7F8144CE8 -:10057000144DAC4203DA54F8041B8847F9E700F045 -:1005800041F8114C114DAC4203DA54F8041B884772 -:10059000F9E703F055B80000000900200011002021 -:1005A000000000080001002000090020F83C0008BD -:1005B00000110020201100202011002028260020FA -:1005C000A0010008A0010008A0010008A001000887 -:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F -:1005E000BDEC108ABDE8F08F002383F31188284604 -:1005F000A047002002F04CFDFEE702F0D1FC00DF36 -:10060000FEE700002DE9F04102F062FF074602F02C -:10061000ADFF054600283ED12B4B9F423BD0013316 -:100620009F423BD0294B27F0FF029A423AD1F8B2C1 -:1006300000F054FAA84642F2107400F059FC08B1D8 -:100640000024A04600F050FA064678B384BB464624 -:1006500035B11F4B9F4203D002F080FF0024264695 -:10066000002002F03FFF1B4B1B6913F0400322D018 -:100670000EB100F031F800F05FFC00F031FE00F048 -:1006800031FF0546CCB100F02DFF401BA04214D92C -:1006900000F022F8F3E7A8460024CEE704464FF026 -:1006A0000108CAE780464FF47A74C6E70446CFE7EC -:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 -:1006C00002F0ECFCDEE700BF010007B0000008B05C -:1006D000263A09B00004004838B51D4A1D4B196878 -:1006E000013134D004339342F9D11B4C194DD4F865 -:1006F0000428AA422BD3194B9B6803F1006303F52E -:10070000D0439A4223D202F0FDFE02F00FFF0020F8 -:1007100000F000FE124B0220187000F037FE114B63 -:10072000DA690022DA61D96999699A619B6972B6BE -:100730004FF0E0232021C3F8085DD4F80038D4F846 -:10074000042881F311889D4683F30888104738BD3B -:100750002068000800680008006000080011002000 -:100760002011002000100240094A136849F2690074 -:1007700099B21B0C00FB01331360064B186844F25E -:10078000506182B2000C01FB0200186080B2704719 -:100790001C1100201811002010B500211022044661 -:1007A00000F00EFE034B03CB206061601868A06070 -:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 -:1007C00000F090FEAB6840F2ED22C31A934232D99A -:1007D00006AFA8602B4628220021384601F05EFBB8 -:1007E00005F10E0000F0E4FD002604465FFA80F9F2 -:1007F00005F10E08F3B2F100994501F1280107D97E -:1008000008EB06030822384601F048FB0136F1E701 -:1008100008230122CDE9023205340C4B0193A4B226 -:1008200030230093CDE9047405A3D3E90023297B89 -:10083000074801F04BF93BB0BDE8F083AFF300800F -:1008400078F6339F93CACD8D682100207521002052 -:100850003C21002070B50D4614461E4601F0CCF830 -:1008600050B9022E10D1012C0ED112A3D3E90023CE -:10087000C5E90023012007E0282C10D005D8012C61 -:1008800009D0052C0FD0002070BD302CFBD10BA35C -:10089000D3E90023ECE70BA3D3E90023E8E70BA39C -:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B -:1008B000AFF30080401DA12026812A0B78F6339FDC -:1008C00093CACD8D9E6AC421818A46EE26417272FA -:1008D000DF25D7B7F017304A39059E5613B50446C1 -:1008E0002346084620220021019001F0D7FA227900 -:1008F0000198032A234628BF032203F8042F20214E -:10090000022201F0CBFA62790198072A234628BF18 -:10091000072203F8052F2221032201F0BFFAA27952 -:100920000198072A234628BF072203F8062F25210E -:10093000032201F0B3FA019804F1080310222821E0 -:1009400001F0ACFA382002B010BD00002DE9F04FE4 -:10095000ADF5017D21AD0EAE40F2751280460F4619 -:1009600022A80021296000F02BFD482200213046FA -:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 -:10098000F2F0186093E80700012386E807000DF1F4 -:100990005A003382FFF700FF4EF60343338406AB61 -:1009A00018464D4903F0C2F81D22306429463046EE -:1009B00086F83C20FFF792FF12AB0446014608225E -:1009C000284601F06BFA0822A1180DF149032846C8 -:1009D00001F064FA0DF14A03082204F110012846DF -:1009E00001F05CFA13AB202204F11801284601F053 -:1009F00055FA14AB402204F13801284601F04EFAB2 -:100A000016AB082204F17801284601F047FA0DF1EF -:100A10005903082204F18001284601F03FFA04F14D -:100A2000880A0DF15A0904F5847B4B465146082289 -:100A300028460AF1080A01F031FAD34509F1010903 -:100A4000F3D11BAB08225946284601F027FA04F5DA -:100A500088744FF0000996F834304B450AD9B36BCF -:100A600021464B440822284601F018FA083409F1BF -:100A70000109F0E74FF0000996F83C304B4504EBD4 -:100A8000C90108D9336C08224B44284601F006FA04 -:100A900009F10109F0E700230393BB7E02930731BC -:100AA00007F119030193C1F3CF010123CDE90451EB -:100AB0000093F97E05A3D3E90023404601F006F830 -:100AC0000DF5017DBDE8F08FAFF300809E6AC42173 -:100AD000818A46EE241100203C3B0008014B18702F -:100AE000704700BF30110020F0B5334B1C7B85B040 -:100AF00034B1324B0E221A810024204605B0F0BDDD -:100B00002F4A1068516802AB03C308232D492E48B1 -:100B10000DEB030202F0E8FF054630B9274B2B48E6 -:100B20000A221A8100F098FCE6E70169B1F5663FF8 -:100B300006D9224B26480B221A8100F08DFCDCE7F7 -:100B4000438BB3F57B7F09D01C4A22480C211181CD -:100B50004FF47B72194600F07FFCCEE71E4A024438 -:100B600002F11003994204D2144B1C4810221A813E -:100B7000E3E710398E1A2046134900F0B7FC3246DD -:100B8000074605F11801204600F0B0FCAB689F4213 -:100B900002D1EB6898420AD0084B0D221A810090CE -:100BA000D5E902123B460E4800F056FCA4E70D487A -:100BB00000F052FC0124A0E768210020241100204D -:100BC000ED3B0008DC970300006800085C3B000870 -:100BD000683B00087A3B00080898FFF7983B00083C -:100BE000B53B0008DE3B00082DE9F04FADB006AF85 -:100BF00080460C4600F000FF054600285AD1237EAF -:100C0000022B1BD1E38A012B18D100F06BFC0646A6 -:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C -:100C2000F0F206F5167602FB103316FA83F3C9F8D4 -:100C30000030E37E33B9A84B00221A709C37BD46C2 -:100C4000BDE8F08FA38AEEB2013BB34205F1010586 -:100C50000BD93B1D1E44E90000960023082201F039 -:100C6000F801204600F0DEFFECE707F11400FFF783 -:100C700093FD324607F11401381D02F025FF0028CC -:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 -:100C90001673C9F80030D1E7FB1CF87001460093C9 -:100CA00007220346204600F0BDFFF978404600F0D9 -:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 -:100CC000052BBBD1BFF34F8F8449854BCA6802F413 -:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 -:100CE000ACD1637E7F4D01336A7BDBB29342E94630 -:100CF00003D1E27E2B7B9A4265D0CD469EE721460A -:100D00004046FFF723FE99E7A38A013B9BB2C92B1C -:100D100094D8744D2E7B26BB05F10C03009308225A -:100D200033463146204600F07DFF731CF2B2D900F5 -:100D30001E46A38A013B9A4205DA0E322A440092EB -:100D400000230822EEE700230022C5E90023002348 -:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 -:100D60002B73002507F114093B1D0822294648462C -:100D7000C7E90155FD6001F091F83B7A05F1010AE0 -:100D8000AB424FEACA0608D9FB6808222B44314619 -:100D9000484601F083F85546EFE7C6F3CF06E17EFB -:100DA000CDE9049600230393A37E029319342823EC -:100DB0000093019446A3D3E90023404600F086FE49 -:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 -:100DD00014801022009341460123204600F022FF98 -:100DE000A68A023EB6B2F31C9B109B000733DB08B9 -:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 -:100E0000C801B34201F110010AD20AEB08030093B2 -:100E100008220023204600F005FF08F10108ECE756 -:100E200095F8D70000F080FAD5F8D83004461BB901 -:100E300095F8D70000F088FAD5F8D83033449C42B2 -:100E400004D295F8D700013000F07EFA4FEA960BF5 -:100E50004FF000081FFA88F18B45D5E9003209D917 -:100E60000AEB880103EB8800012200F0B1FA08F1D7 -:100E70000108EFE7F31842F10002C5E90032D5F8A6 -:100E8000D83095F8D70006EB0308C5F8D88000F0F5 -:100E90004BFA804509D395F8D730D5F8D8000133FF -:100EA000001B85F8D730C5F8D800FF2E08D80023DE -:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D -:100EC0002B68094A9B0A013313810023AB6014E7A6 -:100ED00026417272DF25D7B73521002000ED00E0F2 -:100EE0000400FA0568210020241100203821002088 -:100EF00010B54FF000540C4B22689A4211D10B4BA5 -:100F0000627D1A700A48237D03730A49C9220E3094 -:100F100000F044FAE0220021204600F051FA0120BE -:100F200010BD0020FCE700BF9AAD44C53011002081 -:100F300068210020160000202DE9FF41434C0223C8 -:100F400063710023029324250A23581EB5FBF3F690 -:100F50007343D3F12402C1B23ED002280346F4D138 -:100F60009DF80B303A493B485A1E9DF80A30013B28 -:100F70001B0443EA0253BDF80820013A13434B60B7 -:100F800001F044FD00230193334B3449009334486E -:100F9000344B4FF4805200F001FD334B197811B1FE -:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D -:100FB0004FF4C873B0FBF3F202FB130305F5167090 -:100FC00010FA83F0294B186002F0D0FA08B10F2311 -:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF -:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA -:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F -:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 -:10101000CDB2591E0F2916D86A1E072A8CBF00228E -:101020000122591901FB06601149B1FBF0F1114889 -:10103000814295D1002A93D0ADF808608DF80A302E -:101040008DF80B508CE71346EBE700BF241100200E -:1010500010110020802200205508000834110020C3 -:101060003C210020E90B000830110020382100202D -:101070000051250240420F002DE9F04F90A7D7E91B -:1010800000670FF24429D9E90089874D93B0DFF852 -:1010900040B2864C284600F07DFD0DF1300A0790E5 -:1010A00070B310220021504600F08AF9079B197B8B -:1010B0004FF0000261F303028DF830205868996800 -:1010C0000EAA03C21B680D9A63F31C029DF8303010 -:1010D0000D9243F020038DF830300023524619461C -:1010E000584601F0A3FC079028B9284600F056FDA9 -:1010F000079B2370CEE72378072B3CD8013323705E -:1011000018220021504600F05BF9DFF8C4B100233B -:1011100019465246584601F0B1FC014678BB1022F0 -:1011200008A800F04DF94FF0904209AC536983F0E4 -:101130001003536100F0D8F90B4612A9024611E9D9 -:10114000030084E803009DF83410C1F3030089060E -:101150004CBF0E9CBDF838408DF82C0046BFC4F340 -:101160001C0444F00044C4F30A0408A92846089467 -:1011700000F0DCFECBE7284600F010FDC0E7284673 -:1011800000F03AFC0446002848D1DFF848B100F0EE -:10119000A9F9DBF80030984240D300F0A3F907909A -:1011A000FFF7E2FA079A8DF8204003464FF4C87023 -:1011B00002F51672B3FBF0F101FB103312FA83F360 -:1011C000CBF80030DFF810B19BF8001011B9012303 -:1011D0008DF8203050460791FFF7DEFA0799C1F1EC -:1011E0001004E4B2062C28BF0624224651440DF117 -:1011F000210000F0D3F808AB0393182302930134C5 -:101200002B4B0193E4B20123009304943B463246F6 -:10121000284600F0F3FB00238BF8003000F062F961 -:10122000244A254C1368C31AB3F57A7F31D3106072 -:1012300000F05AF902460B46284600F0B9FC284651 -:1012400000F0DAFB28B3237BDFF890B0002B14BF4B -:10125000032302238BF8053000F044F94FF47A732E -:101260005146B0FBF3F0CBF800005846FFF736FBD1 -:10127000182307300293114B0193C0F3CF0040F2C3 -:101280005513CDE903A0009342464B46284600F093 -:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 -:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 -:1012B0003421002048220020682100204C220020F8 -:1012C000401DA12026812A0BF1C6A7C1D068080FB6 -:1012D0008022002038210020352100202411002008 -:1012E00070B501F0B5FF094E094D30800024286823 -:1012F0003388834208D901F0A7FF2B6804440133E7 -:10130000B4F5D04F2B60F2D370BD00BF7C2200201B -:101310005022002002F03AB800F10060920000F57F -:10132000D04001F0D5BF0000054B1A68054B1B8863 -:101330009B1A834202D9104401F086BF00207047F7 -:10134000502200207C22002038B5074D0446286832 -:10135000204401F07FFF28B928682044BDE83840C8 -:1013600001F08ABF38BD00BF50220020064991F825 -:10137000243033B10023086A81F824300822FFF7B3 -:10138000CBBF0120704700BF54220020022802BFBB -:101390004FF090434FF480129A61704710B50023CC -:1013A000934203D0CC5CC4540133F9E710BD000074 -:1013B00003460246D01A12F9011B0029FAD17047E0 -:1013C00002440346934202D003F8011BFAE7704738 -:1013D0002DE9F8431F4D144695F82420074688460A -:1013E00052BBDFF870909CB395F824302BB92022C3 -:1013F000FF2148462F62FFF7E3FF95F82400C0F174 -:101400000802A24228BF2246D6B24146920005EB0E -:101410008000FFF7C3FF95F82430A41B1E44F6B2EA -:10142000082E17449044E4B285F82460DBD1FFF71E -:101430009DFF0028D7D108E02B6A03EB820383428B -:10144000CFD0FFF793FF0028CBD10020BDE8F88371 -:101450000120FBE7542200200FB4002004B07047A5 -:1014600000B59BB0EFF3098168226846FFF796FF4D -:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E -:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D -:10149000EFF3098168226846FFF780FFEFF30583C9 -:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF -:1014B000FEE700BF00ED00E000B59BB0EFF309814F -:1014C00068226846FFF76AFFEFF30583034B5A6B08 -:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 -:1014E000FEE7000001F08EBF01F064BF30B5094D8A -:1014F0000A4491420DD011F8013B5840082340F3B3 -:101500000004013B2C4013F0FF0384EA5000F6D1A5 -:10151000EFE730BD2083B8ED2DE9F041C56915B97D -:10152000C161BDE8F0814B6823F06047C3F38A4690 -:101530004FEAD37EC3F3807816EA230638BF3E46CF -:10154000AC462B465A68BEEBD27F22F060440AD0EC -:10155000002A18DAA40CB44217D19D420FD10D60B5 -:10156000DEE71346EEE7A74207D102F08044C2F35C -:10157000807242450BD054B1EFE708D2EDE7CCF8CA -:1015800000100B60CDE7B44201D0B442E5D81A6830 -:101590009C46002AE5D11960C3E700002DE9F04719 -:1015A000089D01F007044FEAD508224405F007051D -:1015B00000EBD1004FF47F49944201D1BDE8F087A0 -:1015C00004F0070705F0070A57453E4638BF564660 -:1015D000C6F10806111B8E4228BF0E46E10808EB33 -:1015E000D50E415C13F80EC0B94029FA06F721FA6E -:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 -:10160000010C03F80EC034443544D5E780EA0120CC -:10161000082341F2210201B24000002980B203F107 -:10162000FF33B8BF504013F0FF03F4D17047000000 -:1016300038B50C468D18A54200D138BD14F8011BF1 -:10164000FFF7E4FFF7E7000002684AB113680360A0 -:10165000C388018901339BB29942C38038BF03819B -:101660001046704770B588B0202204460D46684683 -:101670000021FFF7A5FE20460495FFF7E5FF02468F -:1016800058B16B46054608AE1C4603CCB4422860F0 -:101690006960234605F10805F6D1104608B070BD13 -:1016A000082817D909280CD00A280CD00B280CD0F0 -:1016B0000C280CD00D280CD00E2814BF4020302050 -:1016C00070470C2070471020704714207047182076 -:1016D0007047202070470000082817D90C280CD923 -:1016E00010280CD914280CD918280CD920280CD96A -:1016F00030288CBF0F200E207047092070470A2029 -:1017000070470B2070470C2070470D207047000079 -:1017100010B54B6823B9CA8A63F30902CA8210BDA7 -:10172000C4681A681C60C360438A013B43824A60F4 -:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 -:1017400009010629814692460B4630D00020AAB2F4 -:1017500007F119049EB2052E1FFA80F80FD89045A4 -:1017600003F1010306D3FB8A0A4462F30903FB82F7 -:1017700001201AE01AF80060E6540130EAE79045CB -:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 -:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 -:1017A000044638B978606FF00200BDE8F88F4FF05A -:1017B0000008E6E7002606607860ADB24FF0000B47 -:1017C000454510D90AEB0803221D13F8011B91555A -:1017D000B1B208F101081B291FFA88F82BD0454542 -:1017E00006F10106F1D8FB8AC3F30902154465F33B -:1017F0000903BCE7013292B21C462368002BF9D1E1 -:10180000AB1F0B441C21B3FBF1F301339BB29A4293 -:10181000D3D2BBF1000FD0D14846FFF715FF20B956 -:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 -:1018300020600446C1E74545D5D94846FFF704FF77 -:1018400008B92060AFE7C0F800B000262060044669 -:10185000B6E700002DE9F04F2DED028B83B0CDE906 -:101860000013BDF83C5007469146002A00F09280D4 -:101870002DB10E9B002B00F08D80072D32D807F183 -:101880000C00FFF7E1FE044638B96FF00204204671 -:1018900003B0BDEC028BBDE8F08F14220021FFF7EE -:1018A0008FFD0E992A4604F10800FFF777FD681CAA -:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 -:1018C000013814FA80F003F01F0363F03F03037242 -:1018D000009B43F00041616038462146FFF71CFE43 -:1018E0000124D4E700F10C034FF0000808EE103A91 -:1018F0004FF0800A4646444618EE100AFFF7A4FE51 -:1019000083460028C1D014220021FFF759FDC6BB31 -:10191000019BABF8083002200E9B00F108029919D8 -:101920005BFA82F20130C0B2082801D0AE422AD35D -:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E -:1019400002F01F0242EA4812AE4208BF4FF0400ABE -:101950005BFA81F14AEA020A43F0004281F808A0EA -:101960008BF81000CBF8042059463846FFF7D4FD19 -:101970000134AE4224B288F001084FF0000ABBD116 -:1019800085E70020C8E711F801CB02F801CB01364A -:10199000B6B2C7E76FF0010479E70000F8B5154665 -:1019A0000E462822002104461F46FFF709FD069B2C -:1019B0006360B5F5001F079BA76034BF6A094FF647 -:1019C000FF72236204F10C0097B200239A4205D8FB -:1019D0000023036027826382A382F8BD066001337F -:1019E00030462036F2E7000003781BB94BB2002BDB -:1019F000C8BF017070470000007870472DE9F74FAD -:101A0000DDF83C90BDF830500D9E9DF83840BDF893 -:101A10004070804692469B46B9F1000F01D1002FDD -:101A200051D11F2C4FD898F80000B0B9072F47D8D4 -:101A300035F0030347D13A4649464FF6FF70FFF7AA -:101A4000F7FD20F001002D02400445EA0464400C3B -:101A500044EA40244FF6FF7321E040EA0520072FB7 -:101A600040EA0464F6D900254FF6FF73C5F1200063 -:101A7000A5F120022AFA05F10BFA00F001432BFA36 -:101A800002F211431846C9B2FFF7C0FD0835402DD8 -:101A90000346EBD13A464946FFF7CAFD0346CDE976 -:101AA0000097324621464046FFF7D4FE3378013393 -:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B -:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 -:101AD00085B09246DDF848800F9D9DF840209DF826 -:101AE0004490BDF84C7006469B46B8F1000F01D1FA -:101AF000002F48D11F2A46D83378002B46D00C023D -:101B000044EA02649DF8381044EAC93444EA0144C6 -:101B10001C43072F44F0800432D900234FF6FF7294 -:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC -:101B300041EA0C012BFA00F00143C9B210460393AD -:101B4000FFF764FD039B0833402B0246E8D13A4679 -:101B50004146FFF76DFD0346CDE900872A46214641 -:101B60003046FFF777FEB9F1010F06D12B7801332C -:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 -:101B80004FF6FF73E8E76FF00100F6E76FF0030030 -:101B9000F3E70000C06900B104307047C3691A68F8 -:101BA000C261C2681A60C360438A013B43827047C6 -:101BB0002DE9F041D0F81880194E14461D464146D3 -:101BC000002709B9BDE8F081D1E90223A21A65EB2B -:101BD0000303964277EB03031ED283698B420DD138 -:101BE000FFF796FD83691B688361C3680B60438AB6 -:101BF000C1608169013B43828846E2E7FFF788FDC7 -:101C00000B68C8F80030C3680B60438AC160013BB1 -:101C10004382D8F80010D4E788460968D1E700BFAE -:101C200080841E002DE9F04F8BB00D46DDF85090FA -:101C300014469B468046002800F01981B9F1000F38 -:101C400000F01581531E3F2B00F21181012A03D1B0 -:101C5000BBF1000F40F00B810023CDE90833B8F849 -:101C60001430B5EBC30F4FEAC30703D300200BB00A -:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C -:101C8000FFB227461BB9D8F81030002B7AD02F2D81 -:101C90004ED8C5F13006B7424FF000032CBFF6B264 -:101CA0003E4600932946D8F8080008AB3246FFF7B5 -:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 -:101CC00003F10053063BDB000493D8F80C30039378 -:101CD0003021039B13B1BAF1000F2CD1D8F81000BA -:101CE00040B1BAF1000F05D0009608AB5246691A10 -:101CF000FFF754FC38B2002FB8D066070AD00AAB01 -:101D000003EBD401624211F8083C02F007021341D0 -:101D100001F8083C082C3CD9102C40F2B580202C4E -:101D200040F2B780BBF1000F00F09C80082334E044 -:101D3000BA460026C2E7049BE02B28BFE0230693A7 -:101D40000B44AB42059314D95A1B03980096924555 -:101D500034BF5246D2B2691A08AB04300792FFF77B -:101D60001DFC079A1644AAEB020A1544F6B25FFA64 -:101D70008AFA049B069A05999B1A0493039B1B6895 -:101D80000393A6E70093D8F8080008AB3A46294623 -:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F -:101DA000082C12D89DF82030621E23FA02F2D507C3 -:101DB00006D54FF0FF3202FA04F423438DF82030A9 -:101DC0009DF8203089F8003051E7102C12D8BDF86A -:101DD0002030621E23FA02F2D10706D54FF0FF32FF -:101DE00002FA04F42343ADF82030BDF82030A9F8FE -:101DF00000303CE7202C0FD80899631E21FA03F32A -:101E0000DA0705D54FF0FF3202FA04F40C430894C8 -:101E1000089BC9F800302AE7402C2BD0DDE9086583 -:101E2000611EC4F12102A4F1210326FA01F105FA91 -:101E300002F225FA03F311431943CB0712D501220D -:101E4000A4F12003C4F1200102FA03F322FA01F104 -:101E5000A240524243EA010363EB430332432B4364 -:101E6000CDE90823DDE90823C9E90023FFE66FF087 -:101E70000100FCE66FF00800F9E6082CA0D9102C50 -:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD -:101E900083E7BBF1000FBBD004237EE730B5012AF6 -:101EA000144638BF0124402C85B028BF40240025AB -:101EB000012ACDE9025518D81B788DF80830630740 -:101EC0000AD004AB03EBD405624215F8083C02F0DB -:101ED0000702934005F8083C009103462246002182 -:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 -:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D -:101F000000231B680293CDE90223D8E710B5CB6804 -:101F10001BB98B600B618B8210BDC4681A681C6092 -:101F2000C360438A013B4382CA60F0E72DE9F04F6A -:101F3000D1F8008093B018F0800FCDE90323C8F3E7 -:101F4000C01219BFC8F3C03BC8F306264FF0020BFE -:101F50001646B8F1000F04460D4680F2D18118F004 -:101F6000C043059340F0CC810B7B002B00F0C8816F -:101F7000BBF1020F03D00178B14240F0C48108F0F8 -:101F80007F0106916AB3C8F3074A2B44069A93F877 -:101F90000390760646EA0B4646EA82465FEAD91384 -:101FA00046EA0A06079300F0908000220023CDE95C -:101FB0000A23069B009367685B4652460AA920469F -:101FC000B84700287ED0A7699FB9314604F10C00BC -:101FD000FFF748FB0746E0B96FF0020013B0BDE819 -:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A -:101FF000CBE73B699E420DD03F68002FF9D13146B7 -:1020000004F10C00FFF72EFB07460028E4D0A3697B -:102010003B60A761DDE90A2300264FF6FF70C6F199 -:10202000200E22FA06F103FA0EFEA6F1200C23FA86 -:102030000CFC41EA0E0141EA0C01C9B208360992D2 -:102040000893FFF7E3FA402EDDE90832E7D1B882C2 -:10205000FB7D09F01F06C3F384039B1BD7E9022114 -:1020600098B2002BBCBF00F120031BB252EA010062 -:10207000C8F304680FD00398821A049860EB01013A -:10208000A74890424FF000028A4104D3079A002AE1 -:102090005BD0012B23DDFA7D4FEA890302F00302B6 -:1020A00003F07C031343FB7539462046FFF730FBF2 -:1020B000079BA3B9FB7DC3F38402013262F386035D -:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 -:1020D0000C0083E73B699E42BAD03F68F6E719F0EF -:1020E000400F32D0039BBB60049BFB601422002195 -:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 -:102100000C932B7BADF83EA0013BDBB2ADF83C302D -:10211000069B8DF8433094F824308DF840B083F05E -:1021200001038DF844308DF84160A3688DF842803A -:102130000AA920469847FB7DC3F38403013303F0CB -:102140001F039B02FB82002048E7FB7DC9F340127E -:10215000B2EBD31F40F0DA80C3F38403B34240F004 -:10216000D88007992B7B4FEA9912002934D0D207E7 -:1021700041D4032B40F2D080039BBB60049BFB60E7 -:102180002B7BAE1D033BDBB23246394604F10C001B -:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 -:1021A000FB7DC3F38403013303F01F039B02FB8217 -:1021B000032013E7AB883B832A7B033AB88AD2B269 -:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D -:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C -:1021E0003246394604F10C00FFF7A4FA0028D3DB8D -:1021F0002A7B013AE2E7F98AC1F30901013B05298B -:10220000DAB259D8281D002307F11A0C9A4208D9CE -:1022100010F801EB0CF801E0013101330629DBB2C3 -:10222000F4D103990A9104990B91934207F11A0191 -:102230000C9138BF043379680D9134BF55FA83F39C -:1022400000230E93FB8AADF83EA0C3F309031A44A2 -:10225000069B8DF8433094F82430ADF83C2083F091 -:1022600001038DF8443000238DF840B08DF84160B3 -:102270008DF842807B602A7BB88A013A291DFFF7DE -:10228000D7F93B8BB882834203D1A3680AA92046C1 -:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 -:1022A0008403013303F01F039B02FB823B8B9842A4 -:1022B00014BF1120002091E67B68002BB1D00620CE -:1022C00001E01C306346D3F800C0BCF1000FF8D128 -:1022D000091A081D05F1040C00EB030905989DF887 -:1022E000143001EB000EBEF11B0F9AD89A4298D918 -:1022F0001CF8013B09F8013B059B01330593EDE711 -:102300006FF009006AE66FF00A0067E66FF00D00F3 -:1023100064E66FF00E0061E66FF00F005EE600BF4E -:1023200080841E00F0B53D4D3D4FEB6943F00073D6 -:10233000EB61EB693B4B9B6AD3F800623E4046F091 -:102340000106C3F80062D3F800423C4044EA002092 -:1023500040F00100C3F80002002951D00020C3F86A -:102360001C020646C3F80402C3F80C02C3F81402A8 -:1023700003EBC00401300E28C4F84062C4F8446284 -:10238000F6D100274FF0010C9678148816F0010F53 -:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A -:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 -:1023B0000E0EC3F80CE2760742BFD3F81462064350 -:1023C000C3F8146203EBC4045668C4F8406296680C -:1023D000C4F84462D3F81C4201372043B942C3F821 -:1023E0001C0202F10C02CFD1D3F8002222F001022C -:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 -:102400000122C3F84012C3F84412C3F80412C3F8FF -:102410001412C3F80C22C3F81C22E5E70010024096 -:102420000000FFFF80220020184A916A08B58B68DF -:102430008B6013F0010104D013F00C0F18BF4FF4A0 -:102440008031D80506D513F4406F14BF41F4003134 -:1024500041F00201D80306D513F4402F14BF41F414 -:10246000802141F00401D3690BB10848984720232B -:1024700083F311880648002100F038FE002383F31F -:102480001188BDE8084001F0AFB800BF80220020ED -:102490008822002038B5124CA36ADD68AA0712D042 -:1024A0005A6922F002025A61A36913B10121204640 -:1024B0009847202383F311880A48002100F016FE74 -:1024C000002383F31188EB0606D5A36A1021D96097 -:1024D000236A0BB102489847BDE8384001F084B840 -:1024E000802200209022002038B5124CA36A1D697A -:1024F000AA0712D05A6922F010025A61A36913B1D7 -:10250000022120469847202383F311880A4800219E -:1025100000F0ECFD002383F31188EB0606D5A36AD7 -:1025200010211961236A0BB102489847BDE8384071 -:1025300001F05AB8802200209022002038B50F4CBC -:10254000A36A5D685D602A070AD5042222701A68B2 -:1025500022F002021A60636A13B1002120469847F4 -:102560006B0706D5A36A9969236A13B10348090466 -:102570009847BDE8384001F037B800BF80220020FE -:1025800010B50E4C204600F02FFA0D4BA3620B2124 -:10259000132000F009FA0B21142000F005FA0B219A -:1025A000152000F001FA0B21162000F0FDF90022A1 -:1025B000BDE8104011460E20FFF7B4BE8022002077 -:1025C000006400400F4B984210B5044605D10E4BF5 -:1025D000DA6942F00072DA61DB69A36A01221A60EB -:1025E000A36A5A68D20707D5626851681268D96130 -:1025F0001A60064A5A6110BD0121082000F06CFCE7 -:10260000EEE700BF80220020001002405B8701003F -:1026100003291AD8DFE801F0020A0F14836A9B68C5 -:1026200013F0E05F14BF012000207047836A9868B0 -:10263000C0F380607047836A9868C0F3C0607047D9 -:10264000836A9868C0F300707047002070470000EC -:1026500010B5032925D8DFE801F00225292D836A6A -:102660009968C1F30161183103EB011310788406F6 -:102670004CBF54689488C0F300114FEA410148BF31 -:1026800041EAC40100F00F004CBF41F0040141EAEF -:102690004451586041F001019068D2689860DA6056 -:1026A000196010BD836A03F5C073DFE7836A03F521 -:1026B000C873DBE7836A03F5D073D7E701290AD033 -:1026C00002290FD081B9836ADA68920701D11869AB -:1026D00003E001207047836AD86810F0030018BF38 -:1026E00001207047836AF2E70020704710B539B9BE -:1026F000836AD96889071BD11B699C0704D110BD67 -:10270000012915D00229FAD1816AD1F8C031D1F856 -:10271000C441D1F8C8011061D1F8CC01506120202A -:1027200008610869800717D1486940F0100012E07D -:10273000816AD1F8B031D1F8B441D1F8B801106153 -:10274000D1F8BC0150612020C860C868800703D15F -:10275000486940F002004861C3F34000C3F38001C0 -:10276000000140EA4111107920F03000014311715D -:1027700089064BBF91681189DB085B0D4CBF63F381 -:102780001C0163F30A01137948BF916064F30303EA -:1027900013714FEA14234FEA144458BF1181137088 -:1027A0005480ACE7026843681143016003B11847E5 -:1027B00070470000024A136843F0C003136070477B -:1027C00000380140024A136843F0C00313607047A9 -:1027D0000044004037B51D4C1D4D204600F006FB5F -:1027E000009404F114001B490023202200F0C8F9D2 -:1027F0002022009404F13800174B184900F042FAE7 -:10280000174BC4E91735174C0C21252000F0CCF8E4 -:10281000204600F0EBFA04F1140013490094002361 -:10282000202200F0ADF904F13800104B104900945B -:10283000202200F027FA0F4B0C212620C4E917357F -:1028400003B0BDE8304000F0AFB800BFAC220020BC -:102850000051250284230020B5270008C42300204E -:102860000038014018230020A4230020C5270008B9 -:10287000E4230020004400402DE9F047C66D37688E -:10288000F46934622107054618D014F0080118BF16 -:102890008021E20748BF41F02001A30748BF41F073 -:1028A0004001600748BF41F48071202383F3118801 -:1028B000281DFFF777FF002383F31188E2050AD56F -:1028C000202383F311884FF40071281DFFF76AFF5E -:1028D000002383F311884FF020094FF0000A14F011 -:1028E000200838D13B0616D54FF0200905F1380AEB -:1028F000200610D589F31188504600F0F7F900281A -:1029000036DA0821281DFFF74DFF27F080033360DA -:10291000002383F31188790614D5620612D520238B -:1029200083F31188D5E913239A4208D12B6C33B174 -:102930001021281D27F04007FFF734FF37600023E0 -:1029400083F31188E30619D5AA6E1369B3B1BDE804 -:10295000F0475069184789F31188B38C95F86410D3 -:102960002846194000F04EFA8AF31188F469B6E758 -:1029700080B2308588F31188F469B9E7BDE8F08743 -:1029800008B50348FFF778FFBDE8084000F02CBE0B -:10299000AC22002008B50348FFF76EFFBDE80840F1 -:1029A00000F022BE1823002000F1604303F56143CC -:1029B0000901C9B283F80013012200F01F039A40F5 -:1029C00043099B0003F1604303F56143C3F8802191 -:1029D0001A60704700F16040090100F56D40C9B20E -:1029E00001767047FFF7CCBD012300F10802C0E972 -:1029F0000222037000F110020023C0E90422C0E9A2 -:102A00000633C0E9083343607047000010B5202347 -:102A1000044683F31188022303704160FFF7D2FD5F -:102A200004232370002383F3118810BD2DE9F041A6 -:102A30001F4604460D461646202383F3118800F1F5 -:102A400008082378052B0DD029462046FFF7E0FD26 -:102A500040B1204632462946FFF7FAFD002080F3B8 -:102A6000118808E03946404600F024FB0028E8D0F1 -:102A7000002383F31188BDE8F08100002DE9F041C7 -:102A80001F4604460D461646202383F3118800F1A5 -:102A900010082378052B0DD029462046FFF70EFE9F -:102AA00040B1204632462946FFF720FE002080F341 -:102AB000118808E03946404600F0FCFA0028E8D0CA -:102AC000002383F31188BDE8F0810000F8B51546B6 -:102AD00082680669AA420B46816938BF8568761A02 -:102AE000B54204460BD218462A46FEF757FCA369A6 -:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 -:102B000018463246FEF74AFCAF1BE1683A463044AD -:102B1000FEF744FCE3683B44EBE718462A46FEF721 -:102B20003DFCE368E5E7000083689342F7B515468E -:102B3000044638BF8568D0E90460361AB5420BD226 -:102B40002A46FEF72BFC63692B446361A368284681 -:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 -:102B60001DFC0199E068AF1B3A463144FEF716FCA4 -:102B7000E3683B44E9E72A46FEF710FCE368E4E734 -:102B800010B50A440024C361029B8460C0E90000C0 -:102B9000C0E90511C1600261036210BD08B5D0E94A -:102BA0000532934201D1826882B982680132826023 -:102BB0005A1C42611970D0E904329A4224BFC3689A -:102BC0004361002100F086FA002008BD4FF0FF307D -:102BD000FBE7000070B5202304460E4683F31188FE -:102BE000A568A5B1A368A269013BA360531CA361BA -:102BF00015782269934224BFE368A361E3690BB1AE -:102C000020469847002383F31188284607E0314681 -:102C1000204600F04FFA0028E2DA85F3118870BDF3 -:102C20002DE9F74F04460E4617469846D0F81C90FB -:102C30004FF0200A8AF311884FF0000B154665B15A -:102C40002A4631462046FFF741FF034660B9414618 -:102C5000204600F02FFA0028F1D0002383F31188DA -:102C6000781B03B0BDE8F08FB9F1000F03D00190DD -:102C70002046C847019B8BF31188ED1A1E448AF346 -:102C80001188DCE7C0E90511C160C3611144009BF4 -:102C90008260C0E90000016103627047F8B5044634 -:102CA0000D461646202383F31188A768A7B1A368B1 -:102CB000013BA36063695A1C62611D70D4E9043250 -:102CC0009A4224BFE3686361E3690BB120469847E9 -:102CD000002080F3118807E03146204600F0EAF931 -:102CE0000028E2DA87F31188F8BD0000D0E9052357 -:102CF0009A4210B501D182687AB982680132826045 -:102D00005A1C82611C7803699A4224BFC36883619C -:102D1000002100F0DFF9204610BD4FF0FF30FBE747 -:102D20002DE9F74F04460E4617469846D0F81C90FA -:102D30004FF0200A8AF311884FF0000B154665B159 -:102D40002A4631462046FFF7EFFE034660B941466A -:102D5000204600F0AFF90028F1D0002383F311885A -:102D6000781B03B0BDE8F08FB9F1000F03D00190DC -:102D70002046C847019B8BF31188ED1A1E448AF345 -:102D80001188DCE7026843681143016003B118470A -:102D9000704700001430FFF743BF00004FF0FF33CF -:102DA0001430FFF73DBF00003830FFF7B9BF000017 -:102DB0004FF0FF333830FFF7B3BF00001430FFF798 -:102DC00009BF00004FF0FF311430FFF703BF0000D0 -:102DD0003830FFF763BF00004FF0FF323830FFF7A5 -:102DE0005DBF000000207047FFF7F4BC044B036098 -:102DF0000023C0E90233436001230374704700BF1E -:102E0000F83B000838B5C36904460D461BB90421D8 -:102E10000844FFF7B7FF294604F11400FFF7BEFE90 -:102E2000002806DA201D4FF48061BDE83840FFF726 -:102E3000A9BF38BD024B0022C3E900339A60704736 -:102E400004240020002303748268054B1B689968E2 -:102E50009142FBD25A68036042601060586070472C -:102E60000424002008B5202383F31188037C032B5E -:102E700005D0042B0DD02BB983F3118808BD43690D -:102E800000221A604FF0FF334361FFF7DBFF00239E -:102E9000F2E7D0E9003213605A60F3E700230374CD -:102EA0008268054B1B6899689142FBD85A68036099 -:102EB000426010605860704704240020054B196977 -:102EC0000874186802681A6053601861012303745B -:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 -:102EE000044610D02B690A4A01A800F01BF92046BD -:102EF000FFF7E4FF049B13B101A800F02FF92B6941 -:102F0000586907B030BDFFF7D9FFF8E70424002067 -:102F1000652E000838B50C4D41612B6981689A68AF -:102F20009142044603D8BDE83840FFF78BBF1846EE -:102F3000FFF7B4FF01232C61014623742046BDE84E -:102F40003840FDF745BB00BF04240020044B1A683D -:102F50001B6990689B68984294BF002001207047CD -:102F60000424002010B5084C236820691A682260E8 -:102F70005460012223611A74FFF790FF0146206913 -:102F8000BDE81040FDF724BB0424002008B5FFF77E -:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 -:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 -:102FB00000F0AAF80A498022204600F031F80123E7 -:102FC00044F8180C037400F0EBFA002383F3118823 -:102FD00062B60448BDE8104000F042B82C2400203E -:102FE000203C0008303C000800F0CAB8EFF3118024 -:102FF00020B9EFF30583202282F311887047000087 -:1030000010B530B9EFF30584C4F3080414B180F3AC -:10301000118810BDFFF7BAFF84F31188F9E70000AB -:1030200082600222028270478368A3F17C0243F827 -:103030000C2C026943F83C2C426943F8382C074AAF -:1030400043F81C2CC26843F8102C022203F8082C09 -:10305000002203F8072CA3F118007047E9050008C7 -:1030600010B5202383F31188FFF7DEFF002104460B -:10307000FFF750FF002383F31188204610BD0000A6 -:10308000024B1B6958610F20FFF718BF0424002072 -:10309000202383F31188FFF7F3BF000008B5014632 -:1030A000202383F311880820FFF716FF002383F302 -:1030B000118808BD49B1064B42681B6918605A6007 -:1030C000136043600420FFF707BF4FF0FF307047E5 -:1030D000042400200368984206D01A6802605060F9 -:1030E00059611846FFF7AEBE7047000038B5044678 -:1030F0000D462068844200D138BD036823605C60BF -:103100004561FFF79FFEF4E7054B03F11402C3E9A5 -:1031100005224FF0FF32DA6100221A62704700BFC9 -:103120000424002010B5C0E903230B4A136A536935 -:103130009C68A1420CD85C68816003604460206098 -:1031400058609868411A99604FF0FF33D36110BD01 -:103150001B68091BECE700BF04240020036881689A -:103160009A680A449A60426813605A600023C360F8 -:10317000024B4FF0FF32DA61704700BF0424002099 -:1031800038B50F4C236A22460133236252F8143FAC -:10319000934206D09A68013A9A60202563699A683A -:1031A00002B138BDD3E9001001604860D968DA6027 -:1031B00082F311881869884785F31188EEE700BF0C -:1031C0000424002000207047FEE700007047000044 -:1031D0004FF0FF3070470000BFF34F8F024AD368B3 -:1031E000DB07FCD4704700BF0020024008B5074B46 -:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 -:10320000044A5A6002F188325A6008BD90250020B5 -:10321000002002402301674508B5054B1B7833B9F0 -:10322000FFF7DAFF034A136943F08003136108BD17 -:1032300090250020002002407F289ABF00F58030B2 -:10324000C0020020704700004FF40060704700008B -:10325000802070477F2808B50BD8FFF7EDFF00F5F9 -:1032600000630268013204D104308342F9D10120A5 -:1032700008BD0020FCE700007F2838B5044623D8AD -:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 -:10329000DA6002221A6105462046FFF7CDFF586129 -:1032A0001A6942F040021A614FF40061FFF794FF7F -:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 -:1032C000BDE83840FFF7C6BF002038BD00200240EF -:1032D00012F001032DE9F04704460E46154606D0CC -:1032E000244B40F2BD221A600020BDE8F08781180F -:1032F000214A914204D91F4A40F2C2211160F3E7EA -:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 -:1033100031464FF0010AA61B012D06EB0107884636 -:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E -:103330000030C9F810A03B800024FFF74DFFC9F80A -:1033400010403B8831F8022B9BB29A420FD0094BB8 -:1033500040F2D9221A60094B1F60094B1D60094BCE -:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 -:10337000D2E700BF8C250020000004088025002033 -:10338000882500208425002000200240084908B537 -:103390000B7828B11BB9FFF729FF01230B7008BD7B -:1033A000002BFCD0BDE808400870FFF735BF00BF18 -:1033B0009025002030B583B0FFF718FE0E4B0F4D5F -:1033C0001B6A2A684FF47A7101FB03F3934237BFFB -:1033D0000B4A0B49516814682B602EBFD1E900419C -:1033E000013151601C1941F100010191FFF708FE04 -:1033F0000199204603B030BD04240020942500200C -:103400009825002030B583B0FFF7F0FD114B124D29 -:103410001B6A2A684FF47A7101FB03F3934237BFAA -:103420000E4A0E49516814682B602EBFD1E9004145 -:10343000013151601C1941F100010191FFF7E0FDDC -:1034400001994FF47A7200232046FCF7A9FE03B0DD -:1034500030BD00BF042400209425002098250020C2 -:1034600010B50244064BD2B2904200D110BD441CAC -:1034700000B253F8200041F8040BE0B2F4E700BFBB -:10348000502800400F4B30B51C6A240407D41C6A36 -:1034900044F440741C621C6A44F400441C620A4CEC -:1034A000236843F4807323600244084BD2B29042F5 -:1034B00000D130BD441C00B251F8045B43F82050E9 -:1034C000E0B2F4E7001002400070004050280040D5 -:1034D00007B5012201A90020FFF7C2FF019803B040 -:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 -:1034F000012201A900200194FFF7C4FF02B010BD12 -:1035000070470000074B45F255521A6002225A607C -:1035100040F6FF729A604CF6CC421A60024B0122D0 -:103520001A70704700300040A4250020034B1B7820 -:103530001BB1034B4AF6AA221A607047A42500204B -:1035400000300040044B1A682AB902F1804202F5AB -:103550000432526A1A607047A0250020024B4FF0D7 -:1035600080725A62704700BF0010024008B5FFF732 -:10357000E9FF024B1868C0F3407008BDA025002089 -:10358000EFF3098305494A6B22F001024A6368336D -:1035900083F30988002383F31188704700EF00E06C -:1035A000202080F3118862B60C4B0D4AD96821F4B3 -:1035B000E0610904090C0A43DA60D3F8FC200949E8 -:1035C00042F08072C3F8FC200A6842F001020A60EF -:1035D0001022DA7783F82200704700BF00ED00E088 -:1035E0000003FA05001000E010B5202383F31188D2 -:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 -:103600000984683C4FF08073E361094BDB6B2366F0 -:1036100084F30988FFF79AFC10B1064BA36110BD33 -:10362000054BFBE783F31188F9E700BF00ED00E0ED -:1036300000EF00E0FB050008FE05000870470000F1 -:10364000FEE700000A4B0B480B4A90420BD30B4B92 -:10365000DA1C121AC11E22F003028B4238BF00226C -:103660000021FDF7ADBE53F8041B40F8041BECE746 -:10367000183D0008282600202826002028260020A3 -:10368000704700004B6843608B688360CB68C36001 -:103690000B6943614B6903628B6943620B6803608A -:1036A0007047000008B51B4B9A6A42F4FC029A620C -:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB -:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 -:1036D00002F11C0100F58060FFF7D4FF02F1380110 -:1036E00000F58060FFF7CEFF02F1540100F5806025 -:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D -:1037000002F18C0100F58060FFF7BCFFBDE80840C6 -:1037100000F05AB800100240483C000808B500F01C -:1037200093F9FFF741FCBDE80840FFF70BBF00002D -:103730007047000010B5214CA36A63F4FC03A36238 -:10374000A36A03F4FC03A3624FF0FF32A36A236968 -:1037500022612369002323612169E168E260E26854 -:10376000E360E268E269164942F08052E261E26990 -:103770000A6842F480720A60226A02F44072B2F56A -:10378000407F1EBF4FF4803222622362236A1B04F3 -:1037900007D4236A43F440732362236A43F400434B -:1037A000236200F031F9A369064A43F00103A361E3 -:1037B000A369136843F02003136010BD001002409A -:1037C00000700040000001401E4B1A6842F00102E8 -:1037D0001A601A689007FCD55A6822F003025A60F2 -:1037E0005A6812F00C02FBD1196801F0F901196056 -:1037F0005A601A6842F480321A601A689103FCD544 -:10380000114A5A604FF40452DA6230221A631A687D -:1038100042F080721A601A689201FCD50B4912229C -:103820000A600A6802F00702022AFAD15A6842F0D6 -:1038300002025A605A6802F00C02082AFAD11A6B86 -:103840001A6370470010024000241D00002002404F -:10385000084A08B5516913680B4003F0010353612E -:1038600023B1054A13680BB150689847BDE808407A -:10387000FFF7BABE00040140A8250020084A08B599 -:10388000516913680B4003F00203536123B1054AE9 -:1038900093680BB1D0689847BDE80840FFF7A4BE15 -:1038A00000040140A8250020084A08B551691368A2 -:1038B0000B4003F00403536123B1054A13690BB1B4 -:1038C00050699847BDE80840FFF78EBE00040140EC -:1038D000A8250020084A08B5516913680B4003F079 -:1038E0000803536123B1054A93690BB1D069984726 -:1038F000BDE80840FFF778BE00040140A82500207D -:10390000084A08B5516913680B4003F0100353616E -:1039100023B1054A136A0BB1506A9847BDE80840C5 -:10392000FFF762BE00040140A8250020174B10B528 -:103930005A691C68144004F478725A61A30604D5CD -:10394000134A936A0BB1D06A9847600604D5104AAF -:10395000136B0BB1506B9847210604D50C4A936B3F -:103960000BB1D06B9847E20504D5094A136C0BB133 -:10397000506C9847A30504D5054A936C0BB1D06CE5 -:103980009847BDE81040FFF72FBE00BF000401407C -:10399000A82500201A4B10B55A691C68144004F47D -:1039A0007C425A61620504D5164A136D0BB1506D05 -:1039B0009847230504D5134A936D0BB1D06D9847F2 -:1039C000E00404D50F4A136E0BB1506E9847A10462 -:1039D00004D50C4A936E0BB1D06E9847620404D59F -:1039E000084A136F0BB1506F9847230404D5054A5A -:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F -:103A000000040140A8250020062108B50846FEF75D -:103A1000CBFF06210720FEF7C7FF06210820FEF78F -:103A2000C3FF06210920FEF7BFFF06210A20FEF78B -:103A3000BBFF06211720FEF7B7FFBDE808400621AF -:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 -:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE -:103A6000084000F001B8000000F00EB80023054A3D -:103A700019460133102BC2E9001102F10802F8D1F6 -:103A8000704700BFA82500204FF0E023044A5A6188 -:103A900000229A6107221A6108210B20FEF79ABFC3 -:103AA0003F19010008B5202383F31188FFF79CFA22 -:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 -:103AC0000840FFF791BD000010B501390244904253 -:103AD00001D1002005E0037811F8014FA34201D085 -:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E -:103AF00017780144044603F1FF3C8C42204601D96B -:103B0000002009E00578BD4204F10104F5D10CEB79 -:103B10000405D618A54201D1BDE8F08115F8018D44 -:103B200016F801EDF045F5D0E7E70000034611F87F -:103B3000012B03F8012B002AF9D170476F72672E11 -:103B40006172647570696C6F742E61705F706572FC -:103B50006970685F48574553430000004E6F20610D -:103B60007070207369670A00426164206677206C78 -:103B7000656E6774682025750A0042616420626F73 -:103B80006172645F69642025752073686F756C6469 -:103B90002062652025750A004261642066772064F2 -:103BA000657363726970746F72206C656E67746898 -:103BB0002025750A004261642061707020435243E1 -:103BC000203078253038783A3078253038782030F1 -:103BD00078253038783A3078253038780A00476FC1 -:103BE0006F64206669726D776172650A0040A2E4B5 -:103BF000F16468910600000000000000B12D00088B -:103C00009D2D0008D92D0008C52D0008D12D0008D4 -:103C1000BD2D0008A92D0008952D0008E52D0008F0 -:103C20006D61696E0000000069646C650000000051 -:103C3000283C0008482400208025002001000000C6 -:103C4000A52F000800000000A001A82A0000000025 -:103C5000FAAABEAA50001424EFFF0000007700006B -:103C6000709709000100000000000000AAAAAAAA9B -:103C700001000000FFFF0000000000000000000045 -:103C80000000000000000000AAAAAAAA000000008C -:103C9000FFFF000000000000000000000000000026 -:103CA00000000000AAAAAAAA00000000FFFF00006E -:103CB0000000000000000000000000000000000004 -:103CC000AAAAAAAA00000000FFFF0000000000004E -:103CD000000000000000000000000000AAAAAAAA3C -:103CE00000000000FFFF00000000000000000000D6 -:103CF000E0C4FF7F01000000EC03000000000000B2 -:103D000000980300000000006400000000000000B4 -:083D1000FE2A0100D2040000AC +:1000000000090020B5040008CD250008852500085A +:10001000AD25000885250008A5250008B7040008BF +:10002000B7040008B7040008B7040008C135000889 +:10003000B7040008B7040008B704000875430008B7 +:10004000B7040008B7040008B7040008B7040008A4 +:10005000B7040008B70400085940000885400008AC +:10006000B1400008DD40000809410008B70400085D +:10007000B7040008B7040008B7040008B704000874 +:10008000B7040008B7040008B704000839250008C1 +:100090006525000875250008B704000835410008EB +:1000A000B7040008B7040008B7040008B704000844 +:1000B000B7040008B7040008B7040008B704000834 +:1000C000B7040008B7040008B7040008B704000824 +:1000D000B70400086545000879450008B704000822 +:1000E0009D410008B7040008B7040008B7040008E1 +:1000F000B7040008B7040008B7040008B7040008F4 +:10010000B7040008B7040008B7040008B7040008E3 +:10011000B7040008B7040008B7040008B7040008D3 +:10012000B7040008B7040008B7040008B7040008C3 +:10013000B7040008B7040008B7040008B7040008B3 +:10014000B7040008B7040008B7040008B7040008A3 +:10015000B7040008B7040008B7040008B704000893 +:10016000B7040008B7040008B7040008B704000883 +:10017000B7040008B7040008B7040008B704000873 +:10018000B7040008B7040008B7040008B704000863 +:10019000B7040008B7040008B7040008B704000853 +:1001A0002112000800000000000000000000000014 +:1001B00053B94AB9002908BF00281CBF4FF0FF31CE +:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA +:1001D00000F006F8DDF804E0DDE9022304B0704722 +:1001E0002DE9F047089D04468E46002B4DD18A42EA +:1001F000944669D9B2FA82F252B101FA02F3C2F11D +:10020000200120FA01F10CFA02FC41EA030E9440AD +:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE +:1002200016E341EA034306FB07F199420AD91CEBA6 +:10023000030306F1FF3080F01F81994240F21C81D8 +:10024000023E63445B1AA4B2B3FBF8F008FB103320 +:1002500044EA034400FB07F7A7420AD91CEB040455 +:1002600000F1FF3380F00A81A74240F20781644425 +:10027000023840EA0640E41B00261DB1D4400023AA +:10028000C5E900433146BDE8F0878B4209D9002D0E +:1002900000F0EF800026C5E9000130463146BDE898 +:1002A000F087B3FA83F6002E4AD18B4202D3824202 +:1002B00000F2F980841A61EB030301209E46002DB1 +:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 +:1002D000002A40F09280A1EB0C014FEA1C471FFA64 +:1002E0008CFE0126200CB1FBF7F307FB131140EA4B +:1002F00001410EFB03F0884208D91CEB010103F118 +:10030000FF3802D2884200F2CB804346091AA4B2D9 +:10031000B1FBF7F007FB101144EA01440EFB00FEAD +:10032000A64508D91CEB040400F1FF3102D2A64512 +:1003300000F2BB800846A4EB0E0440EA03409CE7B1 +:10034000C6F12007B34022FA07FC4CEA030C20FA5E +:1003500007F401FA06F31C43F9404FEA1C4900FA7E +:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB +:1003700040EA014108FB0EF0884202FA06F20BD96E +:100380001CEB010108F1FF3A80F08880884240F2BE +:100390008580A8F102086144091AA4B2B1FBF9F002 +:1003A00009FB101144EA014100FB0EFE8E4508D9FD +:1003B0001CEB010100F1FF346CD28E456AD9023882 +:1003C000614440EA0840A0FB0294A1EB0E01A14267 +:1003D000C846A64656D353D05DB1B3EB080261EBD5 +:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF +:1003F000007100263146BDE8F087C2F12003D840E5 +:100400000CFA02FC21FA03F3914001434FEA1C4726 +:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 +:10042000064300FB0EF69E4204FA02F408D91CEBC8 +:10043000030300F1FF382FD29E422DD902386344C6 +:100440009B1B89B2B3FBF7F607FB163341EA034166 +:1004500006FB0EF38B4208D91CEB010106F1FF38B5 +:1004600016D28B4214D9023E6144C91A46EA0046AC +:1004700038E72E46284605E70646E3E61846F8E63E +:100480004B45A9D2B9EB020864EB0C0E0138A3E787 +:100490004646EAE7204694E74046D1E7D0467BE768 +:1004A000023B614432E7304609E76444023842E7E0 +:1004B000704700BF02E000F000F8FEE772B6374870 +:1004C00080F30888364880F3098836483649086042 +:1004D00040F20000CCF200004EF63471CEF2000182 +:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 +:1004F000F0004EF68851CEF200010860BFF34F8F36 +:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 +:10051000CEF200010860062080F31488BFF36F8FCD +:1005200003F04EFC03F0C2FC4FF055301F491B4A4C +:1005300091423CBF41F8040BFAE71D49184A914229 +:100540003CBF41F8040BFAE71A491B4A1B4B9A427D +:100550003EBF51F8040B42F8040BF8E7002018499D +:10056000184A91423CBF41F8040BFAE703F02CFC17 +:1005700003F0D8FC144C154DAC4203DA54F8041BBC +:100580008847F9E700F042F8114C124DAC4203DA0B +:1005900054F8041B8847F9E703F014BC0009002055 +:1005A000001100200000000808ED00E0000100201C +:1005B00000090020704B0008001100207C11002071 +:1005C00080110020583C0020A0010008A401000870 +:1005D000A4010008A40100082DE9F04F2DED108AB8 +:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 +:1005F000002383F311882846A047002003F06AF9FE +:10060000FEE703F0CDF800DFFEE70000F8B500F0EC +:1006100019FE03F079FB074603F0C8FB05460028E6 +:1006200040D12C4B9F423DD001339F423DD02A4BBD +:1006300027F0FF029A423BD1F8B200F03FFC2E4671 +:1006400042F2107400F040FC08B10024264601F08C +:10065000B1F888B3032000F045F80024264635B1F0 +:100660001E4B9F4203D003F099FB00242646002036 +:1006700003F054FB1A4B1B6913F0400322D00EB158 +:1006800000F046F800F052FC00F0DEFD01F0A6FF9D +:100690000546CCB101F0A2FF401BA04214D900F0E6 +:1006A00037F8F3E72E460024CCE704460126C9E7D5 +:1006B00006464FF47A74C5E7002CD0D04FF47A7414 +:1006C0000126CCE71C46DDE700F078FC012003F0B2 +:1006D00007F9DEE7010007B0000008B0263A09B0CC +:1006E00000040048084B187003280CD8DFE800F01D +:1006F00008050208022000F003BE022000F0F8BD49 +:10070000024B00225A6070478011002084110020A3 +:1007100038B501F04FF830B11F4B03221A701F4B50 +:1007200000225A6038BD1E4B1E4A19680131F9D0AB +:1007300004339342F9D11C4C194DD4F80428AA4231 +:10074000F0D31A4B9B6803F1006303F5D0439A4240 +:10075000E8D203F0F7FA03F009FB002000F08EFD69 +:100760000220FFF7BFFF124BDA690022DA61D96974 +:1007700099699A619B6972B64FF0E0233021C3F802 +:10078000085DD4F80038D4F8042881F311889D4618 +:1007900083F308881047C5E78011002084110020EA +:1007A00000680008206800080060000800110020B0 +:1007B00000100240094A136849F2690099B21B0C03 +:1007C00000FB01331360064B186844F2506182B29B +:1007D000000C01FB0200186080B270471411002069 +:1007E0001011002010B500211022044600F0A2FDD7 +:1007F000034B03CB206061601868A06010BD00BF90 +:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 +:100810006CAC40F2751207460D460EA80021C8F8D0 +:10082000001000F087FD4FF4C4720021204600F054 +:1008300081FD01F0D3FE254B4FF47A72B0FBF2F04C +:10084000186093E80700022384E807000DF5E970BB +:100850002382FFF7C7FF4EF603431D49238406A8F2 +:1008600004F0B6F8182384F832310DF2E3266B4415 +:100870000DF1300C1A4603CA6245306071601346B0 +:1008800006F10806F6D141460122204600F09EFD01 +:1008900000230393AB7E029305F11903019380B209 +:1008A0000123CDE904800093E97E06A3D3E9002368 +:1008B000384602F05BFA0DF54E7DBDE8F08100BFD1 +:1008C000AFF300809E6AC421818A46EE8C1100201D +:1008D000E04900082DE9F0412C4C237ADAB080463B +:1008E0000D465BBB27A9284600F080FE074600287E +:1008F00042D19DF89D60C82E3ED801464FF4A662B5 +:10090000204600F017FD4FF48073C4F8F8314FF41F +:100910000073C4F80C334FF44073C4F820343246EB +:100920000DF19E0104F1090000F0F2FC26449DF84F +:100930009C30777223720BB9EB7E237281220021E7 +:1009400006AC27A800F0F6FC0122214627A800F0FB +:1009500089FE00230393AB7E029305F1190380B255 +:1009600001932823CDE904400093E97E05A3D3E950 +:100970000023404602F0FAF95AB0BDE8F08100BF0A +:10098000AFF3008026417272DF25D7B7A83200206E +:10099000F0B5254E4FF48A7505FB0065F1B096F869 +:1009A000D83085F8DC300024D822214685F8E8408C +:1009B0003AA800F0BFFC06F1090000F0B3FCD5F83E +:1009C000E4308DF8F000C2B206AF06F109010DF176 +:1009D000F100CDE93A3400F09BFC394601223AA8F7 +:1009E00000F06CFE80B2CDE9047008230127CDE948 +:1009F000023706F1D803019330230093317A0B4874 +:100A000007A3D3E9002302F0B1F9A04206DD01F00B +:100A1000E5FDC5F8E000384671B0F0BD2046FBE7C3 +:100A200078F6339F93CACD8DA8320020A4210020F0 +:100A30002DE9F0411D4D1E4E1E4F86B0284602F096 +:100A4000C1F9034658B30024CDE90344ADF814407E +:100A5000027B8DF8142099684068029403AA03C2AF +:100A60001B68DFF8548043F00043029301F0B8FDA7 +:100A7000821941F10003009402A9384601F07CF884 +:100A8000A04205DD284602F0A1F988F80040D5E72C +:100A900098F80030072B05D8013388F8003006B0ED +:100AA000BDE8F081014802F091F9F8E7A4210020A7 +:100AB00040420F00D8210020DD37002070B50D46E0 +:100AC00014461E4602F0AEF850B9022E10D1012C89 +:100AD0000ED112A3D3E90023C5E90023012007E0CA +:100AE000282C10D005D8012C09D0052C0FD00020BF +:100AF00070BD302CFBD10BA3D3E90023ECE70BA393 +:100B0000D3E90023E8E70BA3D3E90023E4E70BA331 +:100B1000D3E90023E0E700BFAFF30080401DA12030 +:100B200026812A0B78F6339F93CACD8D9E6AC42105 +:100B3000818A46EE26417272DF25D7B7F017304A18 +:100B400039059E5638B505460E4C0021013500F09A +:100B5000B7FBA4F82C55B4F82C0500F099FB78B13C +:100B6000B4F82C0500F0A4FB014648B9B4F82C05F4 +:100B700000F0A6FBB4F82C350133A4F82C35EAE7D5 +:100B800038BD00BFA832002010B50A4B0A4A1A60CF +:100B900003F5805393F860203AB9DC6D2CB1204600 +:100BA00000F082FE204603F053FEBDE810400348EB +:100BB00000F07ABED8210020384A000820320020F8 +:100BC0002DE9F04F8FB000AF05460C4602F02AF831 +:100BD000002849D1237E022B1BD1E38A012B18D197 +:100BE00001F0FCFC0646FFF7E5FD03464FF4C87034 +:100BF000DFF8C482B3FBF0F206F5167602FB103381 +:100C000016FA83F3C8F80030E37E33B9A34B002211 +:100C10001A703C37BD46BDE8F08F07F1240120462D +:100C200000F0A2FC0028F4D107F11400FFF7DAFD70 +:100C300097F8264007F11401224607F1270003F038 +:100C400051FE0028E2D10F2C08D8944B1C70D8F824 +:100C50000030A3F51673C8F80030DAE797F82410CF +:100C6000284601F0D7FFD4E7E38A282B2BD010D8F1 +:100C7000012B23D0052BCCD1BFF34F8F8849894B53 +:100C8000CA6802F4E0621343CB60BFF34F8F00BF2A +:100C9000FDE7302BBDD1844EE17E327A9142B8D14E +:100CA000607E3146002291F8DC50854200F0A5803C +:100CB0000132042A01F58A71F5D1AAE721462846B6 +:100CC000FFF7A0FDA5E721462846FFF703FEA0E7B2 +:100CD000B2F8EC507B6005F103094FEA99094FEA3D +:100CE0008902D11DC908A8EBC1039D46EB4600212E +:100CF000584600F01FFB04F1EE012A4631445846E5 +:100D000000F006FB7B6813B9012000F0B7FA96F8F3 +:100D1000D20000F0BDFA044630B9307200F0D8FAC3 +:100D2000204600F0ABFAB1E0D6F8D4203AB996F8F4 +:100D3000D200B6F82C25824201D8FFF703FFD6F87F +:100D4000D4202A44944208D296F8D200B6F82C2532 +:100D50000130824201D8FFF7F5FE70685FFA89F230 +:100D6000594600F0EFFA08B9C54679E0726896F87E +:100D7000D2002A447260D6F8D42005EB0209C6F8E6 +:100D8000D49000F085FA814509D396F8D220D6F8A0 +:100D9000D4000132001B86F8D220C6F8D400FF2D03 +:100DA0000FD80024347200F093FA204600F066FA5F +:100DB00000F000FD3D4B188108B9FFF7A9FCC546BE +:100DC00027E7BB6896F8D9000AFB0362FB68D2F8F4 +:100DD000E41082F8E83001F58061C2F8E030C2F832 +:100DE000E410FFF7D5FDFFF723FE96F8D920013276 +:100DF00002F0030286F8D920B6E74FF48A7A0AFB9C +:100E000002F505F1EA013144204600F083FCF86068 +:100E100000287FF4FEAE3544012285F8E82001F079 +:100E2000DDFBD5F8E020D6ED007ADFED216A801AEF +:100E3000192838BF192040F6B832904228BF104612 +:100E4000B8EE677A07EE900AF8EEE77A67EEA67AD0 +:100E5000DFED186AE7EE267AFCEEE77AC6ED007A57 +:100E600096F8D930BB60BA6873680AFB02F432198D +:100E700092F8E81059B1D2F8E4108B42E8463FF4FA +:100E800027AF002182F8E810C2F8E010C546736869 +:100E9000064A9B0A01331381BBE600BF9D21002057 +:100EA00000ED00E00400FA05A83200208C110020BB +:100EB000CDCCCC3D6666663FA0210020014B18706A +:100EC000704700BF9811002038B54FF00054134B05 +:100ED00022689A4220D1124B627D12481A70237DFB +:100EE00003724FF48073C0F8F8314FF40073C0F808 +:100EF0000C3300254FF44073C0F820340A49C0F881 +:100F0000E450C922093000F003FAE02229462046C5 +:100F100000F010FA012038BD0020FCE79AAD44C56E +:100F200098110020A83200201600002037B500F0EC +:100F300041FC194D194928810223012218486B717F +:100F400001F0EAF900230193164B17490093174863 +:100F5000174B4FF4805201F035FE164B197811B142 +:100F6000124801F057FE01F039FB0446FFF722FC5E +:100F70004FF4C873B0FBF3F202FB130304F51670D1 +:100F800010FA83F00C4B186002F010FF08B10F2329 +:100F90002B8103B030BD00BF8C11002040420F00F8 +:100FA000D8210020BD0A00089C110020A4210020A7 +:100FB000C10B000898110020A02100202DE9F04F5E +:100FC0002DED028B8EA7D7E900670FF23C29D9E9F6 +:100FD0000089864C95B00DAD9FED828BFFF728FD03 +:100FE000DFF82CB200230C93ADF83C300D936B600E +:100FF00000230DF125028DED008B4FF0010A09A9A8 +:1010000058468DF825308DF824A001F035F99DF86B +:1010100024200023002A40F0AB80204601F002FE8D +:101020000546002847D1DFF8ECB101F0D7FADBF82C +:10103000003098423FD301F0D1FA0790FFF7BAFB96 +:10104000079A4FF4C873B0FBF3F101FB130302F5E9 +:10105000167010FA83F0CBF80000DFF8BCB19BF8F3 +:1010600000100791002914BF2B46534610A88DF895 +:101070003030FFF7B7FB0799C1F11002D2B2062A50 +:1010800010AB28BF062219440DF13100079200F081 +:101090003FF9079A0CAB0393182302930132544B88 +:1010A000D2B2CDE900A304923B463246204601F07D +:1010B000FFFD8BF8005001F091FA4E4A4E4D136837 +:1010C000C31AB3F57A7F32D3106001F089FA024671 +:1010D0000B46204601F084FE204601F0A3FD30B30C +:1010E0002B7ADFF838A1002B14BF032302238AF8E0 +:1010F000053001F073FA0DF1400B4FF47A730122C1 +:10110000B0FBF3F05946CAF80000504600F004FA6C +:1011100018230293394B019380B240F25513CDE965 +:1011200003B0009342464B46204601F0C1FD2B7AA6 +:10113000CBB101F053FA4FF0000A83464FF48A72A4 +:1011400095F8D900504400F0030002FB005393F8D7 +:10115000E81089B30AF1010ABAF1040FF0D12B7A31 +:10116000002B7FF438AF15B0BDEC028BBDE8F08FDB +:101170004FF0904110A84A6982F010024A61194666 +:10118000102200F0D7F80DF126030AAA0CA9584640 +:1011900000F0F0FD95E8030011AB83E803009DF833 +:1011A0003C308DF84C300C9B109310A9DDE90A23DC +:1011B000204601F0E9FF1BE7D3F8E01049B12B68A6 +:1011C000FA2B38BFFA23ABEB01010533B1EB430F28 +:1011D000C0D3FFF7DDFB4FF48A720028BAD1BEE717 +:1011E000AFF300800000000000000000A4210020F8 +:1011F0009C210020D8370020A8320020DC370020B6 +:10120000401DA12026812A0BF1C6A7C1D068080F76 +:10121000D8210020A02100209D2100208C11002039 +:1012200008B5054800F040FEBDE80840034A0449FF +:10123000002003F007BB00BFD82100201838002091 +:10124000890B00087047000070B502F013FC094ECE +:10125000094D3080002428683388834208D902F081 +:1012600005FC2B6804440133B4F5D04F2B60F2D356 +:1012700070BD00BF0C380020E037002002F086BCB3 +:1012800000F10060920000F5D04002F02DBC00009B +:10129000054B1A68054B1B889B1A834202D91044E0 +:1012A00002F0E4BB00207047E03700200C3800203B +:1012B000024B1B68184402F0DFBB00BFE037002080 +:1012C000024B1B68184402F0E9BB00BFE037002066 +:1012D000064991F8243033B10023086A81F824309C +:1012E0000822FFF7CDBF0120704700BFE437002080 +:1012F000022802BF4FF0904310229A61704700000D +:10130000022802BF4FF090434FF480129A61704759 +:1013100010B50023934203D0CC5CC4540133F9E7E9 +:1013200010BD000003460246D01A12F9011B002925 +:10133000FAD1704702440346934202D003F8011BDE +:10134000FAE770472DE9F8431F4D144695F824201D +:101350000746884652BBDFF870909CB395F824305E +:101360002BB92022FF2148462F62FFF7E3FF95F8B3 +:101370002400C0F10802A24228BF2246D6B241464C +:10138000920005EB8000FFF7C3FF95F82430A41B03 +:101390001E44F6B2082E17449044E4B285F8246047 +:1013A000DBD1FFF795FF0028D7D108E02B6A03EBCC +:1013B00082038342CFD0FFF78BFF0028CBD10020E0 +:1013C000BDE8F8830120FBE7E43700202DE9F04772 +:1013D0000D46044600219046284640F27912FFF758 +:1013E000A9FF234620220021284601F06FFE231D7D +:1013F00002222021284601F069FE631D03222221DA +:10140000284601F063FEA31D03222521284601F092 +:101410005DFE04F1080310222821284601F056FE43 +:1014200004F1100308223821284601F04FFE04F190 +:10143000110308224021284601F048FE04F112035E +:1014400008224821284601F041FE04F1140320221D +:101450005021284601F03AFE04F118034022702181 +:10146000284601F033FE04F120030822B02128466B +:1014700001F02CFE04F121030822B821284601F0D6 +:1014800025FE04F12207C0263B46314608222846A5 +:10149000083601F01BFEB6F5A07F07F10107F3D176 +:1014A00004F1320308223146284601F00FFE0027DE +:1014B00004F1330A94F832304FEAC7099F4209F524 +:1014C000A47615D3B8F1000F08D1314604F599730D +:1014D0000722284601F0FAFD09F24F16274694F834 +:1014E00032213B1B93420CD3F01DC008BDE8F087AE +:1014F0000AEB070308223146284601F0E7FD0137D1 +:10150000D8E707F2331331460822284601F0DEFD02 +:1015100008360137E3E7000013B50446084600210A +:1015200001602346C0F803102022019001F0CEFD97 +:101530000198231D0222202101F0C8FD0198631D9E +:101540000322222101F0C2FD0198A31D03222521BF +:1015500001F0BCFD019804F108031022282101F0DC +:10156000B5FD072002B010BDF7B50023047F009140 +:101570000E4607221946054601F06CFC731C0093C9 +:10158000012200230721284601F064FCC4B9B31CE2 +:101590000093052223460821284601F05BFC0D2418 +:1015A0003746B278BB1B934211D32B7FA88A0734EE +:1015B000E408BBB9844294BF0020012003B0F0BD11 +:1015C000AB8ADB00083BDB08B3700824E8E7FB1CB0 +:1015D0000093214600230822284601F03BFC0834F2 +:1015E0000137DEE7201A18BF0120E7E7F7B500232F +:1015F000047F00910E4608221946054601F02AFC98 +:10160000731CC4B90822009311462346284601F0F2 +:1016100021FC1024012372785F1C013B934211D3FB +:101620002B7FA88A0734E408BBB9844294BF00200A +:10163000012003B0F0BDAB8ADB00083BDB08737010 +:101640000824E7E7F31900932146002308222846DF +:1016500001F000FC08343B46DDE7201A18BF0120EA +:10166000E7E70000F8B50E46054614460021812242 +:101670003046FFF75FFE2B4608220021304601F07E +:1016800025FD7CB96B1C07220821304601F01EFDA8 +:101690000F2401236A785F1C013B934204D3E01DB1 +:1016A000C008F8BD0824F4E7EB19214608223046AB +:1016B00001F00CFD08343B46ECE70000F8B50E469F +:1016C000054614460021CE223046FFF733FE2B4656 +:1016D00028220021304601F0F9FC7CB905F108030D +:1016E00008222821304601F0F1FC30242F462A7AC6 +:1016F0007B1B934204D3E01DC008F8BD2824F5E706 +:1017000007F1090321460822304601F0DFFC0834C6 +:101710000137ECE7F7B5047F00910E460123102254 +:101720000021054601F096FBC4B9B31C00930922C1 +:1017300023461021284601F08DFB19243746728874 +:10174000BB1B9A4211D82B7FA88A0734E408BBB987 +:10175000844294BF0020012003B0F0BDAB8ADB00BF +:10176000103BDB0873801024E8E73B1D0093214603 +:1017700000230822284601F06DFB08340137DEE71C +:10178000201A18BF0120E7E730B5094D0A449142FD +:101790000DD011F8013B5840082340F30004013BF1 +:1017A0002C4013F0FF0384EA5000F6D1EFE730BD80 +:1017B0002083B8EDF7B5364A106851686B4603C30D +:1017C0006A4634493448082303F09CF8044690BB29 +:1017D0000A25324A106851686B4603C36A4630498D +:1017E0002D48082303F08EF80446002847D00369EB +:1017F000B3F5663F43D8B0F86620B2F57B7F3ED1A3 +:10180000284A024402F15C018B4238D35C3B2249F6 +:1018100000209E1AFFF7B8FF3246074604F1640124 +:101820000020FFF7B1FFA3689F4228D1E3689842E8 +:1018300008BF002523E00369B3F5663F26D8428B35 +:10184000B2F57B7F20D1174A024402F110018B428E +:1018500018D3103B104900209D1AFFF795FF2A4628 +:10186000064604F118010020FFF78EFFA3689E4290 +:1018700002D1E368984201D00D25AAE70025284649 +:1018800003B0F0BD1025A4E70C25A2E70B25A0E7C7 +:10189000FC490008DC97030000680008054A0008BE +:1018A000909703000898FFF710B5037C044613B91E +:1018B000006803F00FF8204610BD00000023BFF3BE +:1018C0005B8FC360BFF35B8FBFF35B8F8360BFF33E +:1018D0005B8F7047BFF35B8F0068BFF35B8F704710 +:1018E00070B505460C30FFF7F5FF05F10806044614 +:1018F0003046FFF7EFFFA04206D930466D68FFF78C +:10190000E9FF2544281A70BD3046FFF7E3FF201A8F +:10191000F9E7000070B50546406898B105F1080088 +:10192000FFF7D8FF05F10C0604463046FFF7D2FF5B +:101930008442304694BF6D680025FFF7CBFF013C21 +:101940002C44201A70BD000038B50C460546FFF740 +:10195000C7FFA04210D305F10800FFF7BBFF044406 +:101960006868B4FBF0F100FB1144BFF35B8F01200A +:10197000AC60BFF35B8F38BD0020FCE72DE9F04180 +:10198000144607460D46FFF7C5FF844228BF0446AC +:10199000D4B1B84658F80C6B4046FFF79BFF304473 +:1019A000286040467E68FFF795FF331A9C4203D8B3 +:1019B0006C600120BDE8F0816B60A41B3B68AB60EC +:1019C0002044E8600220F5E72046F3E738B50C46EE +:1019D0000546FFF79FFFA04210D305F10C00FFF76B +:1019E00079FF04446868B4FBF0F100FB1144BFF3D5 +:1019F0005B8F0120EC60BFF35B8F38BD0020FCE7FC +:101A00002DE9FF41884669460746FFF7B7FF6C4658 +:101A100006B204EBC6060025B44209D0626820680D +:101A200008EB0501FFF774FC636808341D44F3E715 +:101A300029463846FFF7CAFF284604B0BDE8F081C2 +:101A4000F8B505460C300F46FFF744FF05F10806D0 +:101A500004463046FFF73EFFA042304688BF6C6820 +:101A6000FFF738FF201A386020B130462C68FFF7A6 +:101A700031FF2044F8BD000073B5144606460D46FC +:101A8000FFF72EFF844228BF04460190DCB101A974 +:101A90003046FFF7D5FF019B33B93268C5E9023301 +:101AA000C5E9002401200CE09C4238BF0194286065 +:101AB000019868608442F5D93368AB60241AEC6001 +:101AC000022002B070BD2046FBE700002DE9FF4177 +:101AD0000F466946FFF7D0FF6C4600B204EBC00525 +:101AE0000026AC4209D0D4F8048054F8081BB81979 +:101AF0004246FFF70DFC4644F3E7304604B0BDE82C +:101B0000F081000038B50546FFF7E0FF04460146C6 +:101B10002846FFF719FF204638BD0000302383F325 +:101B2000118862B670470000002383F3118862B603 +:101B30007047000010B4026854681A4623465DF8E6 +:101B4000044B184701207047002070470020704761 +:101B500070470000002070470E20704700F580504D +:101B600090F8C800C0F340007047000000F58050B6 +:101B700090F9C90070470000F7B50C68BDF82070F7 +:101B800014F000541E466FD10B7B082B6CD8FFF766 +:101B9000C5FF4569AB685B010CD4AB681B0108D479 +:101BA000AC6814F080545DD1FFF7BEFF204603B04F +:101BB000F0BD01240B6804F1180C002BB8BFDB004A +:101BC0004FEA0C1CB4BF43F004035B0545F80C302E +:101BD0000B680FFA84FC13F0804F18BF05EB0C1E46 +:101BE00005EB0C1C1EBFDEF8803143F00203CEF87B +:101BF00080310B7BCCF8843105EB04158B68C5F87C +:101C00008C314B68C5F88831DCF8803143F0010332 +:101C1000CCF8803100EB441541F268031D4403EB1E +:101C200044130344C5E9002608330D4601F10C0CAA +:101C300055F804EB43F804EB6545F9D184342D885D +:101C40001D8000EB441407F00303257925F00B05F4 +:101C50002B432371FFF768FF0097334600F0E0FC49 +:101C60000120A4E70224A5E74FF0FF309FE7000022 +:101C700013B500F580540191E06DFFF74BFE1F286E +:101C80000AD90199E06D2022FFF7BAFEA0F12003E6 +:101C90005842584102B010BD0020FBE708B500F5DE +:101CA0008050FFF73BFFC06DFFF708FEBDE808401E +:101CB000FFF73ABF00220260828142608260704773 +:101CC00010B500220023C0E900230023044603814D +:101CD0000C30FFF7EFFF204610BD0000F0B50546C1 +:101CE00000F580500C4690F8C83013F0040FC3F391 +:101CF000800108BF114661F3820304F1840680F875 +:101D0000C83005EB461389B01B79D8072ED57AB3B6 +:101D100019072DD46846FFF7D3FF05EB441303F5ED +:101D2000835303F1180703AA10331868596814463F +:101D300003C40833BB422246F7D1186820609B8851 +:101D4000A380DDE90E23CDE900230123ADF808309F +:101D50002B686946DB6B2846984705EB46152B79BF +:101D60001A075CBF43F008032B7101E0002AF4D18D +:101D700009B0F0BD2DE9F047074688B007F580545B +:101D800068469A468846FFF7C9FE9146FFF798FFD6 +:101D9000E06DFFF7A5FD1F2829D9E06D20226946D7 +:101DA000FFF7B0FE202822D103AD444605AB2E46F6 +:101DB00003CE9E4220606160354604F10804F6D1EE +:101DC00030682060B388A380DDE90023C9E90023DF +:101DD000BDF80830AAF80030FFF7A6FE4A46534681 +:101DE0004146384608B0BDE8F04700F007BCFFF7B1 +:101DF0009BFE002008B0BDE8F08700002DE9F84FF9 +:101E00000023C0E90133254B044640F8183B0F4638 +:101E1000FFF750FF04F12800FFF752FF04F14808D4 +:101E200004F582554646083530462036FFF748FF10 +:101E3000AE42F9D104F580554FF480534FF00009BC +:101E4000C5E91339C5F848800123EE6504F58758C4 +:101E500004F58456C5F8549085F8583085F86030FC +:101E6000083608F108084FF0000A4FF0000B46E969 +:101E700008ABA6F11800FFF71DFF203646F8289C96 +:101E80004645F4D185F8C97017B1054800F0A0FBAC +:101E9000044B63612046BDE8F88F00BF384A000854 +:101EA000104A00080064004010B5044B197804463D +:101EB0004A1C1A70FFF7A2FF204610BD14380020FC +:101EC0002DE9F047002950D0294B2A4FB7FBF1F5F7 +:101ED00099428CBF0A231123581EB5FBF3FC03FB68 +:101EE0001C53C4B22BB102280346F5D80020BDE82C +:101EF000F0870CF1FF36B6F5806FF7D2C4EBC40E55 +:101F00000EF103034FEAE309C3F3C703A4EB03088D +:101F100009F1010A4FF47A755FFA88F009FB05555B +:101F20005AFA88F8B5FBF8F5B5F5617FC1BF0EF137 +:101F3000FF33C3F3C703E01AC0B25C1C50FA84F449 +:101F40000CFB04F4B7FBF4F4A142CFD1013BDBB2AC +:101F50000F2BCBD80138C0B20728C7D80021107189 +:101F600016809170D3700120C1E70846BFE700BF1B +:101F70003F420F000051250270B505460E464FF452 +:101F80007A746B695B6803F00103B3424FF00100A0 +:101F900004D001F0A5FC013CF3D1204670BD000047 +:101FA00030B54269936913F0700F16D000230B4CC3 +:101FB000936103F1840200EB421211794D0709D5B8 +:101FC000890707D5416954F823508D60117941F094 +:101FD000040111710133032BEBD130BD244A0008F9 +:101FE00073B51D46436916469A68D207044609D55B +:101FF0009A6801219960C2F34002CDE90065002191 +:10200000FFF76CFE63699A68D1050BD59A684FF4A7 +:1020100080719960C2F34022CDE90065012120461C +:10202000FFF75CFE63699A68D2030BD59A684FF498 +:1020300080319960C2F34042CDE90065022120461B +:10204000FFF74CFE204602B0BDE87040FFF7A8BF86 +:10205000F8B50446466900296CD106F10C073868CA +:1020600080076AD006EB01153868D5F8B00110F08A +:10207000040FD5F8B0011ABFC00840F00040400D71 +:10208000A061D5F8B0C11CF0020F1CBF40F0804029 +:10209000A061D5F8B40106EB011100F00F0084F83F +:1020A0002400D1F8B8012077D1F8B801000A607790 +:1020B000D1F8B801000CA077D1F8B801000EE07794 +:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 +:1020D0002100D1F8BC01000C84F82200D1F8BC1119 +:1020E000090E84F823103821396004F1340004F11A +:1020F000180104F1240551F8046B40F8046BA9425F +:10210000F9D109880180C4E90A23214600232386E6 +:1021100051F8283B2046DB6B984704F58052204657 +:1021200092F8C83043F0040382F8C830BDE8F840A4 +:10213000FFF736BF06F1100791E7F8BD10B504466A +:1021400000F04EFA02460B4652EA030102D0013A71 +:1021500063F100030449086820B12146BDE810403E +:10216000FFF776BF10BD00BF10380020F8B500F5AE +:1021700083511E46FFF7D2FCDFF844C0083100242B +:1021800004F1840500EB45152B795F070ED4DB06BF +:102190000CD5D1E900739742B34107D243695CF88B +:1021A00024709F602B7943F004032B710134032CBE +:1021B00001F12001E4D1BDE8F840FFF7B5BC00BF54 +:1021C000244A000808B5FFF7A9FCFFF7E9FEBDE8BF +:1021D0000840FFF7A9BC0000F8B5436905469868B8 +:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C +:1021F00095FC05F583541034002606F1840305EBA5 +:1022000043131B791A0706D50136032E04F1200467 +:10221000F3D1012007E05B07F6D42146384600F0F1 +:1022200039FA0028F0D1FFF77FFCF8BD0120FCE768 +:1022300000F5805008B5FFF771FCC06DFFF750FB4B +:10224000FFF772FC43090CBF0120002008BD00000D +:10225000F8B51D46002313700F4606461446FFF7D7 +:10226000E7FF80F00100387025B129463046FFF7BE +:10227000B3FF2070F8BD00002DE9B8410C461546AB +:102280001F46804600F0ACF90B462178024609B99A +:10229000287850B14046FFF769FFFFF793FF3B46B0 +:1022A0002A462146FFF7D4FF0120BDE8B88100008F +:1022B00010B5FFF733FC174BDA6942F00072DA61B0 +:1022C0001A6942F000721A611A6900F5805422F00E +:1022D00000721A61FFF728FC94F8C830DB0718D4A5 +:1022E000B9B103211320FFF719FC01F0C7F903214D +:1022F000142001F0C3F90321152001F0BFF994F86F +:10230000C83043F0010384F8C830BDE81040FFF73F +:102310000BBC10BD001002402DE9F04700F58055C0 +:1023200088B095F8C930012B0446884616467FD8F8 +:10233000804F57F823200AB947F82300D7F800A0A8 +:10234000C4F80C802674BAF1000F63D095F8C93038 +:10235000012B6FD001212046FFF7AAFFFFF7DEFB1C +:102360006269136823F0020313606269136843F023 +:1023700001031360636900275F6101212046FFF7B5 +:10238000D3FBFFF7F9FD002800F09580E86DFFF71B +:1023900095FA04F58359BA4609F10809202200216B +:1023A0006846FEF7C7FF02A8FFF784FCCDF818A027 +:1023B0006A4609EB07030DF1180E9446BCE80300CA +:1023C000F44518605960624603F10803F5D1DCF862 +:1023D0000000186020379CF804201A71602FDDD1AE +:1023E00095F8C8306FF38203002785F8C8306A4635 +:1023F00041462046ADF80070ADF802708DF80470CB +:10240000FFF75EFD636948BB4FF400421A6008B0F5 +:10241000BDE8F08741F2D00002F01CFA814610B10D +:102420005146FFF7EBFCC7F80090B9F1000F8DD1D2 +:102430000020ECE7386803681B6B984701460028CA +:1024400088D13868FFF734FF3868036832465B6824 +:102450004146984700287FF47DAFE9E761221A6082 +:102460009DF802309DF803201B06120402F470222E +:1024700003F040731343BDF80020C2F30902134375 +:102480009DF804201205022E02F4E0020CBF4FF06A +:1024900000410021134362690B43D3616369132236 +:1024A0005A616269136823F00103136039462046BC +:1024B000FFF762FD08B96369A6E795F8C93093BBD9 +:1024C0006169D1F8002242F00102C1F8002261697D +:1024D000D1F8002222F47C5222F00E02C1F8002230 +:1024E0006169D1F8002242F46062C1F80022626999 +:1024F000C2F814326269C2F80432626941F6FF71AF +:10250000C2F80C126269C2F840326269C2F8443201 +:1025100063690122C3F81C226269D2F8003223F0F9 +:102520000103C2F8003295F8C83043F0020385F881 +:10253000C8306CE71038002008B500F051F850EAB8 +:102540000103024602D0421E61F10001044B1868EB +:1025500010B10B46FFF744FDBDE8084001F064B838 +:102560001038002008B50020FFF7E8FDBDE808405E +:1025700001F05AB808B50120FFF7E0FDBDE80840BA +:1025800001F052B800B59BB0EFF3098168226846AC +:10259000FEF7BEFEEFF30583014B9B6BFEE700BF2A +:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF +:1025B000EFF3098168226846FEF7AAFEEFF3058370 +:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 +:1025D0000FB408B5029801F019F9FEE701F02EBB1F +:1025E00001F004BB13B56C4684E80600031D94E8B3 +:1025F000030083E80500012002B010BD73B58568B3 +:10260000019155B11B885B0707D4D0E900369B6B5D +:102610009847019AC1B23046A847012002B070BD68 +:10262000F0B5866889B005460C465EB1BDF8383015 +:102630005B070AD4D0E900379B6B98472246C1B2AA +:102640003846B047012009B0F0BD00220023CDE993 +:1026500000230023ADF808300A4603AB01F1080659 +:10266000106851681C4603C40832B2422346F7D1B1 +:10267000106820609288A280FFF7B2FF0423ADF8B3 +:1026800008302B68CDE90001DB6B69462846984786 +:10269000D8E7000030B503680968DD0FB5EBD17FDE +:1026A00023F0604421F060424FEAD1700BD0002B40 +:1026B000B8BFA40C0029B8BF920C944202D034BF1A +:1026C0000120002030BD944205D1C1F38070C3F3D6 +:1026D00080738342F6D194422CBF00200120F1E7A1 +:1026E0002DE9F041456A15B94162BDE8F0814B68BA +:1026F00023F06047C3F38A464FEAD37EC3F3807862 +:1027000016EA230638BF3E46AC462B465A68BEEB57 +:10271000D27F22F060440AD0002A18DAA40CB44216 +:1027200017D19D420FD10D60DEE71346EEE7A742B9 +:1027300007D102F08044C2F3807242450BD054B1FD +:10274000EFE708D2EDE7CCF800100B60CDE7B4421C +:1027500001D0B442E5D81A689C46002AE5D1196038 +:10276000C3E700002DE9F047089D01F007044FEA98 +:10277000D508224405F0070500EBD1004FF47F494E +:10278000944201D1BDE8F08704F0070705F0070A7D +:1027900057453E4638BF5646C6F10806111B8E42C5 +:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 +:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 +:1027C00047FA0AF739408CEA010C03F80EC034448A +:1027D0003544D5E780EA0120082341F2210201B205 +:1027E0004000002980B203F1FF33B8BF504013F01E +:1027F000FF03F4D17047000038B50C468D18A54290 +:1028000000D138BD14F8011BFFF7E4FFF7E7000023 +:1028100042684AB1136843604389818901339BB29E +:102820009942438138BF83811046704770B588B0A4 +:10283000202204460D4668460021FEF77BFD204617 +:102840000495FFF7E5FF024658B16B46054608AE12 +:102850001C4603CCB44228606960234605F1080594 +:10286000F6D1104608B070BD082817D909280CD039 +:102870000A280CD00B280CD00C280CD00D280CD01A +:102880000E2814BF4020302070470C2070471020C5 +:1028900070471420704718207047202070470000B0 +:1028A000082817D90C280CD910280CD914280CD9B1 +:1028B00018280CD920280CD930288CBF0F200E20C6 +:1028C0007047092070470A2070470B2070470C2082 +:1028D00070470D20704700002DE9F843078C072F43 +:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 +:1028F0002006A5F1200029FA05F108FA06F628FAC3 +:1029000000F031430143C9B21846FFF763FF0835B1 +:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 +:102920006BBF4FF6FF70BDE8F883000010B54B6831 +:1029300023B9CA8A63F30902CA8210BD04691A68FE +:102940001C600361C38A013BC3824A60EFE7000059 +:102950002DE9F84F1D46CB8A0F46C3F3090105291F +:10296000814692460B4630D00020AAB207F11A04E5 +:102970009EB2042E1FFA80F80FD8904503F1010390 +:1029800006D3FB8A0A4462F30903FB8201201AE0A2 +:102990001AF80060E6540130EAE79045F1D2A1F15F +:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 +:1029B0008BF6002C45D14846FFF72AFF044638B96C +:1029C00078606FF00200BDE8F88F4FF00008E6E78E +:1029D000002606607860ADB24FF0000B454510D977 +:1029E0000AEB0803221D13F8011B9155B1B208F13F +:1029F00001081B291FFA88F82BD0454506F101066E +:102A0000F1D8FB8AC3F30902154465F30903BCE757 +:102A1000013292B21C462368002BF9D16B1F0B4484 +:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 +:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 +:102A4000BFE70122E7E7C0F800B05E462060044619 +:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 +:102A6000AFE7C0F800B0002620600446B6E70000DB +:102A70002DE9F04F2DED028B1C4683B05B6901926E +:102A800007468846002B00F09A80238C2BB1E26920 +:102A9000002A00F09480072B35D807F10C00FFF7CF +:102AA000B7FE054638B96FF00205284603B0BDEC05 +:102AB000028BBDE8F08F14220021FEF73BFC228C34 +:102AC000E16905F10800FEF723FC208C013080B29B +:102AD000FFF7E6FEFFF7C8FE013880B22084013020 +:102AE00028746369228C1B782A4403F01F0363F067 +:102AF0003F0348F000411372384669602946FFF7EA +:102B0000EFFD0125D1E700F10C034FF0000908EEBD +:102B1000103A4FF0800A4E464D4618EE100AFFF765 +:102B200077FE83460028BED014220021FEF702FC67 +:102B3000002E3AD1019BABF8083002220BF1080EAF +:102B40001FFA82FC0CF10100BCF1060F218C80B24F +:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 +:102B60001278013802F01F028E4208BF4FF0400A6F +:102B700042EA49121BFA80F14AEA020A013048F09F +:102B8000004281F808A08BF81000CBF804205946C9 +:102B90003846FFF7A5FD238C0135B3422DB289F0ED +:102BA00001094FF0000AB8D17FE70022C6E7E169CA +:102BB000895D0EF802100136B6B20132C0E76FF03F +:102BC000010572E7F8B515460E463022002104468D +:102BD0001F46FEF7AFFB069B6360B5F5001F079B22 +:102BE000A76034BF6A094FF6FF72A36297B2E6612D +:102BF00004F1100000239A4206D800230360A78244 +:102C0000E3822383E360F8BD06600133304620365B +:102C1000F1E7000003781BB94BB2002BC8BF01706D +:102C20007047000000787047F8B50C46C969074640 +:102C300011B9238C002B37D1257E1F2D34D838783D +:102C400028BB228C072A2CD8268A36F003032BD1E6 +:102C50004FF6FF70FFF7D0FD20F001003102400475 +:102C600041EA0561400C41EA40254FF6FF722346D8 +:102C700029463846FFF7FCFE002807DD6269137815 +:102C80000133DBB21F2B88BF00231370F8BD218AEC +:102C90002D0645EA012505432046FFF71DFE0246A5 +:102CA000E5E76FF00300F1E76FF00100EEE70000E9 +:102CB00070B58AB0044616460021282268461D4693 +:102CC000FEF738FBBDF83830ADF810300F9B059398 +:102CD0009DF840308DF81830119B07936946BDF878 +:102CE0004830ADF820302046CDE90265FFF79CFF63 +:102CF0000AB070BD2DE9F041D36905460C46164671 +:102D00000BB9138C5BBB377E1F2F28D895F800803A +:102D1000B8F1000F26D03046FFF7DEFD33782102F0 +:102D200041EAC33141EA0801338A41EA076141EAD5 +:102D300003410246334641F080012846FFF798FEE2 +:102D400000280ADD3378012B07D17269137801332B +:102D5000DBB21F2B88BF00231370BDE8F0816FF03A +:102D60000100FAE76FF00300F7E70000F0B58BB061 +:102D700004460D4617460021282268461E46FEF7E7 +:102D8000D9FA9DF84C305A1E534253418DF8003009 +:102D90009DF84030ADF81030119B05939DF84830F8 +:102DA0008DF81830149B07936A46BDF85430ADF87F +:102DB000203029462046CDE90276FFF79BFF0BB075 +:102DC000F0BD0000406A00B104307047436A1A68E1 +:102DD000426202691A600361C38A013BC382704781 +:102DE0002DE9F041D0F82080194E14461D46414689 +:102DF000002709B9BDE8F081D1E90223A21A65EBE9 +:102E00000303964277EB03031ED2036A8B420DD174 +:102E1000FFF78CFD036A1B68036203690B60C38ABA +:102E20000161016A013BC3828846E2E7FFF77EFD4C +:102E30000B68C8F8003003690B60C38A0161013B6D +:102E4000C382D8F80010D4E788460968D1E700BFEC +:102E500080841E002DE9F04F8BB00D46DDF85090B8 +:102E600014469B468046002800F01981B9F1000FF6 +:102E700000F01581531E3F2B00F21181012A03D16E +:102E8000BBF1000F40F00B810023CDE90833B8F807 +:102E90001430B5EBC30F4FEAC30703D300200BB0C8 +:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A +:102EB000FFB227461BB9D8F81030002B7AD0272D47 +:102EC0004ED8C5F12806B7424FF000032CBFF6B22A +:102ED0003E4600932946D8F8080008AB3246FFF773 +:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 +:102EF00003F10053053BDB000493D8F80C30039337 +:102F00002821039B13B1BAF1000F2CD1D8F810007F +:102F100040B1BAF1000F05D0009608AB5246691ACD +:102F2000FFF720FC38B2002FB8D066070AD00AABF2 +:102F300003EBD401624211F8083C02F0070213418E +:102F400001F8083C082C3CD9102C40F2B580202C0C +:102F500040F2B780BBF1000F00F09C80082334E002 +:102F6000BA460026C2E7049BE02B28BFE023069365 +:102F70000B44AB42059314D95A1B03980096924513 +:102F800034BF5246D2B2691A08AB04300792FFF739 +:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 +:102FA0008AFA049B069A05999B1A0493039B1B6853 +:102FB0000393A6E70093D8F8080008AB3A462946E1 +:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD +:102FD000082C12D89DF82030621E23FA02F2D50781 +:102FE00006D54FF0FF3202FA04F423438DF8203067 +:102FF0009DF8203089F8003051E7102C12D8BDF828 +:103000002030621E23FA02F2D10706D54FF0FF32BC +:1030100002FA04F42343ADF82030BDF82030A9F8BB +:1030200000303CE7202C0FD80899631E21FA03F3E7 +:10303000DA0705D54FF0FF3202FA04F40C43089486 +:10304000089BC9F800302AE7402C2BD0DDE9086541 +:10305000611EC4F12102A4F1210326FA01F105FA4F +:1030600002F225FA03F311431943CB0712D50122CB +:10307000A4F12003C4F1200102FA03F322FA01F1C2 +:10308000A240524243EA010363EB430332432B4322 +:10309000CDE90823DDE90823C9E90023FFE66FF045 +:1030A0000100FCE66FF00800F9E6082CA0D9102C0E +:1030B000B3D9202CEED8C3E7BBF1000FADD002236B +:1030C00083E7BBF1000FBBD004237EE730B5012AB4 +:1030D000144638BF0124402C85B028BF4024002569 +:1030E000012ACDE9025518D81B788DF808306307FE +:1030F0000AD004AB03EBD405624215F8083C02F099 +:103100000702934005F8083C00910346224600213F +:1031100002A8FFF727FB05B030BD082AE4D9102A22 +:1031200003D81B88ADF80830E1E7202A8DBFD3E92A +:1031300000231B680293CDE90223D8E710B5CB68C2 +:103140001BB98B600B618B8210BD04691A681C600F +:103150000361C38A013BC382CA60F0E703064CBF28 +:10316000C0F3C0300220704708B50246FFF7F6FFF3 +:10317000022806D15306C2F30F2001D100F003004C +:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E +:1031900003230A6804461046FFF7E0FF022814BF25 +:1031A000C2F306260026002A0D46824680F2F281EE +:1031B00012F0C04940F0EE81097B002900F0EA815D +:1031C000022803D02378B34240F0E781C2F30463BE +:1031D0000693104602F07F030593FFF7C5FF059B9A +:1031E00029444FEA834848EA0A4848EA4668CE78C4 +:1031F00000230022CDE90823F309834648EA0008AA +:10320000029367D0059B009302466768534608A95E +:103210002046B847002800F0C381276A4FB94146CD +:1032200004F10C00FFF702FB074690B96FF00200B3 +:1032300054E03B6998450DD03F68002FF9D14146D5 +:1032400004F10C00FFF7F2FA07460028EED0236ADB +:103250003B60276297F817C006F01F08CCF3840C78 +:10326000ACEB08001FFA80FE0028B8BF0EF120006A +:10327000A8EB0C031FFA83FED7E90221B8BF00B206 +:10328000002B0793BEBF0EF120031BB2079352EA37 +:10329000010338D0039BDFF824E39A1A049B4FF014 +:1032A000000C63EB010196457CEB01032BD36B7B98 +:1032B00097F81AE0734519D1029B002B78D00128AA +:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF +:1032D00016D337E0276A27B96FF00C0013B0BDE8AA +:1032E000F08F3B699845B5D03F68F4E7B24890420B +:1032F0007CEB010301D30020F0E7029B002BFAD006 +:10330000079B0F2B17DCFA7DB30002F0030203F0DA +:103310007C031343FB7539462046FFF707FB6B7BA5 +:10332000BB76029B3BB9FB7DC3F38402013262F39F +:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A +:10334000002B35D0B309022B32D0039BBB60049B0A +:10335000FB60142200210DA8FDF7ECFF039B0A93EC +:10336000049B0B932B1D0C932B7BADF83EB0013BC4 +:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 +:10338000433094F82C308DF840A083F001038DF881 +:1033900044308DF84180A3680AA920469847FB7DF8 +:1033A000C3F38403013303F01F039B02FB82A2E7F4 +:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 +:1033C0008403434540F0F280029A2B7BB609002A21 +:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 +:1033E000049BFB602B7BAE1D033BDBB232463946B0 +:1033F00004F10C00FFF7ACFA00280CDA394620463D +:10340000FFF794FAFB7DC3F38403013303F01F033A +:103410009B02FB820AE7DDE90884AB883B834FF619 +:10342000FF73C9F12000A9F1200228FA09F104FA7A +:1034300000F0014324FA02F211431846C9B2FFF723 +:10344000C9F909F10809B9F1400F0346E9D1B88279 +:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 +:10346000DA43C2F3C01262F3C713FB7543E786B9B0 +:103470002E1D013BDBB23246394604F10C00FFF74A +:1034800067FA0028BADB2A7BB88A013AD2B2314601 +:10349000E2E7F98AC1F30901013B0429DAB25BD8FA +:1034A000281D002307F11B069A4208D910F801CB0A +:1034B00006F801C0013101330529DBB2F4D10399CB +:1034C0000A9104990B91934207F11B010C9138BFAB +:1034D000043379680D9134BF55FA83F300230E93BA +:1034E000FB8AADF83EB0C3F309031A44069B8DF87E +:1034F0004230059B8DF8433094F82C30ADF83C20D9 +:1035000083F001038DF8443000238DF840A08DF83E +:1035100041807B602A7BB88A013A291DFFF76CF94C +:103520003B8BB882834203D1A3680AA920469847FF +:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 +:10354000013303F01F039B02FB823B8B9A420CBFAB +:1035500000206FF01000C1E67B68002BAFD0052083 +:1035600001E01C3033461E68002EFAD1091A081DEE +:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 +:103580009DD89A429BD916F8013B00F8013B09F1FE +:103590000109EFE76FF00900A0E66FF00A009DE671 +:1035A0006FF00B009AE66FF00D0097E66FF00E00DB +:1035B00094E66FF00F0091E640420F0080841E00F9 +:1035C000EFF3098305494A6B22F001024A6368332D +:1035D00083F30988002383F31188704700EF00E02C +:1035E000302080F3118862B60C4B0D4AD96821F463 +:1035F000E0610904090C0A43DA60D3F8FC200949A8 +:1036000042F08072C3F8FC200A6842F001020A60AE +:103610002022DA7783F82200704700BF00ED00E037 +:103620000003FA05001000E010B5302383F3118881 +:103630000E4B5B6813F4006314D0F1EE103AEFF315 +:103640000984683C4FF08073E361094BDB6B2366B0 +:1036500084F3098800F098F810B1064BA36110BDFF +:10366000054BFBE783F31188F9E700BF00ED00E0AD +:1036700000EF00E0030600080606000800F16043C2 +:1036800003F561430901C9B283F80013012200F078 +:103690001F039A4043099B0003F1604303F5614314 +:1036A000C3F880211A60704700F16040090100F5FD +:1036B0006D40C9B2017670470023037582680369C3 +:1036C0001B6899689142FBD25A680360426010609F +:1036D0005860704700230375826803691B68996806 +:1036E0009142FBD85A68036042601060586070478E +:1036F00008B50846302383F311880B7D032B05D0D2 +:10370000042B0DD02BB983F3118808BD8B690022DF +:103710001A604FF0FF338361FFF7CEFF0023F2E71B +:10372000D1E9003213605A60F3E70000FFF7C4BF2D +:10373000054BD9680875186802681A605360012241 +:103740000275D860FCF748BF2038002030B50C4B1C +:10375000DD684B1C87B004460FD02B46094A6846EB +:1037600000F0FEF82046FFF7E3FF009B13B1684628 +:1037700000F000F9A86907B030BDFFF7D9FFF9E7FD +:1037800020380020F1360008044B1A68DB68906886 +:103790009B68984294BF0020012070472038002089 +:1037A000084B10B51C68D86822681A605360012263 +:1037B0002275DC60FFF78EFF01462046BDE8104011 +:1037C000FCF70ABF20380020044B1A68DB689268B7 +:1037D0009B689A4201D9FFF7E3BF70472038002069 +:1037E00038B5074C07490848012300252370656058 +:1037F00000F00AFB0223237085F3118838BD00BF57 +:10380000483A00207C4A00082038002008B572B6EB +:10381000044B186500F0CEF900F092FA024B032237 +:103820001A70FEE720380020483A002000F0B4B8B3 +:10383000EFF3118020B9EFF30583302282F3118872 +:103840007047000010B530B9EFF30584C4F30804E5 +:1038500014B180F3118810BDFFF7B6FF84F311880F +:10386000F9E700008B60022308618B8208467047ED +:103870008368A3F1840243F8142C026943F8442CB2 +:10388000426943F8402C094A43F8242CC26843F8A3 +:10389000182C022203F80C2C002203F80B2C044AEB +:1038A00043F8102CA3F12000704700BFF105000879 +:1038B0002038002008B5FFF7DBFFBDE80840FFF720 +:1038C00035BF0000024BDB6898610F20FFF730BF67 +:1038D00020380020302383F31188FFF7F3BF000066 +:1038E00008B50146302383F311880820FFF72EFF27 +:1038F000002383F3118808BD064BDB6839B14268A9 +:1039000018605A60136043600420FFF71FBF4FF038 +:10391000FF307047203800200368984206D01A68AC +:103920000260506099611846FFF700BF70470000C1 +:1039300010B50A4C23699A6891420CD85A68816084 +:103940000360426010609A685860511A99604FF0A5 +:10395000FF33A36110BD1B68891AECE720380020F3 +:1039600010B4C0E9032300235DF8044B4361FFF763 +:10397000DFBF0000036881689A680A449A60426861 +:1039800013605A6000230360024B4FF0FF329A61CC +:10399000704700BF2038002070B5124DEB692A46F1 +:1039A0000133EB6152F8103F934206D09A68013A16 +:1039B0009A6030262C69A36803B170BDD4E9002158 +:1039C0000A605160236083F31188D4E903312046F3 +:1039D000984786F3118861690029EBD02046FFF7EC +:1039E000A7FFE7E72038002000207047FEE700002F +:1039F000704700004FF0FF3070470000BFF34F8F5B +:103A0000024AD368DB07FCD4704700BF00200240A5 +:103A100008B5074B1B7853B9FFF7F0FF054B1A6940 +:103A2000120641BF044A5A6002F188325A6008BD4A +:103A3000603A0020002002402301674508B5054B8D +:103A40001B7833B9FFF7DAFF034A136943F08003A9 +:103A5000136108BD603A0020002002407F289ABF11 +:103A600000F58030C0020020704700004FF4006075 +:103A700070470000802070477F2808B50BD8FFF7FB +:103A8000EDFF00F500630268013204D10430834287 +:103A9000F9D1012008BD0020FCE700007F2810B507 +:103AA00004461CD8FFF7AAFFFFF7B2FF0D4BF32225 +:103AB000DA6002221A61FFF7D1FF58611A6942F0F9 +:103AC00040021A614FF40061FFF798FF00F034F9EB +:103AD000FFF7B4FF2046BDE81040FFF7CDBF002040 +:103AE00010BD00BF002002402DE9F84312F0010391 +:103AF000144606D01F4B40F2F3221A600020BDE8A6 +:103B0000F88385181C4A954204D91A4A4FF43E712D +:103B10001160F3E7FFF77CFFFFF770FFDFF86880C5 +:103B2000451A4FF00109012C05EB01060F4603D899 +:103B3000FFF784FF0120E2E73B88C8F8109033804C +:103B40000020FFF75BFFC8F81000338831F8022B24 +:103B50009BB29A420CD0074B40F20F321A60074BCF +:103B60001E60074B1C60074B1F60FFF767FFC6E72F +:103B7000023CD8E75C3A002000000408503A0020DC +:103B8000583A0020543A002000200240084908B565 +:103B90000B7828B11BB9FFF73BFF01230B7008BD61 +:103BA000002BFCD0BDE808400870FFF747BF00BFFE +:103BB000603A002008B54FF420414FF0005000F06B +:103BC000BDF8BDE808404FF400514FF0805000F0C0 +:103BD000B5B800000846114600F05EBE012000F0B6 +:103BE0005BBE0000084600F075BE000030B583B033 +:103BF000FFF71EFE0E4B0F4DDB692A684FF47A71FA +:103C000001FB03F3934237BF0B4A0B495168146819 +:103C10002B602EBFD1E90041013151601C1941F1E7 +:103C200000010191FFF70EFE0199204603B030BD5F +:103C300020380020643A0020683A002030B583B074 +:103C4000FFF7F6FD114B124DDB692A684FF47A71CC +:103C500001FB03F3934237BF0E4A0E4951681468C3 +:103C60002B602EBFD1E90041013151601C1941F197 +:103C700000010191FFF7E6FD01994FF47A720023EC +:103C80002046FCF795FA03B030BD00BF2038002075 +:103C9000643A0020683A002010B50244064BD2B2C4 +:103CA000904200D110BD441C00B253F8200041F8EE +:103CB000040BE0B2F4E700BF502800400F4B30B5D2 +:103CC0001C6A240407D41C6A44F440741C621C6AF5 +:103CD00044F400441C620A4C236843F4807323605C +:103CE0000244084BD2B2904200D130BD441C00B215 +:103CF00051F8045B43F82050E0B2F4E700100240B2 +:103D0000007000405028004007B5012201A90020A2 +:103D1000FFF7C2FF019803B05DF804FB13B504463A +:103D2000FFF7F2FFA04205D0012201A90020019473 +:103D3000FFF7C4FF02B010BD7047000070470000DD +:103D400070470000074B45F255521A6002225A6034 +:103D500040F6FF729A604CF6CC421A60024B012288 +:103D60001A70704700300040743A0020034B1B78F3 +:103D70001BB1034B4AF6AA221A607047743A00201E +:103D800000300040044B1A682AB902F1804202F563 +:103D90000432526A1A607047703A0020024B4FF0AA +:103DA00080725A62704700BF0010024008B5FFF7EA +:103DB000E9FF024B1868C0F3407008BD703A00205C +:103DC00070470000FEE700000A4B0B480B4A904288 +:103DD0000BD30B4BDA1C121AC11E22F003028B42CA +:103DE00038BF00220021FDF7A5BA53F8041B40F8A4 +:103DF000041BECE7EC4B0008583C0020583C00202A +:103E0000583C0020FEE7000070B51B4B0163002505 +:103E1000044686B0586085620E46FFF7E1FB04F168 +:103E20001003C4E904334FF0FF33A361134BE56182 +:103E3000D969A5600A462B46C4E9082304F1340178 +:103E4000C4E900440E4AE562256580232046FFF759 +:103E500009FD0123E0600B4A03750092726801922C +:103E6000B268CDE90223084B6846CDE90435FFF777 +:103E700021FD06B070BD00BF483A00202038002068 +:103E8000884A00088D4A0008053E00084B684360D8 +:103E90008B688360CB68C3600B6943614B690362C5 +:103EA0008B6943620B6803607047000008B51B4BC9 +:103EB0009A6A42F4FC029A629A6A22F4FC029A62BA +:103EC0009A6A5A6942F4FC025A61154A5B691146C2 +:103ED0004FF09040FFF7DAFF02F11C0100F580601F +:103EE000FFF7D4FF02F1380100F58060FFF7CEFF45 +:103EF00002F1540100F58060FFF7C8FF02F1700184 +:103F000000F58060FFF7C2FF02F18C0100F58060D0 +:103F1000FFF7BCFFBDE8084000F05AB800100240AF +:103F2000944A000808B500F093F9FFF759FCBDE882 +:103F30000840FFF727BF00007047000010B5214C74 +:103F4000A36A63F4FC03A362A36A03F4FC03A36201 +:103F50004FF0FF32A36A23692261236900232361A2 +:103F60002169E168E260E268E360E268E2691649BB +:103F700042F08052E261E2690A6842F480720A60AB +:103F8000226A02F44072B2F5407F1EBF4FF48032C5 +:103F900022622362236A1B0407D4236A43F440731A +:103FA0002362236A43F40043236200F031F9A369DA +:103FB000064A43F00103A361A369136843F0200399 +:103FC000136010BD0010024000700040000001406E +:103FD0001E4B1A6842F001021A601A689007FCD55D +:103FE0005A6822F003025A605A6812F00C02FBD1A0 +:103FF000196801F0F90119605A601A6842F48032B8 +:104000001A601A689103FCD5114A5A604FF40452A1 +:10401000DA6230221A631A6842F080721A601A68F3 +:104020009201FCD50B4912220A600A6802F00702CD +:10403000022AFAD15A6842F002025A605A6802F023 +:104040000C02082AFAD11A6B1A637047001002405A +:1040500000241D0000200240084A08B55169136879 +:104060000B4003F00103536123B1054A13680BB100 +:1040700050689847BDE80840FFF7D6BA00040140F1 +:10408000783A0020084A08B5516913680B4003F0DC +:104090000203536123B1054A93680BB1D068984776 +:1040A000BDE80840FFF7C0BA00040140783A00209C +:1040B000084A08B5516913680B4003F004035361C3 +:1040C00023B1054A13690BB150699847BDE8084010 +:1040D000FFF7AABA00040140783A0020084A08B560 +:1040E000516913680B4003F00803536123B1054A7B +:1040F00093690BB1D0699847BDE80840FFF794BABF +:1041000000040140783A0020084A08B55169136854 +:104110000B4003F01003536123B1054A136A0BB13E +:10412000506A9847BDE80840FFF77EBA0004014096 +:10413000783A0020174B10B55A691C68144004F4F3 +:1041400078725A61A30604D5134A936A0BB1D06AF8 +:104150009847600604D5104A136B0BB1506B984713 +:10416000210604D50C4A936B0BB1D06B9847E2053E +:1041700004D5094A136C0BB1506C9847A30504D5BC +:10418000054A936C0BB1D06C9847BDE81040FFF71F +:104190004BBA00BF00040140783A00201A4B10B51A +:1041A0005A691C68144004F47C425A61620504D5C3 +:1041B000164A136D0BB1506D9847230504D5134A69 +:1041C000936D0BB1D06D9847E00404D50F4A136E80 +:1041D0000BB1506E9847A10404D50C4A936E0BB1F5 +:1041E000D06E9847620404D5084A136F0BB1506F24 +:1041F0009847230404D5054A936F0BB1D06F9847B5 +:10420000BDE81040FFF710BA00040140783A0020E2 +:10421000062108B50846FFF731FA06210720FFF707 +:104220002DFA06210820FFF729FA06210920FFF7B9 +:1042300025FA06210A20FFF721FA06211720FFF7A9 +:104240001DFABDE8084006212820FFF717BA000034 +:1042500008B5FFF773FE00F067F800F03DF8FFF7D0 +:104260006BFEBDE8084000F05DB8000002684368DE +:104270001143016003B1184770470000143000F08B +:104280002FBA00004FF0FF33143000F029BA0000BD +:10429000383000F0A5BA00004FF0FF33383000F09E +:1042A0009FBA0000143000F0F5B900004FF0FF3164 +:1042B000143000F0EFB90000383000F04FBA0000C1 +:1042C0004FF0FF32383000F049BA0000012914BF26 +:1042D0006FF013000020704700F06CB8044B0360CF +:1042E0000023C0E90233436001230374704700BF19 +:1042F0003C4B000838B5C36904460D461BB9042180 +:104300000844FFF7B3FF294604F1140000F0A6F9B2 +:10431000002806DA201D4FF40061BDE83840FFF7A1 +:10432000A5BF38BD00F00EB80023054A1946013379 +:10433000102BC2E9001102F10802F8D1704700BF4A +:10434000783A00204FF0E023044A5A6100229A6133 +:1043500007221A6108210B20FFF7A6B93F190100B7 +:1043600008B5302383F31188FFF760FA002383F345 +:10437000118808BD08B5FFF7F3FFBDE80840FFF757 +:1043800053B90000026843681143016003B1184744 +:1043900070470000024A136843F0C003136070477F +:1043A00000380140024A136843F0C00313607047AD +:1043B0000044004037B51D4C1D4D2046FFF78EFFD1 +:1043C000009404F114001B490023202200F038F966 +:1043D0002022009404F13800174B184900F0B2F97C +:1043E000174BC4E91735174C0C212520FFF746F968 +:1043F0002046FFF773FF04F11400134900940023D3 +:10440000202200F01DF904F13800104B10490094EF +:10441000202200F097F90F4B0C212620C4E9173514 +:1044200003B0BDE83040FFF729B900BFF83A0020DB +:1044300000512502D03B002095430008103C00208D +:1044400000380140643B0020F03B0020A5430008F9 +:10445000303C0020004400402DE9F047C66D37682D +:10446000F46934622107054619D014F0080118BF19 +:104470004FF48071E20748BF41F02001A30748BF15 +:1044800041F04001600748BF41F08001302383F3D1 +:104490001188281DFFF776FF002383F31188E205BA +:1044A0000AD5302383F311884FF48061281DFFF76C +:1044B00069FF002383F311884FF030094FF0000AA1 +:1044C00014F0200838D13B0616D54FF0300905F11D +:1044D000380A200610D589F31188504600F066F995 +:1044E000002836DA0821281DFFF74CFF27F080034B +:1044F0003360002383F31188790614D5620612D540 +:10450000302383F31188D5E913239A4208D12B6C09 +:1045100033B11021281D27F04007FFF733FF376024 +:10452000002383F31188E30619D5AA6E1369B3B18A +:10453000BDE8F0475069184789F31188B38C95F8A6 +:10454000641028461940FFF7D5FE8AF31188F469F4 +:10455000B6E780B2308588F31188F469B9E7BDE821 +:10456000F087000008B50348FFF776FFBDE8084074 +:10457000FFF75AB8F83A002008B50348FFF76CFF78 +:10458000BDE80840FFF750B8643B0020F8B5154679 +:1045900082680669AA420B46816938BF8568761A27 +:1045A000B54204460BD218462A46FCF7B1FEA36971 +:1045B0002B44A361A3685B1BA3602846F8BD0CD9FC +:1045C00018463246FCF7A4FEAF1BE1683A46304479 +:1045D000FCF79EFEE3683B44EBE718462A46FCF7EF +:1045E00097FEE368E5E7000083689342F7B5154658 +:1045F000044638BF8568D0E90460361AB5420BD24C +:104600002A46FCF785FE63692B446361A36828464C +:104610005B1BA36003B0F0BD0DD932460191FCF7DE +:1046200077FE0199E068AF1B3A463144FCF770FE13 +:10463000E3683B44E9E72A46FCF76AFEE368E4E7FF +:1046400010B50A440024C361029B8460C0E90000E5 +:10465000C0E90511C1600261036210BD08B5D0E96F +:104660000532934201D1826882B982680132826048 +:104670005A1C42611970D0E904329A4224BFC368BF +:1046800043610021FFF748F9002008BD4FF0FF30DB +:10469000FBE7000070B5302304460E4683F3118813 +:1046A000A568A5B1A368A269013BA360531CA361DF +:1046B00015782269934224BFE368A361E3690BB1D3 +:1046C00020469847002383F31188284607E03146A7 +:1046D0002046FFF711F90028E2DA85F3118870BD52 +:1046E0002DE9F74F04460E4617469846D0F81C9021 +:1046F0004FF0300A8AF311884FF0000B154665B170 +:104700002A4631462046FFF741FF034660B941463D +:104710002046FFF7F1F80028F1D0002383F3118839 +:10472000781B03B0BDE8F08FB9F1000F03D0019002 +:104730002046C847019B8BF31188ED1A1E448AF36B +:104740001188DCE7C0E90511C160C3611144009B19 +:104750008260C0E90000016103627047F8B5044659 +:104760000D461646302383F31188A768A7B1A368C6 +:10477000013BA36063695A1C62611D70D4E9043275 +:104780009A4224BFE3686361E3690BB1204698470E +:10479000002080F3118807E031462046FFF7ACF88F +:1047A0000028E2DA87F31188F8BD0000D0E905237C +:1047B0009A4210B501D182687AB98268013282606A +:1047C0005A1C82611C7803699A4224BFC3688361C2 +:1047D0000021FFF7A1F8204610BD4FF0FF30FBE7A6 +:1047E0002DE9F74F04460E4617469846D0F81C9020 +:1047F0004FF0300A8AF311884FF0000B154665B16F +:104800002A4631462046FFF7EFFE034660B941468F +:104810002046FFF771F80028F1D0002383F31188B8 +:10482000781B03B0BDE8F08FB9F1000F03D0019001 +:104830002046C847019B8BF31188ED1A1E448AF36A +:104840001188DCE70B460146184600F02DB8000041 +:1048500000F040B8012838BF012010B504462046BA +:1048600000F030F830B900F007F808B900F00CF8A3 +:104870008047F4E710BD0000024B1868BFF35B8F60 +:10488000704700BF503C002008B5062000F084F8B7 +:104890000120FFF7ABF80000024B0A4601461868FA +:1048A000FFF798B91811002010B5054C13462CB12C +:1048B0000A4601460220AFF3008010BD2046FCE707 +:1048C00000000000024B01461868FFF787B900BFDF +:1048D00018110020024B01461868FFF783B900BF8A +:1048E0001811002010B501390244904201D1002076 +:1048F00005E0037811F8014FA34201D0181B10BD49 +:104900000130F2E72DE9F041A3B1C91A177801444B +:10491000044603F1FF3C8C42204601D9002009E007 +:104920000578BD4204F10104F5D10CEB0405D6185D +:10493000A54201D1BDE8F08115F8018D16F801ED11 +:10494000F045F5D0E7E700001F2938B504460D46CD +:1049500004D9162303604FF0FF3038BD426C12B10A +:1049600052F821304BB9204600F030F82A46014673 +:104970002046BDE8384000F017B8012B0AD0591C7A +:1049800003D1162303600120E7E7002442F8254005 +:10499000284698470020E0E7024B01461868FFF7D9 +:1049A000D3BF00BF1811002038B5074D00230446BF +:1049B000084611462B60FFF71DF8431C02D12B68F7 +:1049C00003B1236038BD00BF543C0020FFF70CB892 +:1049D000034611F8012B03F8012B002AF9D1704787 +:1049E0006F72672E6172647570696C6F742E6633B6 +:1049F00030332D48574553430000000040A2E4F1F6 +:104A0000646891060041A3E5F26569920700000021 +:104A10004261642043414E496661636520696E646A +:104A200065782E00800000000080000000008000FB +:104A30000000000000000000351B000819230008DA +:104A400079220008451B0008791B0008751D000825 +:104A5000491B0008591B00084D1B0008551B000886 +:104A6000511B00089D1C00085D1B0008E52500087F +:104A70006D1B0008711C000863300000784A0008B4 +:104A800078380020483A00206D61696E0069646CD6 +:104A900065000000A001A82A00000000FAAABEAA32 +:104AA00050001424EFFF0000007700007097090009 +:104AB0000100000000000000AAAAAAAA010000004C +:104AC000FFFF0000000000000000000000000000E8 +:104AD00000000000AAAAAAAA00000000FFFF000030 +:104AE00000000000000000000000000000000000C6 +:104AF000AAAAAAAA00000000FFFF00000000000010 +:104B0000000000000000000000000000AAAAAAAAFD +:104B100000000000FFFF0000000000000000000097 +:104B20000000000000000000AAAAAAAA00000000DD +:104B3000FFFF000000000000000000000000000077 +:104B40009942000885420008C1420008AD420008B1 +:104B5000B9420008A5420008914200087D420008C1 +:104B6000CD4200087CB6FF7F01000000000000007D +:104B7000EC030000000000000098030000000000AB +:104B8000FE2A0100D20400001C11002000000000D9 +:104B90000000000000000000000000000000000015 +:104BA0000000000000000000000000000000000005 +:104BB00000000000000000000000000000000000F5 +:104BC00000000000000000000000000000000000E5 +:104BD00000000000000000000000000000000000D5 +:0C4BE000000000000000000000000000C9 :00000001FF diff --git a/Tools/bootloaders/f303-M10025_bl.bin b/Tools/bootloaders/f303-M10025_bl.bin index 0273a8c5c6a5f4..a0a56a32285786 100755 Binary files a/Tools/bootloaders/f303-M10025_bl.bin and b/Tools/bootloaders/f303-M10025_bl.bin differ diff --git a/Tools/bootloaders/f303-M10025_bl.hex b/Tools/bootloaders/f303-M10025_bl.hex index e67a02b507359f..7d09f547760507 100644 --- a/Tools/bootloaders/f303-M10025_bl.hex +++ b/Tools/bootloaders/f303-M10025_bl.hex @@ -1,980 +1,1217 @@ :020000040800F2 -:1000000000090020A5040008E1140008611400089C -:10001000B9140008611400088D140008A704000832 -:10002000A7040008A7040008A704000881350008F9 -:10003000A7040008A7040008A7040008B93A0008AC -:10004000A7040008A7040008A7040008A7040008E4 -:10005000A7040008A7040008513800087D380008EC -:10006000A9380008D538000801390008A70400089D -:10007000A7040008A7040008A7040008A7040008B4 -:10008000A7040008A7040008A70400082924000802 -:1000900095240008E92400083D2500082D390008B2 -:1000A000A7040008A7040008A7040008A704000884 -:1000B000A7040008A7040008A7040008A704000874 -:1000C000A7040008A7040008A7040008A704000864 -:1000D000A70400088129000895290008A704000842 -:1000E00095390008A7040008A7040008A704000821 -:1000F000A7040008A7040008A7040008A704000834 -:10010000A7040008A7040008A7040008A704000823 -:10011000A7040008A7040008A7040008A704000813 -:10012000A7040008A7040008A7040008A704000803 -:10013000A7040008A7040008A7040008A7040008F3 -:10014000A7040008A7040008A7040008A7040008E3 -:10015000A7040008A7040008A7040008A7040008D3 -:10016000A7040008A7040008A7040008A7040008C3 -:10017000A7040008A7040008A7040008A7040008B3 -:10018000A7040008A7040008A7040008A7040008A3 -:10019000A7040008A7040008A7040008A704000893 -:1001A00053B94AB9002908BF00281CBF4FF0FF31DE -:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA -:1001C00000F006F8DDF804E0DDE9022304B0704732 -:1001D0002DE9F047089D04468E46002B4DD18A42FA -:1001E000944669D9B2FA82F252B101FA02F3C2F12D -:1001F000200120FA01F10CFA02FC41EA030E9440BE -:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE -:1002100016E341EA034306FB07F199420AD91CEBB6 -:10022000030306F1FF3080F01F81994240F21C81E8 -:10023000023E63445B1AA4B2B3FBF8F008FB103330 -:1002400044EA034400FB07F7A7420AD91CEB040465 -:1002500000F1FF3380F00A81A74240F20781644435 -:10026000023840EA0640E41B00261DB1D4400023BA -:10027000C5E900433146BDE8F0878B4209D9002D1E -:1002800000F0EF800026C5E9000130463146BDE8A8 -:10029000F087B3FA83F6002E4AD18B4202D3824212 -:1002A00000F2F980841A61EB030301209E46002DC1 -:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 -:1002C000002A40F09280A1EB0C014FEA1C471FFA74 -:1002D0008CFE0126200CB1FBF7F307FB131140EA5B -:1002E00001410EFB03F0884208D91CEB010103F128 -:1002F000FF3802D2884200F2CB804346091AA4B2EA -:10030000B1FBF7F007FB101144EA01440EFB00FEBD -:10031000A64508D91CEB040400F1FF3102D2A64522 -:1003200000F2BB800846A4EB0E0440EA03409CE7C1 -:10033000C6F12007B34022FA07FC4CEA030C20FA6E -:1003400007F401FA06F31C43F9404FEA1C4900FA8E -:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B -:1003600040EA014108FB0EF0884202FA06F20BD97E -:100370001CEB010108F1FF3A80F08880884240F2CE -:100380008580A8F102086144091AA4B2B1FBF9F012 -:1003900009FB101144EA014100FB0EFE8E4508D90D -:1003A0001CEB010100F1FF346CD28E456AD9023892 -:1003B000614440EA0840A0FB0294A1EB0E01A14277 -:1003C000C846A64656D353D05DB1B3EB080261EBE5 -:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF -:1003E000007100263146BDE8F087C2F12003D840F5 -:1003F0000CFA02FC21FA03F3914001434FEA1C4737 -:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 -:10041000064300FB0EF69E4204FA02F408D91CEBD8 -:10042000030300F1FF382FD29E422DD902386344D6 -:100430009B1B89B2B3FBF7F607FB163341EA034176 -:1004400006FB0EF38B4208D91CEB010106F1FF38C5 -:1004500016D28B4214D9023E6144C91A46EA0046BC -:1004600038E72E46284605E70646E3E61846F8E64E -:100470004B45A9D2B9EB020864EB0C0E0138A3E797 -:100480004646EAE7204694E74046D1E7D0467BE778 -:10049000023B614432E7304609E76444023842E7F0 -:1004A000704700BF02E000F000F8FEE772B63A487D -:1004B00080F30888394880F3098839484EF6085196 -:1004C000CEF20001086040F20000CCF200004EF6CF -:1004D0003471CEF200010860BFF34F8FBFF36F8F0E -:1004E00040F20000C0F2F0004EF68851CEF200015A -:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 -:10050000100A4EF63C71CEF200010860062080F31E -:100510001488BFF36F8F03F0B3F803F08FF803F084 -:10052000C1F84FF055301F491B4A91423CBF41F87A -:10053000040BFAE71C49194A91423CBF41F8040BED -:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C -:1005500042F8040BF8E700201749184A91423CBFC3 -:1005600041F8040BFAE703F06DF803F0D7F8144CE8 -:10057000144DAC4203DA54F8041B8847F9E700F045 -:1005800041F8114C114DAC4203DA54F8041B884772 -:10059000F9E703F055B80000000900200011002021 -:1005A000000000080001002000090020F83C0008BD -:1005B00000110020201100202011002028260020FA -:1005C000A0010008A0010008A0010008A001000887 -:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F -:1005E000BDEC108ABDE8F08F002383F31188284604 -:1005F000A047002002F04CFDFEE702F0D1FC00DF36 -:10060000FEE700002DE9F04102F062FF074602F02C -:10061000ADFF054600283ED12B4B9F423BD0013316 -:100620009F423BD0294B27F0FF029A423AD1F8B2C1 -:1006300000F054FAA84642F2107400F059FC08B1D8 -:100640000024A04600F050FA064678B384BB464624 -:1006500035B11F4B9F4203D002F080FF0024264695 -:10066000002002F03FFF1B4B1B6913F0400322D018 -:100670000EB100F031F800F05FFC00F031FE00F048 -:1006800031FF0546CCB100F02DFF401BA04214D92C -:1006900000F022F8F3E7A8460024CEE704464FF026 -:1006A0000108CAE780464FF47A74C6E70446CFE7EC -:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 -:1006C00002F0ECFCDEE700BF010007B0000008B05C -:1006D000263A09B00004004838B51D4A1D4B196878 -:1006E000013134D004339342F9D11B4C194DD4F865 -:1006F0000428AA422BD3194B9B6803F1006303F52E -:10070000D0439A4223D202F0FDFE02F00FFF0020F8 -:1007100000F000FE124B0220187000F037FE114B63 -:10072000DA690022DA61D96999699A619B6972B6BE -:100730004FF0E0232021C3F8085DD4F80038D4F846 -:10074000042881F311889D4683F30888104738BD3B -:100750002068000800680008006000080011002000 -:100760002011002000100240094A136849F2690074 -:1007700099B21B0C00FB01331360064B186844F25E -:10078000506182B2000C01FB0200186080B2704719 -:100790001C1100201811002010B500211022044661 -:1007A00000F00EFE034B03CB206061601868A06070 -:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 -:1007C00000F090FEAB6840F2ED22C31A934232D99A -:1007D00006AFA8602B4628220021384601F05EFBB8 -:1007E00005F10E0000F0E4FD002604465FFA80F9F2 -:1007F00005F10E08F3B2F100994501F1280107D97E -:1008000008EB06030822384601F048FB0136F1E701 -:1008100008230122CDE9023205340C4B0193A4B226 -:1008200030230093CDE9047405A3D3E90023297B89 -:10083000074801F04BF93BB0BDE8F083AFF300800F -:1008400078F6339F93CACD8D682100207521002052 -:100850003C21002070B50D4614461E4601F0CCF830 -:1008600050B9022E10D1012C0ED112A3D3E90023CE -:10087000C5E90023012007E0282C10D005D8012C61 -:1008800009D0052C0FD0002070BD302CFBD10BA35C -:10089000D3E90023ECE70BA3D3E90023E8E70BA39C -:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B -:1008B000AFF30080401DA12026812A0B78F6339FDC -:1008C00093CACD8D9E6AC421818A46EE26417272FA -:1008D000DF25D7B7F017304A39059E5613B50446C1 -:1008E0002346084620220021019001F0D7FA227900 -:1008F0000198032A234628BF032203F8042F20214E -:10090000022201F0CBFA62790198072A234628BF18 -:10091000072203F8052F2221032201F0BFFAA27952 -:100920000198072A234628BF072203F8062F25210E -:10093000032201F0B3FA019804F1080310222821E0 -:1009400001F0ACFA382002B010BD00002DE9F04FE4 -:10095000ADF5017D21AD0EAE40F2751280460F4619 -:1009600022A80021296000F02BFD482200213046FA -:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 -:10098000F2F0186093E80700012386E807000DF1F4 -:100990005A003382FFF700FF4EF60343338407AB60 -:1009A00018464D4903F0C2F81822306429463046F3 -:1009B00086F83C20FFF792FF12AB0446014608225E -:1009C000284601F06BFA0822A1180DF149032846C8 -:1009D00001F064FA0DF14A03082204F110012846DF -:1009E00001F05CFA13AB202204F11801284601F053 -:1009F00055FA14AB402204F13801284601F04EFAB2 -:100A000016AB082204F17801284601F047FA0DF1EF -:100A10005903082204F18001284601F03FFA04F14D -:100A2000880A0DF15A0904F5847B4B465146082289 -:100A300028460AF1080A01F031FAD34509F1010903 -:100A4000F3D11BAB08225946284601F027FA04F5DA -:100A500088744FF0000996F834304B450AD9B36BCF -:100A600021464B440822284601F018FA083409F1BF -:100A70000109F0E74FF0000996F83C304B4504EBD4 -:100A8000C90108D9336C08224B44284601F006FA04 -:100A900009F10109F0E700230393BB7E02930731BC -:100AA00007F119030193C1F3CF010123CDE90451EB -:100AB0000093F97E05A3D3E90023404601F006F830 -:100AC0000DF5017DBDE8F08FAFF300809E6AC42173 -:100AD000818A46EE241100203C3B0008014B18702F -:100AE000704700BF30110020F0B5334B1C7B85B040 -:100AF00034B1324B0E221A810024204605B0F0BDDD -:100B00002F4A1068516802AB03C308232D492E48B1 -:100B10000DEB030202F0E8FF054630B9274B2B48E6 -:100B20000A221A8100F098FCE6E70169B1F5663FF8 -:100B300006D9224B26480B221A8100F08DFCDCE7F7 -:100B4000438BB3F57B7F09D01C4A22480C211181CD -:100B50004FF47B72194600F07FFCCEE71E4A024438 -:100B600002F11003994204D2144B1C4810221A813E -:100B7000E3E710398E1A2046134900F0B7FC3246DD -:100B8000074605F11801204600F0B0FCAB689F4213 -:100B900002D1EB6898420AD0084B0D221A810090CE -:100BA000D5E902123B460E4800F056FCA4E70D487A -:100BB00000F052FC0124A0E768210020241100204D -:100BC000E93B0008DC97030000680008583B000878 -:100BD000643B0008763B00080898FFF7943B000848 -:100BE000B13B0008DA3B00082DE9F04FADB006AF8D -:100BF00080460C4600F000FF054600285AD1237EAF -:100C0000022B1BD1E38A012B18D100F06BFC0646A6 -:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C -:100C2000F0F206F5167602FB103316FA83F3C9F8D4 -:100C30000030E37E33B9A84B00221A709C37BD46C2 -:100C4000BDE8F08FA38AEEB2013BB34205F1010586 -:100C50000BD93B1D1E44E90000960023082201F039 -:100C6000F801204600F0DEFFECE707F11400FFF783 -:100C700093FD324607F11401381D02F025FF0028CC -:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 -:100C90001673C9F80030D1E7FB1CF87001460093C9 -:100CA00007220346204600F0BDFFF978404600F0D9 -:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 -:100CC000052BBBD1BFF34F8F8449854BCA6802F413 -:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 -:100CE000ACD1637E7F4D01336A7BDBB29342E94630 -:100CF00003D1E27E2B7B9A4265D0CD469EE721460A -:100D00004046FFF723FE99E7A38A013B9BB2C92B1C -:100D100094D8744D2E7B26BB05F10C03009308225A -:100D200033463146204600F07DFF731CF2B2D900F5 -:100D30001E46A38A013B9A4205DA0E322A440092EB -:100D400000230822EEE700230022C5E90023002348 -:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 -:100D60002B73002507F114093B1D0822294648462C -:100D7000C7E90155FD6001F091F83B7A05F1010AE0 -:100D8000AB424FEACA0608D9FB6808222B44314619 -:100D9000484601F083F85546EFE7C6F3CF06E17EFB -:100DA000CDE9049600230393A37E029319342823EC -:100DB0000093019446A3D3E90023404600F086FE49 -:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 -:100DD00014801022009341460123204600F022FF98 -:100DE000A68A023EB6B2F31C9B109B000733DB08B9 -:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 -:100E0000C801B34201F110010AD20AEB08030093B2 -:100E100008220023204600F005FF08F10108ECE756 -:100E200095F8D70000F080FAD5F8D83004461BB901 -:100E300095F8D70000F088FAD5F8D83033449C42B2 -:100E400004D295F8D700013000F07EFA4FEA960BF5 -:100E50004FF000081FFA88F18B45D5E9003209D917 -:100E60000AEB880103EB8800012200F0B1FA08F1D7 -:100E70000108EFE7F31842F10002C5E90032D5F8A6 -:100E8000D83095F8D70006EB0308C5F8D88000F0F5 -:100E90004BFA804509D395F8D730D5F8D8000133FF -:100EA000001B85F8D730C5F8D800FF2E08D80023DE -:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D -:100EC0002B68094A9B0A013313810023AB6014E7A6 -:100ED00026417272DF25D7B73521002000ED00E0F2 -:100EE0000400FA0568210020241100203821002088 -:100EF00010B54FF000540C4B22689A4211D10B4BA5 -:100F0000627D1A700A48237D03730A49C9220E3094 -:100F100000F044FAE0220021204600F051FA0120BE -:100F200010BD0020FCE700BF9AAD44C53011002081 -:100F300068210020160000202DE9FF41434C0223C8 -:100F400063710023029324250A23581EB5FBF3F690 -:100F50007343D3F12402C1B23ED002280346F4D138 -:100F60009DF80B303A493B485A1E9DF80A30013B28 -:100F70001B0443EA0253BDF80820013A13434B60B7 -:100F800001F044FD00230193334B3449009334486E -:100F9000344B4FF4805200F001FD334B197811B1FE -:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D -:100FB0004FF4C873B0FBF3F202FB130305F5167090 -:100FC00010FA83F0294B186002F0D0FA08B10F2311 -:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF -:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA -:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F -:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 -:10101000CDB2591E0F2916D86A1E072A8CBF00228E -:101020000122591901FB06601149B1FBF0F1114889 -:10103000814295D1002A93D0ADF808608DF80A302E -:101040008DF80B508CE71346EBE700BF241100200E -:1010500010110020802200205508000834110020C3 -:101060003C210020E90B000830110020382100202D -:101070000051250240420F002DE9F04F90A7D7E91B -:1010800000670FF24429D9E90089874D93B0DFF852 -:1010900040B2864C284600F07DFD0DF1300A0790E5 -:1010A00070B310220021504600F08AF9079B197B8B -:1010B0004FF0000261F303028DF830205868996800 -:1010C0000EAA03C21B680D9A63F31C029DF8303010 -:1010D0000D9243F020038DF830300023524619461C -:1010E000584601F0A3FC079028B9284600F056FDA9 -:1010F000079B2370CEE72378072B3CD8013323705E -:1011000018220021504600F05BF9DFF8C4B100233B -:1011100019465246584601F0B1FC014678BB1022F0 -:1011200008A800F04DF94FF0904209AC536983F0E4 -:101130001003536100F0D8F90B4612A9024611E9D9 -:10114000030084E803009DF83410C1F3030089060E -:101150004CBF0E9CBDF838408DF82C0046BFC4F340 -:101160001C0444F00044C4F30A0408A92846089467 -:1011700000F0DCFECBE7284600F010FDC0E7284673 -:1011800000F03AFC0446002848D1DFF848B100F0EE -:10119000A9F9DBF80030984240D300F0A3F907909A -:1011A000FFF7E2FA079A8DF8204003464FF4C87023 -:1011B00002F51672B3FBF0F101FB103312FA83F360 -:1011C000CBF80030DFF810B19BF8001011B9012303 -:1011D0008DF8203050460791FFF7DEFA0799C1F1EC -:1011E0001004E4B2062C28BF0624224651440DF117 -:1011F000210000F0D3F808AB0393182302930134C5 -:101200002B4B0193E4B20123009304943B463246F6 -:10121000284600F0F3FB00238BF8003000F062F961 -:10122000244A254C1368C31AB3F57A7F31D3106072 -:1012300000F05AF902460B46284600F0B9FC284651 -:1012400000F0DAFB28B3237BDFF890B0002B14BF4B -:10125000032302238BF8053000F044F94FF47A732E -:101260005146B0FBF3F0CBF800005846FFF736FBD1 -:10127000182307300293114B0193C0F3CF0040F2C3 -:101280005513CDE903A0009342464B46284600F093 -:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 -:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 -:1012B0003421002048220020682100204C220020F8 -:1012C000401DA12026812A0BF1C6A7C1D068080FB6 -:1012D0008022002038210020352100202411002008 -:1012E00070B501F0B5FF094E094D30800024286823 -:1012F0003388834208D901F0A7FF2B6804440133E7 -:10130000B4F5D04F2B60F2D370BD00BF7C2200201B -:101310005022002002F03AB800F10060920000F57F -:10132000D04001F0D5BF0000054B1A68054B1B8863 -:101330009B1A834202D9104401F086BF00207047F7 -:10134000502200207C22002038B5074D0446286832 -:10135000204401F07FFF28B928682044BDE83840C8 -:1013600001F08ABF38BD00BF50220020064991F825 -:10137000243033B10023086A81F824300822FFF7B3 -:10138000CBBF0120704700BF54220020022802BFBB -:101390004FF090434FF480129A61704710B50023CC -:1013A000934203D0CC5CC4540133F9E710BD000074 -:1013B00003460246D01A12F9011B0029FAD17047E0 -:1013C00002440346934202D003F8011BFAE7704738 -:1013D0002DE9F8431F4D144695F82420074688460A -:1013E00052BBDFF870909CB395F824302BB92022C3 -:1013F000FF2148462F62FFF7E3FF95F82400C0F174 -:101400000802A24228BF2246D6B24146920005EB0E -:101410008000FFF7C3FF95F82430A41B1E44F6B2EA -:10142000082E17449044E4B285F82460DBD1FFF71E -:101430009DFF0028D7D108E02B6A03EB820383428B -:10144000CFD0FFF793FF0028CBD10020BDE8F88371 -:101450000120FBE7542200200FB4002004B07047A5 -:1014600000B59BB0EFF3098168226846FFF796FF4D -:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E -:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D -:10149000EFF3098168226846FFF780FFEFF30583C9 -:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF -:1014B000FEE700BF00ED00E000B59BB0EFF309814F -:1014C00068226846FFF76AFFEFF30583034B5A6B08 -:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 -:1014E000FEE7000001F08EBF01F064BF30B5094D8A -:1014F0000A4491420DD011F8013B5840082340F3B3 -:101500000004013B2C4013F0FF0384EA5000F6D1A5 -:10151000EFE730BD2083B8ED2DE9F041C56915B97D -:10152000C161BDE8F0814B6823F06047C3F38A4690 -:101530004FEAD37EC3F3807816EA230638BF3E46CF -:10154000AC462B465A68BEEBD27F22F060440AD0EC -:10155000002A18DAA40CB44217D19D420FD10D60B5 -:10156000DEE71346EEE7A74207D102F08044C2F35C -:10157000807242450BD054B1EFE708D2EDE7CCF8CA -:1015800000100B60CDE7B44201D0B442E5D81A6830 -:101590009C46002AE5D11960C3E700002DE9F04719 -:1015A000089D01F007044FEAD508224405F007051D -:1015B00000EBD1004FF47F49944201D1BDE8F087A0 -:1015C00004F0070705F0070A57453E4638BF564660 -:1015D000C6F10806111B8E4228BF0E46E10808EB33 -:1015E000D50E415C13F80EC0B94029FA06F721FA6E -:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 -:10160000010C03F80EC034443544D5E780EA0120CC -:10161000082341F2210201B24000002980B203F107 -:10162000FF33B8BF504013F0FF03F4D17047000000 -:1016300038B50C468D18A54200D138BD14F8011BF1 -:10164000FFF7E4FFF7E7000002684AB113680360A0 -:10165000C388018901339BB29942C38038BF03819B -:101660001046704770B588B0202204460D46684683 -:101670000021FFF7A5FE20460495FFF7E5FF02468F -:1016800058B16B46054608AE1C4603CCB4422860F0 -:101690006960234605F10805F6D1104608B070BD13 -:1016A000082817D909280CD00A280CD00B280CD0F0 -:1016B0000C280CD00D280CD00E2814BF4020302050 -:1016C00070470C2070471020704714207047182076 -:1016D0007047202070470000082817D90C280CD923 -:1016E00010280CD914280CD918280CD920280CD96A -:1016F00030288CBF0F200E207047092070470A2029 -:1017000070470B2070470C2070470D207047000079 -:1017100010B54B6823B9CA8A63F30902CA8210BDA7 -:10172000C4681A681C60C360438A013B43824A60F4 -:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 -:1017400009010629814692460B4630D00020AAB2F4 -:1017500007F119049EB2052E1FFA80F80FD89045A4 -:1017600003F1010306D3FB8A0A4462F30903FB82F7 -:1017700001201AE01AF80060E6540130EAE79045CB -:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 -:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 -:1017A000044638B978606FF00200BDE8F88F4FF05A -:1017B0000008E6E7002606607860ADB24FF0000B47 -:1017C000454510D90AEB0803221D13F8011B91555A -:1017D000B1B208F101081B291FFA88F82BD0454542 -:1017E00006F10106F1D8FB8AC3F30902154465F33B -:1017F0000903BCE7013292B21C462368002BF9D1E1 -:10180000AB1F0B441C21B3FBF1F301339BB29A4293 -:10181000D3D2BBF1000FD0D14846FFF715FF20B956 -:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 -:1018300020600446C1E74545D5D94846FFF704FF77 -:1018400008B92060AFE7C0F800B000262060044669 -:10185000B6E700002DE9F04F2DED028B83B0CDE906 -:101860000013BDF83C5007469146002A00F09280D4 -:101870002DB10E9B002B00F08D80072D32D807F183 -:101880000C00FFF7E1FE044638B96FF00204204671 -:1018900003B0BDEC028BBDE8F08F14220021FFF7EE -:1018A0008FFD0E992A4604F10800FFF777FD681CAA -:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 -:1018C000013814FA80F003F01F0363F03F03037242 -:1018D000009B43F00041616038462146FFF71CFE43 -:1018E0000124D4E700F10C034FF0000808EE103A91 -:1018F0004FF0800A4646444618EE100AFFF7A4FE51 -:1019000083460028C1D014220021FFF759FDC6BB31 -:10191000019BABF8083002200E9B00F108029919D8 -:101920005BFA82F20130C0B2082801D0AE422AD35D -:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E -:1019400002F01F0242EA4812AE4208BF4FF0400ABE -:101950005BFA81F14AEA020A43F0004281F808A0EA -:101960008BF81000CBF8042059463846FFF7D4FD19 -:101970000134AE4224B288F001084FF0000ABBD116 -:1019800085E70020C8E711F801CB02F801CB01364A -:10199000B6B2C7E76FF0010479E70000F8B5154665 -:1019A0000E462822002104461F46FFF709FD069B2C -:1019B0006360B5F5001F079BA76034BF6A094FF647 -:1019C000FF72236204F10C0097B200239A4205D8FB -:1019D0000023036027826382A382F8BD066001337F -:1019E00030462036F2E7000003781BB94BB2002BDB -:1019F000C8BF017070470000007870472DE9F74FAD -:101A0000DDF83C90BDF830500D9E9DF83840BDF893 -:101A10004070804692469B46B9F1000F01D1002FDD -:101A200051D11F2C4FD898F80000B0B9072F47D8D4 -:101A300035F0030347D13A4649464FF6FF70FFF7AA -:101A4000F7FD20F001002D02400445EA0464400C3B -:101A500044EA40244FF6FF7321E040EA0520072FB7 -:101A600040EA0464F6D900254FF6FF73C5F1200063 -:101A7000A5F120022AFA05F10BFA00F001432BFA36 -:101A800002F211431846C9B2FFF7C0FD0835402DD8 -:101A90000346EBD13A464946FFF7CAFD0346CDE976 -:101AA0000097324621464046FFF7D4FE3378013393 -:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B -:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 -:101AD00085B09246DDF848800F9D9DF840209DF826 -:101AE0004490BDF84C7006469B46B8F1000F01D1FA -:101AF000002F48D11F2A46D83378002B46D00C023D -:101B000044EA02649DF8381044EAC93444EA0144C6 -:101B10001C43072F44F0800432D900234FF6FF7294 -:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC -:101B300041EA0C012BFA00F00143C9B210460393AD -:101B4000FFF764FD039B0833402B0246E8D13A4679 -:101B50004146FFF76DFD0346CDE900872A46214641 -:101B60003046FFF777FEB9F1010F06D12B7801332C -:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 -:101B80004FF6FF73E8E76FF00100F6E76FF0030030 -:101B9000F3E70000C06900B104307047C3691A68F8 -:101BA000C261C2681A60C360438A013B43827047C6 -:101BB0002DE9F041D0F81880194E14461D464146D3 -:101BC000002709B9BDE8F081D1E90223A21A65EB2B -:101BD0000303964277EB03031ED283698B420DD138 -:101BE000FFF796FD83691B688361C3680B60438AB6 -:101BF000C1608169013B43828846E2E7FFF788FDC7 -:101C00000B68C8F80030C3680B60438AC160013BB1 -:101C10004382D8F80010D4E788460968D1E700BFAE -:101C200080841E002DE9F04F8BB00D46DDF85090FA -:101C300014469B468046002800F01981B9F1000F38 -:101C400000F01581531E3F2B00F21181012A03D1B0 -:101C5000BBF1000F40F00B810023CDE90833B8F849 -:101C60001430B5EBC30F4FEAC30703D300200BB00A -:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C -:101C8000FFB227461BB9D8F81030002B7AD02F2D81 -:101C90004ED8C5F13006B7424FF000032CBFF6B264 -:101CA0003E4600932946D8F8080008AB3246FFF7B5 -:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 -:101CC00003F10053063BDB000493D8F80C30039378 -:101CD0003021039B13B1BAF1000F2CD1D8F81000BA -:101CE00040B1BAF1000F05D0009608AB5246691A10 -:101CF000FFF754FC38B2002FB8D066070AD00AAB01 -:101D000003EBD401624211F8083C02F007021341D0 -:101D100001F8083C082C3CD9102C40F2B580202C4E -:101D200040F2B780BBF1000F00F09C80082334E044 -:101D3000BA460026C2E7049BE02B28BFE0230693A7 -:101D40000B44AB42059314D95A1B03980096924555 -:101D500034BF5246D2B2691A08AB04300792FFF77B -:101D60001DFC079A1644AAEB020A1544F6B25FFA64 -:101D70008AFA049B069A05999B1A0493039B1B6895 -:101D80000393A6E70093D8F8080008AB3A46294623 -:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F -:101DA000082C12D89DF82030621E23FA02F2D507C3 -:101DB00006D54FF0FF3202FA04F423438DF82030A9 -:101DC0009DF8203089F8003051E7102C12D8BDF86A -:101DD0002030621E23FA02F2D10706D54FF0FF32FF -:101DE00002FA04F42343ADF82030BDF82030A9F8FE -:101DF00000303CE7202C0FD80899631E21FA03F32A -:101E0000DA0705D54FF0FF3202FA04F40C430894C8 -:101E1000089BC9F800302AE7402C2BD0DDE9086583 -:101E2000611EC4F12102A4F1210326FA01F105FA91 -:101E300002F225FA03F311431943CB0712D501220D -:101E4000A4F12003C4F1200102FA03F322FA01F104 -:101E5000A240524243EA010363EB430332432B4364 -:101E6000CDE90823DDE90823C9E90023FFE66FF087 -:101E70000100FCE66FF00800F9E6082CA0D9102C50 -:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD -:101E900083E7BBF1000FBBD004237EE730B5012AF6 -:101EA000144638BF0124402C85B028BF40240025AB -:101EB000012ACDE9025518D81B788DF80830630740 -:101EC0000AD004AB03EBD405624215F8083C02F0DB -:101ED0000702934005F8083C009103462246002182 -:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 -:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D -:101F000000231B680293CDE90223D8E710B5CB6804 -:101F10001BB98B600B618B8210BDC4681A681C6092 -:101F2000C360438A013B4382CA60F0E72DE9F04F6A -:101F3000D1F8008093B018F0800FCDE90323C8F3E7 -:101F4000C01219BFC8F3C03BC8F306264FF0020BFE -:101F50001646B8F1000F04460D4680F2D18118F004 -:101F6000C043059340F0CC810B7B002B00F0C8816F -:101F7000BBF1020F03D00178B14240F0C48108F0F8 -:101F80007F0106916AB3C8F3074A2B44069A93F877 -:101F90000390760646EA0B4646EA82465FEAD91384 -:101FA00046EA0A06079300F0908000220023CDE95C -:101FB0000A23069B009367685B4652460AA920469F -:101FC000B84700287ED0A7699FB9314604F10C00BC -:101FD000FFF748FB0746E0B96FF0020013B0BDE819 -:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A -:101FF000CBE73B699E420DD03F68002FF9D13146B7 -:1020000004F10C00FFF72EFB07460028E4D0A3697B -:102010003B60A761DDE90A2300264FF6FF70C6F199 -:10202000200E22FA06F103FA0EFEA6F1200C23FA86 -:102030000CFC41EA0E0141EA0C01C9B208360992D2 -:102040000893FFF7E3FA402EDDE90832E7D1B882C2 -:10205000FB7D09F01F06C3F384039B1BD7E9022114 -:1020600098B2002BBCBF00F120031BB252EA010062 -:10207000C8F304680FD00398821A049860EB01013A -:10208000A74890424FF000028A4104D3079A002AE1 -:102090005BD0012B23DDFA7D4FEA890302F00302B6 -:1020A00003F07C031343FB7539462046FFF730FBF2 -:1020B000079BA3B9FB7DC3F38402013262F386035D -:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 -:1020D0000C0083E73B699E42BAD03F68F6E719F0EF -:1020E000400F32D0039BBB60049BFB601422002195 -:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 -:102100000C932B7BADF83EA0013BDBB2ADF83C302D -:10211000069B8DF8433094F824308DF840B083F05E -:1021200001038DF844308DF84160A3688DF842803A -:102130000AA920469847FB7DC3F38403013303F0CB -:102140001F039B02FB82002048E7FB7DC9F340127E -:10215000B2EBD31F40F0DA80C3F38403B34240F004 -:10216000D88007992B7B4FEA9912002934D0D207E7 -:1021700041D4032B40F2D080039BBB60049BFB60E7 -:102180002B7BAE1D033BDBB23246394604F10C001B -:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 -:1021A000FB7DC3F38403013303F01F039B02FB8217 -:1021B000032013E7AB883B832A7B033AB88AD2B269 -:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D -:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C -:1021E0003246394604F10C00FFF7A4FA0028D3DB8D -:1021F0002A7B013AE2E7F98AC1F30901013B05298B -:10220000DAB259D8281D002307F11A0C9A4208D9CE -:1022100010F801EB0CF801E0013101330629DBB2C3 -:10222000F4D103990A9104990B91934207F11A0191 -:102230000C9138BF043379680D9134BF55FA83F39C -:1022400000230E93FB8AADF83EA0C3F309031A44A2 -:10225000069B8DF8433094F82430ADF83C2083F091 -:1022600001038DF8443000238DF840B08DF84160B3 -:102270008DF842807B602A7BB88A013A291DFFF7DE -:10228000D7F93B8BB882834203D1A3680AA92046C1 -:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 -:1022A0008403013303F01F039B02FB823B8B9842A4 -:1022B00014BF1120002091E67B68002BB1D00620CE -:1022C00001E01C306346D3F800C0BCF1000FF8D128 -:1022D000091A081D05F1040C00EB030905989DF887 -:1022E000143001EB000EBEF11B0F9AD89A4298D918 -:1022F0001CF8013B09F8013B059B01330593EDE711 -:102300006FF009006AE66FF00A0067E66FF00D00F3 -:1023100064E66FF00E0061E66FF00F005EE600BF4E -:1023200080841E00F0B53D4D3D4FEB6943F00073D6 -:10233000EB61EB693B4B9B6AD3F800623E4046F091 -:102340000106C3F80062D3F800423C4044EA002092 -:1023500040F00100C3F80002002951D00020C3F86A -:102360001C020646C3F80402C3F80C02C3F81402A8 -:1023700003EBC00401300E28C4F84062C4F8446284 -:10238000F6D100274FF0010C9678148816F0010F53 -:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A -:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 -:1023B0000E0EC3F80CE2760742BFD3F81462064350 -:1023C000C3F8146203EBC4045668C4F8406296680C -:1023D000C4F84462D3F81C4201372043B942C3F821 -:1023E0001C0202F10C02CFD1D3F8002222F001022C -:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 -:102400000122C3F84012C3F84412C3F80412C3F8FF -:102410001412C3F80C22C3F81C22E5E70010024096 -:102420000000FFFF80220020184A916A08B58B68DF -:102430008B6013F0010104D013F00C0F18BF4FF4A0 -:102440008031D80506D513F4406F14BF41F4003134 -:1024500041F00201D80306D513F4402F14BF41F414 -:10246000802141F00401D3690BB10848984720232B -:1024700083F311880648002100F038FE002383F31F -:102480001188BDE8084001F0AFB800BF80220020ED -:102490008822002038B5124CA36ADD68AA0712D042 -:1024A0005A6922F002025A61A36913B10121204640 -:1024B0009847202383F311880A48002100F016FE74 -:1024C000002383F31188EB0606D5A36A1021D96097 -:1024D000236A0BB102489847BDE8384001F084B840 -:1024E000802200209022002038B5124CA36A1D697A -:1024F000AA0712D05A6922F010025A61A36913B1D7 -:10250000022120469847202383F311880A4800219E -:1025100000F0ECFD002383F31188EB0606D5A36AD7 -:1025200010211961236A0BB102489847BDE8384071 -:1025300001F05AB8802200209022002038B50F4CBC -:10254000A36A5D685D602A070AD5042222701A68B2 -:1025500022F002021A60636A13B1002120469847F4 -:102560006B0706D5A36A9969236A13B10348090466 -:102570009847BDE8384001F037B800BF80220020FE -:1025800010B50E4C204600F02FFA0D4BA3620B2124 -:10259000132000F009FA0B21142000F005FA0B219A -:1025A000152000F001FA0B21162000F0FDF90022A1 -:1025B000BDE8104011460E20FFF7B4BE8022002077 -:1025C000006400400F4B984210B5044605D10E4BF5 -:1025D000DA6942F00072DA61DB69A36A01221A60EB -:1025E000A36A5A68D20707D5626851681268D96130 -:1025F0001A60064A5A6110BD0121082000F06CFCE7 -:10260000EEE700BF80220020001002405B8701003F -:1026100003291AD8DFE801F0020A0F14836A9B68C5 -:1026200013F0E05F14BF012000207047836A9868B0 -:10263000C0F380607047836A9868C0F3C0607047D9 -:10264000836A9868C0F300707047002070470000EC -:1026500010B5032925D8DFE801F00225292D836A6A -:102660009968C1F30161183103EB011310788406F6 -:102670004CBF54689488C0F300114FEA410148BF31 -:1026800041EAC40100F00F004CBF41F0040141EAEF -:102690004451586041F001019068D2689860DA6056 -:1026A000196010BD836A03F5C073DFE7836A03F521 -:1026B000C873DBE7836A03F5D073D7E701290AD033 -:1026C00002290FD081B9836ADA68920701D11869AB -:1026D00003E001207047836AD86810F0030018BF38 -:1026E00001207047836AF2E70020704710B539B9BE -:1026F000836AD96889071BD11B699C0704D110BD67 -:10270000012915D00229FAD1816AD1F8C031D1F856 -:10271000C441D1F8C8011061D1F8CC01506120202A -:1027200008610869800717D1486940F0100012E07D -:10273000816AD1F8B031D1F8B441D1F8B801106153 -:10274000D1F8BC0150612020C860C868800703D15F -:10275000486940F002004861C3F34000C3F38001C0 -:10276000000140EA4111107920F03000014311715D -:1027700089064BBF91681189DB085B0D4CBF63F381 -:102780001C0163F30A01137948BF916064F30303EA -:1027900013714FEA14234FEA144458BF1181137088 -:1027A0005480ACE7026843681143016003B11847E5 -:1027B00070470000024A136843F0C003136070477B -:1027C00000380140024A136843F0C00313607047A9 -:1027D0000044004037B51D4C1D4D204600F006FB5F -:1027E000009404F114001B490023202200F0C8F9D2 -:1027F0002022009404F13800174B184900F042FAE7 -:10280000174BC4E91735174C0C21252000F0CCF8E4 -:10281000204600F0EBFA04F1140013490094002361 -:10282000202200F0ADF904F13800104B104900945B -:10283000202200F027FA0F4B0C212620C4E917357F -:1028400003B0BDE8304000F0AFB800BFAC220020BC -:102850000051250284230020B5270008C42300204E -:102860000038014018230020A4230020C5270008B9 -:10287000E4230020004400402DE9F047C66D37688E -:10288000F46934622107054618D014F0080118BF16 -:102890008021E20748BF41F02001A30748BF41F073 -:1028A0004001600748BF41F48071202383F3118801 -:1028B000281DFFF777FF002383F31188E2050AD56F -:1028C000202383F311884FF40071281DFFF76AFF5E -:1028D000002383F311884FF020094FF0000A14F011 -:1028E000200838D13B0616D54FF0200905F1380AEB -:1028F000200610D589F31188504600F0F7F900281A -:1029000036DA0821281DFFF74DFF27F080033360DA -:10291000002383F31188790614D5620612D520238B -:1029200083F31188D5E913239A4208D12B6C33B174 -:102930001021281D27F04007FFF734FF37600023E0 -:1029400083F31188E30619D5AA6E1369B3B1BDE804 -:10295000F0475069184789F31188B38C95F86410D3 -:102960002846194000F04EFA8AF31188F469B6E758 -:1029700080B2308588F31188F469B9E7BDE8F08743 -:1029800008B50348FFF778FFBDE8084000F02CBE0B -:10299000AC22002008B50348FFF76EFFBDE80840F1 -:1029A00000F022BE1823002000F1604303F56143CC -:1029B0000901C9B283F80013012200F01F039A40F5 -:1029C00043099B0003F1604303F56143C3F8802191 -:1029D0001A60704700F16040090100F56D40C9B20E -:1029E00001767047FFF7CCBD012300F10802C0E972 -:1029F0000222037000F110020023C0E90422C0E9A2 -:102A00000633C0E9083343607047000010B5202347 -:102A1000044683F31188022303704160FFF7D2FD5F -:102A200004232370002383F3118810BD2DE9F041A6 -:102A30001F4604460D461646202383F3118800F1F5 -:102A400008082378052B0DD029462046FFF7E0FD26 -:102A500040B1204632462946FFF7FAFD002080F3B8 -:102A6000118808E03946404600F024FB0028E8D0F1 -:102A7000002383F31188BDE8F08100002DE9F041C7 -:102A80001F4604460D461646202383F3118800F1A5 -:102A900010082378052B0DD029462046FFF70EFE9F -:102AA00040B1204632462946FFF720FE002080F341 -:102AB000118808E03946404600F0FCFA0028E8D0CA -:102AC000002383F31188BDE8F0810000F8B51546B6 -:102AD00082680669AA420B46816938BF8568761A02 -:102AE000B54204460BD218462A46FEF757FCA369A6 -:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 -:102B000018463246FEF74AFCAF1BE1683A463044AD -:102B1000FEF744FCE3683B44EBE718462A46FEF721 -:102B20003DFCE368E5E7000083689342F7B515468E -:102B3000044638BF8568D0E90460361AB5420BD226 -:102B40002A46FEF72BFC63692B446361A368284681 -:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 -:102B60001DFC0199E068AF1B3A463144FEF716FCA4 -:102B7000E3683B44E9E72A46FEF710FCE368E4E734 -:102B800010B50A440024C361029B8460C0E90000C0 -:102B9000C0E90511C1600261036210BD08B5D0E94A -:102BA0000532934201D1826882B982680132826023 -:102BB0005A1C42611970D0E904329A4224BFC3689A -:102BC0004361002100F086FA002008BD4FF0FF307D -:102BD000FBE7000070B5202304460E4683F31188FE -:102BE000A568A5B1A368A269013BA360531CA361BA -:102BF00015782269934224BFE368A361E3690BB1AE -:102C000020469847002383F31188284607E0314681 -:102C1000204600F04FFA0028E2DA85F3118870BDF3 -:102C20002DE9F74F04460E4617469846D0F81C90FB -:102C30004FF0200A8AF311884FF0000B154665B15A -:102C40002A4631462046FFF741FF034660B9414618 -:102C5000204600F02FFA0028F1D0002383F31188DA -:102C6000781B03B0BDE8F08FB9F1000F03D00190DD -:102C70002046C847019B8BF31188ED1A1E448AF346 -:102C80001188DCE7C0E90511C160C3611144009BF4 -:102C90008260C0E90000016103627047F8B5044634 -:102CA0000D461646202383F31188A768A7B1A368B1 -:102CB000013BA36063695A1C62611D70D4E9043250 -:102CC0009A4224BFE3686361E3690BB120469847E9 -:102CD000002080F3118807E03146204600F0EAF931 -:102CE0000028E2DA87F31188F8BD0000D0E9052357 -:102CF0009A4210B501D182687AB982680132826045 -:102D00005A1C82611C7803699A4224BFC36883619C -:102D1000002100F0DFF9204610BD4FF0FF30FBE747 -:102D20002DE9F74F04460E4617469846D0F81C90FA -:102D30004FF0200A8AF311884FF0000B154665B159 -:102D40002A4631462046FFF7EFFE034660B941466A -:102D5000204600F0AFF90028F1D0002383F311885A -:102D6000781B03B0BDE8F08FB9F1000F03D00190DC -:102D70002046C847019B8BF31188ED1A1E448AF345 -:102D80001188DCE7026843681143016003B118470A -:102D9000704700001430FFF743BF00004FF0FF33CF -:102DA0001430FFF73DBF00003830FFF7B9BF000017 -:102DB0004FF0FF333830FFF7B3BF00001430FFF798 -:102DC00009BF00004FF0FF311430FFF703BF0000D0 -:102DD0003830FFF763BF00004FF0FF323830FFF7A5 -:102DE0005DBF000000207047FFF7F4BC044B036098 -:102DF0000023C0E90233436001230374704700BF1E -:102E0000F43B000838B5C36904460D461BB90421DC -:102E10000844FFF7B7FF294604F11400FFF7BEFE90 -:102E2000002806DA201D4FF48061BDE83840FFF726 -:102E3000A9BF38BD024B0022C3E900339A60704736 -:102E400004240020002303748268054B1B689968E2 -:102E50009142FBD25A68036042601060586070472C -:102E60000424002008B5202383F31188037C032B5E -:102E700005D0042B0DD02BB983F3118808BD43690D -:102E800000221A604FF0FF334361FFF7DBFF00239E -:102E9000F2E7D0E9003213605A60F3E700230374CD -:102EA0008268054B1B6899689142FBD85A68036099 -:102EB000426010605860704704240020054B196977 -:102EC0000874186802681A6053601861012303745B -:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 -:102EE000044610D02B690A4A01A800F01BF92046BD -:102EF000FFF7E4FF049B13B101A800F02FF92B6941 -:102F0000586907B030BDFFF7D9FFF8E70424002067 -:102F1000652E000838B50C4D41612B6981689A68AF -:102F20009142044603D8BDE83840FFF78BBF1846EE -:102F3000FFF7B4FF01232C61014623742046BDE84E -:102F40003840FDF745BB00BF04240020044B1A683D -:102F50001B6990689B68984294BF002001207047CD -:102F60000424002010B5084C236820691A682260E8 -:102F70005460012223611A74FFF790FF0146206913 -:102F8000BDE81040FDF724BB0424002008B5FFF77E -:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 -:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 -:102FB00000F0AAF80A498022204600F031F80123E7 -:102FC00044F8180C037400F0EBFA002383F3118823 -:102FD00062B60448BDE8104000F042B82C2400203E -:102FE0001C3C00082C3C000800F0CAB8EFF311802C -:102FF00020B9EFF30583202282F311887047000087 -:1030000010B530B9EFF30584C4F3080414B180F3AC -:10301000118810BDFFF7BAFF84F31188F9E70000AB -:1030200082600222028270478368A3F17C0243F827 -:103030000C2C026943F83C2C426943F8382C074AAF -:1030400043F81C2CC26843F8102C022203F8082C09 -:10305000002203F8072CA3F118007047E9050008C7 -:1030600010B5202383F31188FFF7DEFF002104460B -:10307000FFF750FF002383F31188204610BD0000A6 -:10308000024B1B6958610F20FFF718BF0424002072 -:10309000202383F31188FFF7F3BF000008B5014632 -:1030A000202383F311880820FFF716FF002383F302 -:1030B000118808BD49B1064B42681B6918605A6007 -:1030C000136043600420FFF707BF4FF0FF307047E5 -:1030D000042400200368984206D01A6802605060F9 -:1030E00059611846FFF7AEBE7047000038B5044678 -:1030F0000D462068844200D138BD036823605C60BF -:103100004561FFF79FFEF4E7054B03F11402C3E9A5 -:1031100005224FF0FF32DA6100221A62704700BFC9 -:103120000424002010B5C0E903230B4A136A536935 -:103130009C68A1420CD85C68816003604460206098 -:1031400058609868411A99604FF0FF33D36110BD01 -:103150001B68091BECE700BF04240020036881689A -:103160009A680A449A60426813605A600023C360F8 -:10317000024B4FF0FF32DA61704700BF0424002099 -:1031800038B50F4C236A22460133236252F8143FAC -:10319000934206D09A68013A9A60202563699A683A -:1031A00002B138BDD3E9001001604860D968DA6027 -:1031B00082F311881869884785F31188EEE700BF0C -:1031C0000424002000207047FEE700007047000044 -:1031D0004FF0FF3070470000BFF34F8F024AD368B3 -:1031E000DB07FCD4704700BF0020024008B5074B46 -:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 -:10320000044A5A6002F188325A6008BD90250020B5 -:10321000002002402301674508B5054B1B7833B9F0 -:10322000FFF7DAFF034A136943F08003136108BD17 -:1032300090250020002002407F289ABF00F58030B2 -:10324000C0020020704700004FF40060704700008B -:10325000802070477F2808B50BD8FFF7EDFF00F5F9 -:1032600000630268013204D104308342F9D10120A5 -:1032700008BD0020FCE700007F2838B5044623D8AD -:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 -:10329000DA6002221A6105462046FFF7CDFF586129 -:1032A0001A6942F040021A614FF40061FFF794FF7F -:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 -:1032C000BDE83840FFF7C6BF002038BD00200240EF -:1032D00012F001032DE9F04704460E46154606D0CC -:1032E000244B40F2BD221A600020BDE8F08781180F -:1032F000214A914204D91F4A40F2C2211160F3E7EA -:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 -:1033100031464FF0010AA61B012D06EB0107884636 -:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E -:103330000030C9F810A03B800024FFF74DFFC9F80A -:1033400010403B8831F8022B9BB29A420FD0094BB8 -:1033500040F2D9221A60094B1F60094B1D60094BCE -:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 -:10337000D2E700BF8C250020000004088025002033 -:10338000882500208425002000200240084908B537 -:103390000B7828B11BB9FFF729FF01230B7008BD7B -:1033A000002BFCD0BDE808400870FFF735BF00BF18 -:1033B0009025002030B583B0FFF718FE0E4B0F4D5F -:1033C0001B6A2A684FF47A7101FB03F3934237BFFB -:1033D0000B4A0B49516814682B602EBFD1E900419C -:1033E000013151601C1941F100010191FFF708FE04 -:1033F0000199204603B030BD04240020942500200C -:103400009825002030B583B0FFF7F0FD114B124D29 -:103410001B6A2A684FF47A7101FB03F3934237BFAA -:103420000E4A0E49516814682B602EBFD1E9004145 -:10343000013151601C1941F100010191FFF7E0FDDC -:1034400001994FF47A7200232046FCF7A9FE03B0DD -:1034500030BD00BF042400209425002098250020C2 -:1034600010B50244064BD2B2904200D110BD441CAC -:1034700000B253F8200041F8040BE0B2F4E700BFBB -:10348000502800400F4B30B51C6A240407D41C6A36 -:1034900044F440741C621C6A44F400441C620A4CEC -:1034A000236843F4807323600244084BD2B29042F5 -:1034B00000D130BD441C00B251F8045B43F82050E9 -:1034C000E0B2F4E7001002400070004050280040D5 -:1034D00007B5012201A90020FFF7C2FF019803B040 -:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 -:1034F000012201A900200194FFF7C4FF02B010BD12 -:1035000070470000074B45F255521A6002225A607C -:1035100040F6FF729A604CF6CC421A60024B0122D0 -:103520001A70704700300040A4250020034B1B7820 -:103530001BB1034B4AF6AA221A607047A42500204B -:1035400000300040044B1A682AB902F1804202F5AB -:103550000432526A1A607047A0250020024B4FF0D7 -:1035600080725A62704700BF0010024008B5FFF732 -:10357000E9FF024B1868C0F3407008BDA025002089 -:10358000EFF3098305494A6B22F001024A6368336D -:1035900083F30988002383F31188704700EF00E06C -:1035A000202080F3118862B60C4B0D4AD96821F4B3 -:1035B000E0610904090C0A43DA60D3F8FC200949E8 -:1035C00042F08072C3F8FC200A6842F001020A60EF -:1035D0001022DA7783F82200704700BF00ED00E088 -:1035E0000003FA05001000E010B5202383F31188D2 -:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 -:103600000984683C4FF08073E361094BDB6B2366F0 -:1036100084F30988FFF79AFC10B1064BA36110BD33 -:10362000054BFBE783F31188F9E700BF00ED00E0ED -:1036300000EF00E0FB050008FE05000870470000F1 -:10364000FEE700000A4B0B480B4A90420BD30B4B92 -:10365000DA1C121AC11E22F003028B4238BF00226C -:103660000021FDF7ADBE53F8041B40F8041BECE746 -:10367000183D0008282600202826002028260020A3 -:10368000704700004B6843608B688360CB68C36001 -:103690000B6943614B6903628B6943620B6803608A -:1036A0007047000008B51B4B9A6A42F4FC029A620C -:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB -:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 -:1036D00002F11C0100F58060FFF7D4FF02F1380110 -:1036E00000F58060FFF7CEFF02F1540100F5806025 -:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D -:1037000002F18C0100F58060FFF7BCFFBDE80840C6 -:1037100000F05AB800100240443C000808B500F020 -:1037200093F9FFF741FCBDE80840FFF70BBF00002D -:103730007047000010B5214CA36A63F4FC03A36238 -:10374000A36A03F4FC03A3624FF0FF32A36A236968 -:1037500022612369002323612169E168E260E26854 -:10376000E360E268E269164942F08052E261E26990 -:103770000A6842F480720A60226A02F44072B2F56A -:10378000407F1EBF4FF4803222622362236A1B04F3 -:1037900007D4236A43F440732362236A43F400434B -:1037A000236200F031F9A369064A43F00103A361E3 -:1037B000A369136843F02003136010BD001002409A -:1037C00000700040000001401E4B1A6842F00102E8 -:1037D0001A601A689007FCD55A6822F003025A60F2 -:1037E0005A6812F00C02FBD1196801F0F901196056 -:1037F0005A601A6842F480321A601A689103FCD544 -:10380000114A5A604FF40452DA6230221A631A687D -:1038100042F080721A601A689201FCD50B4912229C -:103820000A600A6802F00702022AFAD15A6842F0D6 -:1038300002025A605A6802F00C02082AFAD11A6B86 -:103840001A6370470010024000241D00002002404F -:10385000084A08B5516913680B4003F0010353612E -:1038600023B1054A13680BB150689847BDE808407A -:10387000FFF7BABE00040140A8250020084A08B599 -:10388000516913680B4003F00203536123B1054AE9 -:1038900093680BB1D0689847BDE80840FFF7A4BE15 -:1038A00000040140A8250020084A08B551691368A2 -:1038B0000B4003F00403536123B1054A13690BB1B4 -:1038C00050699847BDE80840FFF78EBE00040140EC -:1038D000A8250020084A08B5516913680B4003F079 -:1038E0000803536123B1054A93690BB1D069984726 -:1038F000BDE80840FFF778BE00040140A82500207D -:10390000084A08B5516913680B4003F0100353616E -:1039100023B1054A136A0BB1506A9847BDE80840C5 -:10392000FFF762BE00040140A8250020174B10B528 -:103930005A691C68144004F478725A61A30604D5CD -:10394000134A936A0BB1D06A9847600604D5104AAF -:10395000136B0BB1506B9847210604D50C4A936B3F -:103960000BB1D06B9847E20504D5094A136C0BB133 -:10397000506C9847A30504D5054A936C0BB1D06CE5 -:103980009847BDE81040FFF72FBE00BF000401407C -:10399000A82500201A4B10B55A691C68144004F47D -:1039A0007C425A61620504D5164A136D0BB1506D05 -:1039B0009847230504D5134A936D0BB1D06D9847F2 -:1039C000E00404D50F4A136E0BB1506E9847A10462 -:1039D00004D50C4A936E0BB1D06E9847620404D59F -:1039E000084A136F0BB1506F9847230404D5054A5A -:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F -:103A000000040140A8250020062108B50846FEF75D -:103A1000CBFF06210720FEF7C7FF06210820FEF78F -:103A2000C3FF06210920FEF7BFFF06210A20FEF78B -:103A3000BBFF06211720FEF7B7FFBDE808400621AF -:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 -:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE -:103A6000084000F001B8000000F00EB80023054A3D -:103A700019460133102BC2E9001102F10802F8D1F6 -:103A8000704700BFA82500204FF0E023044A5A6188 -:103A900000229A6107221A6108210B20FEF79ABFC3 -:103AA0003F19010008B5202383F31188FFF79CFA22 -:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 -:103AC0000840FFF791BD000010B501390244904253 -:103AD00001D1002005E0037811F8014FA34201D085 -:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E -:103AF00017780144044603F1FF3C8C42204601D96B -:103B0000002009E00578BD4204F10104F5D10CEB79 -:103B10000405D618A54201D1BDE8F08115F8018D44 -:103B200016F801EDF045F5D0E7E70000034611F87F -:103B3000012B03F8012B002AF9D170476F72672E11 -:103B40006172647570696C6F742E6D726F5F6D3128 -:103B500030303235000000004E6F206170702073ED -:103B600069670A00426164206677206C656E67743D -:103B7000682025750A0042616420626F6172645F8B -:103B800069642025752073686F756C6420626520F8 -:103B900025750A004261642066772064657363724C -:103BA0006970746F72206C656E6774682025750A81 -:103BB00000426164206170702043524320307825B8 -:103BC0003038783A307825303878203078253038D9 -:103BD000783A3078253038780A00476F6F6420666D -:103BE00069726D776172650A0040A2E4F1646891C0 -:103BF0000600000000000000B12D00089D2D000807 -:103C0000D92D0008C52D0008D12D0008BD2D0008B4 -:103C1000A92D0008952D0008E52D00086D61696E3D -:103C20000000000069646C6500000000243C00088E -:103C3000482400208025002001000000A52F000856 -:103C400000000000A001A82A00000000FAAABEAAF5 -:103C500050001424EFFF0000007700007097090067 -:103C60000100000000000000AAAAAAAA01000000AA -:103C7000FFFF000000000000000000000000000046 -:103C800000000000AAAAAAAA00000000FFFF00008E -:103C90000000000000000000000000000000000024 -:103CA000AAAAAAAA00000000FFFF0000000000006E -:103CB000000000000000000000000000AAAAAAAA5C -:103CC00000000000FFFF00000000000000000000F6 -:103CD0000000000000000000AAAAAAAA000000003C -:103CE000FFFF00000000000000000000E4C4FF7FB0 -:103CF0000100000000000000EC03000000000000D4 -:103D000000980300000000006400000000000000B4 -:083D1000FE2A0100D2040000AC +:1000000000090020B5040008CD250008852500085A +:10001000AD25000885250008A5250008B7040008BF +:10002000B7040008B7040008B7040008C135000889 +:10003000B7040008B7040008B704000875430008B7 +:10004000B7040008B7040008B7040008B7040008A4 +:10005000B7040008B70400085940000885400008AC +:10006000B1400008DD40000809410008B70400085D +:10007000B7040008B7040008B7040008B704000874 +:10008000B7040008B7040008B704000839250008C1 +:100090006525000875250008B704000835410008EB +:1000A000B7040008B7040008B7040008B704000844 +:1000B000B7040008B7040008B7040008B704000834 +:1000C000B7040008B7040008B7040008B704000824 +:1000D000B70400086545000879450008B704000822 +:1000E0009D410008B7040008B7040008B7040008E1 +:1000F000B7040008B7040008B7040008B7040008F4 +:10010000B7040008B7040008B7040008B7040008E3 +:10011000B7040008B7040008B7040008B7040008D3 +:10012000B7040008B7040008B7040008B7040008C3 +:10013000B7040008B7040008B7040008B7040008B3 +:10014000B7040008B7040008B7040008B7040008A3 +:10015000B7040008B7040008B7040008B704000893 +:10016000B7040008B7040008B7040008B704000883 +:10017000B7040008B7040008B7040008B704000873 +:10018000B7040008B7040008B7040008B704000863 +:10019000B7040008B7040008B7040008B704000853 +:1001A0002112000800000000000000000000000014 +:1001B00053B94AB9002908BF00281CBF4FF0FF31CE +:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA +:1001D00000F006F8DDF804E0DDE9022304B0704722 +:1001E0002DE9F047089D04468E46002B4DD18A42EA +:1001F000944669D9B2FA82F252B101FA02F3C2F11D +:10020000200120FA01F10CFA02FC41EA030E9440AD +:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE +:1002200016E341EA034306FB07F199420AD91CEBA6 +:10023000030306F1FF3080F01F81994240F21C81D8 +:10024000023E63445B1AA4B2B3FBF8F008FB103320 +:1002500044EA034400FB07F7A7420AD91CEB040455 +:1002600000F1FF3380F00A81A74240F20781644425 +:10027000023840EA0640E41B00261DB1D4400023AA +:10028000C5E900433146BDE8F0878B4209D9002D0E +:1002900000F0EF800026C5E9000130463146BDE898 +:1002A000F087B3FA83F6002E4AD18B4202D3824202 +:1002B00000F2F980841A61EB030301209E46002DB1 +:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 +:1002D000002A40F09280A1EB0C014FEA1C471FFA64 +:1002E0008CFE0126200CB1FBF7F307FB131140EA4B +:1002F00001410EFB03F0884208D91CEB010103F118 +:10030000FF3802D2884200F2CB804346091AA4B2D9 +:10031000B1FBF7F007FB101144EA01440EFB00FEAD +:10032000A64508D91CEB040400F1FF3102D2A64512 +:1003300000F2BB800846A4EB0E0440EA03409CE7B1 +:10034000C6F12007B34022FA07FC4CEA030C20FA5E +:1003500007F401FA06F31C43F9404FEA1C4900FA7E +:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB +:1003700040EA014108FB0EF0884202FA06F20BD96E +:100380001CEB010108F1FF3A80F08880884240F2BE +:100390008580A8F102086144091AA4B2B1FBF9F002 +:1003A00009FB101144EA014100FB0EFE8E4508D9FD +:1003B0001CEB010100F1FF346CD28E456AD9023882 +:1003C000614440EA0840A0FB0294A1EB0E01A14267 +:1003D000C846A64656D353D05DB1B3EB080261EBD5 +:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF +:1003F000007100263146BDE8F087C2F12003D840E5 +:100400000CFA02FC21FA03F3914001434FEA1C4726 +:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 +:10042000064300FB0EF69E4204FA02F408D91CEBC8 +:10043000030300F1FF382FD29E422DD902386344C6 +:100440009B1B89B2B3FBF7F607FB163341EA034166 +:1004500006FB0EF38B4208D91CEB010106F1FF38B5 +:1004600016D28B4214D9023E6144C91A46EA0046AC +:1004700038E72E46284605E70646E3E61846F8E63E +:100480004B45A9D2B9EB020864EB0C0E0138A3E787 +:100490004646EAE7204694E74046D1E7D0467BE768 +:1004A000023B614432E7304609E76444023842E7E0 +:1004B000704700BF02E000F000F8FEE772B6374870 +:1004C00080F30888364880F3098836483649086042 +:1004D00040F20000CCF200004EF63471CEF2000182 +:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 +:1004F000F0004EF68851CEF200010860BFF34F8F36 +:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 +:10051000CEF200010860062080F31488BFF36F8FCD +:1005200003F04EFC03F0C2FC4FF055301F491B4A4C +:1005300091423CBF41F8040BFAE71D49184A914229 +:100540003CBF41F8040BFAE71A491B4A1B4B9A427D +:100550003EBF51F8040B42F8040BF8E7002018499D +:10056000184A91423CBF41F8040BFAE703F02CFC17 +:1005700003F0D8FC144C154DAC4203DA54F8041BBC +:100580008847F9E700F042F8114C124DAC4203DA0B +:1005900054F8041B8847F9E703F014BC0009002055 +:1005A000001100200000000808ED00E0000100201C +:1005B00000090020704B0008001100207C11002071 +:1005C00080110020583C0020A0010008A401000870 +:1005D000A4010008A40100082DE9F04F2DED108AB8 +:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 +:1005F000002383F311882846A047002003F06AF9FE +:10060000FEE703F0CDF800DFFEE70000F8B500F0EC +:1006100019FE03F079FB074603F0C8FB05460028E6 +:1006200040D12C4B9F423DD001339F423DD02A4BBD +:1006300027F0FF029A423BD1F8B200F03FFC2E4671 +:1006400042F2107400F040FC08B10024264601F08C +:10065000B1F888B3032000F045F80024264635B1F0 +:100660001E4B9F4203D003F099FB00242646002036 +:1006700003F054FB1A4B1B6913F0400322D00EB158 +:1006800000F046F800F052FC00F0DEFD01F0A6FF9D +:100690000546CCB101F0A2FF401BA04214D900F0E6 +:1006A00037F8F3E72E460024CCE704460126C9E7D5 +:1006B00006464FF47A74C5E7002CD0D04FF47A7414 +:1006C0000126CCE71C46DDE700F078FC012003F0B2 +:1006D00007F9DEE7010007B0000008B0263A09B0CC +:1006E00000040048084B187003280CD8DFE800F01D +:1006F00008050208022000F003BE022000F0F8BD49 +:10070000024B00225A6070478011002084110020A3 +:1007100038B501F04FF830B11F4B03221A701F4B50 +:1007200000225A6038BD1E4B1E4A19680131F9D0AB +:1007300004339342F9D11C4C194DD4F80428AA4231 +:10074000F0D31A4B9B6803F1006303F5D0439A4240 +:10075000E8D203F0F7FA03F009FB002000F08EFD69 +:100760000220FFF7BFFF124BDA690022DA61D96974 +:1007700099699A619B6972B64FF0E0233021C3F802 +:10078000085DD4F80038D4F8042881F311889D4618 +:1007900083F308881047C5E78011002084110020EA +:1007A00000680008206800080060000800110020B0 +:1007B00000100240094A136849F2690099B21B0C03 +:1007C00000FB01331360064B186844F2506182B29B +:1007D000000C01FB0200186080B270471411002069 +:1007E0001011002010B500211022044600F0A2FDD7 +:1007F000034B03CB206061601868A06010BD00BF90 +:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 +:100810006CAC40F2751207460D460EA80021C8F8D0 +:10082000001000F087FD4FF4C4720021204600F054 +:1008300081FD01F0D3FE254B4FF47A72B0FBF2F04C +:10084000186093E80700022384E807000DF5E970BB +:100850002382FFF7C7FF4EF603431D49238406A8F2 +:1008600004F0B6F8192384F832310DF2E32206AB16 +:100870000DF1300C1E4603CE6645106051603346C4 +:1008800002F10802F6D13378137041460122204666 +:1008900000F09CFD00230393AB7E029305F1190346 +:1008A000019380B20123CDE904800093E97E05A382 +:1008B000D3E90023384602F059FA0DF54E7DBDE824 +:1008C000F08100BF9E6AC421818A46EE8C1100200F +:1008D000E04900082DE9F0412C4C237ADAB080463B +:1008E0000D465BBB27A9284600F080FE074600287E +:1008F00042D19DF89D60C82E3ED801464FF4A662B5 +:10090000204600F017FD4FF48073C4F8F8314FF41F +:100910000073C4F80C334FF44073C4F820343246EB +:100920000DF19E0104F1090000F0F2FC26449DF84F +:100930009C30777223720BB9EB7E237281220021E7 +:1009400006AC27A800F0F6FC0122214627A800F0FB +:1009500089FE00230393AB7E029305F1190380B255 +:1009600001932823CDE904400093E97E05A3D3E950 +:100970000023404602F0FAF95AB0BDE8F08100BF0A +:10098000AFF3008026417272DF25D7B7A83200206E +:10099000F0B5254E4FF48A7505FB0065F1B096F869 +:1009A000D83085F8DC300024D822214685F8E8408C +:1009B0003AA800F0BFFC06F1090000F0B3FCD5F83E +:1009C000E4308DF8F000C2B206AF06F109010DF176 +:1009D000F100CDE93A3400F09BFC394601223AA8F7 +:1009E00000F06CFE80B2CDE9047008230127CDE948 +:1009F000023706F1D803019330230093317A0B4874 +:100A000007A3D3E9002302F0B1F9A04206DD01F00B +:100A1000E5FDC5F8E000384671B0F0BD2046FBE7C3 +:100A200078F6339F93CACD8DA8320020A4210020F0 +:100A30002DE9F0411D4D1E4E1E4F86B0284602F096 +:100A4000C1F9034658B30024CDE90344ADF814407E +:100A5000027B8DF8142099684068029403AA03C2AF +:100A60001B68DFF8548043F00043029301F0B8FDA7 +:100A7000821941F10003009402A9384601F07CF884 +:100A8000A04205DD284602F0A1F988F80040D5E72C +:100A900098F80030072B05D8013388F8003006B0ED +:100AA000BDE8F081014802F091F9F8E7A4210020A7 +:100AB00040420F00D8210020DD37002070B50D46E0 +:100AC00014461E4602F0AEF850B9022E10D1012C89 +:100AD0000ED112A3D3E90023C5E90023012007E0CA +:100AE000282C10D005D8012C09D0052C0FD00020BF +:100AF00070BD302CFBD10BA3D3E90023ECE70BA393 +:100B0000D3E90023E8E70BA3D3E90023E4E70BA331 +:100B1000D3E90023E0E700BFAFF30080401DA12030 +:100B200026812A0B78F6339F93CACD8D9E6AC42105 +:100B3000818A46EE26417272DF25D7B7F017304A18 +:100B400039059E5638B505460E4C0021013500F09A +:100B5000B7FBA4F82C55B4F82C0500F099FB78B13C +:100B6000B4F82C0500F0A4FB014648B9B4F82C05F4 +:100B700000F0A6FBB4F82C350133A4F82C35EAE7D5 +:100B800038BD00BFA832002010B50A4B0A4A1A60CF +:100B900003F5805393F860203AB9DC6D2CB1204600 +:100BA00000F082FE204603F053FEBDE810400348EB +:100BB00000F07ABED8210020384A000820320020F8 +:100BC0002DE9F04F8FB000AF05460C4602F02AF831 +:100BD000002849D1237E022B1BD1E38A012B18D197 +:100BE00001F0FCFC0646FFF7E5FD03464FF4C87034 +:100BF000DFF8C482B3FBF0F206F5167602FB103381 +:100C000016FA83F3C8F80030E37E33B9A34B002211 +:100C10001A703C37BD46BDE8F08F07F1240120462D +:100C200000F0A2FC0028F4D107F11400FFF7DAFD70 +:100C300097F8264007F11401224607F1270003F038 +:100C400051FE0028E2D10F2C08D8944B1C70D8F824 +:100C50000030A3F51673C8F80030DAE797F82410CF +:100C6000284601F0D7FFD4E7E38A282B2BD010D8F1 +:100C7000012B23D0052BCCD1BFF34F8F8849894B53 +:100C8000CA6802F4E0621343CB60BFF34F8F00BF2A +:100C9000FDE7302BBDD1844EE17E327A9142B8D14E +:100CA000607E3146002291F8DC50854200F0A5803C +:100CB0000132042A01F58A71F5D1AAE721462846B6 +:100CC000FFF7A0FDA5E721462846FFF703FEA0E7B2 +:100CD000B2F8EC507B6005F103094FEA99094FEA3D +:100CE0008902D11DC908A8EBC1039D46EB4600212E +:100CF000584600F01FFB04F1EE012A4631445846E5 +:100D000000F006FB7B6813B9012000F0B7FA96F8F3 +:100D1000D20000F0BDFA044630B9307200F0D8FAC3 +:100D2000204600F0ABFAB1E0D6F8D4203AB996F8F4 +:100D3000D200B6F82C25824201D8FFF703FFD6F87F +:100D4000D4202A44944208D296F8D200B6F82C2532 +:100D50000130824201D8FFF7F5FE70685FFA89F230 +:100D6000594600F0EFFA08B9C54679E0726896F87E +:100D7000D2002A447260D6F8D42005EB0209C6F8E6 +:100D8000D49000F085FA814509D396F8D220D6F8A0 +:100D9000D4000132001B86F8D220C6F8D400FF2D03 +:100DA0000FD80024347200F093FA204600F066FA5F +:100DB00000F000FD3D4B188108B9FFF7A9FCC546BE +:100DC00027E7BB6896F8D9000AFB0362FB68D2F8F4 +:100DD000E41082F8E83001F58061C2F8E030C2F832 +:100DE000E410FFF7D5FDFFF723FE96F8D920013276 +:100DF00002F0030286F8D920B6E74FF48A7A0AFB9C +:100E000002F505F1EA013144204600F083FCF86068 +:100E100000287FF4FEAE3544012285F8E82001F079 +:100E2000DDFBD5F8E020D6ED007ADFED216A801AEF +:100E3000192838BF192040F6B832904228BF104612 +:100E4000B8EE677A07EE900AF8EEE77A67EEA67AD0 +:100E5000DFED186AE7EE267AFCEEE77AC6ED007A57 +:100E600096F8D930BB60BA6873680AFB02F432198D +:100E700092F8E81059B1D2F8E4108B42E8463FF4FA +:100E800027AF002182F8E810C2F8E010C546736869 +:100E9000064A9B0A01331381BBE600BF9D21002057 +:100EA00000ED00E00400FA05A83200208C110020BB +:100EB000CDCCCC3D6666663FA0210020014B18706A +:100EC000704700BF9811002038B54FF00054134B05 +:100ED00022689A4220D1124B627D12481A70237DFB +:100EE00003724FF48073C0F8F8314FF40073C0F808 +:100EF0000C3300254FF44073C0F820340A49C0F881 +:100F0000E450C922093000F003FAE02229462046C5 +:100F100000F010FA012038BD0020FCE79AAD44C56E +:100F200098110020A83200201600002037B500F0EC +:100F300041FC194D194928810223012218486B717F +:100F400001F0EAF900230193164B17490093174863 +:100F5000174B4FF4805201F035FE164B197811B142 +:100F6000124801F057FE01F039FB0446FFF722FC5E +:100F70004FF4C873B0FBF3F202FB130304F51670D1 +:100F800010FA83F00C4B186002F010FF08B10F2329 +:100F90002B8103B030BD00BF8C11002040420F00F8 +:100FA000D8210020BD0A00089C110020A4210020A7 +:100FB000C10B000898110020A02100202DE9F04F5E +:100FC0002DED028B8EA7D7E900670FF23C29D9E9F6 +:100FD0000089864C95B00DAD9FED828BFFF728FD03 +:100FE000DFF82CB200230C93ADF83C300D936B600E +:100FF00000230DF125028DED008B4FF0010A09A9A8 +:1010000058468DF825308DF824A001F035F99DF86B +:1010100024200023002A40F0AB80204601F002FE8D +:101020000546002847D1DFF8ECB101F0D7FADBF82C +:10103000003098423FD301F0D1FA0790FFF7BAFB96 +:10104000079A4FF4C873B0FBF3F101FB130302F5E9 +:10105000167010FA83F0CBF80000DFF8BCB19BF8F3 +:1010600000100791002914BF2B46534610A88DF895 +:101070003030FFF7B7FB0799C1F11002D2B2062A50 +:1010800010AB28BF062219440DF13100079200F081 +:101090003FF9079A0CAB0393182302930132544B88 +:1010A000D2B2CDE900A304923B463246204601F07D +:1010B000FFFD8BF8005001F091FA4E4A4E4D136837 +:1010C000C31AB3F57A7F32D3106001F089FA024671 +:1010D0000B46204601F084FE204601F0A3FD30B30C +:1010E0002B7ADFF838A1002B14BF032302238AF8E0 +:1010F000053001F073FA0DF1400B4FF47A730122C1 +:10110000B0FBF3F05946CAF80000504600F004FA6C +:1011100018230293394B019380B240F25513CDE965 +:1011200003B0009342464B46204601F0C1FD2B7AA6 +:10113000CBB101F053FA4FF0000A83464FF48A72A4 +:1011400095F8D900504400F0030002FB005393F8D7 +:10115000E81089B30AF1010ABAF1040FF0D12B7A31 +:10116000002B7FF438AF15B0BDEC028BBDE8F08FDB +:101170004FF0904110A84A6982F010024A61194666 +:10118000102200F0D7F80DF126030AAA0CA9584640 +:1011900000F0F0FD95E8030011AB83E803009DF833 +:1011A0003C308DF84C300C9B109310A9DDE90A23DC +:1011B000204601F0E9FF1BE7D3F8E01049B12B68A6 +:1011C000FA2B38BFFA23ABEB01010533B1EB430F28 +:1011D000C0D3FFF7DDFB4FF48A720028BAD1BEE717 +:1011E000AFF300800000000000000000A4210020F8 +:1011F0009C210020D8370020A8320020DC370020B6 +:10120000401DA12026812A0BF1C6A7C1D068080F76 +:10121000D8210020A02100209D2100208C11002039 +:1012200008B5054800F040FEBDE80840034A0449FF +:10123000002003F007BB00BFD82100201838002091 +:10124000890B00087047000070B502F013FC094ECE +:10125000094D3080002428683388834208D902F081 +:1012600005FC2B6804440133B4F5D04F2B60F2D356 +:1012700070BD00BF0C380020E037002002F086BCB3 +:1012800000F10060920000F5D04002F02DBC00009B +:10129000054B1A68054B1B889B1A834202D91044E0 +:1012A00002F0E4BB00207047E03700200C3800203B +:1012B000024B1B68184402F0DFBB00BFE037002080 +:1012C000024B1B68184402F0E9BB00BFE037002066 +:1012D000064991F8243033B10023086A81F824309C +:1012E0000822FFF7CDBF0120704700BFE437002080 +:1012F000022802BF4FF0904310229A61704700000D +:10130000022802BF4FF090434FF480129A61704759 +:1013100010B50023934203D0CC5CC4540133F9E7E9 +:1013200010BD000003460246D01A12F9011B002925 +:10133000FAD1704702440346934202D003F8011BDE +:10134000FAE770472DE9F8431F4D144695F824201D +:101350000746884652BBDFF870909CB395F824305E +:101360002BB92022FF2148462F62FFF7E3FF95F8B3 +:101370002400C0F10802A24228BF2246D6B241464C +:10138000920005EB8000FFF7C3FF95F82430A41B03 +:101390001E44F6B2082E17449044E4B285F8246047 +:1013A000DBD1FFF795FF0028D7D108E02B6A03EBCC +:1013B00082038342CFD0FFF78BFF0028CBD10020E0 +:1013C000BDE8F8830120FBE7E43700202DE9F04772 +:1013D0000D46044600219046284640F27912FFF758 +:1013E000A9FF234620220021284601F06FFE231D7D +:1013F00002222021284601F069FE631D03222221DA +:10140000284601F063FEA31D03222521284601F092 +:101410005DFE04F1080310222821284601F056FE43 +:1014200004F1100308223821284601F04FFE04F190 +:10143000110308224021284601F048FE04F112035E +:1014400008224821284601F041FE04F1140320221D +:101450005021284601F03AFE04F118034022702181 +:10146000284601F033FE04F120030822B02128466B +:1014700001F02CFE04F121030822B821284601F0D6 +:1014800025FE04F12207C0263B46314608222846A5 +:10149000083601F01BFEB6F5A07F07F10107F3D176 +:1014A00004F1320308223146284601F00FFE0027DE +:1014B00004F1330A94F832304FEAC7099F4209F524 +:1014C000A47615D3B8F1000F08D1314604F599730D +:1014D0000722284601F0FAFD09F24F16274694F834 +:1014E00032213B1B93420CD3F01DC008BDE8F087AE +:1014F0000AEB070308223146284601F0E7FD0137D1 +:10150000D8E707F2331331460822284601F0DEFD02 +:1015100008360137E3E7000013B50446084600210A +:1015200001602346C0F803102022019001F0CEFD97 +:101530000198231D0222202101F0C8FD0198631D9E +:101540000322222101F0C2FD0198A31D03222521BF +:1015500001F0BCFD019804F108031022282101F0DC +:10156000B5FD072002B010BDF7B50023047F009140 +:101570000E4607221946054601F06CFC731C0093C9 +:10158000012200230721284601F064FCC4B9B31CE2 +:101590000093052223460821284601F05BFC0D2418 +:1015A0003746B278BB1B934211D32B7FA88A0734EE +:1015B000E408BBB9844294BF0020012003B0F0BD11 +:1015C000AB8ADB00083BDB08B3700824E8E7FB1CB0 +:1015D0000093214600230822284601F03BFC0834F2 +:1015E0000137DEE7201A18BF0120E7E7F7B500232F +:1015F000047F00910E4608221946054601F02AFC98 +:10160000731CC4B90822009311462346284601F0F2 +:1016100021FC1024012372785F1C013B934211D3FB +:101620002B7FA88A0734E408BBB9844294BF00200A +:10163000012003B0F0BDAB8ADB00083BDB08737010 +:101640000824E7E7F31900932146002308222846DF +:1016500001F000FC08343B46DDE7201A18BF0120EA +:10166000E7E70000F8B50E46054614460021812242 +:101670003046FFF75FFE2B4608220021304601F07E +:1016800025FD7CB96B1C07220821304601F01EFDA8 +:101690000F2401236A785F1C013B934204D3E01DB1 +:1016A000C008F8BD0824F4E7EB19214608223046AB +:1016B00001F00CFD08343B46ECE70000F8B50E469F +:1016C000054614460021CE223046FFF733FE2B4656 +:1016D00028220021304601F0F9FC7CB905F108030D +:1016E00008222821304601F0F1FC30242F462A7AC6 +:1016F0007B1B934204D3E01DC008F8BD2824F5E706 +:1017000007F1090321460822304601F0DFFC0834C6 +:101710000137ECE7F7B5047F00910E460123102254 +:101720000021054601F096FBC4B9B31C00930922C1 +:1017300023461021284601F08DFB19243746728874 +:10174000BB1B9A4211D82B7FA88A0734E408BBB987 +:10175000844294BF0020012003B0F0BDAB8ADB00BF +:10176000103BDB0873801024E8E73B1D0093214603 +:1017700000230822284601F06DFB08340137DEE71C +:10178000201A18BF0120E7E730B5094D0A449142FD +:101790000DD011F8013B5840082340F30004013BF1 +:1017A0002C4013F0FF0384EA5000F6D1EFE730BD80 +:1017B0002083B8EDF7B5364A106851686B4603C30D +:1017C0006A4634493448082303F09CF8044690BB29 +:1017D0000A25324A106851686B4603C36A4630498D +:1017E0002D48082303F08EF80446002847D00369EB +:1017F000B3F5663F43D8B0F86620B2F57B7F3ED1A3 +:10180000284A024402F15C018B4238D35C3B2249F6 +:1018100000209E1AFFF7B8FF3246074604F1640124 +:101820000020FFF7B1FFA3689F4228D1E3689842E8 +:1018300008BF002523E00369B3F5663F26D8428B35 +:10184000B2F57B7F20D1174A024402F110018B428E +:1018500018D3103B104900209D1AFFF795FF2A4628 +:10186000064604F118010020FFF78EFFA3689E4290 +:1018700002D1E368984201D00D25AAE70025284649 +:1018800003B0F0BD1025A4E70C25A2E70B25A0E7C7 +:10189000FC490008DC97030000680008054A0008BE +:1018A000909703000898FFF710B5037C044613B91E +:1018B000006803F00FF8204610BD00000023BFF3BE +:1018C0005B8FC360BFF35B8FBFF35B8F8360BFF33E +:1018D0005B8F7047BFF35B8F0068BFF35B8F704710 +:1018E00070B505460C30FFF7F5FF05F10806044614 +:1018F0003046FFF7EFFFA04206D930466D68FFF78C +:10190000E9FF2544281A70BD3046FFF7E3FF201A8F +:10191000F9E7000070B50546406898B105F1080088 +:10192000FFF7D8FF05F10C0604463046FFF7D2FF5B +:101930008442304694BF6D680025FFF7CBFF013C21 +:101940002C44201A70BD000038B50C460546FFF740 +:10195000C7FFA04210D305F10800FFF7BBFF044406 +:101960006868B4FBF0F100FB1144BFF35B8F01200A +:10197000AC60BFF35B8F38BD0020FCE72DE9F04180 +:10198000144607460D46FFF7C5FF844228BF0446AC +:10199000D4B1B84658F80C6B4046FFF79BFF304473 +:1019A000286040467E68FFF795FF331A9C4203D8B3 +:1019B0006C600120BDE8F0816B60A41B3B68AB60EC +:1019C0002044E8600220F5E72046F3E738B50C46EE +:1019D0000546FFF79FFFA04210D305F10C00FFF76B +:1019E00079FF04446868B4FBF0F100FB1144BFF3D5 +:1019F0005B8F0120EC60BFF35B8F38BD0020FCE7FC +:101A00002DE9FF41884669460746FFF7B7FF6C4658 +:101A100006B204EBC6060025B44209D0626820680D +:101A200008EB0501FFF774FC636808341D44F3E715 +:101A300029463846FFF7CAFF284604B0BDE8F081C2 +:101A4000F8B505460C300F46FFF744FF05F10806D0 +:101A500004463046FFF73EFFA042304688BF6C6820 +:101A6000FFF738FF201A386020B130462C68FFF7A6 +:101A700031FF2044F8BD000073B5144606460D46FC +:101A8000FFF72EFF844228BF04460190DCB101A974 +:101A90003046FFF7D5FF019B33B93268C5E9023301 +:101AA000C5E9002401200CE09C4238BF0194286065 +:101AB000019868608442F5D93368AB60241AEC6001 +:101AC000022002B070BD2046FBE700002DE9FF4177 +:101AD0000F466946FFF7D0FF6C4600B204EBC00525 +:101AE0000026AC4209D0D4F8048054F8081BB81979 +:101AF0004246FFF70DFC4644F3E7304604B0BDE82C +:101B0000F081000038B50546FFF7E0FF04460146C6 +:101B10002846FFF719FF204638BD0000302383F325 +:101B2000118862B670470000002383F3118862B603 +:101B30007047000010B4026854681A4623465DF8E6 +:101B4000044B184701207047002070470020704761 +:101B500070470000002070470E20704700F580504D +:101B600090F8C800C0F340007047000000F58050B6 +:101B700090F9C90070470000F7B50C68BDF82070F7 +:101B800014F000541E466FD10B7B082B6CD8FFF766 +:101B9000C5FF4569AB685B010CD4AB681B0108D479 +:101BA000AC6814F080545DD1FFF7BEFF204603B04F +:101BB000F0BD01240B6804F1180C002BB8BFDB004A +:101BC0004FEA0C1CB4BF43F004035B0545F80C302E +:101BD0000B680FFA84FC13F0804F18BF05EB0C1E46 +:101BE00005EB0C1C1EBFDEF8803143F00203CEF87B +:101BF00080310B7BCCF8843105EB04158B68C5F87C +:101C00008C314B68C5F88831DCF8803143F0010332 +:101C1000CCF8803100EB441541F268031D4403EB1E +:101C200044130344C5E9002608330D4601F10C0CAA +:101C300055F804EB43F804EB6545F9D184342D885D +:101C40001D8000EB441407F00303257925F00B05F4 +:101C50002B432371FFF768FF0097334600F0E0FC49 +:101C60000120A4E70224A5E74FF0FF309FE7000022 +:101C700013B500F580540191E06DFFF74BFE1F286E +:101C80000AD90199E06D2022FFF7BAFEA0F12003E6 +:101C90005842584102B010BD0020FBE708B500F5DE +:101CA0008050FFF73BFFC06DFFF708FEBDE808401E +:101CB000FFF73ABF00220260828142608260704773 +:101CC00010B500220023C0E900230023044603814D +:101CD0000C30FFF7EFFF204610BD0000F0B50546C1 +:101CE00000F580500C4690F8C83013F0040FC3F391 +:101CF000800108BF114661F3820304F1840680F875 +:101D0000C83005EB461389B01B79D8072ED57AB3B6 +:101D100019072DD46846FFF7D3FF05EB441303F5ED +:101D2000835303F1180703AA10331868596814463F +:101D300003C40833BB422246F7D1186820609B8851 +:101D4000A380DDE90E23CDE900230123ADF808309F +:101D50002B686946DB6B2846984705EB46152B79BF +:101D60001A075CBF43F008032B7101E0002AF4D18D +:101D700009B0F0BD2DE9F047074688B007F580545B +:101D800068469A468846FFF7C9FE9146FFF798FFD6 +:101D9000E06DFFF7A5FD1F2829D9E06D20226946D7 +:101DA000FFF7B0FE202822D103AD444605AB2E46F6 +:101DB00003CE9E4220606160354604F10804F6D1EE +:101DC00030682060B388A380DDE90023C9E90023DF +:101DD000BDF80830AAF80030FFF7A6FE4A46534681 +:101DE0004146384608B0BDE8F04700F007BCFFF7B1 +:101DF0009BFE002008B0BDE8F08700002DE9F84FF9 +:101E00000023C0E90133254B044640F8183B0F4638 +:101E1000FFF750FF04F12800FFF752FF04F14808D4 +:101E200004F582554646083530462036FFF748FF10 +:101E3000AE42F9D104F580554FF480534FF00009BC +:101E4000C5E91339C5F848800123EE6504F58758C4 +:101E500004F58456C5F8549085F8583085F86030FC +:101E6000083608F108084FF0000A4FF0000B46E969 +:101E700008ABA6F11800FFF71DFF203646F8289C96 +:101E80004645F4D185F8C97017B1054800F0A0FBAC +:101E9000044B63612046BDE8F88F00BF384A000854 +:101EA000104A00080064004010B5044B197804463D +:101EB0004A1C1A70FFF7A2FF204610BD14380020FC +:101EC0002DE9F047002950D0294B2A4FB7FBF1F5F7 +:101ED00099428CBF0A231123581EB5FBF3FC03FB68 +:101EE0001C53C4B22BB102280346F5D80020BDE82C +:101EF000F0870CF1FF36B6F5806FF7D2C4EBC40E55 +:101F00000EF103034FEAE309C3F3C703A4EB03088D +:101F100009F1010A4FF47A755FFA88F009FB05555B +:101F20005AFA88F8B5FBF8F5B5F5617FC1BF0EF137 +:101F3000FF33C3F3C703E01AC0B25C1C50FA84F449 +:101F40000CFB04F4B7FBF4F4A142CFD1013BDBB2AC +:101F50000F2BCBD80138C0B20728C7D80021107189 +:101F600016809170D3700120C1E70846BFE700BF1B +:101F70003F420F000051250270B505460E464FF452 +:101F80007A746B695B6803F00103B3424FF00100A0 +:101F900004D001F0A5FC013CF3D1204670BD000047 +:101FA00030B54269936913F0700F16D000230B4CC3 +:101FB000936103F1840200EB421211794D0709D5B8 +:101FC000890707D5416954F823508D60117941F094 +:101FD000040111710133032BEBD130BD244A0008F9 +:101FE00073B51D46436916469A68D207044609D55B +:101FF0009A6801219960C2F34002CDE90065002191 +:10200000FFF76CFE63699A68D1050BD59A684FF4A7 +:1020100080719960C2F34022CDE90065012120461C +:10202000FFF75CFE63699A68D2030BD59A684FF498 +:1020300080319960C2F34042CDE90065022120461B +:10204000FFF74CFE204602B0BDE87040FFF7A8BF86 +:10205000F8B50446466900296CD106F10C073868CA +:1020600080076AD006EB01153868D5F8B00110F08A +:10207000040FD5F8B0011ABFC00840F00040400D71 +:10208000A061D5F8B0C11CF0020F1CBF40F0804029 +:10209000A061D5F8B40106EB011100F00F0084F83F +:1020A0002400D1F8B8012077D1F8B801000A607790 +:1020B000D1F8B801000CA077D1F8B801000EE07794 +:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 +:1020D0002100D1F8BC01000C84F82200D1F8BC1119 +:1020E000090E84F823103821396004F1340004F11A +:1020F000180104F1240551F8046B40F8046BA9425F +:10210000F9D109880180C4E90A23214600232386E6 +:1021100051F8283B2046DB6B984704F58052204657 +:1021200092F8C83043F0040382F8C830BDE8F840A4 +:10213000FFF736BF06F1100791E7F8BD10B504466A +:1021400000F04EFA02460B4652EA030102D0013A71 +:1021500063F100030449086820B12146BDE810403E +:10216000FFF776BF10BD00BF10380020F8B500F5AE +:1021700083511E46FFF7D2FCDFF844C0083100242B +:1021800004F1840500EB45152B795F070ED4DB06BF +:102190000CD5D1E900739742B34107D243695CF88B +:1021A00024709F602B7943F004032B710134032CBE +:1021B00001F12001E4D1BDE8F840FFF7B5BC00BF54 +:1021C000244A000808B5FFF7A9FCFFF7E9FEBDE8BF +:1021D0000840FFF7A9BC0000F8B5436905469868B8 +:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C +:1021F00095FC05F583541034002606F1840305EBA5 +:1022000043131B791A0706D50136032E04F1200467 +:10221000F3D1012007E05B07F6D42146384600F0F1 +:1022200039FA0028F0D1FFF77FFCF8BD0120FCE768 +:1022300000F5805008B5FFF771FCC06DFFF750FB4B +:10224000FFF772FC43090CBF0120002008BD00000D +:10225000F8B51D46002313700F4606461446FFF7D7 +:10226000E7FF80F00100387025B129463046FFF7BE +:10227000B3FF2070F8BD00002DE9B8410C461546AB +:102280001F46804600F0ACF90B462178024609B99A +:10229000287850B14046FFF769FFFFF793FF3B46B0 +:1022A0002A462146FFF7D4FF0120BDE8B88100008F +:1022B00010B5FFF733FC174BDA6942F00072DA61B0 +:1022C0001A6942F000721A611A6900F5805422F00E +:1022D00000721A61FFF728FC94F8C830DB0718D4A5 +:1022E000B9B103211320FFF719FC01F0C7F903214D +:1022F000142001F0C3F90321152001F0BFF994F86F +:10230000C83043F0010384F8C830BDE81040FFF73F +:102310000BBC10BD001002402DE9F04700F58055C0 +:1023200088B095F8C930012B0446884616467FD8F8 +:10233000804F57F823200AB947F82300D7F800A0A8 +:10234000C4F80C802674BAF1000F63D095F8C93038 +:10235000012B6FD001212046FFF7AAFFFFF7DEFB1C +:102360006269136823F0020313606269136843F023 +:1023700001031360636900275F6101212046FFF7B5 +:10238000D3FBFFF7F9FD002800F09580E86DFFF71B +:1023900095FA04F58359BA4609F10809202200216B +:1023A0006846FEF7C7FF02A8FFF784FCCDF818A027 +:1023B0006A4609EB07030DF1180E9446BCE80300CA +:1023C000F44518605960624603F10803F5D1DCF862 +:1023D0000000186020379CF804201A71602FDDD1AE +:1023E00095F8C8306FF38203002785F8C8306A4635 +:1023F00041462046ADF80070ADF802708DF80470CB +:10240000FFF75EFD636948BB4FF400421A6008B0F5 +:10241000BDE8F08741F2D00002F01CFA814610B10D +:102420005146FFF7EBFCC7F80090B9F1000F8DD1D2 +:102430000020ECE7386803681B6B984701460028CA +:1024400088D13868FFF734FF3868036832465B6824 +:102450004146984700287FF47DAFE9E761221A6082 +:102460009DF802309DF803201B06120402F470222E +:1024700003F040731343BDF80020C2F30902134375 +:102480009DF804201205022E02F4E0020CBF4FF06A +:1024900000410021134362690B43D3616369132236 +:1024A0005A616269136823F00103136039462046BC +:1024B000FFF762FD08B96369A6E795F8C93093BBD9 +:1024C0006169D1F8002242F00102C1F8002261697D +:1024D000D1F8002222F47C5222F00E02C1F8002230 +:1024E0006169D1F8002242F46062C1F80022626999 +:1024F000C2F814326269C2F80432626941F6FF71AF +:10250000C2F80C126269C2F840326269C2F8443201 +:1025100063690122C3F81C226269D2F8003223F0F9 +:102520000103C2F8003295F8C83043F0020385F881 +:10253000C8306CE71038002008B500F051F850EAB8 +:102540000103024602D0421E61F10001044B1868EB +:1025500010B10B46FFF744FDBDE8084001F064B838 +:102560001038002008B50020FFF7E8FDBDE808405E +:1025700001F05AB808B50120FFF7E0FDBDE80840BA +:1025800001F052B800B59BB0EFF3098168226846AC +:10259000FEF7BEFEEFF30583014B9B6BFEE700BF2A +:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF +:1025B000EFF3098168226846FEF7AAFEEFF3058370 +:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 +:1025D0000FB408B5029801F019F9FEE701F02EBB1F +:1025E00001F004BB13B56C4684E80600031D94E8B3 +:1025F000030083E80500012002B010BD73B58568B3 +:10260000019155B11B885B0707D4D0E900369B6B5D +:102610009847019AC1B23046A847012002B070BD68 +:10262000F0B5866889B005460C465EB1BDF8383015 +:102630005B070AD4D0E900379B6B98472246C1B2AA +:102640003846B047012009B0F0BD00220023CDE993 +:1026500000230023ADF808300A4603AB01F1080659 +:10266000106851681C4603C40832B2422346F7D1B1 +:10267000106820609288A280FFF7B2FF0423ADF8B3 +:1026800008302B68CDE90001DB6B69462846984786 +:10269000D8E7000030B503680968DD0FB5EBD17FDE +:1026A00023F0604421F060424FEAD1700BD0002B40 +:1026B000B8BFA40C0029B8BF920C944202D034BF1A +:1026C0000120002030BD944205D1C1F38070C3F3D6 +:1026D00080738342F6D194422CBF00200120F1E7A1 +:1026E0002DE9F041456A15B94162BDE8F0814B68BA +:1026F00023F06047C3F38A464FEAD37EC3F3807862 +:1027000016EA230638BF3E46AC462B465A68BEEB57 +:10271000D27F22F060440AD0002A18DAA40CB44216 +:1027200017D19D420FD10D60DEE71346EEE7A742B9 +:1027300007D102F08044C2F3807242450BD054B1FD +:10274000EFE708D2EDE7CCF800100B60CDE7B4421C +:1027500001D0B442E5D81A689C46002AE5D1196038 +:10276000C3E700002DE9F047089D01F007044FEA98 +:10277000D508224405F0070500EBD1004FF47F494E +:10278000944201D1BDE8F08704F0070705F0070A7D +:1027900057453E4638BF5646C6F10806111B8E42C5 +:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 +:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 +:1027C00047FA0AF739408CEA010C03F80EC034448A +:1027D0003544D5E780EA0120082341F2210201B205 +:1027E0004000002980B203F1FF33B8BF504013F01E +:1027F000FF03F4D17047000038B50C468D18A54290 +:1028000000D138BD14F8011BFFF7E4FFF7E7000023 +:1028100042684AB1136843604389818901339BB29E +:102820009942438138BF83811046704770B588B0A4 +:10283000202204460D4668460021FEF77BFD204617 +:102840000495FFF7E5FF024658B16B46054608AE12 +:102850001C4603CCB44228606960234605F1080594 +:10286000F6D1104608B070BD082817D909280CD039 +:102870000A280CD00B280CD00C280CD00D280CD01A +:102880000E2814BF4020302070470C2070471020C5 +:1028900070471420704718207047202070470000B0 +:1028A000082817D90C280CD910280CD914280CD9B1 +:1028B00018280CD920280CD930288CBF0F200E20C6 +:1028C0007047092070470A2070470B2070470C2082 +:1028D00070470D20704700002DE9F843078C072F43 +:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 +:1028F0002006A5F1200029FA05F108FA06F628FAC3 +:1029000000F031430143C9B21846FFF763FF0835B1 +:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 +:102920006BBF4FF6FF70BDE8F883000010B54B6831 +:1029300023B9CA8A63F30902CA8210BD04691A68FE +:102940001C600361C38A013BC3824A60EFE7000059 +:102950002DE9F84F1D46CB8A0F46C3F3090105291F +:10296000814692460B4630D00020AAB207F11A04E5 +:102970009EB2042E1FFA80F80FD8904503F1010390 +:1029800006D3FB8A0A4462F30903FB8201201AE0A2 +:102990001AF80060E6540130EAE79045F1D2A1F15F +:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 +:1029B0008BF6002C45D14846FFF72AFF044638B96C +:1029C00078606FF00200BDE8F88F4FF00008E6E78E +:1029D000002606607860ADB24FF0000B454510D977 +:1029E0000AEB0803221D13F8011B9155B1B208F13F +:1029F00001081B291FFA88F82BD0454506F101066E +:102A0000F1D8FB8AC3F30902154465F30903BCE757 +:102A1000013292B21C462368002BF9D16B1F0B4484 +:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 +:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 +:102A4000BFE70122E7E7C0F800B05E462060044619 +:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 +:102A6000AFE7C0F800B0002620600446B6E70000DB +:102A70002DE9F04F2DED028B1C4683B05B6901926E +:102A800007468846002B00F09A80238C2BB1E26920 +:102A9000002A00F09480072B35D807F10C00FFF7CF +:102AA000B7FE054638B96FF00205284603B0BDEC05 +:102AB000028BBDE8F08F14220021FEF73BFC228C34 +:102AC000E16905F10800FEF723FC208C013080B29B +:102AD000FFF7E6FEFFF7C8FE013880B22084013020 +:102AE00028746369228C1B782A4403F01F0363F067 +:102AF0003F0348F000411372384669602946FFF7EA +:102B0000EFFD0125D1E700F10C034FF0000908EEBD +:102B1000103A4FF0800A4E464D4618EE100AFFF765 +:102B200077FE83460028BED014220021FEF702FC67 +:102B3000002E3AD1019BABF8083002220BF1080EAF +:102B40001FFA82FC0CF10100BCF1060F218C80B24F +:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 +:102B60001278013802F01F028E4208BF4FF0400A6F +:102B700042EA49121BFA80F14AEA020A013048F09F +:102B8000004281F808A08BF81000CBF804205946C9 +:102B90003846FFF7A5FD238C0135B3422DB289F0ED +:102BA00001094FF0000AB8D17FE70022C6E7E169CA +:102BB000895D0EF802100136B6B20132C0E76FF03F +:102BC000010572E7F8B515460E463022002104468D +:102BD0001F46FEF7AFFB069B6360B5F5001F079B22 +:102BE000A76034BF6A094FF6FF72A36297B2E6612D +:102BF00004F1100000239A4206D800230360A78244 +:102C0000E3822383E360F8BD06600133304620365B +:102C1000F1E7000003781BB94BB2002BC8BF01706D +:102C20007047000000787047F8B50C46C969074640 +:102C300011B9238C002B37D1257E1F2D34D838783D +:102C400028BB228C072A2CD8268A36F003032BD1E6 +:102C50004FF6FF70FFF7D0FD20F001003102400475 +:102C600041EA0561400C41EA40254FF6FF722346D8 +:102C700029463846FFF7FCFE002807DD6269137815 +:102C80000133DBB21F2B88BF00231370F8BD218AEC +:102C90002D0645EA012505432046FFF71DFE0246A5 +:102CA000E5E76FF00300F1E76FF00100EEE70000E9 +:102CB00070B58AB0044616460021282268461D4693 +:102CC000FEF738FBBDF83830ADF810300F9B059398 +:102CD0009DF840308DF81830119B07936946BDF878 +:102CE0004830ADF820302046CDE90265FFF79CFF63 +:102CF0000AB070BD2DE9F041D36905460C46164671 +:102D00000BB9138C5BBB377E1F2F28D895F800803A +:102D1000B8F1000F26D03046FFF7DEFD33782102F0 +:102D200041EAC33141EA0801338A41EA076141EAD5 +:102D300003410246334641F080012846FFF798FEE2 +:102D400000280ADD3378012B07D17269137801332B +:102D5000DBB21F2B88BF00231370BDE8F0816FF03A +:102D60000100FAE76FF00300F7E70000F0B58BB061 +:102D700004460D4617460021282268461E46FEF7E7 +:102D8000D9FA9DF84C305A1E534253418DF8003009 +:102D90009DF84030ADF81030119B05939DF84830F8 +:102DA0008DF81830149B07936A46BDF85430ADF87F +:102DB000203029462046CDE90276FFF79BFF0BB075 +:102DC000F0BD0000406A00B104307047436A1A68E1 +:102DD000426202691A600361C38A013BC382704781 +:102DE0002DE9F041D0F82080194E14461D46414689 +:102DF000002709B9BDE8F081D1E90223A21A65EBE9 +:102E00000303964277EB03031ED2036A8B420DD174 +:102E1000FFF78CFD036A1B68036203690B60C38ABA +:102E20000161016A013BC3828846E2E7FFF77EFD4C +:102E30000B68C8F8003003690B60C38A0161013B6D +:102E4000C382D8F80010D4E788460968D1E700BFEC +:102E500080841E002DE9F04F8BB00D46DDF85090B8 +:102E600014469B468046002800F01981B9F1000FF6 +:102E700000F01581531E3F2B00F21181012A03D16E +:102E8000BBF1000F40F00B810023CDE90833B8F807 +:102E90001430B5EBC30F4FEAC30703D300200BB0C8 +:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A +:102EB000FFB227461BB9D8F81030002B7AD0272D47 +:102EC0004ED8C5F12806B7424FF000032CBFF6B22A +:102ED0003E4600932946D8F8080008AB3246FFF773 +:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 +:102EF00003F10053053BDB000493D8F80C30039337 +:102F00002821039B13B1BAF1000F2CD1D8F810007F +:102F100040B1BAF1000F05D0009608AB5246691ACD +:102F2000FFF720FC38B2002FB8D066070AD00AABF2 +:102F300003EBD401624211F8083C02F0070213418E +:102F400001F8083C082C3CD9102C40F2B580202C0C +:102F500040F2B780BBF1000F00F09C80082334E002 +:102F6000BA460026C2E7049BE02B28BFE023069365 +:102F70000B44AB42059314D95A1B03980096924513 +:102F800034BF5246D2B2691A08AB04300792FFF739 +:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 +:102FA0008AFA049B069A05999B1A0493039B1B6853 +:102FB0000393A6E70093D8F8080008AB3A462946E1 +:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD +:102FD000082C12D89DF82030621E23FA02F2D50781 +:102FE00006D54FF0FF3202FA04F423438DF8203067 +:102FF0009DF8203089F8003051E7102C12D8BDF828 +:103000002030621E23FA02F2D10706D54FF0FF32BC +:1030100002FA04F42343ADF82030BDF82030A9F8BB +:1030200000303CE7202C0FD80899631E21FA03F3E7 +:10303000DA0705D54FF0FF3202FA04F40C43089486 +:10304000089BC9F800302AE7402C2BD0DDE9086541 +:10305000611EC4F12102A4F1210326FA01F105FA4F +:1030600002F225FA03F311431943CB0712D50122CB +:10307000A4F12003C4F1200102FA03F322FA01F1C2 +:10308000A240524243EA010363EB430332432B4322 +:10309000CDE90823DDE90823C9E90023FFE66FF045 +:1030A0000100FCE66FF00800F9E6082CA0D9102C0E +:1030B000B3D9202CEED8C3E7BBF1000FADD002236B +:1030C00083E7BBF1000FBBD004237EE730B5012AB4 +:1030D000144638BF0124402C85B028BF4024002569 +:1030E000012ACDE9025518D81B788DF808306307FE +:1030F0000AD004AB03EBD405624215F8083C02F099 +:103100000702934005F8083C00910346224600213F +:1031100002A8FFF727FB05B030BD082AE4D9102A22 +:1031200003D81B88ADF80830E1E7202A8DBFD3E92A +:1031300000231B680293CDE90223D8E710B5CB68C2 +:103140001BB98B600B618B8210BD04691A681C600F +:103150000361C38A013BC382CA60F0E703064CBF28 +:10316000C0F3C0300220704708B50246FFF7F6FFF3 +:10317000022806D15306C2F30F2001D100F003004C +:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E +:1031900003230A6804461046FFF7E0FF022814BF25 +:1031A000C2F306260026002A0D46824680F2F281EE +:1031B00012F0C04940F0EE81097B002900F0EA815D +:1031C000022803D02378B34240F0E781C2F30463BE +:1031D0000693104602F07F030593FFF7C5FF059B9A +:1031E00029444FEA834848EA0A4848EA4668CE78C4 +:1031F00000230022CDE90823F309834648EA0008AA +:10320000029367D0059B009302466768534608A95E +:103210002046B847002800F0C381276A4FB94146CD +:1032200004F10C00FFF702FB074690B96FF00200B3 +:1032300054E03B6998450DD03F68002FF9D14146D5 +:1032400004F10C00FFF7F2FA07460028EED0236ADB +:103250003B60276297F817C006F01F08CCF3840C78 +:10326000ACEB08001FFA80FE0028B8BF0EF120006A +:10327000A8EB0C031FFA83FED7E90221B8BF00B206 +:10328000002B0793BEBF0EF120031BB2079352EA37 +:10329000010338D0039BDFF824E39A1A049B4FF014 +:1032A000000C63EB010196457CEB01032BD36B7B98 +:1032B00097F81AE0734519D1029B002B78D00128AA +:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF +:1032D00016D337E0276A27B96FF00C0013B0BDE8AA +:1032E000F08F3B699845B5D03F68F4E7B24890420B +:1032F0007CEB010301D30020F0E7029B002BFAD006 +:10330000079B0F2B17DCFA7DB30002F0030203F0DA +:103310007C031343FB7539462046FFF707FB6B7BA5 +:10332000BB76029B3BB9FB7DC3F38402013262F39F +:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A +:10334000002B35D0B309022B32D0039BBB60049B0A +:10335000FB60142200210DA8FDF7ECFF039B0A93EC +:10336000049B0B932B1D0C932B7BADF83EB0013BC4 +:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 +:10338000433094F82C308DF840A083F001038DF881 +:1033900044308DF84180A3680AA920469847FB7DF8 +:1033A000C3F38403013303F01F039B02FB82A2E7F4 +:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 +:1033C0008403434540F0F280029A2B7BB609002A21 +:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 +:1033E000049BFB602B7BAE1D033BDBB232463946B0 +:1033F00004F10C00FFF7ACFA00280CDA394620463D +:10340000FFF794FAFB7DC3F38403013303F01F033A +:103410009B02FB820AE7DDE90884AB883B834FF619 +:10342000FF73C9F12000A9F1200228FA09F104FA7A +:1034300000F0014324FA02F211431846C9B2FFF723 +:10344000C9F909F10809B9F1400F0346E9D1B88279 +:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 +:10346000DA43C2F3C01262F3C713FB7543E786B9B0 +:103470002E1D013BDBB23246394604F10C00FFF74A +:1034800067FA0028BADB2A7BB88A013AD2B2314601 +:10349000E2E7F98AC1F30901013B0429DAB25BD8FA +:1034A000281D002307F11B069A4208D910F801CB0A +:1034B00006F801C0013101330529DBB2F4D10399CB +:1034C0000A9104990B91934207F11B010C9138BFAB +:1034D000043379680D9134BF55FA83F300230E93BA +:1034E000FB8AADF83EB0C3F309031A44069B8DF87E +:1034F0004230059B8DF8433094F82C30ADF83C20D9 +:1035000083F001038DF8443000238DF840A08DF83E +:1035100041807B602A7BB88A013A291DFFF76CF94C +:103520003B8BB882834203D1A3680AA920469847FF +:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 +:10354000013303F01F039B02FB823B8B9A420CBFAB +:1035500000206FF01000C1E67B68002BAFD0052083 +:1035600001E01C3033461E68002EFAD1091A081DEE +:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 +:103580009DD89A429BD916F8013B00F8013B09F1FE +:103590000109EFE76FF00900A0E66FF00A009DE671 +:1035A0006FF00B009AE66FF00D0097E66FF00E00DB +:1035B00094E66FF00F0091E640420F0080841E00F9 +:1035C000EFF3098305494A6B22F001024A6368332D +:1035D00083F30988002383F31188704700EF00E02C +:1035E000302080F3118862B60C4B0D4AD96821F463 +:1035F000E0610904090C0A43DA60D3F8FC200949A8 +:1036000042F08072C3F8FC200A6842F001020A60AE +:103610002022DA7783F82200704700BF00ED00E037 +:103620000003FA05001000E010B5302383F3118881 +:103630000E4B5B6813F4006314D0F1EE103AEFF315 +:103640000984683C4FF08073E361094BDB6B2366B0 +:1036500084F3098800F098F810B1064BA36110BDFF +:10366000054BFBE783F31188F9E700BF00ED00E0AD +:1036700000EF00E0030600080606000800F16043C2 +:1036800003F561430901C9B283F80013012200F078 +:103690001F039A4043099B0003F1604303F5614314 +:1036A000C3F880211A60704700F16040090100F5FD +:1036B0006D40C9B2017670470023037582680369C3 +:1036C0001B6899689142FBD25A680360426010609F +:1036D0005860704700230375826803691B68996806 +:1036E0009142FBD85A68036042601060586070478E +:1036F00008B50846302383F311880B7D032B05D0D2 +:10370000042B0DD02BB983F3118808BD8B690022DF +:103710001A604FF0FF338361FFF7CEFF0023F2E71B +:10372000D1E9003213605A60F3E70000FFF7C4BF2D +:10373000054BD9680875186802681A605360012241 +:103740000275D860FCF748BF2038002030B50C4B1C +:10375000DD684B1C87B004460FD02B46094A6846EB +:1037600000F0FEF82046FFF7E3FF009B13B1684628 +:1037700000F000F9A86907B030BDFFF7D9FFF9E7FD +:1037800020380020F1360008044B1A68DB68906886 +:103790009B68984294BF0020012070472038002089 +:1037A000084B10B51C68D86822681A605360012263 +:1037B0002275DC60FFF78EFF01462046BDE8104011 +:1037C000FCF70ABF20380020044B1A68DB689268B7 +:1037D0009B689A4201D9FFF7E3BF70472038002069 +:1037E00038B5074C07490848012300252370656058 +:1037F00000F00AFB0223237085F3118838BD00BF57 +:10380000483A00207C4A00082038002008B572B6EB +:10381000044B186500F0CEF900F092FA024B032237 +:103820001A70FEE720380020483A002000F0B4B8B3 +:10383000EFF3118020B9EFF30583302282F3118872 +:103840007047000010B530B9EFF30584C4F30804E5 +:1038500014B180F3118810BDFFF7B6FF84F311880F +:10386000F9E700008B60022308618B8208467047ED +:103870008368A3F1840243F8142C026943F8442CB2 +:10388000426943F8402C094A43F8242CC26843F8A3 +:10389000182C022203F80C2C002203F80B2C044AEB +:1038A00043F8102CA3F12000704700BFF105000879 +:1038B0002038002008B5FFF7DBFFBDE80840FFF720 +:1038C00035BF0000024BDB6898610F20FFF730BF67 +:1038D00020380020302383F31188FFF7F3BF000066 +:1038E00008B50146302383F311880820FFF72EFF27 +:1038F000002383F3118808BD064BDB6839B14268A9 +:1039000018605A60136043600420FFF71FBF4FF038 +:10391000FF307047203800200368984206D01A68AC +:103920000260506099611846FFF700BF70470000C1 +:1039300010B50A4C23699A6891420CD85A68816084 +:103940000360426010609A685860511A99604FF0A5 +:10395000FF33A36110BD1B68891AECE720380020F3 +:1039600010B4C0E9032300235DF8044B4361FFF763 +:10397000DFBF0000036881689A680A449A60426861 +:1039800013605A6000230360024B4FF0FF329A61CC +:10399000704700BF2038002070B5124DEB692A46F1 +:1039A0000133EB6152F8103F934206D09A68013A16 +:1039B0009A6030262C69A36803B170BDD4E9002158 +:1039C0000A605160236083F31188D4E903312046F3 +:1039D000984786F3118861690029EBD02046FFF7EC +:1039E000A7FFE7E72038002000207047FEE700002F +:1039F000704700004FF0FF3070470000BFF34F8F5B +:103A0000024AD368DB07FCD4704700BF00200240A5 +:103A100008B5074B1B7853B9FFF7F0FF054B1A6940 +:103A2000120641BF044A5A6002F188325A6008BD4A +:103A3000603A0020002002402301674508B5054B8D +:103A40001B7833B9FFF7DAFF034A136943F08003A9 +:103A5000136108BD603A0020002002407F289ABF11 +:103A600000F58030C0020020704700004FF4006075 +:103A700070470000802070477F2808B50BD8FFF7FB +:103A8000EDFF00F500630268013204D10430834287 +:103A9000F9D1012008BD0020FCE700007F2810B507 +:103AA00004461CD8FFF7AAFFFFF7B2FF0D4BF32225 +:103AB000DA6002221A61FFF7D1FF58611A6942F0F9 +:103AC00040021A614FF40061FFF798FF00F034F9EB +:103AD000FFF7B4FF2046BDE81040FFF7CDBF002040 +:103AE00010BD00BF002002402DE9F84312F0010391 +:103AF000144606D01F4B40F2F3221A600020BDE8A6 +:103B0000F88385181C4A954204D91A4A4FF43E712D +:103B10001160F3E7FFF77CFFFFF770FFDFF86880C5 +:103B2000451A4FF00109012C05EB01060F4603D899 +:103B3000FFF784FF0120E2E73B88C8F8109033804C +:103B40000020FFF75BFFC8F81000338831F8022B24 +:103B50009BB29A420CD0074B40F20F321A60074BCF +:103B60001E60074B1C60074B1F60FFF767FFC6E72F +:103B7000023CD8E75C3A002000000408503A0020DC +:103B8000583A0020543A002000200240084908B565 +:103B90000B7828B11BB9FFF73BFF01230B7008BD61 +:103BA000002BFCD0BDE808400870FFF747BF00BFFE +:103BB000603A002008B54FF420414FF0005000F06B +:103BC000BDF8BDE808404FF400514FF0805000F0C0 +:103BD000B5B800000846114600F05EBE012000F0B6 +:103BE0005BBE0000084600F075BE000030B583B033 +:103BF000FFF71EFE0E4B0F4DDB692A684FF47A71FA +:103C000001FB03F3934237BF0B4A0B495168146819 +:103C10002B602EBFD1E90041013151601C1941F1E7 +:103C200000010191FFF70EFE0199204603B030BD5F +:103C300020380020643A0020683A002030B583B074 +:103C4000FFF7F6FD114B124DDB692A684FF47A71CC +:103C500001FB03F3934237BF0E4A0E4951681468C3 +:103C60002B602EBFD1E90041013151601C1941F197 +:103C700000010191FFF7E6FD01994FF47A720023EC +:103C80002046FCF795FA03B030BD00BF2038002075 +:103C9000643A0020683A002010B50244064BD2B2C4 +:103CA000904200D110BD441C00B253F8200041F8EE +:103CB000040BE0B2F4E700BF502800400F4B30B5D2 +:103CC0001C6A240407D41C6A44F440741C621C6AF5 +:103CD00044F400441C620A4C236843F4807323605C +:103CE0000244084BD2B2904200D130BD441C00B215 +:103CF00051F8045B43F82050E0B2F4E700100240B2 +:103D0000007000405028004007B5012201A90020A2 +:103D1000FFF7C2FF019803B05DF804FB13B504463A +:103D2000FFF7F2FFA04205D0012201A90020019473 +:103D3000FFF7C4FF02B010BD7047000070470000DD +:103D400070470000074B45F255521A6002225A6034 +:103D500040F6FF729A604CF6CC421A60024B012288 +:103D60001A70704700300040743A0020034B1B78F3 +:103D70001BB1034B4AF6AA221A607047743A00201E +:103D800000300040044B1A682AB902F1804202F563 +:103D90000432526A1A607047703A0020024B4FF0AA +:103DA00080725A62704700BF0010024008B5FFF7EA +:103DB000E9FF024B1868C0F3407008BD703A00205C +:103DC00070470000FEE700000A4B0B480B4A904288 +:103DD0000BD30B4BDA1C121AC11E22F003028B42CA +:103DE00038BF00220021FDF7A5BA53F8041B40F8A4 +:103DF000041BECE7EC4B0008583C0020583C00202A +:103E0000583C0020FEE7000070B51B4B0163002505 +:103E1000044686B0586085620E46FFF7E1FB04F168 +:103E20001003C4E904334FF0FF33A361134BE56182 +:103E3000D969A5600A462B46C4E9082304F1340178 +:103E4000C4E900440E4AE562256580232046FFF759 +:103E500009FD0123E0600B4A03750092726801922C +:103E6000B268CDE90223084B6846CDE90435FFF777 +:103E700021FD06B070BD00BF483A00202038002068 +:103E8000884A00088D4A0008053E00084B684360D8 +:103E90008B688360CB68C3600B6943614B690362C5 +:103EA0008B6943620B6803607047000008B51B4BC9 +:103EB0009A6A42F4FC029A629A6A22F4FC029A62BA +:103EC0009A6A5A6942F4FC025A61154A5B691146C2 +:103ED0004FF09040FFF7DAFF02F11C0100F580601F +:103EE000FFF7D4FF02F1380100F58060FFF7CEFF45 +:103EF00002F1540100F58060FFF7C8FF02F1700184 +:103F000000F58060FFF7C2FF02F18C0100F58060D0 +:103F1000FFF7BCFFBDE8084000F05AB800100240AF +:103F2000944A000808B500F093F9FFF759FCBDE882 +:103F30000840FFF727BF00007047000010B5214C74 +:103F4000A36A63F4FC03A362A36A03F4FC03A36201 +:103F50004FF0FF32A36A23692261236900232361A2 +:103F60002169E168E260E268E360E268E2691649BB +:103F700042F08052E261E2690A6842F480720A60AB +:103F8000226A02F44072B2F5407F1EBF4FF48032C5 +:103F900022622362236A1B0407D4236A43F440731A +:103FA0002362236A43F40043236200F031F9A369DA +:103FB000064A43F00103A361A369136843F0200399 +:103FC000136010BD0010024000700040000001406E +:103FD0001E4B1A6842F001021A601A689007FCD55D +:103FE0005A6822F003025A605A6812F00C02FBD1A0 +:103FF000196801F0F90119605A601A6842F48032B8 +:104000001A601A689103FCD5114A5A604FF40452A1 +:10401000DA6230221A631A6842F080721A601A68F3 +:104020009201FCD50B4912220A600A6802F00702CD +:10403000022AFAD15A6842F002025A605A6802F023 +:104040000C02082AFAD11A6B1A637047001002405A +:1040500000241D0000200240084A08B55169136879 +:104060000B4003F00103536123B1054A13680BB100 +:1040700050689847BDE80840FFF7D6BA00040140F1 +:10408000783A0020084A08B5516913680B4003F0DC +:104090000203536123B1054A93680BB1D068984776 +:1040A000BDE80840FFF7C0BA00040140783A00209C +:1040B000084A08B5516913680B4003F004035361C3 +:1040C00023B1054A13690BB150699847BDE8084010 +:1040D000FFF7AABA00040140783A0020084A08B560 +:1040E000516913680B4003F00803536123B1054A7B +:1040F00093690BB1D0699847BDE80840FFF794BABF +:1041000000040140783A0020084A08B55169136854 +:104110000B4003F01003536123B1054A136A0BB13E +:10412000506A9847BDE80840FFF77EBA0004014096 +:10413000783A0020174B10B55A691C68144004F4F3 +:1041400078725A61A30604D5134A936A0BB1D06AF8 +:104150009847600604D5104A136B0BB1506B984713 +:10416000210604D50C4A936B0BB1D06B9847E2053E +:1041700004D5094A136C0BB1506C9847A30504D5BC +:10418000054A936C0BB1D06C9847BDE81040FFF71F +:104190004BBA00BF00040140783A00201A4B10B51A +:1041A0005A691C68144004F47C425A61620504D5C3 +:1041B000164A136D0BB1506D9847230504D5134A69 +:1041C000936D0BB1D06D9847E00404D50F4A136E80 +:1041D0000BB1506E9847A10404D50C4A936E0BB1F5 +:1041E000D06E9847620404D5084A136F0BB1506F24 +:1041F0009847230404D5054A936F0BB1D06F9847B5 +:10420000BDE81040FFF710BA00040140783A0020E2 +:10421000062108B50846FFF731FA06210720FFF707 +:104220002DFA06210820FFF729FA06210920FFF7B9 +:1042300025FA06210A20FFF721FA06211720FFF7A9 +:104240001DFABDE8084006212820FFF717BA000034 +:1042500008B5FFF773FE00F067F800F03DF8FFF7D0 +:104260006BFEBDE8084000F05DB8000002684368DE +:104270001143016003B1184770470000143000F08B +:104280002FBA00004FF0FF33143000F029BA0000BD +:10429000383000F0A5BA00004FF0FF33383000F09E +:1042A0009FBA0000143000F0F5B900004FF0FF3164 +:1042B000143000F0EFB90000383000F04FBA0000C1 +:1042C0004FF0FF32383000F049BA0000012914BF26 +:1042D0006FF013000020704700F06CB8044B0360CF +:1042E0000023C0E90233436001230374704700BF19 +:1042F0003C4B000838B5C36904460D461BB9042180 +:104300000844FFF7B3FF294604F1140000F0A6F9B2 +:10431000002806DA201D4FF40061BDE83840FFF7A1 +:10432000A5BF38BD00F00EB80023054A1946013379 +:10433000102BC2E9001102F10802F8D1704700BF4A +:10434000783A00204FF0E023044A5A6100229A6133 +:1043500007221A6108210B20FFF7A6B93F190100B7 +:1043600008B5302383F31188FFF760FA002383F345 +:10437000118808BD08B5FFF7F3FFBDE80840FFF757 +:1043800053B90000026843681143016003B1184744 +:1043900070470000024A136843F0C003136070477F +:1043A00000380140024A136843F0C00313607047AD +:1043B0000044004037B51D4C1D4D2046FFF78EFFD1 +:1043C000009404F114001B490023202200F038F966 +:1043D0002022009404F13800174B184900F0B2F97C +:1043E000174BC4E91735174C0C212520FFF746F968 +:1043F0002046FFF773FF04F11400134900940023D3 +:10440000202200F01DF904F13800104B10490094EF +:10441000202200F097F90F4B0C212620C4E9173514 +:1044200003B0BDE83040FFF729B900BFF83A0020DB +:1044300000512502D03B002095430008103C00208D +:1044400000380140643B0020F03B0020A5430008F9 +:10445000303C0020004400402DE9F047C66D37682D +:10446000F46934622107054619D014F0080118BF19 +:104470004FF48071E20748BF41F02001A30748BF15 +:1044800041F04001600748BF41F08001302383F3D1 +:104490001188281DFFF776FF002383F31188E205BA +:1044A0000AD5302383F311884FF48061281DFFF76C +:1044B00069FF002383F311884FF030094FF0000AA1 +:1044C00014F0200838D13B0616D54FF0300905F11D +:1044D000380A200610D589F31188504600F066F995 +:1044E000002836DA0821281DFFF74CFF27F080034B +:1044F0003360002383F31188790614D5620612D540 +:10450000302383F31188D5E913239A4208D12B6C09 +:1045100033B11021281D27F04007FFF733FF376024 +:10452000002383F31188E30619D5AA6E1369B3B18A +:10453000BDE8F0475069184789F31188B38C95F8A6 +:10454000641028461940FFF7D5FE8AF31188F469F4 +:10455000B6E780B2308588F31188F469B9E7BDE821 +:10456000F087000008B50348FFF776FFBDE8084074 +:10457000FFF75AB8F83A002008B50348FFF76CFF78 +:10458000BDE80840FFF750B8643B0020F8B5154679 +:1045900082680669AA420B46816938BF8568761A27 +:1045A000B54204460BD218462A46FCF7B1FEA36971 +:1045B0002B44A361A3685B1BA3602846F8BD0CD9FC +:1045C00018463246FCF7A4FEAF1BE1683A46304479 +:1045D000FCF79EFEE3683B44EBE718462A46FCF7EF +:1045E00097FEE368E5E7000083689342F7B5154658 +:1045F000044638BF8568D0E90460361AB5420BD24C +:104600002A46FCF785FE63692B446361A36828464C +:104610005B1BA36003B0F0BD0DD932460191FCF7DE +:1046200077FE0199E068AF1B3A463144FCF770FE13 +:10463000E3683B44E9E72A46FCF76AFEE368E4E7FF +:1046400010B50A440024C361029B8460C0E90000E5 +:10465000C0E90511C1600261036210BD08B5D0E96F +:104660000532934201D1826882B982680132826048 +:104670005A1C42611970D0E904329A4224BFC368BF +:1046800043610021FFF748F9002008BD4FF0FF30DB +:10469000FBE7000070B5302304460E4683F3118813 +:1046A000A568A5B1A368A269013BA360531CA361DF +:1046B00015782269934224BFE368A361E3690BB1D3 +:1046C00020469847002383F31188284607E03146A7 +:1046D0002046FFF711F90028E2DA85F3118870BD52 +:1046E0002DE9F74F04460E4617469846D0F81C9021 +:1046F0004FF0300A8AF311884FF0000B154665B170 +:104700002A4631462046FFF741FF034660B941463D +:104710002046FFF7F1F80028F1D0002383F3118839 +:10472000781B03B0BDE8F08FB9F1000F03D0019002 +:104730002046C847019B8BF31188ED1A1E448AF36B +:104740001188DCE7C0E90511C160C3611144009B19 +:104750008260C0E90000016103627047F8B5044659 +:104760000D461646302383F31188A768A7B1A368C6 +:10477000013BA36063695A1C62611D70D4E9043275 +:104780009A4224BFE3686361E3690BB1204698470E +:10479000002080F3118807E031462046FFF7ACF88F +:1047A0000028E2DA87F31188F8BD0000D0E905237C +:1047B0009A4210B501D182687AB98268013282606A +:1047C0005A1C82611C7803699A4224BFC3688361C2 +:1047D0000021FFF7A1F8204610BD4FF0FF30FBE7A6 +:1047E0002DE9F74F04460E4617469846D0F81C9020 +:1047F0004FF0300A8AF311884FF0000B154665B16F +:104800002A4631462046FFF7EFFE034660B941468F +:104810002046FFF771F80028F1D0002383F31188B8 +:10482000781B03B0BDE8F08FB9F1000F03D0019001 +:104830002046C847019B8BF31188ED1A1E448AF36A +:104840001188DCE70B460146184600F02DB8000041 +:1048500000F040B8012838BF012010B504462046BA +:1048600000F030F830B900F007F808B900F00CF8A3 +:104870008047F4E710BD0000024B1868BFF35B8F60 +:10488000704700BF503C002008B5062000F084F8B7 +:104890000120FFF7ABF80000024B0A4601461868FA +:1048A000FFF798B91811002010B5054C13462CB12C +:1048B0000A4601460220AFF3008010BD2046FCE707 +:1048C00000000000024B01461868FFF787B900BFDF +:1048D00018110020024B01461868FFF783B900BF8A +:1048E0001811002010B501390244904201D1002076 +:1048F00005E0037811F8014FA34201D0181B10BD49 +:104900000130F2E72DE9F041A3B1C91A177801444B +:10491000044603F1FF3C8C42204601D9002009E007 +:104920000578BD4204F10104F5D10CEB0405D6185D +:10493000A54201D1BDE8F08115F8018D16F801ED11 +:10494000F045F5D0E7E700001F2938B504460D46CD +:1049500004D9162303604FF0FF3038BD426C12B10A +:1049600052F821304BB9204600F030F82A46014673 +:104970002046BDE8384000F017B8012B0AD0591C7A +:1049800003D1162303600120E7E7002442F8254005 +:10499000284698470020E0E7024B01461868FFF7D9 +:1049A000D3BF00BF1811002038B5074D00230446BF +:1049B000084611462B60FFF71DF8431C02D12B68F7 +:1049C00003B1236038BD00BF543C0020FFF70CB892 +:1049D000034611F8012B03F8012B002AF9D1704787 +:1049E0006F72672E6172647570696C6F742E6633B6 +:1049F00030332D4D313030323500000040A2E4F12B +:104A0000646891060041A3E5F26569920700000021 +:104A10004261642043414E496661636520696E646A +:104A200065782E00800000000080000000008000FB +:104A30000000000000000000351B000819230008DA +:104A400079220008451B0008791B0008751D000825 +:104A5000491B0008591B00084D1B0008551B000886 +:104A6000511B00089D1C00085D1B0008E52500087F +:104A70006D1B0008711C000863300000784A0008B4 +:104A800078380020483A00206D61696E0069646CD6 +:104A900065000000A001A82A00000000FAAABEAA32 +:104AA00050001424EFFF0000007700007097090009 +:104AB0000100000000000000AAAAAAAA010000004C +:104AC000FFFF0000000000000000000000000000E8 +:104AD00000000000AAAAAAAA00000000FFFF000030 +:104AE00000000000000000000000000000000000C6 +:104AF000AAAAAAAA00000000FFFF00000000000010 +:104B0000000000000000000000000000AAAAAAAAFD +:104B100000000000FFFF0000000000000000000097 +:104B20000000000000000000AAAAAAAA00000000DD +:104B3000FFFF000000000000000000000000000077 +:104B40009942000885420008C1420008AD420008B1 +:104B5000B9420008A5420008914200087D420008C1 +:104B6000CD4200087CB6FF7F01000000000000007D +:104B7000EC030000000000000098030000000000AB +:104B8000FE2A0100D20400001C11002000000000D9 +:104B90000000000000000000000000000000000015 +:104BA0000000000000000000000000000000000005 +:104BB00000000000000000000000000000000000F5 +:104BC00000000000000000000000000000000000E5 +:104BD00000000000000000000000000000000000D5 +:0C4BE000000000000000000000000000C9 :00000001FF diff --git a/Tools/bootloaders/f303-M10070_bl.bin b/Tools/bootloaders/f303-M10070_bl.bin index ea2f3b654dab5b..e09904fb01dd9a 100755 Binary files a/Tools/bootloaders/f303-M10070_bl.bin and b/Tools/bootloaders/f303-M10070_bl.bin differ diff --git a/Tools/bootloaders/f303-M10070_bl.elf b/Tools/bootloaders/f303-M10070_bl.elf index cd8dd84fe75473..403ba5566ccc74 100755 Binary files a/Tools/bootloaders/f303-M10070_bl.elf and b/Tools/bootloaders/f303-M10070_bl.elf differ diff --git a/Tools/bootloaders/f303-M10070_bl.hex b/Tools/bootloaders/f303-M10070_bl.hex index 18f1da6c868910..9f424cf403bd91 100644 --- a/Tools/bootloaders/f303-M10070_bl.hex +++ b/Tools/bootloaders/f303-M10070_bl.hex @@ -1,980 +1,1217 @@ :020000040800F2 -:1000000000090020A5040008E1140008611400089C -:10001000B9140008611400088D140008A704000832 -:10002000A7040008A7040008A704000881350008F9 -:10003000A7040008A7040008A7040008B93A0008AC -:10004000A7040008A7040008A7040008A7040008E4 -:10005000A7040008A7040008513800087D380008EC -:10006000A9380008D538000801390008A70400089D -:10007000A7040008A7040008A7040008A7040008B4 -:10008000A7040008A7040008A70400082924000802 -:1000900095240008E92400083D2500082D390008B2 -:1000A000A7040008A7040008A7040008A704000884 -:1000B000A7040008A7040008A7040008A704000874 -:1000C000A7040008A7040008A7040008A704000864 -:1000D000A70400088129000895290008A704000842 -:1000E00095390008A7040008A7040008A704000821 -:1000F000A7040008A7040008A7040008A704000834 -:10010000A7040008A7040008A7040008A704000823 -:10011000A7040008A7040008A7040008A704000813 -:10012000A7040008A7040008A7040008A704000803 -:10013000A7040008A7040008A7040008A7040008F3 -:10014000A7040008A7040008A7040008A7040008E3 -:10015000A7040008A7040008A7040008A7040008D3 -:10016000A7040008A7040008A7040008A7040008C3 -:10017000A7040008A7040008A7040008A7040008B3 -:10018000A7040008A7040008A7040008A7040008A3 -:10019000A7040008A7040008A7040008A704000893 -:1001A00053B94AB9002908BF00281CBF4FF0FF31DE -:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA -:1001C00000F006F8DDF804E0DDE9022304B0704732 -:1001D0002DE9F047089D04468E46002B4DD18A42FA -:1001E000944669D9B2FA82F252B101FA02F3C2F12D -:1001F000200120FA01F10CFA02FC41EA030E9440BE -:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE -:1002100016E341EA034306FB07F199420AD91CEBB6 -:10022000030306F1FF3080F01F81994240F21C81E8 -:10023000023E63445B1AA4B2B3FBF8F008FB103330 -:1002400044EA034400FB07F7A7420AD91CEB040465 -:1002500000F1FF3380F00A81A74240F20781644435 -:10026000023840EA0640E41B00261DB1D4400023BA -:10027000C5E900433146BDE8F0878B4209D9002D1E -:1002800000F0EF800026C5E9000130463146BDE8A8 -:10029000F087B3FA83F6002E4AD18B4202D3824212 -:1002A00000F2F980841A61EB030301209E46002DC1 -:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 -:1002C000002A40F09280A1EB0C014FEA1C471FFA74 -:1002D0008CFE0126200CB1FBF7F307FB131140EA5B -:1002E00001410EFB03F0884208D91CEB010103F128 -:1002F000FF3802D2884200F2CB804346091AA4B2EA -:10030000B1FBF7F007FB101144EA01440EFB00FEBD -:10031000A64508D91CEB040400F1FF3102D2A64522 -:1003200000F2BB800846A4EB0E0440EA03409CE7C1 -:10033000C6F12007B34022FA07FC4CEA030C20FA6E -:1003400007F401FA06F31C43F9404FEA1C4900FA8E -:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B -:1003600040EA014108FB0EF0884202FA06F20BD97E -:100370001CEB010108F1FF3A80F08880884240F2CE -:100380008580A8F102086144091AA4B2B1FBF9F012 -:1003900009FB101144EA014100FB0EFE8E4508D90D -:1003A0001CEB010100F1FF346CD28E456AD9023892 -:1003B000614440EA0840A0FB0294A1EB0E01A14277 -:1003C000C846A64656D353D05DB1B3EB080261EBE5 -:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF -:1003E000007100263146BDE8F087C2F12003D840F5 -:1003F0000CFA02FC21FA03F3914001434FEA1C4737 -:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 -:10041000064300FB0EF69E4204FA02F408D91CEBD8 -:10042000030300F1FF382FD29E422DD902386344D6 -:100430009B1B89B2B3FBF7F607FB163341EA034176 -:1004400006FB0EF38B4208D91CEB010106F1FF38C5 -:1004500016D28B4214D9023E6144C91A46EA0046BC -:1004600038E72E46284605E70646E3E61846F8E64E -:100470004B45A9D2B9EB020864EB0C0E0138A3E797 -:100480004646EAE7204694E74046D1E7D0467BE778 -:10049000023B614432E7304609E76444023842E7F0 -:1004A000704700BF02E000F000F8FEE772B63A487D -:1004B00080F30888394880F3098839484EF6085196 -:1004C000CEF20001086040F20000CCF200004EF6CF -:1004D0003471CEF200010860BFF34F8FBFF36F8F0E -:1004E00040F20000C0F2F0004EF68851CEF200015A -:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 -:10050000100A4EF63C71CEF200010860062080F31E -:100510001488BFF36F8F03F0B3F803F08FF803F084 -:10052000C1F84FF055301F491B4A91423CBF41F87A -:10053000040BFAE71C49194A91423CBF41F8040BED -:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C -:1005500042F8040BF8E700201749184A91423CBFC3 -:1005600041F8040BFAE703F06DF803F0D7F8144CE8 -:10057000144DAC4203DA54F8041B8847F9E700F045 -:1005800041F8114C114DAC4203DA54F8041B884772 -:10059000F9E703F055B80000000900200011002021 -:1005A000000000080001002000090020F83C0008BD -:1005B00000110020201100202011002028260020FA -:1005C000A0010008A0010008A0010008A001000887 -:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F -:1005E000BDEC108ABDE8F08F002383F31188284604 -:1005F000A047002002F04CFDFEE702F0D1FC00DF36 -:10060000FEE700002DE9F04102F062FF074602F02C -:10061000ADFF054600283ED12B4B9F423BD0013316 -:100620009F423BD0294B27F0FF029A423AD1F8B2C1 -:1006300000F054FAA84642F2107400F059FC08B1D8 -:100640000024A04600F050FA064678B384BB464624 -:1006500035B11F4B9F4203D002F080FF0024264695 -:10066000002002F03FFF1B4B1B6913F0400322D018 -:100670000EB100F031F800F05FFC00F031FE00F048 -:1006800031FF0546CCB100F02DFF401BA04214D92C -:1006900000F022F8F3E7A8460024CEE704464FF026 -:1006A0000108CAE780464FF47A74C6E70446CFE7EC -:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 -:1006C00002F0ECFCDEE700BF010007B0000008B05C -:1006D000263A09B00004004838B51D4A1D4B196878 -:1006E000013134D004339342F9D11B4C194DD4F865 -:1006F0000428AA422BD3194B9B6803F1006303F52E -:10070000D0439A4223D202F0FDFE02F00FFF0020F8 -:1007100000F000FE124B0220187000F037FE114B63 -:10072000DA690022DA61D96999699A619B6972B6BE -:100730004FF0E0232021C3F8085DD4F80038D4F846 -:10074000042881F311889D4683F30888104738BD3B -:100750002068000800680008006000080011002000 -:100760002011002000100240094A136849F2690074 -:1007700099B21B0C00FB01331360064B186844F25E -:10078000506182B2000C01FB0200186080B2704719 -:100790001C1100201811002010B500211022044661 -:1007A00000F00EFE034B03CB206061601868A06070 -:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 -:1007C00000F090FEAB6840F2ED22C31A934232D99A -:1007D00006AFA8602B4628220021384601F05EFBB8 -:1007E00005F10E0000F0E4FD002604465FFA80F9F2 -:1007F00005F10E08F3B2F100994501F1280107D97E -:1008000008EB06030822384601F048FB0136F1E701 -:1008100008230122CDE9023205340C4B0193A4B226 -:1008200030230093CDE9047405A3D3E90023297B89 -:10083000074801F04BF93BB0BDE8F083AFF300800F -:1008400078F6339F93CACD8D682100207521002052 -:100850003C21002070B50D4614461E4601F0CCF830 -:1008600050B9022E10D1012C0ED112A3D3E90023CE -:10087000C5E90023012007E0282C10D005D8012C61 -:1008800009D0052C0FD0002070BD302CFBD10BA35C -:10089000D3E90023ECE70BA3D3E90023E8E70BA39C -:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B -:1008B000AFF30080401DA12026812A0B78F6339FDC -:1008C00093CACD8D9E6AC421818A46EE26417272FA -:1008D000DF25D7B7F017304A39059E5613B50446C1 -:1008E0002346084620220021019001F0D7FA227900 -:1008F0000198032A234628BF032203F8042F20214E -:10090000022201F0CBFA62790198072A234628BF18 -:10091000072203F8052F2221032201F0BFFAA27952 -:100920000198072A234628BF072203F8062F25210E -:10093000032201F0B3FA019804F1080310222821E0 -:1009400001F0ACFA382002B010BD00002DE9F04FE4 -:10095000ADF5017D21AD0EAE40F2751280460F4619 -:1009600022A80021296000F02BFD482200213046FA -:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 -:10098000F2F0186093E80700012386E807000DF1F4 -:100990005A003382FFF700FF4EF60343338407AB60 -:1009A00018464D4903F0C2F81B22306429463046F0 -:1009B00086F83C20FFF792FF12AB0446014608225E -:1009C000284601F06BFA0822A1180DF149032846C8 -:1009D00001F064FA0DF14A03082204F110012846DF -:1009E00001F05CFA13AB202204F11801284601F053 -:1009F00055FA14AB402204F13801284601F04EFAB2 -:100A000016AB082204F17801284601F047FA0DF1EF -:100A10005903082204F18001284601F03FFA04F14D -:100A2000880A0DF15A0904F5847B4B465146082289 -:100A300028460AF1080A01F031FAD34509F1010903 -:100A4000F3D11BAB08225946284601F027FA04F5DA -:100A500088744FF0000996F834304B450AD9B36BCF -:100A600021464B440822284601F018FA083409F1BF -:100A70000109F0E74FF0000996F83C304B4504EBD4 -:100A8000C90108D9336C08224B44284601F006FA04 -:100A900009F10109F0E700230393BB7E02930731BC -:100AA00007F119030193C1F3CF010123CDE90451EB -:100AB0000093F97E05A3D3E90023404601F006F830 -:100AC0000DF5017DBDE8F08FAFF300809E6AC42173 -:100AD000818A46EE241100203C3B0008014B18702F -:100AE000704700BF30110020F0B5334B1C7B85B040 -:100AF00034B1324B0E221A810024204605B0F0BDDD -:100B00002F4A1068516802AB03C308232D492E48B1 -:100B10000DEB030202F0E8FF054630B9274B2B48E6 -:100B20000A221A8100F098FCE6E70169B1F5663FF8 -:100B300006D9224B26480B221A8100F08DFCDCE7F7 -:100B4000438BB3F57B7F09D01C4A22480C211181CD -:100B50004FF47B72194600F07FFCCEE71E4A024438 -:100B600002F11003994204D2144B1C4810221A813E -:100B7000E3E710398E1A2046134900F0B7FC3246DD -:100B8000074605F11801204600F0B0FCAB689F4213 -:100B900002D1EB6898420AD0084B0D221A810090CE -:100BA000D5E902123B460E4800F056FCA4E70D487A -:100BB00000F052FC0124A0E768210020241100204D -:100BC000E93B0008DC97030000680008583B000878 -:100BD000643B0008763B00080898FFF7943B000848 -:100BE000B13B0008DA3B00082DE9F04FADB006AF8D -:100BF00080460C4600F000FF054600285AD1237EAF -:100C0000022B1BD1E38A012B18D100F06BFC0646A6 -:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C -:100C2000F0F206F5167602FB103316FA83F3C9F8D4 -:100C30000030E37E33B9A84B00221A709C37BD46C2 -:100C4000BDE8F08FA38AEEB2013BB34205F1010586 -:100C50000BD93B1D1E44E90000960023082201F039 -:100C6000F801204600F0DEFFECE707F11400FFF783 -:100C700093FD324607F11401381D02F025FF0028CC -:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 -:100C90001673C9F80030D1E7FB1CF87001460093C9 -:100CA00007220346204600F0BDFFF978404600F0D9 -:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 -:100CC000052BBBD1BFF34F8F8449854BCA6802F413 -:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 -:100CE000ACD1637E7F4D01336A7BDBB29342E94630 -:100CF00003D1E27E2B7B9A4265D0CD469EE721460A -:100D00004046FFF723FE99E7A38A013B9BB2C92B1C -:100D100094D8744D2E7B26BB05F10C03009308225A -:100D200033463146204600F07DFF731CF2B2D900F5 -:100D30001E46A38A013B9A4205DA0E322A440092EB -:100D400000230822EEE700230022C5E90023002348 -:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 -:100D60002B73002507F114093B1D0822294648462C -:100D7000C7E90155FD6001F091F83B7A05F1010AE0 -:100D8000AB424FEACA0608D9FB6808222B44314619 -:100D9000484601F083F85546EFE7C6F3CF06E17EFB -:100DA000CDE9049600230393A37E029319342823EC -:100DB0000093019446A3D3E90023404600F086FE49 -:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 -:100DD00014801022009341460123204600F022FF98 -:100DE000A68A023EB6B2F31C9B109B000733DB08B9 -:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 -:100E0000C801B34201F110010AD20AEB08030093B2 -:100E100008220023204600F005FF08F10108ECE756 -:100E200095F8D70000F080FAD5F8D83004461BB901 -:100E300095F8D70000F088FAD5F8D83033449C42B2 -:100E400004D295F8D700013000F07EFA4FEA960BF5 -:100E50004FF000081FFA88F18B45D5E9003209D917 -:100E60000AEB880103EB8800012200F0B1FA08F1D7 -:100E70000108EFE7F31842F10002C5E90032D5F8A6 -:100E8000D83095F8D70006EB0308C5F8D88000F0F5 -:100E90004BFA804509D395F8D730D5F8D8000133FF -:100EA000001B85F8D730C5F8D800FF2E08D80023DE -:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D -:100EC0002B68094A9B0A013313810023AB6014E7A6 -:100ED00026417272DF25D7B73521002000ED00E0F2 -:100EE0000400FA0568210020241100203821002088 -:100EF00010B54FF000540C4B22689A4211D10B4BA5 -:100F0000627D1A700A48237D03730A49C9220E3094 -:100F100000F044FAE0220021204600F051FA0120BE -:100F200010BD0020FCE700BF9AAD44C53011002081 -:100F300068210020160000202DE9FF41434C0223C8 -:100F400063710023029324250A23581EB5FBF3F690 -:100F50007343D3F12402C1B23ED002280346F4D138 -:100F60009DF80B303A493B485A1E9DF80A30013B28 -:100F70001B0443EA0253BDF80820013A13434B60B7 -:100F800001F044FD00230193334B3449009334486E -:100F9000344B4FF4805200F001FD334B197811B1FE -:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D -:100FB0004FF4C873B0FBF3F202FB130305F5167090 -:100FC00010FA83F0294B186002F0D0FA08B10F2311 -:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF -:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA -:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F -:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 -:10101000CDB2591E0F2916D86A1E072A8CBF00228E -:101020000122591901FB06601149B1FBF0F1114889 -:10103000814295D1002A93D0ADF808608DF80A302E -:101040008DF80B508CE71346EBE700BF241100200E -:1010500010110020802200205508000834110020C3 -:101060003C210020E90B000830110020382100202D -:101070000051250240420F002DE9F04F90A7D7E91B -:1010800000670FF24429D9E90089874D93B0DFF852 -:1010900040B2864C284600F07DFD0DF1300A0790E5 -:1010A00070B310220021504600F08AF9079B197B8B -:1010B0004FF0000261F303028DF830205868996800 -:1010C0000EAA03C21B680D9A63F31C029DF8303010 -:1010D0000D9243F020038DF830300023524619461C -:1010E000584601F0A3FC079028B9284600F056FDA9 -:1010F000079B2370CEE72378072B3CD8013323705E -:1011000018220021504600F05BF9DFF8C4B100233B -:1011100019465246584601F0B1FC014678BB1022F0 -:1011200008A800F04DF94FF0904209AC536983F0E4 -:101130001003536100F0D8F90B4612A9024611E9D9 -:10114000030084E803009DF83410C1F3030089060E -:101150004CBF0E9CBDF838408DF82C0046BFC4F340 -:101160001C0444F00044C4F30A0408A92846089467 -:1011700000F0DCFECBE7284600F010FDC0E7284673 -:1011800000F03AFC0446002848D1DFF848B100F0EE -:10119000A9F9DBF80030984240D300F0A3F907909A -:1011A000FFF7E2FA079A8DF8204003464FF4C87023 -:1011B00002F51672B3FBF0F101FB103312FA83F360 -:1011C000CBF80030DFF810B19BF8001011B9012303 -:1011D0008DF8203050460791FFF7DEFA0799C1F1EC -:1011E0001004E4B2062C28BF0624224651440DF117 -:1011F000210000F0D3F808AB0393182302930134C5 -:101200002B4B0193E4B20123009304943B463246F6 -:10121000284600F0F3FB00238BF8003000F062F961 -:10122000244A254C1368C31AB3F57A7F31D3106072 -:1012300000F05AF902460B46284600F0B9FC284651 -:1012400000F0DAFB28B3237BDFF890B0002B14BF4B -:10125000032302238BF8053000F044F94FF47A732E -:101260005146B0FBF3F0CBF800005846FFF736FBD1 -:10127000182307300293114B0193C0F3CF0040F2C3 -:101280005513CDE903A0009342464B46284600F093 -:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 -:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 -:1012B0003421002048220020682100204C220020F8 -:1012C000401DA12026812A0BF1C6A7C1D068080FB6 -:1012D0008022002038210020352100202411002008 -:1012E00070B501F0B5FF094E094D30800024286823 -:1012F0003388834208D901F0A7FF2B6804440133E7 -:10130000B4F5D04F2B60F2D370BD00BF7C2200201B -:101310005022002002F03AB800F10060920000F57F -:10132000D04001F0D5BF0000054B1A68054B1B8863 -:101330009B1A834202D9104401F086BF00207047F7 -:10134000502200207C22002038B5074D0446286832 -:10135000204401F07FFF28B928682044BDE83840C8 -:1013600001F08ABF38BD00BF50220020064991F825 -:10137000243033B10023086A81F824300822FFF7B3 -:10138000CBBF0120704700BF54220020022802BFBB -:101390004FF090434FF480129A61704710B50023CC -:1013A000934203D0CC5CC4540133F9E710BD000074 -:1013B00003460246D01A12F9011B0029FAD17047E0 -:1013C00002440346934202D003F8011BFAE7704738 -:1013D0002DE9F8431F4D144695F82420074688460A -:1013E00052BBDFF870909CB395F824302BB92022C3 -:1013F000FF2148462F62FFF7E3FF95F82400C0F174 -:101400000802A24228BF2246D6B24146920005EB0E -:101410008000FFF7C3FF95F82430A41B1E44F6B2EA -:10142000082E17449044E4B285F82460DBD1FFF71E -:101430009DFF0028D7D108E02B6A03EB820383428B -:10144000CFD0FFF793FF0028CBD10020BDE8F88371 -:101450000120FBE7542200200FB4002004B07047A5 -:1014600000B59BB0EFF3098168226846FFF796FF4D -:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E -:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D -:10149000EFF3098168226846FFF780FFEFF30583C9 -:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF -:1014B000FEE700BF00ED00E000B59BB0EFF309814F -:1014C00068226846FFF76AFFEFF30583034B5A6B08 -:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 -:1014E000FEE7000001F08EBF01F064BF30B5094D8A -:1014F0000A4491420DD011F8013B5840082340F3B3 -:101500000004013B2C4013F0FF0384EA5000F6D1A5 -:10151000EFE730BD2083B8ED2DE9F041C56915B97D -:10152000C161BDE8F0814B6823F06047C3F38A4690 -:101530004FEAD37EC3F3807816EA230638BF3E46CF -:10154000AC462B465A68BEEBD27F22F060440AD0EC -:10155000002A18DAA40CB44217D19D420FD10D60B5 -:10156000DEE71346EEE7A74207D102F08044C2F35C -:10157000807242450BD054B1EFE708D2EDE7CCF8CA -:1015800000100B60CDE7B44201D0B442E5D81A6830 -:101590009C46002AE5D11960C3E700002DE9F04719 -:1015A000089D01F007044FEAD508224405F007051D -:1015B00000EBD1004FF47F49944201D1BDE8F087A0 -:1015C00004F0070705F0070A57453E4638BF564660 -:1015D000C6F10806111B8E4228BF0E46E10808EB33 -:1015E000D50E415C13F80EC0B94029FA06F721FA6E -:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 -:10160000010C03F80EC034443544D5E780EA0120CC -:10161000082341F2210201B24000002980B203F107 -:10162000FF33B8BF504013F0FF03F4D17047000000 -:1016300038B50C468D18A54200D138BD14F8011BF1 -:10164000FFF7E4FFF7E7000002684AB113680360A0 -:10165000C388018901339BB29942C38038BF03819B -:101660001046704770B588B0202204460D46684683 -:101670000021FFF7A5FE20460495FFF7E5FF02468F -:1016800058B16B46054608AE1C4603CCB4422860F0 -:101690006960234605F10805F6D1104608B070BD13 -:1016A000082817D909280CD00A280CD00B280CD0F0 -:1016B0000C280CD00D280CD00E2814BF4020302050 -:1016C00070470C2070471020704714207047182076 -:1016D0007047202070470000082817D90C280CD923 -:1016E00010280CD914280CD918280CD920280CD96A -:1016F00030288CBF0F200E207047092070470A2029 -:1017000070470B2070470C2070470D207047000079 -:1017100010B54B6823B9CA8A63F30902CA8210BDA7 -:10172000C4681A681C60C360438A013B43824A60F4 -:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 -:1017400009010629814692460B4630D00020AAB2F4 -:1017500007F119049EB2052E1FFA80F80FD89045A4 -:1017600003F1010306D3FB8A0A4462F30903FB82F7 -:1017700001201AE01AF80060E6540130EAE79045CB -:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 -:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 -:1017A000044638B978606FF00200BDE8F88F4FF05A -:1017B0000008E6E7002606607860ADB24FF0000B47 -:1017C000454510D90AEB0803221D13F8011B91555A -:1017D000B1B208F101081B291FFA88F82BD0454542 -:1017E00006F10106F1D8FB8AC3F30902154465F33B -:1017F0000903BCE7013292B21C462368002BF9D1E1 -:10180000AB1F0B441C21B3FBF1F301339BB29A4293 -:10181000D3D2BBF1000FD0D14846FFF715FF20B956 -:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 -:1018300020600446C1E74545D5D94846FFF704FF77 -:1018400008B92060AFE7C0F800B000262060044669 -:10185000B6E700002DE9F04F2DED028B83B0CDE906 -:101860000013BDF83C5007469146002A00F09280D4 -:101870002DB10E9B002B00F08D80072D32D807F183 -:101880000C00FFF7E1FE044638B96FF00204204671 -:1018900003B0BDEC028BBDE8F08F14220021FFF7EE -:1018A0008FFD0E992A4604F10800FFF777FD681CAA -:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 -:1018C000013814FA80F003F01F0363F03F03037242 -:1018D000009B43F00041616038462146FFF71CFE43 -:1018E0000124D4E700F10C034FF0000808EE103A91 -:1018F0004FF0800A4646444618EE100AFFF7A4FE51 -:1019000083460028C1D014220021FFF759FDC6BB31 -:10191000019BABF8083002200E9B00F108029919D8 -:101920005BFA82F20130C0B2082801D0AE422AD35D -:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E -:1019400002F01F0242EA4812AE4208BF4FF0400ABE -:101950005BFA81F14AEA020A43F0004281F808A0EA -:101960008BF81000CBF8042059463846FFF7D4FD19 -:101970000134AE4224B288F001084FF0000ABBD116 -:1019800085E70020C8E711F801CB02F801CB01364A -:10199000B6B2C7E76FF0010479E70000F8B5154665 -:1019A0000E462822002104461F46FFF709FD069B2C -:1019B0006360B5F5001F079BA76034BF6A094FF647 -:1019C000FF72236204F10C0097B200239A4205D8FB -:1019D0000023036027826382A382F8BD066001337F -:1019E00030462036F2E7000003781BB94BB2002BDB -:1019F000C8BF017070470000007870472DE9F74FAD -:101A0000DDF83C90BDF830500D9E9DF83840BDF893 -:101A10004070804692469B46B9F1000F01D1002FDD -:101A200051D11F2C4FD898F80000B0B9072F47D8D4 -:101A300035F0030347D13A4649464FF6FF70FFF7AA -:101A4000F7FD20F001002D02400445EA0464400C3B -:101A500044EA40244FF6FF7321E040EA0520072FB7 -:101A600040EA0464F6D900254FF6FF73C5F1200063 -:101A7000A5F120022AFA05F10BFA00F001432BFA36 -:101A800002F211431846C9B2FFF7C0FD0835402DD8 -:101A90000346EBD13A464946FFF7CAFD0346CDE976 -:101AA0000097324621464046FFF7D4FE3378013393 -:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B -:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 -:101AD00085B09246DDF848800F9D9DF840209DF826 -:101AE0004490BDF84C7006469B46B8F1000F01D1FA -:101AF000002F48D11F2A46D83378002B46D00C023D -:101B000044EA02649DF8381044EAC93444EA0144C6 -:101B10001C43072F44F0800432D900234FF6FF7294 -:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC -:101B300041EA0C012BFA00F00143C9B210460393AD -:101B4000FFF764FD039B0833402B0246E8D13A4679 -:101B50004146FFF76DFD0346CDE900872A46214641 -:101B60003046FFF777FEB9F1010F06D12B7801332C -:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 -:101B80004FF6FF73E8E76FF00100F6E76FF0030030 -:101B9000F3E70000C06900B104307047C3691A68F8 -:101BA000C261C2681A60C360438A013B43827047C6 -:101BB0002DE9F041D0F81880194E14461D464146D3 -:101BC000002709B9BDE8F081D1E90223A21A65EB2B -:101BD0000303964277EB03031ED283698B420DD138 -:101BE000FFF796FD83691B688361C3680B60438AB6 -:101BF000C1608169013B43828846E2E7FFF788FDC7 -:101C00000B68C8F80030C3680B60438AC160013BB1 -:101C10004382D8F80010D4E788460968D1E700BFAE -:101C200080841E002DE9F04F8BB00D46DDF85090FA -:101C300014469B468046002800F01981B9F1000F38 -:101C400000F01581531E3F2B00F21181012A03D1B0 -:101C5000BBF1000F40F00B810023CDE90833B8F849 -:101C60001430B5EBC30F4FEAC30703D300200BB00A -:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C -:101C8000FFB227461BB9D8F81030002B7AD02F2D81 -:101C90004ED8C5F13006B7424FF000032CBFF6B264 -:101CA0003E4600932946D8F8080008AB3246FFF7B5 -:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 -:101CC00003F10053063BDB000493D8F80C30039378 -:101CD0003021039B13B1BAF1000F2CD1D8F81000BA -:101CE00040B1BAF1000F05D0009608AB5246691A10 -:101CF000FFF754FC38B2002FB8D066070AD00AAB01 -:101D000003EBD401624211F8083C02F007021341D0 -:101D100001F8083C082C3CD9102C40F2B580202C4E -:101D200040F2B780BBF1000F00F09C80082334E044 -:101D3000BA460026C2E7049BE02B28BFE0230693A7 -:101D40000B44AB42059314D95A1B03980096924555 -:101D500034BF5246D2B2691A08AB04300792FFF77B -:101D60001DFC079A1644AAEB020A1544F6B25FFA64 -:101D70008AFA049B069A05999B1A0493039B1B6895 -:101D80000393A6E70093D8F8080008AB3A46294623 -:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F -:101DA000082C12D89DF82030621E23FA02F2D507C3 -:101DB00006D54FF0FF3202FA04F423438DF82030A9 -:101DC0009DF8203089F8003051E7102C12D8BDF86A -:101DD0002030621E23FA02F2D10706D54FF0FF32FF -:101DE00002FA04F42343ADF82030BDF82030A9F8FE -:101DF00000303CE7202C0FD80899631E21FA03F32A -:101E0000DA0705D54FF0FF3202FA04F40C430894C8 -:101E1000089BC9F800302AE7402C2BD0DDE9086583 -:101E2000611EC4F12102A4F1210326FA01F105FA91 -:101E300002F225FA03F311431943CB0712D501220D -:101E4000A4F12003C4F1200102FA03F322FA01F104 -:101E5000A240524243EA010363EB430332432B4364 -:101E6000CDE90823DDE90823C9E90023FFE66FF087 -:101E70000100FCE66FF00800F9E6082CA0D9102C50 -:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD -:101E900083E7BBF1000FBBD004237EE730B5012AF6 -:101EA000144638BF0124402C85B028BF40240025AB -:101EB000012ACDE9025518D81B788DF80830630740 -:101EC0000AD004AB03EBD405624215F8083C02F0DB -:101ED0000702934005F8083C009103462246002182 -:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 -:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D -:101F000000231B680293CDE90223D8E710B5CB6804 -:101F10001BB98B600B618B8210BDC4681A681C6092 -:101F2000C360438A013B4382CA60F0E72DE9F04F6A -:101F3000D1F8008093B018F0800FCDE90323C8F3E7 -:101F4000C01219BFC8F3C03BC8F306264FF0020BFE -:101F50001646B8F1000F04460D4680F2D18118F004 -:101F6000C043059340F0CC810B7B002B00F0C8816F -:101F7000BBF1020F03D00178B14240F0C48108F0F8 -:101F80007F0106916AB3C8F3074A2B44069A93F877 -:101F90000390760646EA0B4646EA82465FEAD91384 -:101FA00046EA0A06079300F0908000220023CDE95C -:101FB0000A23069B009367685B4652460AA920469F -:101FC000B84700287ED0A7699FB9314604F10C00BC -:101FD000FFF748FB0746E0B96FF0020013B0BDE819 -:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A -:101FF000CBE73B699E420DD03F68002FF9D13146B7 -:1020000004F10C00FFF72EFB07460028E4D0A3697B -:102010003B60A761DDE90A2300264FF6FF70C6F199 -:10202000200E22FA06F103FA0EFEA6F1200C23FA86 -:102030000CFC41EA0E0141EA0C01C9B208360992D2 -:102040000893FFF7E3FA402EDDE90832E7D1B882C2 -:10205000FB7D09F01F06C3F384039B1BD7E9022114 -:1020600098B2002BBCBF00F120031BB252EA010062 -:10207000C8F304680FD00398821A049860EB01013A -:10208000A74890424FF000028A4104D3079A002AE1 -:102090005BD0012B23DDFA7D4FEA890302F00302B6 -:1020A00003F07C031343FB7539462046FFF730FBF2 -:1020B000079BA3B9FB7DC3F38402013262F386035D -:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 -:1020D0000C0083E73B699E42BAD03F68F6E719F0EF -:1020E000400F32D0039BBB60049BFB601422002195 -:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 -:102100000C932B7BADF83EA0013BDBB2ADF83C302D -:10211000069B8DF8433094F824308DF840B083F05E -:1021200001038DF844308DF84160A3688DF842803A -:102130000AA920469847FB7DC3F38403013303F0CB -:102140001F039B02FB82002048E7FB7DC9F340127E -:10215000B2EBD31F40F0DA80C3F38403B34240F004 -:10216000D88007992B7B4FEA9912002934D0D207E7 -:1021700041D4032B40F2D080039BBB60049BFB60E7 -:102180002B7BAE1D033BDBB23246394604F10C001B -:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 -:1021A000FB7DC3F38403013303F01F039B02FB8217 -:1021B000032013E7AB883B832A7B033AB88AD2B269 -:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D -:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C -:1021E0003246394604F10C00FFF7A4FA0028D3DB8D -:1021F0002A7B013AE2E7F98AC1F30901013B05298B -:10220000DAB259D8281D002307F11A0C9A4208D9CE -:1022100010F801EB0CF801E0013101330629DBB2C3 -:10222000F4D103990A9104990B91934207F11A0191 -:102230000C9138BF043379680D9134BF55FA83F39C -:1022400000230E93FB8AADF83EA0C3F309031A44A2 -:10225000069B8DF8433094F82430ADF83C2083F091 -:1022600001038DF8443000238DF840B08DF84160B3 -:102270008DF842807B602A7BB88A013A291DFFF7DE -:10228000D7F93B8BB882834203D1A3680AA92046C1 -:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 -:1022A0008403013303F01F039B02FB823B8B9842A4 -:1022B00014BF1120002091E67B68002BB1D00620CE -:1022C00001E01C306346D3F800C0BCF1000FF8D128 -:1022D000091A081D05F1040C00EB030905989DF887 -:1022E000143001EB000EBEF11B0F9AD89A4298D918 -:1022F0001CF8013B09F8013B059B01330593EDE711 -:102300006FF009006AE66FF00A0067E66FF00D00F3 -:1023100064E66FF00E0061E66FF00F005EE600BF4E -:1023200080841E00F0B53D4D3D4FEB6943F00073D6 -:10233000EB61EB693B4B9B6AD3F800623E4046F091 -:102340000106C3F80062D3F800423C4044EA002092 -:1023500040F00100C3F80002002951D00020C3F86A -:102360001C020646C3F80402C3F80C02C3F81402A8 -:1023700003EBC00401300E28C4F84062C4F8446284 -:10238000F6D100274FF0010C9678148816F0010F53 -:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A -:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 -:1023B0000E0EC3F80CE2760742BFD3F81462064350 -:1023C000C3F8146203EBC4045668C4F8406296680C -:1023D000C4F84462D3F81C4201372043B942C3F821 -:1023E0001C0202F10C02CFD1D3F8002222F001022C -:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 -:102400000122C3F84012C3F84412C3F80412C3F8FF -:102410001412C3F80C22C3F81C22E5E70010024096 -:102420000000FFFF80220020184A916A08B58B68DF -:102430008B6013F0010104D013F00C0F18BF4FF4A0 -:102440008031D80506D513F4406F14BF41F4003134 -:1024500041F00201D80306D513F4402F14BF41F414 -:10246000802141F00401D3690BB10848984720232B -:1024700083F311880648002100F038FE002383F31F -:102480001188BDE8084001F0AFB800BF80220020ED -:102490008822002038B5124CA36ADD68AA0712D042 -:1024A0005A6922F002025A61A36913B10121204640 -:1024B0009847202383F311880A48002100F016FE74 -:1024C000002383F31188EB0606D5A36A1021D96097 -:1024D000236A0BB102489847BDE8384001F084B840 -:1024E000802200209022002038B5124CA36A1D697A -:1024F000AA0712D05A6922F010025A61A36913B1D7 -:10250000022120469847202383F311880A4800219E -:1025100000F0ECFD002383F31188EB0606D5A36AD7 -:1025200010211961236A0BB102489847BDE8384071 -:1025300001F05AB8802200209022002038B50F4CBC -:10254000A36A5D685D602A070AD5042222701A68B2 -:1025500022F002021A60636A13B1002120469847F4 -:102560006B0706D5A36A9969236A13B10348090466 -:102570009847BDE8384001F037B800BF80220020FE -:1025800010B50E4C204600F02FFA0D4BA3620B2124 -:10259000132000F009FA0B21142000F005FA0B219A -:1025A000152000F001FA0B21162000F0FDF90022A1 -:1025B000BDE8104011460E20FFF7B4BE8022002077 -:1025C000006400400F4B984210B5044605D10E4BF5 -:1025D000DA6942F00072DA61DB69A36A01221A60EB -:1025E000A36A5A68D20707D5626851681268D96130 -:1025F0001A60064A5A6110BD0121082000F06CFCE7 -:10260000EEE700BF80220020001002405B8701003F -:1026100003291AD8DFE801F0020A0F14836A9B68C5 -:1026200013F0E05F14BF012000207047836A9868B0 -:10263000C0F380607047836A9868C0F3C0607047D9 -:10264000836A9868C0F300707047002070470000EC -:1026500010B5032925D8DFE801F00225292D836A6A -:102660009968C1F30161183103EB011310788406F6 -:102670004CBF54689488C0F300114FEA410148BF31 -:1026800041EAC40100F00F004CBF41F0040141EAEF -:102690004451586041F001019068D2689860DA6056 -:1026A000196010BD836A03F5C073DFE7836A03F521 -:1026B000C873DBE7836A03F5D073D7E701290AD033 -:1026C00002290FD081B9836ADA68920701D11869AB -:1026D00003E001207047836AD86810F0030018BF38 -:1026E00001207047836AF2E70020704710B539B9BE -:1026F000836AD96889071BD11B699C0704D110BD67 -:10270000012915D00229FAD1816AD1F8C031D1F856 -:10271000C441D1F8C8011061D1F8CC01506120202A -:1027200008610869800717D1486940F0100012E07D -:10273000816AD1F8B031D1F8B441D1F8B801106153 -:10274000D1F8BC0150612020C860C868800703D15F -:10275000486940F002004861C3F34000C3F38001C0 -:10276000000140EA4111107920F03000014311715D -:1027700089064BBF91681189DB085B0D4CBF63F381 -:102780001C0163F30A01137948BF916064F30303EA -:1027900013714FEA14234FEA144458BF1181137088 -:1027A0005480ACE7026843681143016003B11847E5 -:1027B00070470000024A136843F0C003136070477B -:1027C00000380140024A136843F0C00313607047A9 -:1027D0000044004037B51D4C1D4D204600F006FB5F -:1027E000009404F114001B490023202200F0C8F9D2 -:1027F0002022009404F13800174B184900F042FAE7 -:10280000174BC4E91735174C0C21252000F0CCF8E4 -:10281000204600F0EBFA04F1140013490094002361 -:10282000202200F0ADF904F13800104B104900945B -:10283000202200F027FA0F4B0C212620C4E917357F -:1028400003B0BDE8304000F0AFB800BFAC220020BC -:102850000051250284230020B5270008C42300204E -:102860000038014018230020A4230020C5270008B9 -:10287000E4230020004400402DE9F047C66D37688E -:10288000F46934622107054618D014F0080118BF16 -:102890008021E20748BF41F02001A30748BF41F073 -:1028A0004001600748BF41F48071202383F3118801 -:1028B000281DFFF777FF002383F31188E2050AD56F -:1028C000202383F311884FF40071281DFFF76AFF5E -:1028D000002383F311884FF020094FF0000A14F011 -:1028E000200838D13B0616D54FF0200905F1380AEB -:1028F000200610D589F31188504600F0F7F900281A -:1029000036DA0821281DFFF74DFF27F080033360DA -:10291000002383F31188790614D5620612D520238B -:1029200083F31188D5E913239A4208D12B6C33B174 -:102930001021281D27F04007FFF734FF37600023E0 -:1029400083F31188E30619D5AA6E1369B3B1BDE804 -:10295000F0475069184789F31188B38C95F86410D3 -:102960002846194000F04EFA8AF31188F469B6E758 -:1029700080B2308588F31188F469B9E7BDE8F08743 -:1029800008B50348FFF778FFBDE8084000F02CBE0B -:10299000AC22002008B50348FFF76EFFBDE80840F1 -:1029A00000F022BE1823002000F1604303F56143CC -:1029B0000901C9B283F80013012200F01F039A40F5 -:1029C00043099B0003F1604303F56143C3F8802191 -:1029D0001A60704700F16040090100F56D40C9B20E -:1029E00001767047FFF7CCBD012300F10802C0E972 -:1029F0000222037000F110020023C0E90422C0E9A2 -:102A00000633C0E9083343607047000010B5202347 -:102A1000044683F31188022303704160FFF7D2FD5F -:102A200004232370002383F3118810BD2DE9F041A6 -:102A30001F4604460D461646202383F3118800F1F5 -:102A400008082378052B0DD029462046FFF7E0FD26 -:102A500040B1204632462946FFF7FAFD002080F3B8 -:102A6000118808E03946404600F024FB0028E8D0F1 -:102A7000002383F31188BDE8F08100002DE9F041C7 -:102A80001F4604460D461646202383F3118800F1A5 -:102A900010082378052B0DD029462046FFF70EFE9F -:102AA00040B1204632462946FFF720FE002080F341 -:102AB000118808E03946404600F0FCFA0028E8D0CA -:102AC000002383F31188BDE8F0810000F8B51546B6 -:102AD00082680669AA420B46816938BF8568761A02 -:102AE000B54204460BD218462A46FEF757FCA369A6 -:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 -:102B000018463246FEF74AFCAF1BE1683A463044AD -:102B1000FEF744FCE3683B44EBE718462A46FEF721 -:102B20003DFCE368E5E7000083689342F7B515468E -:102B3000044638BF8568D0E90460361AB5420BD226 -:102B40002A46FEF72BFC63692B446361A368284681 -:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 -:102B60001DFC0199E068AF1B3A463144FEF716FCA4 -:102B7000E3683B44E9E72A46FEF710FCE368E4E734 -:102B800010B50A440024C361029B8460C0E90000C0 -:102B9000C0E90511C1600261036210BD08B5D0E94A -:102BA0000532934201D1826882B982680132826023 -:102BB0005A1C42611970D0E904329A4224BFC3689A -:102BC0004361002100F086FA002008BD4FF0FF307D -:102BD000FBE7000070B5202304460E4683F31188FE -:102BE000A568A5B1A368A269013BA360531CA361BA -:102BF00015782269934224BFE368A361E3690BB1AE -:102C000020469847002383F31188284607E0314681 -:102C1000204600F04FFA0028E2DA85F3118870BDF3 -:102C20002DE9F74F04460E4617469846D0F81C90FB -:102C30004FF0200A8AF311884FF0000B154665B15A -:102C40002A4631462046FFF741FF034660B9414618 -:102C5000204600F02FFA0028F1D0002383F31188DA -:102C6000781B03B0BDE8F08FB9F1000F03D00190DD -:102C70002046C847019B8BF31188ED1A1E448AF346 -:102C80001188DCE7C0E90511C160C3611144009BF4 -:102C90008260C0E90000016103627047F8B5044634 -:102CA0000D461646202383F31188A768A7B1A368B1 -:102CB000013BA36063695A1C62611D70D4E9043250 -:102CC0009A4224BFE3686361E3690BB120469847E9 -:102CD000002080F3118807E03146204600F0EAF931 -:102CE0000028E2DA87F31188F8BD0000D0E9052357 -:102CF0009A4210B501D182687AB982680132826045 -:102D00005A1C82611C7803699A4224BFC36883619C -:102D1000002100F0DFF9204610BD4FF0FF30FBE747 -:102D20002DE9F74F04460E4617469846D0F81C90FA -:102D30004FF0200A8AF311884FF0000B154665B159 -:102D40002A4631462046FFF7EFFE034660B941466A -:102D5000204600F0AFF90028F1D0002383F311885A -:102D6000781B03B0BDE8F08FB9F1000F03D00190DC -:102D70002046C847019B8BF31188ED1A1E448AF345 -:102D80001188DCE7026843681143016003B118470A -:102D9000704700001430FFF743BF00004FF0FF33CF -:102DA0001430FFF73DBF00003830FFF7B9BF000017 -:102DB0004FF0FF333830FFF7B3BF00001430FFF798 -:102DC00009BF00004FF0FF311430FFF703BF0000D0 -:102DD0003830FFF763BF00004FF0FF323830FFF7A5 -:102DE0005DBF000000207047FFF7F4BC044B036098 -:102DF0000023C0E90233436001230374704700BF1E -:102E0000F43B000838B5C36904460D461BB90421DC -:102E10000844FFF7B7FF294604F11400FFF7BEFE90 -:102E2000002806DA201D4FF48061BDE83840FFF726 -:102E3000A9BF38BD024B0022C3E900339A60704736 -:102E400004240020002303748268054B1B689968E2 -:102E50009142FBD25A68036042601060586070472C -:102E60000424002008B5202383F31188037C032B5E -:102E700005D0042B0DD02BB983F3118808BD43690D -:102E800000221A604FF0FF334361FFF7DBFF00239E -:102E9000F2E7D0E9003213605A60F3E700230374CD -:102EA0008268054B1B6899689142FBD85A68036099 -:102EB000426010605860704704240020054B196977 -:102EC0000874186802681A6053601861012303745B -:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 -:102EE000044610D02B690A4A01A800F01BF92046BD -:102EF000FFF7E4FF049B13B101A800F02FF92B6941 -:102F0000586907B030BDFFF7D9FFF8E70424002067 -:102F1000652E000838B50C4D41612B6981689A68AF -:102F20009142044603D8BDE83840FFF78BBF1846EE -:102F3000FFF7B4FF01232C61014623742046BDE84E -:102F40003840FDF745BB00BF04240020044B1A683D -:102F50001B6990689B68984294BF002001207047CD -:102F60000424002010B5084C236820691A682260E8 -:102F70005460012223611A74FFF790FF0146206913 -:102F8000BDE81040FDF724BB0424002008B5FFF77E -:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 -:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 -:102FB00000F0AAF80A498022204600F031F80123E7 -:102FC00044F8180C037400F0EBFA002383F3118823 -:102FD00062B60448BDE8104000F042B82C2400203E -:102FE0001C3C00082C3C000800F0CAB8EFF311802C -:102FF00020B9EFF30583202282F311887047000087 -:1030000010B530B9EFF30584C4F3080414B180F3AC -:10301000118810BDFFF7BAFF84F31188F9E70000AB -:1030200082600222028270478368A3F17C0243F827 -:103030000C2C026943F83C2C426943F8382C074AAF -:1030400043F81C2CC26843F8102C022203F8082C09 -:10305000002203F8072CA3F118007047E9050008C7 -:1030600010B5202383F31188FFF7DEFF002104460B -:10307000FFF750FF002383F31188204610BD0000A6 -:10308000024B1B6958610F20FFF718BF0424002072 -:10309000202383F31188FFF7F3BF000008B5014632 -:1030A000202383F311880820FFF716FF002383F302 -:1030B000118808BD49B1064B42681B6918605A6007 -:1030C000136043600420FFF707BF4FF0FF307047E5 -:1030D000042400200368984206D01A6802605060F9 -:1030E00059611846FFF7AEBE7047000038B5044678 -:1030F0000D462068844200D138BD036823605C60BF -:103100004561FFF79FFEF4E7054B03F11402C3E9A5 -:1031100005224FF0FF32DA6100221A62704700BFC9 -:103120000424002010B5C0E903230B4A136A536935 -:103130009C68A1420CD85C68816003604460206098 -:1031400058609868411A99604FF0FF33D36110BD01 -:103150001B68091BECE700BF04240020036881689A -:103160009A680A449A60426813605A600023C360F8 -:10317000024B4FF0FF32DA61704700BF0424002099 -:1031800038B50F4C236A22460133236252F8143FAC -:10319000934206D09A68013A9A60202563699A683A -:1031A00002B138BDD3E9001001604860D968DA6027 -:1031B00082F311881869884785F31188EEE700BF0C -:1031C0000424002000207047FEE700007047000044 -:1031D0004FF0FF3070470000BFF34F8F024AD368B3 -:1031E000DB07FCD4704700BF0020024008B5074B46 -:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 -:10320000044A5A6002F188325A6008BD90250020B5 -:10321000002002402301674508B5054B1B7833B9F0 -:10322000FFF7DAFF034A136943F08003136108BD17 -:1032300090250020002002407F289ABF00F58030B2 -:10324000C0020020704700004FF40060704700008B -:10325000802070477F2808B50BD8FFF7EDFF00F5F9 -:1032600000630268013204D104308342F9D10120A5 -:1032700008BD0020FCE700007F2838B5044623D8AD -:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 -:10329000DA6002221A6105462046FFF7CDFF586129 -:1032A0001A6942F040021A614FF40061FFF794FF7F -:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 -:1032C000BDE83840FFF7C6BF002038BD00200240EF -:1032D00012F001032DE9F04704460E46154606D0CC -:1032E000244B40F2BD221A600020BDE8F08781180F -:1032F000214A914204D91F4A40F2C2211160F3E7EA -:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 -:1033100031464FF0010AA61B012D06EB0107884636 -:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E -:103330000030C9F810A03B800024FFF74DFFC9F80A -:1033400010403B8831F8022B9BB29A420FD0094BB8 -:1033500040F2D9221A60094B1F60094B1D60094BCE -:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 -:10337000D2E700BF8C250020000004088025002033 -:10338000882500208425002000200240084908B537 -:103390000B7828B11BB9FFF729FF01230B7008BD7B -:1033A000002BFCD0BDE808400870FFF735BF00BF18 -:1033B0009025002030B583B0FFF718FE0E4B0F4D5F -:1033C0001B6A2A684FF47A7101FB03F3934237BFFB -:1033D0000B4A0B49516814682B602EBFD1E900419C -:1033E000013151601C1941F100010191FFF708FE04 -:1033F0000199204603B030BD04240020942500200C -:103400009825002030B583B0FFF7F0FD114B124D29 -:103410001B6A2A684FF47A7101FB03F3934237BFAA -:103420000E4A0E49516814682B602EBFD1E9004145 -:10343000013151601C1941F100010191FFF7E0FDDC -:1034400001994FF47A7200232046FCF7A9FE03B0DD -:1034500030BD00BF042400209425002098250020C2 -:1034600010B50244064BD2B2904200D110BD441CAC -:1034700000B253F8200041F8040BE0B2F4E700BFBB -:10348000502800400F4B30B51C6A240407D41C6A36 -:1034900044F440741C621C6A44F400441C620A4CEC -:1034A000236843F4807323600244084BD2B29042F5 -:1034B00000D130BD441C00B251F8045B43F82050E9 -:1034C000E0B2F4E7001002400070004050280040D5 -:1034D00007B5012201A90020FFF7C2FF019803B040 -:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 -:1034F000012201A900200194FFF7C4FF02B010BD12 -:1035000070470000074B45F255521A6002225A607C -:1035100040F6FF729A604CF6CC421A60024B0122D0 -:103520001A70704700300040A4250020034B1B7820 -:103530001BB1034B4AF6AA221A607047A42500204B -:1035400000300040044B1A682AB902F1804202F5AB -:103550000432526A1A607047A0250020024B4FF0D7 -:1035600080725A62704700BF0010024008B5FFF732 -:10357000E9FF024B1868C0F3407008BDA025002089 -:10358000EFF3098305494A6B22F001024A6368336D -:1035900083F30988002383F31188704700EF00E06C -:1035A000202080F3118862B60C4B0D4AD96821F4B3 -:1035B000E0610904090C0A43DA60D3F8FC200949E8 -:1035C00042F08072C3F8FC200A6842F001020A60EF -:1035D0001022DA7783F82200704700BF00ED00E088 -:1035E0000003FA05001000E010B5202383F31188D2 -:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 -:103600000984683C4FF08073E361094BDB6B2366F0 -:1036100084F30988FFF79AFC10B1064BA36110BD33 -:10362000054BFBE783F31188F9E700BF00ED00E0ED -:1036300000EF00E0FB050008FE05000870470000F1 -:10364000FEE700000A4B0B480B4A90420BD30B4B92 -:10365000DA1C121AC11E22F003028B4238BF00226C -:103660000021FDF7ADBE53F8041B40F8041BECE746 -:10367000183D0008282600202826002028260020A3 -:10368000704700004B6843608B688360CB68C36001 -:103690000B6943614B6903628B6943620B6803608A -:1036A0007047000008B51B4B9A6A42F4FC029A620C -:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB -:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 -:1036D00002F11C0100F58060FFF7D4FF02F1380110 -:1036E00000F58060FFF7CEFF02F1540100F5806025 -:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D -:1037000002F18C0100F58060FFF7BCFFBDE80840C6 -:1037100000F05AB800100240443C000808B500F020 -:1037200093F9FFF741FCBDE80840FFF70BBF00002D -:103730007047000010B5214CA36A63F4FC03A36238 -:10374000A36A03F4FC03A3624FF0FF32A36A236968 -:1037500022612369002323612169E168E260E26854 -:10376000E360E268E269164942F08052E261E26990 -:103770000A6842F480720A60226A02F44072B2F56A -:10378000407F1EBF4FF4803222622362236A1B04F3 -:1037900007D4236A43F440732362236A43F400434B -:1037A000236200F031F9A369064A43F00103A361E3 -:1037B000A369136843F02003136010BD001002409A -:1037C00000700040000001401E4B1A6842F00102E8 -:1037D0001A601A689007FCD55A6822F003025A60F2 -:1037E0005A6812F00C02FBD1196801F0F901196056 -:1037F0005A601A6842F480321A601A689103FCD544 -:10380000114A5A604FF40452DA6230221A631A687D -:1038100042F080721A601A689201FCD50B4912229C -:103820000A600A6802F00702022AFAD15A6842F0D6 -:1038300002025A605A6802F00C02082AFAD11A6B86 -:103840001A6370470010024000241D00002002404F -:10385000084A08B5516913680B4003F0010353612E -:1038600023B1054A13680BB150689847BDE808407A -:10387000FFF7BABE00040140A8250020084A08B599 -:10388000516913680B4003F00203536123B1054AE9 -:1038900093680BB1D0689847BDE80840FFF7A4BE15 -:1038A00000040140A8250020084A08B551691368A2 -:1038B0000B4003F00403536123B1054A13690BB1B4 -:1038C00050699847BDE80840FFF78EBE00040140EC -:1038D000A8250020084A08B5516913680B4003F079 -:1038E0000803536123B1054A93690BB1D069984726 -:1038F000BDE80840FFF778BE00040140A82500207D -:10390000084A08B5516913680B4003F0100353616E -:1039100023B1054A136A0BB1506A9847BDE80840C5 -:10392000FFF762BE00040140A8250020174B10B528 -:103930005A691C68144004F478725A61A30604D5CD -:10394000134A936A0BB1D06A9847600604D5104AAF -:10395000136B0BB1506B9847210604D50C4A936B3F -:103960000BB1D06B9847E20504D5094A136C0BB133 -:10397000506C9847A30504D5054A936C0BB1D06CE5 -:103980009847BDE81040FFF72FBE00BF000401407C -:10399000A82500201A4B10B55A691C68144004F47D -:1039A0007C425A61620504D5164A136D0BB1506D05 -:1039B0009847230504D5134A936D0BB1D06D9847F2 -:1039C000E00404D50F4A136E0BB1506E9847A10462 -:1039D00004D50C4A936E0BB1D06E9847620404D59F -:1039E000084A136F0BB1506F9847230404D5054A5A -:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F -:103A000000040140A8250020062108B50846FEF75D -:103A1000CBFF06210720FEF7C7FF06210820FEF78F -:103A2000C3FF06210920FEF7BFFF06210A20FEF78B -:103A3000BBFF06211720FEF7B7FFBDE808400621AF -:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 -:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE -:103A6000084000F001B8000000F00EB80023054A3D -:103A700019460133102BC2E9001102F10802F8D1F6 -:103A8000704700BFA82500204FF0E023044A5A6188 -:103A900000229A6107221A6108210B20FEF79ABFC3 -:103AA0003F19010008B5202383F31188FFF79CFA22 -:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 -:103AC0000840FFF791BD000010B501390244904253 -:103AD00001D1002005E0037811F8014FA34201D085 -:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E -:103AF00017780144044603F1FF3C8C42204601D96B -:103B0000002009E00578BD4204F10104F5D10CEB79 -:103B10000405D618A54201D1BDE8F08115F8018D44 -:103B200016F801EDF045F5D0E7E70000034611F87F -:103B3000012B03F8012B002AF9D17047696F2E6D14 -:103B4000726F626F746963732E6D31303037305F1E -:103B50006C6F63315F424C004E6F20617070207358 -:103B600069670A00426164206677206C656E67743D -:103B7000682025750A0042616420626F6172645F8B -:103B800069642025752073686F756C6420626520F8 -:103B900025750A004261642066772064657363724C -:103BA0006970746F72206C656E6774682025750A81 -:103BB00000426164206170702043524320307825B8 -:103BC0003038783A307825303878203078253038D9 -:103BD000783A3078253038780A00476F6F6420666D -:103BE00069726D776172650A0040A2E4F1646891C0 -:103BF0000600000000000000B12D00089D2D000807 -:103C0000D92D0008C52D0008D12D0008BD2D0008B4 -:103C1000A92D0008952D0008E52D00086D61696E3D -:103C20000000000069646C6500000000243C00088E -:103C3000482400208025002001000000A52F000856 -:103C400000000000A001A82A00000000FAAABEAAF5 -:103C500050001424EFFF0000007700007097090067 -:103C60000100000000000000AAAAAAAA01000000AA -:103C7000FFFF000000000000000000000000000046 -:103C800000000000AAAAAAAA00000000FFFF00008E -:103C90000000000000000000000000000000000024 -:103CA000AAAAAAAA00000000FFFF0000000000006E -:103CB000000000000000000000000000AAAAAAAA5C -:103CC00000000000FFFF00000000000000000000F6 -:103CD0000000000000000000AAAAAAAA000000003C -:103CE000FFFF00000000000000000000E4C4FF7FB0 -:103CF0000100000000000000EC03000000000000D4 -:103D000000980300000000006400000000000000B4 -:083D1000FE2A0100D2040000AC +:1000000000090020B5040008CD250008852500085A +:10001000AD25000885250008A5250008B7040008BF +:10002000B7040008B7040008B7040008C135000889 +:10003000B7040008B7040008B704000875430008B7 +:10004000B7040008B7040008B7040008B7040008A4 +:10005000B7040008B70400085940000885400008AC +:10006000B1400008DD40000809410008B70400085D +:10007000B7040008B7040008B7040008B704000874 +:10008000B7040008B7040008B704000839250008C1 +:100090006525000875250008B704000835410008EB +:1000A000B7040008B7040008B7040008B704000844 +:1000B000B7040008B7040008B7040008B704000834 +:1000C000B7040008B7040008B7040008B704000824 +:1000D000B70400086545000879450008B704000822 +:1000E0009D410008B7040008B7040008B7040008E1 +:1000F000B7040008B7040008B7040008B7040008F4 +:10010000B7040008B7040008B7040008B7040008E3 +:10011000B7040008B7040008B7040008B7040008D3 +:10012000B7040008B7040008B7040008B7040008C3 +:10013000B7040008B7040008B7040008B7040008B3 +:10014000B7040008B7040008B7040008B7040008A3 +:10015000B7040008B7040008B7040008B704000893 +:10016000B7040008B7040008B7040008B704000883 +:10017000B7040008B7040008B7040008B704000873 +:10018000B7040008B7040008B7040008B704000863 +:10019000B7040008B7040008B7040008B704000853 +:1001A0002112000800000000000000000000000014 +:1001B00053B94AB9002908BF00281CBF4FF0FF31CE +:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA +:1001D00000F006F8DDF804E0DDE9022304B0704722 +:1001E0002DE9F047089D04468E46002B4DD18A42EA +:1001F000944669D9B2FA82F252B101FA02F3C2F11D +:10020000200120FA01F10CFA02FC41EA030E9440AD +:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE +:1002200016E341EA034306FB07F199420AD91CEBA6 +:10023000030306F1FF3080F01F81994240F21C81D8 +:10024000023E63445B1AA4B2B3FBF8F008FB103320 +:1002500044EA034400FB07F7A7420AD91CEB040455 +:1002600000F1FF3380F00A81A74240F20781644425 +:10027000023840EA0640E41B00261DB1D4400023AA +:10028000C5E900433146BDE8F0878B4209D9002D0E +:1002900000F0EF800026C5E9000130463146BDE898 +:1002A000F087B3FA83F6002E4AD18B4202D3824202 +:1002B00000F2F980841A61EB030301209E46002DB1 +:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 +:1002D000002A40F09280A1EB0C014FEA1C471FFA64 +:1002E0008CFE0126200CB1FBF7F307FB131140EA4B +:1002F00001410EFB03F0884208D91CEB010103F118 +:10030000FF3802D2884200F2CB804346091AA4B2D9 +:10031000B1FBF7F007FB101144EA01440EFB00FEAD +:10032000A64508D91CEB040400F1FF3102D2A64512 +:1003300000F2BB800846A4EB0E0440EA03409CE7B1 +:10034000C6F12007B34022FA07FC4CEA030C20FA5E +:1003500007F401FA06F31C43F9404FEA1C4900FA7E +:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB +:1003700040EA014108FB0EF0884202FA06F20BD96E +:100380001CEB010108F1FF3A80F08880884240F2BE +:100390008580A8F102086144091AA4B2B1FBF9F002 +:1003A00009FB101144EA014100FB0EFE8E4508D9FD +:1003B0001CEB010100F1FF346CD28E456AD9023882 +:1003C000614440EA0840A0FB0294A1EB0E01A14267 +:1003D000C846A64656D353D05DB1B3EB080261EBD5 +:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF +:1003F000007100263146BDE8F087C2F12003D840E5 +:100400000CFA02FC21FA03F3914001434FEA1C4726 +:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 +:10042000064300FB0EF69E4204FA02F408D91CEBC8 +:10043000030300F1FF382FD29E422DD902386344C6 +:100440009B1B89B2B3FBF7F607FB163341EA034166 +:1004500006FB0EF38B4208D91CEB010106F1FF38B5 +:1004600016D28B4214D9023E6144C91A46EA0046AC +:1004700038E72E46284605E70646E3E61846F8E63E +:100480004B45A9D2B9EB020864EB0C0E0138A3E787 +:100490004646EAE7204694E74046D1E7D0467BE768 +:1004A000023B614432E7304609E76444023842E7E0 +:1004B000704700BF02E000F000F8FEE772B6374870 +:1004C00080F30888364880F3098836483649086042 +:1004D00040F20000CCF200004EF63471CEF2000182 +:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 +:1004F000F0004EF68851CEF200010860BFF34F8F36 +:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 +:10051000CEF200010860062080F31488BFF36F8FCD +:1005200003F04EFC03F0C2FC4FF055301F491B4A4C +:1005300091423CBF41F8040BFAE71D49184A914229 +:100540003CBF41F8040BFAE71A491B4A1B4B9A427D +:100550003EBF51F8040B42F8040BF8E7002018499D +:10056000184A91423CBF41F8040BFAE703F02CFC17 +:1005700003F0D8FC144C154DAC4203DA54F8041BBC +:100580008847F9E700F042F8114C124DAC4203DA0B +:1005900054F8041B8847F9E703F014BC0009002055 +:1005A000001100200000000808ED00E0000100201C +:1005B00000090020704B0008001100207C11002071 +:1005C00080110020583C0020A0010008A401000870 +:1005D000A4010008A40100082DE9F04F2DED108AB8 +:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 +:1005F000002383F311882846A047002003F06AF9FE +:10060000FEE703F0CDF800DFFEE70000F8B500F0EC +:1006100019FE03F079FB074603F0C8FB05460028E6 +:1006200040D12C4B9F423DD001339F423DD02A4BBD +:1006300027F0FF029A423BD1F8B200F03FFC2E4671 +:1006400042F2107400F040FC08B10024264601F08C +:10065000B1F888B3032000F045F80024264635B1F0 +:100660001E4B9F4203D003F099FB00242646002036 +:1006700003F054FB1A4B1B6913F0400322D00EB158 +:1006800000F046F800F052FC00F0DEFD01F0A6FF9D +:100690000546CCB101F0A2FF401BA04214D900F0E6 +:1006A00037F8F3E72E460024CCE704460126C9E7D5 +:1006B00006464FF47A74C5E7002CD0D04FF47A7414 +:1006C0000126CCE71C46DDE700F078FC012003F0B2 +:1006D00007F9DEE7010007B0000008B0263A09B0CC +:1006E00000040048084B187003280CD8DFE800F01D +:1006F00008050208022000F003BE022000F0F8BD49 +:10070000024B00225A6070478011002084110020A3 +:1007100038B501F04FF830B11F4B03221A701F4B50 +:1007200000225A6038BD1E4B1E4A19680131F9D0AB +:1007300004339342F9D11C4C194DD4F80428AA4231 +:10074000F0D31A4B9B6803F1006303F5D0439A4240 +:10075000E8D203F0F7FA03F009FB002000F08EFD69 +:100760000220FFF7BFFF124BDA690022DA61D96974 +:1007700099699A619B6972B64FF0E0233021C3F802 +:10078000085DD4F80038D4F8042881F311889D4618 +:1007900083F308881047C5E78011002084110020EA +:1007A00000680008206800080060000800110020B0 +:1007B00000100240094A136849F2690099B21B0C03 +:1007C00000FB01331360064B186844F2506182B29B +:1007D000000C01FB0200186080B270471411002069 +:1007E0001011002010B500211022044600F0A2FDD7 +:1007F000034B03CB206061601868A06010BD00BF90 +:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 +:100810006CAC40F2751207460D460EA80021C8F8D0 +:10082000001000F087FD4FF4C4720021204600F054 +:1008300081FD01F0D3FE254B4FF47A72B0FBF2F04C +:10084000186093E80700022384E807000DF5E970BB +:100850002382FFF7C7FF4EF603431D49238406A8F2 +:1008600004F0B6F8192384F832310DF2E32206AB16 +:100870000DF1300C1E4603CE6645106051603346C4 +:1008800002F10802F6D13378137041460122204666 +:1008900000F09CFD00230393AB7E029305F1190346 +:1008A000019380B20123CDE904800093E97E05A382 +:1008B000D3E90023384602F059FA0DF54E7DBDE824 +:1008C000F08100BF9E6AC421818A46EE8C1100200F +:1008D000E04900082DE9F0412C4C237ADAB080463B +:1008E0000D465BBB27A9284600F080FE074600287E +:1008F00042D19DF89D60C82E3ED801464FF4A662B5 +:10090000204600F017FD4FF48073C4F8F8314FF41F +:100910000073C4F80C334FF44073C4F820343246EB +:100920000DF19E0104F1090000F0F2FC26449DF84F +:100930009C30777223720BB9EB7E237281220021E7 +:1009400006AC27A800F0F6FC0122214627A800F0FB +:1009500089FE00230393AB7E029305F1190380B255 +:1009600001932823CDE904400093E97E05A3D3E950 +:100970000023404602F0FAF95AB0BDE8F08100BF0A +:10098000AFF3008026417272DF25D7B7A83200206E +:10099000F0B5254E4FF48A7505FB0065F1B096F869 +:1009A000D83085F8DC300024D822214685F8E8408C +:1009B0003AA800F0BFFC06F1090000F0B3FCD5F83E +:1009C000E4308DF8F000C2B206AF06F109010DF176 +:1009D000F100CDE93A3400F09BFC394601223AA8F7 +:1009E00000F06CFE80B2CDE9047008230127CDE948 +:1009F000023706F1D803019330230093317A0B4874 +:100A000007A3D3E9002302F0B1F9A04206DD01F00B +:100A1000E5FDC5F8E000384671B0F0BD2046FBE7C3 +:100A200078F6339F93CACD8DA8320020A4210020F0 +:100A30002DE9F0411D4D1E4E1E4F86B0284602F096 +:100A4000C1F9034658B30024CDE90344ADF814407E +:100A5000027B8DF8142099684068029403AA03C2AF +:100A60001B68DFF8548043F00043029301F0B8FDA7 +:100A7000821941F10003009402A9384601F07CF884 +:100A8000A04205DD284602F0A1F988F80040D5E72C +:100A900098F80030072B05D8013388F8003006B0ED +:100AA000BDE8F081014802F091F9F8E7A4210020A7 +:100AB00040420F00D8210020DD37002070B50D46E0 +:100AC00014461E4602F0AEF850B9022E10D1012C89 +:100AD0000ED112A3D3E90023C5E90023012007E0CA +:100AE000282C10D005D8012C09D0052C0FD00020BF +:100AF00070BD302CFBD10BA3D3E90023ECE70BA393 +:100B0000D3E90023E8E70BA3D3E90023E4E70BA331 +:100B1000D3E90023E0E700BFAFF30080401DA12030 +:100B200026812A0B78F6339F93CACD8D9E6AC42105 +:100B3000818A46EE26417272DF25D7B7F017304A18 +:100B400039059E5638B505460E4C0021013500F09A +:100B5000B7FBA4F82C55B4F82C0500F099FB78B13C +:100B6000B4F82C0500F0A4FB014648B9B4F82C05F4 +:100B700000F0A6FBB4F82C350133A4F82C35EAE7D5 +:100B800038BD00BFA832002010B50A4B0A4A1A60CF +:100B900003F5805393F860203AB9DC6D2CB1204600 +:100BA00000F082FE204603F053FEBDE810400348EB +:100BB00000F07ABED8210020384A000820320020F8 +:100BC0002DE9F04F8FB000AF05460C4602F02AF831 +:100BD000002849D1237E022B1BD1E38A012B18D197 +:100BE00001F0FCFC0646FFF7E5FD03464FF4C87034 +:100BF000DFF8C482B3FBF0F206F5167602FB103381 +:100C000016FA83F3C8F80030E37E33B9A34B002211 +:100C10001A703C37BD46BDE8F08F07F1240120462D +:100C200000F0A2FC0028F4D107F11400FFF7DAFD70 +:100C300097F8264007F11401224607F1270003F038 +:100C400051FE0028E2D10F2C08D8944B1C70D8F824 +:100C50000030A3F51673C8F80030DAE797F82410CF +:100C6000284601F0D7FFD4E7E38A282B2BD010D8F1 +:100C7000012B23D0052BCCD1BFF34F8F8849894B53 +:100C8000CA6802F4E0621343CB60BFF34F8F00BF2A +:100C9000FDE7302BBDD1844EE17E327A9142B8D14E +:100CA000607E3146002291F8DC50854200F0A5803C +:100CB0000132042A01F58A71F5D1AAE721462846B6 +:100CC000FFF7A0FDA5E721462846FFF703FEA0E7B2 +:100CD000B2F8EC507B6005F103094FEA99094FEA3D +:100CE0008902D11DC908A8EBC1039D46EB4600212E +:100CF000584600F01FFB04F1EE012A4631445846E5 +:100D000000F006FB7B6813B9012000F0B7FA96F8F3 +:100D1000D20000F0BDFA044630B9307200F0D8FAC3 +:100D2000204600F0ABFAB1E0D6F8D4203AB996F8F4 +:100D3000D200B6F82C25824201D8FFF703FFD6F87F +:100D4000D4202A44944208D296F8D200B6F82C2532 +:100D50000130824201D8FFF7F5FE70685FFA89F230 +:100D6000594600F0EFFA08B9C54679E0726896F87E +:100D7000D2002A447260D6F8D42005EB0209C6F8E6 +:100D8000D49000F085FA814509D396F8D220D6F8A0 +:100D9000D4000132001B86F8D220C6F8D400FF2D03 +:100DA0000FD80024347200F093FA204600F066FA5F +:100DB00000F000FD3D4B188108B9FFF7A9FCC546BE +:100DC00027E7BB6896F8D9000AFB0362FB68D2F8F4 +:100DD000E41082F8E83001F58061C2F8E030C2F832 +:100DE000E410FFF7D5FDFFF723FE96F8D920013276 +:100DF00002F0030286F8D920B6E74FF48A7A0AFB9C +:100E000002F505F1EA013144204600F083FCF86068 +:100E100000287FF4FEAE3544012285F8E82001F079 +:100E2000DDFBD5F8E020D6ED007ADFED216A801AEF +:100E3000192838BF192040F6B832904228BF104612 +:100E4000B8EE677A07EE900AF8EEE77A67EEA67AD0 +:100E5000DFED186AE7EE267AFCEEE77AC6ED007A57 +:100E600096F8D930BB60BA6873680AFB02F432198D +:100E700092F8E81059B1D2F8E4108B42E8463FF4FA +:100E800027AF002182F8E810C2F8E010C546736869 +:100E9000064A9B0A01331381BBE600BF9D21002057 +:100EA00000ED00E00400FA05A83200208C110020BB +:100EB000CDCCCC3D6666663FA0210020014B18706A +:100EC000704700BF9811002038B54FF00054134B05 +:100ED00022689A4220D1124B627D12481A70237DFB +:100EE00003724FF48073C0F8F8314FF40073C0F808 +:100EF0000C3300254FF44073C0F820340A49C0F881 +:100F0000E450C922093000F003FAE02229462046C5 +:100F100000F010FA012038BD0020FCE79AAD44C56E +:100F200098110020A83200201600002037B500F0EC +:100F300041FC194D194928810223012218486B717F +:100F400001F0EAF900230193164B17490093174863 +:100F5000174B4FF4805201F035FE164B197811B142 +:100F6000124801F057FE01F039FB0446FFF722FC5E +:100F70004FF4C873B0FBF3F202FB130304F51670D1 +:100F800010FA83F00C4B186002F010FF08B10F2329 +:100F90002B8103B030BD00BF8C11002040420F00F8 +:100FA000D8210020BD0A00089C110020A4210020A7 +:100FB000C10B000898110020A02100202DE9F04F5E +:100FC0002DED028B8EA7D7E900670FF23C29D9E9F6 +:100FD0000089864C95B00DAD9FED828BFFF728FD03 +:100FE000DFF82CB200230C93ADF83C300D936B600E +:100FF00000230DF125028DED008B4FF0010A09A9A8 +:1010000058468DF825308DF824A001F035F99DF86B +:1010100024200023002A40F0AB80204601F002FE8D +:101020000546002847D1DFF8ECB101F0D7FADBF82C +:10103000003098423FD301F0D1FA0790FFF7BAFB96 +:10104000079A4FF4C873B0FBF3F101FB130302F5E9 +:10105000167010FA83F0CBF80000DFF8BCB19BF8F3 +:1010600000100791002914BF2B46534610A88DF895 +:101070003030FFF7B7FB0799C1F11002D2B2062A50 +:1010800010AB28BF062219440DF13100079200F081 +:101090003FF9079A0CAB0393182302930132544B88 +:1010A000D2B2CDE900A304923B463246204601F07D +:1010B000FFFD8BF8005001F091FA4E4A4E4D136837 +:1010C000C31AB3F57A7F32D3106001F089FA024671 +:1010D0000B46204601F084FE204601F0A3FD30B30C +:1010E0002B7ADFF838A1002B14BF032302238AF8E0 +:1010F000053001F073FA0DF1400B4FF47A730122C1 +:10110000B0FBF3F05946CAF80000504600F004FA6C +:1011100018230293394B019380B240F25513CDE965 +:1011200003B0009342464B46204601F0C1FD2B7AA6 +:10113000CBB101F053FA4FF0000A83464FF48A72A4 +:1011400095F8D900504400F0030002FB005393F8D7 +:10115000E81089B30AF1010ABAF1040FF0D12B7A31 +:10116000002B7FF438AF15B0BDEC028BBDE8F08FDB +:101170004FF0904110A84A6982F010024A61194666 +:10118000102200F0D7F80DF126030AAA0CA9584640 +:1011900000F0F0FD95E8030011AB83E803009DF833 +:1011A0003C308DF84C300C9B109310A9DDE90A23DC +:1011B000204601F0E9FF1BE7D3F8E01049B12B68A6 +:1011C000FA2B38BFFA23ABEB01010533B1EB430F28 +:1011D000C0D3FFF7DDFB4FF48A720028BAD1BEE717 +:1011E000AFF300800000000000000000A4210020F8 +:1011F0009C210020D8370020A8320020DC370020B6 +:10120000401DA12026812A0BF1C6A7C1D068080F76 +:10121000D8210020A02100209D2100208C11002039 +:1012200008B5054800F040FEBDE80840034A0449FF +:10123000002003F007BB00BFD82100201838002091 +:10124000890B00087047000070B502F013FC094ECE +:10125000094D3080002428683388834208D902F081 +:1012600005FC2B6804440133B4F5D04F2B60F2D356 +:1012700070BD00BF0C380020E037002002F086BCB3 +:1012800000F10060920000F5D04002F02DBC00009B +:10129000054B1A68054B1B889B1A834202D91044E0 +:1012A00002F0E4BB00207047E03700200C3800203B +:1012B000024B1B68184402F0DFBB00BFE037002080 +:1012C000024B1B68184402F0E9BB00BFE037002066 +:1012D000064991F8243033B10023086A81F824309C +:1012E0000822FFF7CDBF0120704700BFE437002080 +:1012F000022802BF4FF0904310229A61704700000D +:10130000022802BF4FF090434FF480129A61704759 +:1013100010B50023934203D0CC5CC4540133F9E7E9 +:1013200010BD000003460246D01A12F9011B002925 +:10133000FAD1704702440346934202D003F8011BDE +:10134000FAE770472DE9F8431F4D144695F824201D +:101350000746884652BBDFF870909CB395F824305E +:101360002BB92022FF2148462F62FFF7E3FF95F8B3 +:101370002400C0F10802A24228BF2246D6B241464C +:10138000920005EB8000FFF7C3FF95F82430A41B03 +:101390001E44F6B2082E17449044E4B285F8246047 +:1013A000DBD1FFF795FF0028D7D108E02B6A03EBCC +:1013B00082038342CFD0FFF78BFF0028CBD10020E0 +:1013C000BDE8F8830120FBE7E43700202DE9F04772 +:1013D0000D46044600219046284640F27912FFF758 +:1013E000A9FF234620220021284601F06FFE231D7D +:1013F00002222021284601F069FE631D03222221DA +:10140000284601F063FEA31D03222521284601F092 +:101410005DFE04F1080310222821284601F056FE43 +:1014200004F1100308223821284601F04FFE04F190 +:10143000110308224021284601F048FE04F112035E +:1014400008224821284601F041FE04F1140320221D +:101450005021284601F03AFE04F118034022702181 +:10146000284601F033FE04F120030822B02128466B +:1014700001F02CFE04F121030822B821284601F0D6 +:1014800025FE04F12207C0263B46314608222846A5 +:10149000083601F01BFEB6F5A07F07F10107F3D176 +:1014A00004F1320308223146284601F00FFE0027DE +:1014B00004F1330A94F832304FEAC7099F4209F524 +:1014C000A47615D3B8F1000F08D1314604F599730D +:1014D0000722284601F0FAFD09F24F16274694F834 +:1014E00032213B1B93420CD3F01DC008BDE8F087AE +:1014F0000AEB070308223146284601F0E7FD0137D1 +:10150000D8E707F2331331460822284601F0DEFD02 +:1015100008360137E3E7000013B50446084600210A +:1015200001602346C0F803102022019001F0CEFD97 +:101530000198231D0222202101F0C8FD0198631D9E +:101540000322222101F0C2FD0198A31D03222521BF +:1015500001F0BCFD019804F108031022282101F0DC +:10156000B5FD072002B010BDF7B50023047F009140 +:101570000E4607221946054601F06CFC731C0093C9 +:10158000012200230721284601F064FCC4B9B31CE2 +:101590000093052223460821284601F05BFC0D2418 +:1015A0003746B278BB1B934211D32B7FA88A0734EE +:1015B000E408BBB9844294BF0020012003B0F0BD11 +:1015C000AB8ADB00083BDB08B3700824E8E7FB1CB0 +:1015D0000093214600230822284601F03BFC0834F2 +:1015E0000137DEE7201A18BF0120E7E7F7B500232F +:1015F000047F00910E4608221946054601F02AFC98 +:10160000731CC4B90822009311462346284601F0F2 +:1016100021FC1024012372785F1C013B934211D3FB +:101620002B7FA88A0734E408BBB9844294BF00200A +:10163000012003B0F0BDAB8ADB00083BDB08737010 +:101640000824E7E7F31900932146002308222846DF +:1016500001F000FC08343B46DDE7201A18BF0120EA +:10166000E7E70000F8B50E46054614460021812242 +:101670003046FFF75FFE2B4608220021304601F07E +:1016800025FD7CB96B1C07220821304601F01EFDA8 +:101690000F2401236A785F1C013B934204D3E01DB1 +:1016A000C008F8BD0824F4E7EB19214608223046AB +:1016B00001F00CFD08343B46ECE70000F8B50E469F +:1016C000054614460021CE223046FFF733FE2B4656 +:1016D00028220021304601F0F9FC7CB905F108030D +:1016E00008222821304601F0F1FC30242F462A7AC6 +:1016F0007B1B934204D3E01DC008F8BD2824F5E706 +:1017000007F1090321460822304601F0DFFC0834C6 +:101710000137ECE7F7B5047F00910E460123102254 +:101720000021054601F096FBC4B9B31C00930922C1 +:1017300023461021284601F08DFB19243746728874 +:10174000BB1B9A4211D82B7FA88A0734E408BBB987 +:10175000844294BF0020012003B0F0BDAB8ADB00BF +:10176000103BDB0873801024E8E73B1D0093214603 +:1017700000230822284601F06DFB08340137DEE71C +:10178000201A18BF0120E7E730B5094D0A449142FD +:101790000DD011F8013B5840082340F30004013BF1 +:1017A0002C4013F0FF0384EA5000F6D1EFE730BD80 +:1017B0002083B8EDF7B5364A106851686B4603C30D +:1017C0006A4634493448082303F09CF8044690BB29 +:1017D0000A25324A106851686B4603C36A4630498D +:1017E0002D48082303F08EF80446002847D00369EB +:1017F000B3F5663F43D8B0F86620B2F57B7F3ED1A3 +:10180000284A024402F15C018B4238D35C3B2249F6 +:1018100000209E1AFFF7B8FF3246074604F1640124 +:101820000020FFF7B1FFA3689F4228D1E3689842E8 +:1018300008BF002523E00369B3F5663F26D8428B35 +:10184000B2F57B7F20D1174A024402F110018B428E +:1018500018D3103B104900209D1AFFF795FF2A4628 +:10186000064604F118010020FFF78EFFA3689E4290 +:1018700002D1E368984201D00D25AAE70025284649 +:1018800003B0F0BD1025A4E70C25A2E70B25A0E7C7 +:10189000FC490008DC97030000680008054A0008BE +:1018A000909703000898FFF710B5037C044613B91E +:1018B000006803F00FF8204610BD00000023BFF3BE +:1018C0005B8FC360BFF35B8FBFF35B8F8360BFF33E +:1018D0005B8F7047BFF35B8F0068BFF35B8F704710 +:1018E00070B505460C30FFF7F5FF05F10806044614 +:1018F0003046FFF7EFFFA04206D930466D68FFF78C +:10190000E9FF2544281A70BD3046FFF7E3FF201A8F +:10191000F9E7000070B50546406898B105F1080088 +:10192000FFF7D8FF05F10C0604463046FFF7D2FF5B +:101930008442304694BF6D680025FFF7CBFF013C21 +:101940002C44201A70BD000038B50C460546FFF740 +:10195000C7FFA04210D305F10800FFF7BBFF044406 +:101960006868B4FBF0F100FB1144BFF35B8F01200A +:10197000AC60BFF35B8F38BD0020FCE72DE9F04180 +:10198000144607460D46FFF7C5FF844228BF0446AC +:10199000D4B1B84658F80C6B4046FFF79BFF304473 +:1019A000286040467E68FFF795FF331A9C4203D8B3 +:1019B0006C600120BDE8F0816B60A41B3B68AB60EC +:1019C0002044E8600220F5E72046F3E738B50C46EE +:1019D0000546FFF79FFFA04210D305F10C00FFF76B +:1019E00079FF04446868B4FBF0F100FB1144BFF3D5 +:1019F0005B8F0120EC60BFF35B8F38BD0020FCE7FC +:101A00002DE9FF41884669460746FFF7B7FF6C4658 +:101A100006B204EBC6060025B44209D0626820680D +:101A200008EB0501FFF774FC636808341D44F3E715 +:101A300029463846FFF7CAFF284604B0BDE8F081C2 +:101A4000F8B505460C300F46FFF744FF05F10806D0 +:101A500004463046FFF73EFFA042304688BF6C6820 +:101A6000FFF738FF201A386020B130462C68FFF7A6 +:101A700031FF2044F8BD000073B5144606460D46FC +:101A8000FFF72EFF844228BF04460190DCB101A974 +:101A90003046FFF7D5FF019B33B93268C5E9023301 +:101AA000C5E9002401200CE09C4238BF0194286065 +:101AB000019868608442F5D93368AB60241AEC6001 +:101AC000022002B070BD2046FBE700002DE9FF4177 +:101AD0000F466946FFF7D0FF6C4600B204EBC00525 +:101AE0000026AC4209D0D4F8048054F8081BB81979 +:101AF0004246FFF70DFC4644F3E7304604B0BDE82C +:101B0000F081000038B50546FFF7E0FF04460146C6 +:101B10002846FFF719FF204638BD0000302383F325 +:101B2000118862B670470000002383F3118862B603 +:101B30007047000010B4026854681A4623465DF8E6 +:101B4000044B184701207047002070470020704761 +:101B500070470000002070470E20704700F580504D +:101B600090F8C800C0F340007047000000F58050B6 +:101B700090F9C90070470000F7B50C68BDF82070F7 +:101B800014F000541E466FD10B7B082B6CD8FFF766 +:101B9000C5FF4569AB685B010CD4AB681B0108D479 +:101BA000AC6814F080545DD1FFF7BEFF204603B04F +:101BB000F0BD01240B6804F1180C002BB8BFDB004A +:101BC0004FEA0C1CB4BF43F004035B0545F80C302E +:101BD0000B680FFA84FC13F0804F18BF05EB0C1E46 +:101BE00005EB0C1C1EBFDEF8803143F00203CEF87B +:101BF00080310B7BCCF8843105EB04158B68C5F87C +:101C00008C314B68C5F88831DCF8803143F0010332 +:101C1000CCF8803100EB441541F268031D4403EB1E +:101C200044130344C5E9002608330D4601F10C0CAA +:101C300055F804EB43F804EB6545F9D184342D885D +:101C40001D8000EB441407F00303257925F00B05F4 +:101C50002B432371FFF768FF0097334600F0E0FC49 +:101C60000120A4E70224A5E74FF0FF309FE7000022 +:101C700013B500F580540191E06DFFF74BFE1F286E +:101C80000AD90199E06D2022FFF7BAFEA0F12003E6 +:101C90005842584102B010BD0020FBE708B500F5DE +:101CA0008050FFF73BFFC06DFFF708FEBDE808401E +:101CB000FFF73ABF00220260828142608260704773 +:101CC00010B500220023C0E900230023044603814D +:101CD0000C30FFF7EFFF204610BD0000F0B50546C1 +:101CE00000F580500C4690F8C83013F0040FC3F391 +:101CF000800108BF114661F3820304F1840680F875 +:101D0000C83005EB461389B01B79D8072ED57AB3B6 +:101D100019072DD46846FFF7D3FF05EB441303F5ED +:101D2000835303F1180703AA10331868596814463F +:101D300003C40833BB422246F7D1186820609B8851 +:101D4000A380DDE90E23CDE900230123ADF808309F +:101D50002B686946DB6B2846984705EB46152B79BF +:101D60001A075CBF43F008032B7101E0002AF4D18D +:101D700009B0F0BD2DE9F047074688B007F580545B +:101D800068469A468846FFF7C9FE9146FFF798FFD6 +:101D9000E06DFFF7A5FD1F2829D9E06D20226946D7 +:101DA000FFF7B0FE202822D103AD444605AB2E46F6 +:101DB00003CE9E4220606160354604F10804F6D1EE +:101DC00030682060B388A380DDE90023C9E90023DF +:101DD000BDF80830AAF80030FFF7A6FE4A46534681 +:101DE0004146384608B0BDE8F04700F007BCFFF7B1 +:101DF0009BFE002008B0BDE8F08700002DE9F84FF9 +:101E00000023C0E90133254B044640F8183B0F4638 +:101E1000FFF750FF04F12800FFF752FF04F14808D4 +:101E200004F582554646083530462036FFF748FF10 +:101E3000AE42F9D104F580554FF480534FF00009BC +:101E4000C5E91339C5F848800123EE6504F58758C4 +:101E500004F58456C5F8549085F8583085F86030FC +:101E6000083608F108084FF0000A4FF0000B46E969 +:101E700008ABA6F11800FFF71DFF203646F8289C96 +:101E80004645F4D185F8C97017B1054800F0A0FBAC +:101E9000044B63612046BDE8F88F00BF384A000854 +:101EA000104A00080064004010B5044B197804463D +:101EB0004A1C1A70FFF7A2FF204610BD14380020FC +:101EC0002DE9F047002950D0294B2A4FB7FBF1F5F7 +:101ED00099428CBF0A231123581EB5FBF3FC03FB68 +:101EE0001C53C4B22BB102280346F5D80020BDE82C +:101EF000F0870CF1FF36B6F5806FF7D2C4EBC40E55 +:101F00000EF103034FEAE309C3F3C703A4EB03088D +:101F100009F1010A4FF47A755FFA88F009FB05555B +:101F20005AFA88F8B5FBF8F5B5F5617FC1BF0EF137 +:101F3000FF33C3F3C703E01AC0B25C1C50FA84F449 +:101F40000CFB04F4B7FBF4F4A142CFD1013BDBB2AC +:101F50000F2BCBD80138C0B20728C7D80021107189 +:101F600016809170D3700120C1E70846BFE700BF1B +:101F70003F420F000051250270B505460E464FF452 +:101F80007A746B695B6803F00103B3424FF00100A0 +:101F900004D001F0A5FC013CF3D1204670BD000047 +:101FA00030B54269936913F0700F16D000230B4CC3 +:101FB000936103F1840200EB421211794D0709D5B8 +:101FC000890707D5416954F823508D60117941F094 +:101FD000040111710133032BEBD130BD244A0008F9 +:101FE00073B51D46436916469A68D207044609D55B +:101FF0009A6801219960C2F34002CDE90065002191 +:10200000FFF76CFE63699A68D1050BD59A684FF4A7 +:1020100080719960C2F34022CDE90065012120461C +:10202000FFF75CFE63699A68D2030BD59A684FF498 +:1020300080319960C2F34042CDE90065022120461B +:10204000FFF74CFE204602B0BDE87040FFF7A8BF86 +:10205000F8B50446466900296CD106F10C073868CA +:1020600080076AD006EB01153868D5F8B00110F08A +:10207000040FD5F8B0011ABFC00840F00040400D71 +:10208000A061D5F8B0C11CF0020F1CBF40F0804029 +:10209000A061D5F8B40106EB011100F00F0084F83F +:1020A0002400D1F8B8012077D1F8B801000A607790 +:1020B000D1F8B801000CA077D1F8B801000EE07794 +:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 +:1020D0002100D1F8BC01000C84F82200D1F8BC1119 +:1020E000090E84F823103821396004F1340004F11A +:1020F000180104F1240551F8046B40F8046BA9425F +:10210000F9D109880180C4E90A23214600232386E6 +:1021100051F8283B2046DB6B984704F58052204657 +:1021200092F8C83043F0040382F8C830BDE8F840A4 +:10213000FFF736BF06F1100791E7F8BD10B504466A +:1021400000F04EFA02460B4652EA030102D0013A71 +:1021500063F100030449086820B12146BDE810403E +:10216000FFF776BF10BD00BF10380020F8B500F5AE +:1021700083511E46FFF7D2FCDFF844C0083100242B +:1021800004F1840500EB45152B795F070ED4DB06BF +:102190000CD5D1E900739742B34107D243695CF88B +:1021A00024709F602B7943F004032B710134032CBE +:1021B00001F12001E4D1BDE8F840FFF7B5BC00BF54 +:1021C000244A000808B5FFF7A9FCFFF7E9FEBDE8BF +:1021D0000840FFF7A9BC0000F8B5436905469868B8 +:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C +:1021F00095FC05F583541034002606F1840305EBA5 +:1022000043131B791A0706D50136032E04F1200467 +:10221000F3D1012007E05B07F6D42146384600F0F1 +:1022200039FA0028F0D1FFF77FFCF8BD0120FCE768 +:1022300000F5805008B5FFF771FCC06DFFF750FB4B +:10224000FFF772FC43090CBF0120002008BD00000D +:10225000F8B51D46002313700F4606461446FFF7D7 +:10226000E7FF80F00100387025B129463046FFF7BE +:10227000B3FF2070F8BD00002DE9B8410C461546AB +:102280001F46804600F0ACF90B462178024609B99A +:10229000287850B14046FFF769FFFFF793FF3B46B0 +:1022A0002A462146FFF7D4FF0120BDE8B88100008F +:1022B00010B5FFF733FC174BDA6942F00072DA61B0 +:1022C0001A6942F000721A611A6900F5805422F00E +:1022D00000721A61FFF728FC94F8C830DB0718D4A5 +:1022E000B9B103211320FFF719FC01F0C7F903214D +:1022F000142001F0C3F90321152001F0BFF994F86F +:10230000C83043F0010384F8C830BDE81040FFF73F +:102310000BBC10BD001002402DE9F04700F58055C0 +:1023200088B095F8C930012B0446884616467FD8F8 +:10233000804F57F823200AB947F82300D7F800A0A8 +:10234000C4F80C802674BAF1000F63D095F8C93038 +:10235000012B6FD001212046FFF7AAFFFFF7DEFB1C +:102360006269136823F0020313606269136843F023 +:1023700001031360636900275F6101212046FFF7B5 +:10238000D3FBFFF7F9FD002800F09580E86DFFF71B +:1023900095FA04F58359BA4609F10809202200216B +:1023A0006846FEF7C7FF02A8FFF784FCCDF818A027 +:1023B0006A4609EB07030DF1180E9446BCE80300CA +:1023C000F44518605960624603F10803F5D1DCF862 +:1023D0000000186020379CF804201A71602FDDD1AE +:1023E00095F8C8306FF38203002785F8C8306A4635 +:1023F00041462046ADF80070ADF802708DF80470CB +:10240000FFF75EFD636948BB4FF400421A6008B0F5 +:10241000BDE8F08741F2D00002F01CFA814610B10D +:102420005146FFF7EBFCC7F80090B9F1000F8DD1D2 +:102430000020ECE7386803681B6B984701460028CA +:1024400088D13868FFF734FF3868036832465B6824 +:102450004146984700287FF47DAFE9E761221A6082 +:102460009DF802309DF803201B06120402F470222E +:1024700003F040731343BDF80020C2F30902134375 +:102480009DF804201205022E02F4E0020CBF4FF06A +:1024900000410021134362690B43D3616369132236 +:1024A0005A616269136823F00103136039462046BC +:1024B000FFF762FD08B96369A6E795F8C93093BBD9 +:1024C0006169D1F8002242F00102C1F8002261697D +:1024D000D1F8002222F47C5222F00E02C1F8002230 +:1024E0006169D1F8002242F46062C1F80022626999 +:1024F000C2F814326269C2F80432626941F6FF71AF +:10250000C2F80C126269C2F840326269C2F8443201 +:1025100063690122C3F81C226269D2F8003223F0F9 +:102520000103C2F8003295F8C83043F0020385F881 +:10253000C8306CE71038002008B500F051F850EAB8 +:102540000103024602D0421E61F10001044B1868EB +:1025500010B10B46FFF744FDBDE8084001F064B838 +:102560001038002008B50020FFF7E8FDBDE808405E +:1025700001F05AB808B50120FFF7E0FDBDE80840BA +:1025800001F052B800B59BB0EFF3098168226846AC +:10259000FEF7BEFEEFF30583014B9B6BFEE700BF2A +:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF +:1025B000EFF3098168226846FEF7AAFEEFF3058370 +:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 +:1025D0000FB408B5029801F019F9FEE701F02EBB1F +:1025E00001F004BB13B56C4684E80600031D94E8B3 +:1025F000030083E80500012002B010BD73B58568B3 +:10260000019155B11B885B0707D4D0E900369B6B5D +:102610009847019AC1B23046A847012002B070BD68 +:10262000F0B5866889B005460C465EB1BDF8383015 +:102630005B070AD4D0E900379B6B98472246C1B2AA +:102640003846B047012009B0F0BD00220023CDE993 +:1026500000230023ADF808300A4603AB01F1080659 +:10266000106851681C4603C40832B2422346F7D1B1 +:10267000106820609288A280FFF7B2FF0423ADF8B3 +:1026800008302B68CDE90001DB6B69462846984786 +:10269000D8E7000030B503680968DD0FB5EBD17FDE +:1026A00023F0604421F060424FEAD1700BD0002B40 +:1026B000B8BFA40C0029B8BF920C944202D034BF1A +:1026C0000120002030BD944205D1C1F38070C3F3D6 +:1026D00080738342F6D194422CBF00200120F1E7A1 +:1026E0002DE9F041456A15B94162BDE8F0814B68BA +:1026F00023F06047C3F38A464FEAD37EC3F3807862 +:1027000016EA230638BF3E46AC462B465A68BEEB57 +:10271000D27F22F060440AD0002A18DAA40CB44216 +:1027200017D19D420FD10D60DEE71346EEE7A742B9 +:1027300007D102F08044C2F3807242450BD054B1FD +:10274000EFE708D2EDE7CCF800100B60CDE7B4421C +:1027500001D0B442E5D81A689C46002AE5D1196038 +:10276000C3E700002DE9F047089D01F007044FEA98 +:10277000D508224405F0070500EBD1004FF47F494E +:10278000944201D1BDE8F08704F0070705F0070A7D +:1027900057453E4638BF5646C6F10806111B8E42C5 +:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 +:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 +:1027C00047FA0AF739408CEA010C03F80EC034448A +:1027D0003544D5E780EA0120082341F2210201B205 +:1027E0004000002980B203F1FF33B8BF504013F01E +:1027F000FF03F4D17047000038B50C468D18A54290 +:1028000000D138BD14F8011BFFF7E4FFF7E7000023 +:1028100042684AB1136843604389818901339BB29E +:102820009942438138BF83811046704770B588B0A4 +:10283000202204460D4668460021FEF77BFD204617 +:102840000495FFF7E5FF024658B16B46054608AE12 +:102850001C4603CCB44228606960234605F1080594 +:10286000F6D1104608B070BD082817D909280CD039 +:102870000A280CD00B280CD00C280CD00D280CD01A +:102880000E2814BF4020302070470C2070471020C5 +:1028900070471420704718207047202070470000B0 +:1028A000082817D90C280CD910280CD914280CD9B1 +:1028B00018280CD920280CD930288CBF0F200E20C6 +:1028C0007047092070470A2070470B2070470C2082 +:1028D00070470D20704700002DE9F843078C072F43 +:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 +:1028F0002006A5F1200029FA05F108FA06F628FAC3 +:1029000000F031430143C9B21846FFF763FF0835B1 +:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 +:102920006BBF4FF6FF70BDE8F883000010B54B6831 +:1029300023B9CA8A63F30902CA8210BD04691A68FE +:102940001C600361C38A013BC3824A60EFE7000059 +:102950002DE9F84F1D46CB8A0F46C3F3090105291F +:10296000814692460B4630D00020AAB207F11A04E5 +:102970009EB2042E1FFA80F80FD8904503F1010390 +:1029800006D3FB8A0A4462F30903FB8201201AE0A2 +:102990001AF80060E6540130EAE79045F1D2A1F15F +:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 +:1029B0008BF6002C45D14846FFF72AFF044638B96C +:1029C00078606FF00200BDE8F88F4FF00008E6E78E +:1029D000002606607860ADB24FF0000B454510D977 +:1029E0000AEB0803221D13F8011B9155B1B208F13F +:1029F00001081B291FFA88F82BD0454506F101066E +:102A0000F1D8FB8AC3F30902154465F30903BCE757 +:102A1000013292B21C462368002BF9D16B1F0B4484 +:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 +:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 +:102A4000BFE70122E7E7C0F800B05E462060044619 +:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 +:102A6000AFE7C0F800B0002620600446B6E70000DB +:102A70002DE9F04F2DED028B1C4683B05B6901926E +:102A800007468846002B00F09A80238C2BB1E26920 +:102A9000002A00F09480072B35D807F10C00FFF7CF +:102AA000B7FE054638B96FF00205284603B0BDEC05 +:102AB000028BBDE8F08F14220021FEF73BFC228C34 +:102AC000E16905F10800FEF723FC208C013080B29B +:102AD000FFF7E6FEFFF7C8FE013880B22084013020 +:102AE00028746369228C1B782A4403F01F0363F067 +:102AF0003F0348F000411372384669602946FFF7EA +:102B0000EFFD0125D1E700F10C034FF0000908EEBD +:102B1000103A4FF0800A4E464D4618EE100AFFF765 +:102B200077FE83460028BED014220021FEF702FC67 +:102B3000002E3AD1019BABF8083002220BF1080EAF +:102B40001FFA82FC0CF10100BCF1060F218C80B24F +:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 +:102B60001278013802F01F028E4208BF4FF0400A6F +:102B700042EA49121BFA80F14AEA020A013048F09F +:102B8000004281F808A08BF81000CBF804205946C9 +:102B90003846FFF7A5FD238C0135B3422DB289F0ED +:102BA00001094FF0000AB8D17FE70022C6E7E169CA +:102BB000895D0EF802100136B6B20132C0E76FF03F +:102BC000010572E7F8B515460E463022002104468D +:102BD0001F46FEF7AFFB069B6360B5F5001F079B22 +:102BE000A76034BF6A094FF6FF72A36297B2E6612D +:102BF00004F1100000239A4206D800230360A78244 +:102C0000E3822383E360F8BD06600133304620365B +:102C1000F1E7000003781BB94BB2002BC8BF01706D +:102C20007047000000787047F8B50C46C969074640 +:102C300011B9238C002B37D1257E1F2D34D838783D +:102C400028BB228C072A2CD8268A36F003032BD1E6 +:102C50004FF6FF70FFF7D0FD20F001003102400475 +:102C600041EA0561400C41EA40254FF6FF722346D8 +:102C700029463846FFF7FCFE002807DD6269137815 +:102C80000133DBB21F2B88BF00231370F8BD218AEC +:102C90002D0645EA012505432046FFF71DFE0246A5 +:102CA000E5E76FF00300F1E76FF00100EEE70000E9 +:102CB00070B58AB0044616460021282268461D4693 +:102CC000FEF738FBBDF83830ADF810300F9B059398 +:102CD0009DF840308DF81830119B07936946BDF878 +:102CE0004830ADF820302046CDE90265FFF79CFF63 +:102CF0000AB070BD2DE9F041D36905460C46164671 +:102D00000BB9138C5BBB377E1F2F28D895F800803A +:102D1000B8F1000F26D03046FFF7DEFD33782102F0 +:102D200041EAC33141EA0801338A41EA076141EAD5 +:102D300003410246334641F080012846FFF798FEE2 +:102D400000280ADD3378012B07D17269137801332B +:102D5000DBB21F2B88BF00231370BDE8F0816FF03A +:102D60000100FAE76FF00300F7E70000F0B58BB061 +:102D700004460D4617460021282268461E46FEF7E7 +:102D8000D9FA9DF84C305A1E534253418DF8003009 +:102D90009DF84030ADF81030119B05939DF84830F8 +:102DA0008DF81830149B07936A46BDF85430ADF87F +:102DB000203029462046CDE90276FFF79BFF0BB075 +:102DC000F0BD0000406A00B104307047436A1A68E1 +:102DD000426202691A600361C38A013BC382704781 +:102DE0002DE9F041D0F82080194E14461D46414689 +:102DF000002709B9BDE8F081D1E90223A21A65EBE9 +:102E00000303964277EB03031ED2036A8B420DD174 +:102E1000FFF78CFD036A1B68036203690B60C38ABA +:102E20000161016A013BC3828846E2E7FFF77EFD4C +:102E30000B68C8F8003003690B60C38A0161013B6D +:102E4000C382D8F80010D4E788460968D1E700BFEC +:102E500080841E002DE9F04F8BB00D46DDF85090B8 +:102E600014469B468046002800F01981B9F1000FF6 +:102E700000F01581531E3F2B00F21181012A03D16E +:102E8000BBF1000F40F00B810023CDE90833B8F807 +:102E90001430B5EBC30F4FEAC30703D300200BB0C8 +:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A +:102EB000FFB227461BB9D8F81030002B7AD0272D47 +:102EC0004ED8C5F12806B7424FF000032CBFF6B22A +:102ED0003E4600932946D8F8080008AB3246FFF773 +:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 +:102EF00003F10053053BDB000493D8F80C30039337 +:102F00002821039B13B1BAF1000F2CD1D8F810007F +:102F100040B1BAF1000F05D0009608AB5246691ACD +:102F2000FFF720FC38B2002FB8D066070AD00AABF2 +:102F300003EBD401624211F8083C02F0070213418E +:102F400001F8083C082C3CD9102C40F2B580202C0C +:102F500040F2B780BBF1000F00F09C80082334E002 +:102F6000BA460026C2E7049BE02B28BFE023069365 +:102F70000B44AB42059314D95A1B03980096924513 +:102F800034BF5246D2B2691A08AB04300792FFF739 +:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 +:102FA0008AFA049B069A05999B1A0493039B1B6853 +:102FB0000393A6E70093D8F8080008AB3A462946E1 +:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD +:102FD000082C12D89DF82030621E23FA02F2D50781 +:102FE00006D54FF0FF3202FA04F423438DF8203067 +:102FF0009DF8203089F8003051E7102C12D8BDF828 +:103000002030621E23FA02F2D10706D54FF0FF32BC +:1030100002FA04F42343ADF82030BDF82030A9F8BB +:1030200000303CE7202C0FD80899631E21FA03F3E7 +:10303000DA0705D54FF0FF3202FA04F40C43089486 +:10304000089BC9F800302AE7402C2BD0DDE9086541 +:10305000611EC4F12102A4F1210326FA01F105FA4F +:1030600002F225FA03F311431943CB0712D50122CB +:10307000A4F12003C4F1200102FA03F322FA01F1C2 +:10308000A240524243EA010363EB430332432B4322 +:10309000CDE90823DDE90823C9E90023FFE66FF045 +:1030A0000100FCE66FF00800F9E6082CA0D9102C0E +:1030B000B3D9202CEED8C3E7BBF1000FADD002236B +:1030C00083E7BBF1000FBBD004237EE730B5012AB4 +:1030D000144638BF0124402C85B028BF4024002569 +:1030E000012ACDE9025518D81B788DF808306307FE +:1030F0000AD004AB03EBD405624215F8083C02F099 +:103100000702934005F8083C00910346224600213F +:1031100002A8FFF727FB05B030BD082AE4D9102A22 +:1031200003D81B88ADF80830E1E7202A8DBFD3E92A +:1031300000231B680293CDE90223D8E710B5CB68C2 +:103140001BB98B600B618B8210BD04691A681C600F +:103150000361C38A013BC382CA60F0E703064CBF28 +:10316000C0F3C0300220704708B50246FFF7F6FFF3 +:10317000022806D15306C2F30F2001D100F003004C +:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E +:1031900003230A6804461046FFF7E0FF022814BF25 +:1031A000C2F306260026002A0D46824680F2F281EE +:1031B00012F0C04940F0EE81097B002900F0EA815D +:1031C000022803D02378B34240F0E781C2F30463BE +:1031D0000693104602F07F030593FFF7C5FF059B9A +:1031E00029444FEA834848EA0A4848EA4668CE78C4 +:1031F00000230022CDE90823F309834648EA0008AA +:10320000029367D0059B009302466768534608A95E +:103210002046B847002800F0C381276A4FB94146CD +:1032200004F10C00FFF702FB074690B96FF00200B3 +:1032300054E03B6998450DD03F68002FF9D14146D5 +:1032400004F10C00FFF7F2FA07460028EED0236ADB +:103250003B60276297F817C006F01F08CCF3840C78 +:10326000ACEB08001FFA80FE0028B8BF0EF120006A +:10327000A8EB0C031FFA83FED7E90221B8BF00B206 +:10328000002B0793BEBF0EF120031BB2079352EA37 +:10329000010338D0039BDFF824E39A1A049B4FF014 +:1032A000000C63EB010196457CEB01032BD36B7B98 +:1032B00097F81AE0734519D1029B002B78D00128AA +:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF +:1032D00016D337E0276A27B96FF00C0013B0BDE8AA +:1032E000F08F3B699845B5D03F68F4E7B24890420B +:1032F0007CEB010301D30020F0E7029B002BFAD006 +:10330000079B0F2B17DCFA7DB30002F0030203F0DA +:103310007C031343FB7539462046FFF707FB6B7BA5 +:10332000BB76029B3BB9FB7DC3F38402013262F39F +:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A +:10334000002B35D0B309022B32D0039BBB60049B0A +:10335000FB60142200210DA8FDF7ECFF039B0A93EC +:10336000049B0B932B1D0C932B7BADF83EB0013BC4 +:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 +:10338000433094F82C308DF840A083F001038DF881 +:1033900044308DF84180A3680AA920469847FB7DF8 +:1033A000C3F38403013303F01F039B02FB82A2E7F4 +:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 +:1033C0008403434540F0F280029A2B7BB609002A21 +:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 +:1033E000049BFB602B7BAE1D033BDBB232463946B0 +:1033F00004F10C00FFF7ACFA00280CDA394620463D +:10340000FFF794FAFB7DC3F38403013303F01F033A +:103410009B02FB820AE7DDE90884AB883B834FF619 +:10342000FF73C9F12000A9F1200228FA09F104FA7A +:1034300000F0014324FA02F211431846C9B2FFF723 +:10344000C9F909F10809B9F1400F0346E9D1B88279 +:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 +:10346000DA43C2F3C01262F3C713FB7543E786B9B0 +:103470002E1D013BDBB23246394604F10C00FFF74A +:1034800067FA0028BADB2A7BB88A013AD2B2314601 +:10349000E2E7F98AC1F30901013B0429DAB25BD8FA +:1034A000281D002307F11B069A4208D910F801CB0A +:1034B00006F801C0013101330529DBB2F4D10399CB +:1034C0000A9104990B91934207F11B010C9138BFAB +:1034D000043379680D9134BF55FA83F300230E93BA +:1034E000FB8AADF83EB0C3F309031A44069B8DF87E +:1034F0004230059B8DF8433094F82C30ADF83C20D9 +:1035000083F001038DF8443000238DF840A08DF83E +:1035100041807B602A7BB88A013A291DFFF76CF94C +:103520003B8BB882834203D1A3680AA920469847FF +:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 +:10354000013303F01F039B02FB823B8B9A420CBFAB +:1035500000206FF01000C1E67B68002BAFD0052083 +:1035600001E01C3033461E68002EFAD1091A081DEE +:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 +:103580009DD89A429BD916F8013B00F8013B09F1FE +:103590000109EFE76FF00900A0E66FF00A009DE671 +:1035A0006FF00B009AE66FF00D0097E66FF00E00DB +:1035B00094E66FF00F0091E640420F0080841E00F9 +:1035C000EFF3098305494A6B22F001024A6368332D +:1035D00083F30988002383F31188704700EF00E02C +:1035E000302080F3118862B60C4B0D4AD96821F463 +:1035F000E0610904090C0A43DA60D3F8FC200949A8 +:1036000042F08072C3F8FC200A6842F001020A60AE +:103610002022DA7783F82200704700BF00ED00E037 +:103620000003FA05001000E010B5302383F3118881 +:103630000E4B5B6813F4006314D0F1EE103AEFF315 +:103640000984683C4FF08073E361094BDB6B2366B0 +:1036500084F3098800F098F810B1064BA36110BDFF +:10366000054BFBE783F31188F9E700BF00ED00E0AD +:1036700000EF00E0030600080606000800F16043C2 +:1036800003F561430901C9B283F80013012200F078 +:103690001F039A4043099B0003F1604303F5614314 +:1036A000C3F880211A60704700F16040090100F5FD +:1036B0006D40C9B2017670470023037582680369C3 +:1036C0001B6899689142FBD25A680360426010609F +:1036D0005860704700230375826803691B68996806 +:1036E0009142FBD85A68036042601060586070478E +:1036F00008B50846302383F311880B7D032B05D0D2 +:10370000042B0DD02BB983F3118808BD8B690022DF +:103710001A604FF0FF338361FFF7CEFF0023F2E71B +:10372000D1E9003213605A60F3E70000FFF7C4BF2D +:10373000054BD9680875186802681A605360012241 +:103740000275D860FCF748BF2038002030B50C4B1C +:10375000DD684B1C87B004460FD02B46094A6846EB +:1037600000F0FEF82046FFF7E3FF009B13B1684628 +:1037700000F000F9A86907B030BDFFF7D9FFF9E7FD +:1037800020380020F1360008044B1A68DB68906886 +:103790009B68984294BF0020012070472038002089 +:1037A000084B10B51C68D86822681A605360012263 +:1037B0002275DC60FFF78EFF01462046BDE8104011 +:1037C000FCF70ABF20380020044B1A68DB689268B7 +:1037D0009B689A4201D9FFF7E3BF70472038002069 +:1037E00038B5074C07490848012300252370656058 +:1037F00000F00AFB0223237085F3118838BD00BF57 +:10380000483A00207C4A00082038002008B572B6EB +:10381000044B186500F0CEF900F092FA024B032237 +:103820001A70FEE720380020483A002000F0B4B8B3 +:10383000EFF3118020B9EFF30583302282F3118872 +:103840007047000010B530B9EFF30584C4F30804E5 +:1038500014B180F3118810BDFFF7B6FF84F311880F +:10386000F9E700008B60022308618B8208467047ED +:103870008368A3F1840243F8142C026943F8442CB2 +:10388000426943F8402C094A43F8242CC26843F8A3 +:10389000182C022203F80C2C002203F80B2C044AEB +:1038A00043F8102CA3F12000704700BFF105000879 +:1038B0002038002008B5FFF7DBFFBDE80840FFF720 +:1038C00035BF0000024BDB6898610F20FFF730BF67 +:1038D00020380020302383F31188FFF7F3BF000066 +:1038E00008B50146302383F311880820FFF72EFF27 +:1038F000002383F3118808BD064BDB6839B14268A9 +:1039000018605A60136043600420FFF71FBF4FF038 +:10391000FF307047203800200368984206D01A68AC +:103920000260506099611846FFF700BF70470000C1 +:1039300010B50A4C23699A6891420CD85A68816084 +:103940000360426010609A685860511A99604FF0A5 +:10395000FF33A36110BD1B68891AECE720380020F3 +:1039600010B4C0E9032300235DF8044B4361FFF763 +:10397000DFBF0000036881689A680A449A60426861 +:1039800013605A6000230360024B4FF0FF329A61CC +:10399000704700BF2038002070B5124DEB692A46F1 +:1039A0000133EB6152F8103F934206D09A68013A16 +:1039B0009A6030262C69A36803B170BDD4E9002158 +:1039C0000A605160236083F31188D4E903312046F3 +:1039D000984786F3118861690029EBD02046FFF7EC +:1039E000A7FFE7E72038002000207047FEE700002F +:1039F000704700004FF0FF3070470000BFF34F8F5B +:103A0000024AD368DB07FCD4704700BF00200240A5 +:103A100008B5074B1B7853B9FFF7F0FF054B1A6940 +:103A2000120641BF044A5A6002F188325A6008BD4A +:103A3000603A0020002002402301674508B5054B8D +:103A40001B7833B9FFF7DAFF034A136943F08003A9 +:103A5000136108BD603A0020002002407F289ABF11 +:103A600000F58030C0020020704700004FF4006075 +:103A700070470000802070477F2808B50BD8FFF7FB +:103A8000EDFF00F500630268013204D10430834287 +:103A9000F9D1012008BD0020FCE700007F2810B507 +:103AA00004461CD8FFF7AAFFFFF7B2FF0D4BF32225 +:103AB000DA6002221A61FFF7D1FF58611A6942F0F9 +:103AC00040021A614FF40061FFF798FF00F034F9EB +:103AD000FFF7B4FF2046BDE81040FFF7CDBF002040 +:103AE00010BD00BF002002402DE9F84312F0010391 +:103AF000144606D01F4B40F2F3221A600020BDE8A6 +:103B0000F88385181C4A954204D91A4A4FF43E712D +:103B10001160F3E7FFF77CFFFFF770FFDFF86880C5 +:103B2000451A4FF00109012C05EB01060F4603D899 +:103B3000FFF784FF0120E2E73B88C8F8109033804C +:103B40000020FFF75BFFC8F81000338831F8022B24 +:103B50009BB29A420CD0074B40F20F321A60074BCF +:103B60001E60074B1C60074B1F60FFF767FFC6E72F +:103B7000023CD8E75C3A002000000408503A0020DC +:103B8000583A0020543A002000200240084908B565 +:103B90000B7828B11BB9FFF73BFF01230B7008BD61 +:103BA000002BFCD0BDE808400870FFF747BF00BFFE +:103BB000603A002008B54FF420414FF0005000F06B +:103BC000BDF8BDE808404FF400514FF0805000F0C0 +:103BD000B5B800000846114600F05EBE012000F0B6 +:103BE0005BBE0000084600F075BE000030B583B033 +:103BF000FFF71EFE0E4B0F4DDB692A684FF47A71FA +:103C000001FB03F3934237BF0B4A0B495168146819 +:103C10002B602EBFD1E90041013151601C1941F1E7 +:103C200000010191FFF70EFE0199204603B030BD5F +:103C300020380020643A0020683A002030B583B074 +:103C4000FFF7F6FD114B124DDB692A684FF47A71CC +:103C500001FB03F3934237BF0E4A0E4951681468C3 +:103C60002B602EBFD1E90041013151601C1941F197 +:103C700000010191FFF7E6FD01994FF47A720023EC +:103C80002046FCF795FA03B030BD00BF2038002075 +:103C9000643A0020683A002010B50244064BD2B2C4 +:103CA000904200D110BD441C00B253F8200041F8EE +:103CB000040BE0B2F4E700BF502800400F4B30B5D2 +:103CC0001C6A240407D41C6A44F440741C621C6AF5 +:103CD00044F400441C620A4C236843F4807323605C +:103CE0000244084BD2B2904200D130BD441C00B215 +:103CF00051F8045B43F82050E0B2F4E700100240B2 +:103D0000007000405028004007B5012201A90020A2 +:103D1000FFF7C2FF019803B05DF804FB13B504463A +:103D2000FFF7F2FFA04205D0012201A90020019473 +:103D3000FFF7C4FF02B010BD7047000070470000DD +:103D400070470000074B45F255521A6002225A6034 +:103D500040F6FF729A604CF6CC421A60024B012288 +:103D60001A70704700300040743A0020034B1B78F3 +:103D70001BB1034B4AF6AA221A607047743A00201E +:103D800000300040044B1A682AB902F1804202F563 +:103D90000432526A1A607047703A0020024B4FF0AA +:103DA00080725A62704700BF0010024008B5FFF7EA +:103DB000E9FF024B1868C0F3407008BD703A00205C +:103DC00070470000FEE700000A4B0B480B4A904288 +:103DD0000BD30B4BDA1C121AC11E22F003028B42CA +:103DE00038BF00220021FDF7A5BA53F8041B40F8A4 +:103DF000041BECE7EC4B0008583C0020583C00202A +:103E0000583C0020FEE7000070B51B4B0163002505 +:103E1000044686B0586085620E46FFF7E1FB04F168 +:103E20001003C4E904334FF0FF33A361134BE56182 +:103E3000D969A5600A462B46C4E9082304F1340178 +:103E4000C4E900440E4AE562256580232046FFF759 +:103E500009FD0123E0600B4A03750092726801922C +:103E6000B268CDE90223084B6846CDE90435FFF777 +:103E700021FD06B070BD00BF483A00202038002068 +:103E8000884A00088D4A0008053E00084B684360D8 +:103E90008B688360CB68C3600B6943614B690362C5 +:103EA0008B6943620B6803607047000008B51B4BC9 +:103EB0009A6A42F4FC029A629A6A22F4FC029A62BA +:103EC0009A6A5A6942F4FC025A61154A5B691146C2 +:103ED0004FF09040FFF7DAFF02F11C0100F580601F +:103EE000FFF7D4FF02F1380100F58060FFF7CEFF45 +:103EF00002F1540100F58060FFF7C8FF02F1700184 +:103F000000F58060FFF7C2FF02F18C0100F58060D0 +:103F1000FFF7BCFFBDE8084000F05AB800100240AF +:103F2000944A000808B500F093F9FFF759FCBDE882 +:103F30000840FFF727BF00007047000010B5214C74 +:103F4000A36A63F4FC03A362A36A03F4FC03A36201 +:103F50004FF0FF32A36A23692261236900232361A2 +:103F60002169E168E260E268E360E268E2691649BB +:103F700042F08052E261E2690A6842F480720A60AB +:103F8000226A02F44072B2F5407F1EBF4FF48032C5 +:103F900022622362236A1B0407D4236A43F440731A +:103FA0002362236A43F40043236200F031F9A369DA +:103FB000064A43F00103A361A369136843F0200399 +:103FC000136010BD0010024000700040000001406E +:103FD0001E4B1A6842F001021A601A689007FCD55D +:103FE0005A6822F003025A605A6812F00C02FBD1A0 +:103FF000196801F0F90119605A601A6842F48032B8 +:104000001A601A689103FCD5114A5A604FF40452A1 +:10401000DA6230221A631A6842F080721A601A68F3 +:104020009201FCD50B4912220A600A6802F00702CD +:10403000022AFAD15A6842F002025A605A6802F023 +:104040000C02082AFAD11A6B1A637047001002405A +:1040500000241D0000200240084A08B55169136879 +:104060000B4003F00103536123B1054A13680BB100 +:1040700050689847BDE80840FFF7D6BA00040140F1 +:10408000783A0020084A08B5516913680B4003F0DC +:104090000203536123B1054A93680BB1D068984776 +:1040A000BDE80840FFF7C0BA00040140783A00209C +:1040B000084A08B5516913680B4003F004035361C3 +:1040C00023B1054A13690BB150699847BDE8084010 +:1040D000FFF7AABA00040140783A0020084A08B560 +:1040E000516913680B4003F00803536123B1054A7B +:1040F00093690BB1D0699847BDE80840FFF794BABF +:1041000000040140783A0020084A08B55169136854 +:104110000B4003F01003536123B1054A136A0BB13E +:10412000506A9847BDE80840FFF77EBA0004014096 +:10413000783A0020174B10B55A691C68144004F4F3 +:1041400078725A61A30604D5134A936A0BB1D06AF8 +:104150009847600604D5104A136B0BB1506B984713 +:10416000210604D50C4A936B0BB1D06B9847E2053E +:1041700004D5094A136C0BB1506C9847A30504D5BC +:10418000054A936C0BB1D06C9847BDE81040FFF71F +:104190004BBA00BF00040140783A00201A4B10B51A +:1041A0005A691C68144004F47C425A61620504D5C3 +:1041B000164A136D0BB1506D9847230504D5134A69 +:1041C000936D0BB1D06D9847E00404D50F4A136E80 +:1041D0000BB1506E9847A10404D50C4A936E0BB1F5 +:1041E000D06E9847620404D5084A136F0BB1506F24 +:1041F0009847230404D5054A936F0BB1D06F9847B5 +:10420000BDE81040FFF710BA00040140783A0020E2 +:10421000062108B50846FFF731FA06210720FFF707 +:104220002DFA06210820FFF729FA06210920FFF7B9 +:1042300025FA06210A20FFF721FA06211720FFF7A9 +:104240001DFABDE8084006212820FFF717BA000034 +:1042500008B5FFF773FE00F067F800F03DF8FFF7D0 +:104260006BFEBDE8084000F05DB8000002684368DE +:104270001143016003B1184770470000143000F08B +:104280002FBA00004FF0FF33143000F029BA0000BD +:10429000383000F0A5BA00004FF0FF33383000F09E +:1042A0009FBA0000143000F0F5B900004FF0FF3164 +:1042B000143000F0EFB90000383000F04FBA0000C1 +:1042C0004FF0FF32383000F049BA0000012914BF26 +:1042D0006FF013000020704700F06CB8044B0360CF +:1042E0000023C0E90233436001230374704700BF19 +:1042F0003C4B000838B5C36904460D461BB9042180 +:104300000844FFF7B3FF294604F1140000F0A6F9B2 +:10431000002806DA201D4FF40061BDE83840FFF7A1 +:10432000A5BF38BD00F00EB80023054A1946013379 +:10433000102BC2E9001102F10802F8D1704700BF4A +:10434000783A00204FF0E023044A5A6100229A6133 +:1043500007221A6108210B20FFF7A6B93F190100B7 +:1043600008B5302383F31188FFF760FA002383F345 +:10437000118808BD08B5FFF7F3FFBDE80840FFF757 +:1043800053B90000026843681143016003B1184744 +:1043900070470000024A136843F0C003136070477F +:1043A00000380140024A136843F0C00313607047AD +:1043B0000044004037B51D4C1D4D2046FFF78EFFD1 +:1043C000009404F114001B490023202200F038F966 +:1043D0002022009404F13800174B184900F0B2F97C +:1043E000174BC4E91735174C0C212520FFF746F968 +:1043F0002046FFF773FF04F11400134900940023D3 +:10440000202200F01DF904F13800104B10490094EF +:10441000202200F097F90F4B0C212620C4E9173514 +:1044200003B0BDE83040FFF729B900BFF83A0020DB +:1044300000512502D03B002095430008103C00208D +:1044400000380140643B0020F03B0020A5430008F9 +:10445000303C0020004400402DE9F047C66D37682D +:10446000F46934622107054619D014F0080118BF19 +:104470004FF48071E20748BF41F02001A30748BF15 +:1044800041F04001600748BF41F08001302383F3D1 +:104490001188281DFFF776FF002383F31188E205BA +:1044A0000AD5302383F311884FF48061281DFFF76C +:1044B00069FF002383F311884FF030094FF0000AA1 +:1044C00014F0200838D13B0616D54FF0300905F11D +:1044D000380A200610D589F31188504600F066F995 +:1044E000002836DA0821281DFFF74CFF27F080034B +:1044F0003360002383F31188790614D5620612D540 +:10450000302383F31188D5E913239A4208D12B6C09 +:1045100033B11021281D27F04007FFF733FF376024 +:10452000002383F31188E30619D5AA6E1369B3B18A +:10453000BDE8F0475069184789F31188B38C95F8A6 +:10454000641028461940FFF7D5FE8AF31188F469F4 +:10455000B6E780B2308588F31188F469B9E7BDE821 +:10456000F087000008B50348FFF776FFBDE8084074 +:10457000FFF75AB8F83A002008B50348FFF76CFF78 +:10458000BDE80840FFF750B8643B0020F8B5154679 +:1045900082680669AA420B46816938BF8568761A27 +:1045A000B54204460BD218462A46FCF7B1FEA36971 +:1045B0002B44A361A3685B1BA3602846F8BD0CD9FC +:1045C00018463246FCF7A4FEAF1BE1683A46304479 +:1045D000FCF79EFEE3683B44EBE718462A46FCF7EF +:1045E00097FEE368E5E7000083689342F7B5154658 +:1045F000044638BF8568D0E90460361AB5420BD24C +:104600002A46FCF785FE63692B446361A36828464C +:104610005B1BA36003B0F0BD0DD932460191FCF7DE +:1046200077FE0199E068AF1B3A463144FCF770FE13 +:10463000E3683B44E9E72A46FCF76AFEE368E4E7FF +:1046400010B50A440024C361029B8460C0E90000E5 +:10465000C0E90511C1600261036210BD08B5D0E96F +:104660000532934201D1826882B982680132826048 +:104670005A1C42611970D0E904329A4224BFC368BF +:1046800043610021FFF748F9002008BD4FF0FF30DB +:10469000FBE7000070B5302304460E4683F3118813 +:1046A000A568A5B1A368A269013BA360531CA361DF +:1046B00015782269934224BFE368A361E3690BB1D3 +:1046C00020469847002383F31188284607E03146A7 +:1046D0002046FFF711F90028E2DA85F3118870BD52 +:1046E0002DE9F74F04460E4617469846D0F81C9021 +:1046F0004FF0300A8AF311884FF0000B154665B170 +:104700002A4631462046FFF741FF034660B941463D +:104710002046FFF7F1F80028F1D0002383F3118839 +:10472000781B03B0BDE8F08FB9F1000F03D0019002 +:104730002046C847019B8BF31188ED1A1E448AF36B +:104740001188DCE7C0E90511C160C3611144009B19 +:104750008260C0E90000016103627047F8B5044659 +:104760000D461646302383F31188A768A7B1A368C6 +:10477000013BA36063695A1C62611D70D4E9043275 +:104780009A4224BFE3686361E3690BB1204698470E +:10479000002080F3118807E031462046FFF7ACF88F +:1047A0000028E2DA87F31188F8BD0000D0E905237C +:1047B0009A4210B501D182687AB98268013282606A +:1047C0005A1C82611C7803699A4224BFC3688361C2 +:1047D0000021FFF7A1F8204610BD4FF0FF30FBE7A6 +:1047E0002DE9F74F04460E4617469846D0F81C9020 +:1047F0004FF0300A8AF311884FF0000B154665B16F +:104800002A4631462046FFF7EFFE034660B941468F +:104810002046FFF771F80028F1D0002383F31188B8 +:10482000781B03B0BDE8F08FB9F1000F03D0019001 +:104830002046C847019B8BF31188ED1A1E448AF36A +:104840001188DCE70B460146184600F02DB8000041 +:1048500000F040B8012838BF012010B504462046BA +:1048600000F030F830B900F007F808B900F00CF8A3 +:104870008047F4E710BD0000024B1868BFF35B8F60 +:10488000704700BF503C002008B5062000F084F8B7 +:104890000120FFF7ABF80000024B0A4601461868FA +:1048A000FFF798B91811002010B5054C13462CB12C +:1048B0000A4601460220AFF3008010BD2046FCE707 +:1048C00000000000024B01461868FFF787B900BFDF +:1048D00018110020024B01461868FFF783B900BF8A +:1048E0001811002010B501390244904201D1002076 +:1048F00005E0037811F8014FA34201D0181B10BD49 +:104900000130F2E72DE9F041A3B1C91A177801444B +:10491000044603F1FF3C8C42204601D9002009E007 +:104920000578BD4204F10104F5D10CEB0405D6185D +:10493000A54201D1BDE8F08115F8018D16F801ED11 +:10494000F045F5D0E7E700001F2938B504460D46CD +:1049500004D9162303604FF0FF3038BD426C12B10A +:1049600052F821304BB9204600F030F82A46014673 +:104970002046BDE8384000F017B8012B0AD0591C7A +:1049800003D1162303600120E7E7002442F8254005 +:10499000284698470020E0E7024B01461868FFF7D9 +:1049A000D3BF00BF1811002038B5074D00230446BF +:1049B000084611462B60FFF71DF8431C02D12B68F7 +:1049C00003B1236038BD00BF543C0020FFF70CB892 +:1049D000034611F8012B03F8012B002AF9D1704787 +:1049E0006F72672E6172647570696C6F742E6633B6 +:1049F00030332D4D313030373000000040A2E4F12B +:104A0000646891060041A3E5F26569920700000021 +:104A10004261642043414E496661636520696E646A +:104A200065782E00800000000080000000008000FB +:104A30000000000000000000351B000819230008DA +:104A400079220008451B0008791B0008751D000825 +:104A5000491B0008591B00084D1B0008551B000886 +:104A6000511B00089D1C00085D1B0008E52500087F +:104A70006D1B0008711C000863300000784A0008B4 +:104A800078380020483A00206D61696E0069646CD6 +:104A900065000000A001A82A00000000FAAABEAA32 +:104AA00050001424EFFF0000007700007097090009 +:104AB0000100000000000000AAAAAAAA010000004C +:104AC000FFFF0000000000000000000000000000E8 +:104AD00000000000AAAAAAAA00000000FFFF000030 +:104AE00000000000000000000000000000000000C6 +:104AF000AAAAAAAA00000000FFFF00000000000010 +:104B0000000000000000000000000000AAAAAAAAFD +:104B100000000000FFFF0000000000000000000097 +:104B20000000000000000000AAAAAAAA00000000DD +:104B3000FFFF000000000000000000000000000077 +:104B40009942000885420008C1420008AD420008B1 +:104B5000B9420008A5420008914200087D420008C1 +:104B6000CD4200087CB6FF7F01000000000000007D +:104B7000EC030000000000000098030000000000AB +:104B8000FE2A0100D20400001C11002000000000D9 +:104B90000000000000000000000000000000000015 +:104BA0000000000000000000000000000000000005 +:104BB00000000000000000000000000000000000F5 +:104BC00000000000000000000000000000000000E5 +:104BD00000000000000000000000000000000000D5 +:0C4BE000000000000000000000000000C9 :00000001FF diff --git a/Tools/bootloaders/f303-MatekGPS_bl.bin b/Tools/bootloaders/f303-MatekGPS_bl.bin index 1af00725c6cfbe..b011dbc79a2cee 100755 Binary files a/Tools/bootloaders/f303-MatekGPS_bl.bin and b/Tools/bootloaders/f303-MatekGPS_bl.bin differ diff --git a/Tools/bootloaders/f303-MatekGPS_bl.elf b/Tools/bootloaders/f303-MatekGPS_bl.elf index 299e90cccb15de..dd3736d8abc76a 100755 Binary files a/Tools/bootloaders/f303-MatekGPS_bl.elf and b/Tools/bootloaders/f303-MatekGPS_bl.elf differ diff --git a/Tools/bootloaders/f303-MatekGPS_bl.hex b/Tools/bootloaders/f303-MatekGPS_bl.hex index 50f32ca71bc511..fa31d391a6aafc 100644 --- a/Tools/bootloaders/f303-MatekGPS_bl.hex +++ b/Tools/bootloaders/f303-MatekGPS_bl.hex @@ -1,980 +1,1218 @@ :020000040800F2 -:1000000000090020A5040008E1140008611400089C -:10001000B9140008611400088D140008A704000832 -:10002000A7040008A7040008A704000881350008F9 -:10003000A7040008A7040008A7040008B93A0008AC -:10004000A7040008A7040008A7040008A7040008E4 -:10005000A7040008A7040008513800087D380008EC -:10006000A9380008D538000801390008A70400089D -:10007000A7040008A7040008A7040008A7040008B4 -:10008000A7040008A7040008A70400082924000802 -:1000900095240008E92400083D2500082D390008B2 -:1000A000A7040008A7040008A7040008A704000884 -:1000B000A7040008A7040008A7040008A704000874 -:1000C000A7040008A7040008A7040008A704000864 -:1000D000A70400088129000895290008A704000842 -:1000E00095390008A7040008A7040008A704000821 -:1000F000A7040008A7040008A7040008A704000834 -:10010000A7040008A7040008A7040008A704000823 -:10011000A7040008A7040008A7040008A704000813 -:10012000A7040008A7040008A7040008A704000803 -:10013000A7040008A7040008A7040008A7040008F3 -:10014000A7040008A7040008A7040008A7040008E3 -:10015000A7040008A7040008A7040008A7040008D3 -:10016000A7040008A7040008A7040008A7040008C3 -:10017000A7040008A7040008A7040008A7040008B3 -:10018000A7040008A7040008A7040008A7040008A3 -:10019000A7040008A7040008A7040008A704000893 -:1001A00053B94AB9002908BF00281CBF4FF0FF31DE -:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA -:1001C00000F006F8DDF804E0DDE9022304B0704732 -:1001D0002DE9F047089D04468E46002B4DD18A42FA -:1001E000944669D9B2FA82F252B101FA02F3C2F12D -:1001F000200120FA01F10CFA02FC41EA030E9440BE -:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE -:1002100016E341EA034306FB07F199420AD91CEBB6 -:10022000030306F1FF3080F01F81994240F21C81E8 -:10023000023E63445B1AA4B2B3FBF8F008FB103330 -:1002400044EA034400FB07F7A7420AD91CEB040465 -:1002500000F1FF3380F00A81A74240F20781644435 -:10026000023840EA0640E41B00261DB1D4400023BA -:10027000C5E900433146BDE8F0878B4209D9002D1E -:1002800000F0EF800026C5E9000130463146BDE8A8 -:10029000F087B3FA83F6002E4AD18B4202D3824212 -:1002A00000F2F980841A61EB030301209E46002DC1 -:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 -:1002C000002A40F09280A1EB0C014FEA1C471FFA74 -:1002D0008CFE0126200CB1FBF7F307FB131140EA5B -:1002E00001410EFB03F0884208D91CEB010103F128 -:1002F000FF3802D2884200F2CB804346091AA4B2EA -:10030000B1FBF7F007FB101144EA01440EFB00FEBD -:10031000A64508D91CEB040400F1FF3102D2A64522 -:1003200000F2BB800846A4EB0E0440EA03409CE7C1 -:10033000C6F12007B34022FA07FC4CEA030C20FA6E -:1003400007F401FA06F31C43F9404FEA1C4900FA8E -:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B -:1003600040EA014108FB0EF0884202FA06F20BD97E -:100370001CEB010108F1FF3A80F08880884240F2CE -:100380008580A8F102086144091AA4B2B1FBF9F012 -:1003900009FB101144EA014100FB0EFE8E4508D90D -:1003A0001CEB010100F1FF346CD28E456AD9023892 -:1003B000614440EA0840A0FB0294A1EB0E01A14277 -:1003C000C846A64656D353D05DB1B3EB080261EBE5 -:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF -:1003E000007100263146BDE8F087C2F12003D840F5 -:1003F0000CFA02FC21FA03F3914001434FEA1C4737 -:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 -:10041000064300FB0EF69E4204FA02F408D91CEBD8 -:10042000030300F1FF382FD29E422DD902386344D6 -:100430009B1B89B2B3FBF7F607FB163341EA034176 -:1004400006FB0EF38B4208D91CEB010106F1FF38C5 -:1004500016D28B4214D9023E6144C91A46EA0046BC -:1004600038E72E46284605E70646E3E61846F8E64E -:100470004B45A9D2B9EB020864EB0C0E0138A3E797 -:100480004646EAE7204694E74046D1E7D0467BE778 -:10049000023B614432E7304609E76444023842E7F0 -:1004A000704700BF02E000F000F8FEE772B63A487D -:1004B00080F30888394880F3098839484EF6085196 -:1004C000CEF20001086040F20000CCF200004EF6CF -:1004D0003471CEF200010860BFF34F8FBFF36F8F0E -:1004E00040F20000C0F2F0004EF68851CEF200015A -:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 -:10050000100A4EF63C71CEF200010860062080F31E -:100510001488BFF36F8F03F0B3F803F08FF803F084 -:10052000C1F84FF055301F491B4A91423CBF41F87A -:10053000040BFAE71C49194A91423CBF41F8040BED -:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C -:1005500042F8040BF8E700201749184A91423CBFC3 -:1005600041F8040BFAE703F06DF803F0D7F8144CE8 -:10057000144DAC4203DA54F8041B8847F9E700F045 -:1005800041F8114C114DAC4203DA54F8041B884772 -:10059000F9E703F055B80000000900200011002021 -:1005A000000000080001002000090020F83C0008BD -:1005B00000110020201100202011002028260020FA -:1005C000A0010008A0010008A0010008A001000887 -:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F -:1005E000BDEC108ABDE8F08F002383F31188284604 -:1005F000A047002002F04CFDFEE702F0D1FC00DF36 -:10060000FEE700002DE9F04102F062FF074602F02C -:10061000ADFF054600283ED12B4B9F423BD0013316 -:100620009F423BD0294B27F0FF029A423AD1F8B2C1 -:1006300000F054FAA84642F2107400F059FC08B1D8 -:100640000024A04600F050FA064678B384BB464624 -:1006500035B11F4B9F4203D002F080FF0024264695 -:10066000002002F03FFF1B4B1B6913F0400322D018 -:100670000EB100F031F800F05FFC00F031FE00F048 -:1006800031FF0546CCB100F02DFF401BA04214D92C -:1006900000F022F8F3E7A8460024CEE704464FF026 -:1006A0000108CAE780464FF47A74C6E70446CFE7EC -:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 -:1006C00002F0ECFCDEE700BF010007B0000008B05C -:1006D000263A09B00004004838B51D4A1D4B196878 -:1006E000013134D004339342F9D11B4C194DD4F865 -:1006F0000428AA422BD3194B9B6803F1006303F52E -:10070000D0439A4223D202F0FDFE02F00FFF0020F8 -:1007100000F000FE124B0220187000F037FE114B63 -:10072000DA690022DA61D96999699A619B6972B6BE -:100730004FF0E0232021C3F8085DD4F80038D4F846 -:10074000042881F311889D4683F30888104738BD3B -:100750002068000800680008006000080011002000 -:100760002011002000100240094A136849F2690074 -:1007700099B21B0C00FB01331360064B186844F25E -:10078000506182B2000C01FB0200186080B2704719 -:100790001C1100201811002010B500211022044661 -:1007A00000F00EFE034B03CB206061601868A06070 -:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 -:1007C00000F090FEAB6840F2ED22C31A934232D99A -:1007D00006AFA8602B4628220021384601F05EFBB8 -:1007E00005F10E0000F0E4FD002604465FFA80F9F2 -:1007F00005F10E08F3B2F100994501F1280107D97E -:1008000008EB06030822384601F048FB0136F1E701 -:1008100008230122CDE9023205340C4B0193A4B226 -:1008200030230093CDE9047405A3D3E90023297B89 -:10083000074801F04BF93BB0BDE8F083AFF300800F -:1008400078F6339F93CACD8D682100207521002052 -:100850003C21002070B50D4614461E4601F0CCF830 -:1008600050B9022E10D1012C0ED112A3D3E90023CE -:10087000C5E90023012007E0282C10D005D8012C61 -:1008800009D0052C0FD0002070BD302CFBD10BA35C -:10089000D3E90023ECE70BA3D3E90023E8E70BA39C -:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B -:1008B000AFF30080401DA12026812A0B78F6339FDC -:1008C00093CACD8D9E6AC421818A46EE26417272FA -:1008D000DF25D7B7F017304A39059E5613B50446C1 -:1008E0002346084620220021019001F0D7FA227900 -:1008F0000198032A234628BF032203F8042F20214E -:10090000022201F0CBFA62790198072A234628BF18 -:10091000072203F8052F2221032201F0BFFAA27952 -:100920000198072A234628BF072203F8062F25210E -:10093000032201F0B3FA019804F1080310222821E0 -:1009400001F0ACFA382002B010BD00002DE9F04FE4 -:10095000ADF5017D21AD0EAE40F2751280460F4619 -:1009600022A80021296000F02BFD482200213046FA -:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 -:10098000F2F0186093E80700012386E807000DF1F4 -:100990005A003382FFF700FF4EF60343338407AB60 -:1009A00018464D4903F0C2F81B22306429463046F0 -:1009B00086F83C20FFF792FF12AB0446014608225E -:1009C000284601F06BFA0822A1180DF149032846C8 -:1009D00001F064FA0DF14A03082204F110012846DF -:1009E00001F05CFA13AB202204F11801284601F053 -:1009F00055FA14AB402204F13801284601F04EFAB2 -:100A000016AB082204F17801284601F047FA0DF1EF -:100A10005903082204F18001284601F03FFA04F14D -:100A2000880A0DF15A0904F5847B4B465146082289 -:100A300028460AF1080A01F031FAD34509F1010903 -:100A4000F3D11BAB08225946284601F027FA04F5DA -:100A500088744FF0000996F834304B450AD9B36BCF -:100A600021464B440822284601F018FA083409F1BF -:100A70000109F0E74FF0000996F83C304B4504EBD4 -:100A8000C90108D9336C08224B44284601F006FA04 -:100A900009F10109F0E700230393BB7E02930731BC -:100AA00007F119030193C1F3CF010123CDE90451EB -:100AB0000093F97E05A3D3E90023404601F006F830 -:100AC0000DF5017DBDE8F08FAFF300809E6AC42173 -:100AD000818A46EE241100203C3B0008014B18702F -:100AE000704700BF30110020F0B5334B1C7B85B040 -:100AF00034B1324B0E221A810024204605B0F0BDDD -:100B00002F4A1068516802AB03C308232D492E48B1 -:100B10000DEB030202F0E8FF054630B9274B2B48E6 -:100B20000A221A8100F098FCE6E70169B1F5663FF8 -:100B300006D9224B26480B221A8100F08DFCDCE7F7 -:100B4000438BB3F57B7F09D01C4A22480C211181CD -:100B50004FF47B72194600F07FFCCEE71E4A024438 -:100B600002F11003994204D2144B1C4810221A813E -:100B7000E3E710398E1A2046134900F0B7FC3246DD -:100B8000074605F11801204600F0B0FCAB689F4213 -:100B900002D1EB6898420AD0084B0D221A810090CE -:100BA000D5E902123B460E4800F056FCA4E70D487A -:100BB00000F052FC0124A0E768210020241100204D -:100BC000E93B0008DC97030000680008583B000878 -:100BD000643B0008763B00080898FFF7943B000848 -:100BE000B13B0008DA3B00082DE9F04FADB006AF8D -:100BF00080460C4600F000FF054600285AD1237EAF -:100C0000022B1BD1E38A012B18D100F06BFC0646A6 -:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C -:100C2000F0F206F5167602FB103316FA83F3C9F8D4 -:100C30000030E37E33B9A84B00221A709C37BD46C2 -:100C4000BDE8F08FA38AEEB2013BB34205F1010586 -:100C50000BD93B1D1E44E90000960023082201F039 -:100C6000F801204600F0DEFFECE707F11400FFF783 -:100C700093FD324607F11401381D02F025FF0028CC -:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 -:100C90001673C9F80030D1E7FB1CF87001460093C9 -:100CA00007220346204600F0BDFFF978404600F0D9 -:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 -:100CC000052BBBD1BFF34F8F8449854BCA6802F413 -:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 -:100CE000ACD1637E7F4D01336A7BDBB29342E94630 -:100CF00003D1E27E2B7B9A4265D0CD469EE721460A -:100D00004046FFF723FE99E7A38A013B9BB2C92B1C -:100D100094D8744D2E7B26BB05F10C03009308225A -:100D200033463146204600F07DFF731CF2B2D900F5 -:100D30001E46A38A013B9A4205DA0E322A440092EB -:100D400000230822EEE700230022C5E90023002348 -:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 -:100D60002B73002507F114093B1D0822294648462C -:100D7000C7E90155FD6001F091F83B7A05F1010AE0 -:100D8000AB424FEACA0608D9FB6808222B44314619 -:100D9000484601F083F85546EFE7C6F3CF06E17EFB -:100DA000CDE9049600230393A37E029319342823EC -:100DB0000093019446A3D3E90023404600F086FE49 -:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 -:100DD00014801022009341460123204600F022FF98 -:100DE000A68A023EB6B2F31C9B109B000733DB08B9 -:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 -:100E0000C801B34201F110010AD20AEB08030093B2 -:100E100008220023204600F005FF08F10108ECE756 -:100E200095F8D70000F080FAD5F8D83004461BB901 -:100E300095F8D70000F088FAD5F8D83033449C42B2 -:100E400004D295F8D700013000F07EFA4FEA960BF5 -:100E50004FF000081FFA88F18B45D5E9003209D917 -:100E60000AEB880103EB8800012200F0B1FA08F1D7 -:100E70000108EFE7F31842F10002C5E90032D5F8A6 -:100E8000D83095F8D70006EB0308C5F8D88000F0F5 -:100E90004BFA804509D395F8D730D5F8D8000133FF -:100EA000001B85F8D730C5F8D800FF2E08D80023DE -:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D -:100EC0002B68094A9B0A013313810023AB6014E7A6 -:100ED00026417272DF25D7B73521002000ED00E0F2 -:100EE0000400FA0568210020241100203821002088 -:100EF00010B54FF000540C4B22689A4211D10B4BA5 -:100F0000627D1A700A48237D03730A49C9220E3094 -:100F100000F044FAE0220021204600F051FA0120BE -:100F200010BD0020FCE700BF9AAD44C53011002081 -:100F300068210020160000202DE9FF41434C0223C8 -:100F400063710023029324250A23581EB5FBF3F690 -:100F50007343D3F12402C1B23ED002280346F4D138 -:100F60009DF80B303A493B485A1E9DF80A30013B28 -:100F70001B0443EA0253BDF80820013A13434B60B7 -:100F800001F044FD00230193334B3449009334486E -:100F9000344B4FF4805200F001FD334B197811B1FE -:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D -:100FB0004FF4C873B0FBF3F202FB130305F5167090 -:100FC00010FA83F0294B186002F0D0FA08B10F2311 -:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF -:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA -:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F -:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 -:10101000CDB2591E0F2916D86A1E072A8CBF00228E -:101020000122591901FB06601149B1FBF0F1114889 -:10103000814295D1002A93D0ADF808608DF80A302E -:101040008DF80B508CE71346EBE700BF241100200E -:1010500010110020802200205508000834110020C3 -:101060003C210020E90B000830110020382100202D -:101070000051250240420F002DE9F04F90A7D7E91B -:1010800000670FF24429D9E90089874D93B0DFF852 -:1010900040B2864C284600F07DFD0DF1300A0790E5 -:1010A00070B310220021504600F08AF9079B197B8B -:1010B0004FF0000261F303028DF830205868996800 -:1010C0000EAA03C21B680D9A63F31C029DF8303010 -:1010D0000D9243F020038DF830300023524619461C -:1010E000584601F0A3FC079028B9284600F056FDA9 -:1010F000079B2370CEE72378072B3CD8013323705E -:1011000018220021504600F05BF9DFF8C4B100233B -:1011100019465246584601F0B1FC014678BB1022F0 -:1011200008A800F04DF94FF0904209AC536983F0E4 -:101130001003536100F0D8F90B4612A9024611E9D9 -:10114000030084E803009DF83410C1F3030089060E -:101150004CBF0E9CBDF838408DF82C0046BFC4F340 -:101160001C0444F00044C4F30A0408A92846089467 -:1011700000F0DCFECBE7284600F010FDC0E7284673 -:1011800000F03AFC0446002848D1DFF848B100F0EE -:10119000A9F9DBF80030984240D300F0A3F907909A -:1011A000FFF7E2FA079A8DF8204003464FF4C87023 -:1011B00002F51672B3FBF0F101FB103312FA83F360 -:1011C000CBF80030DFF810B19BF8001011B9012303 -:1011D0008DF8203050460791FFF7DEFA0799C1F1EC -:1011E0001004E4B2062C28BF0624224651440DF117 -:1011F000210000F0D3F808AB0393182302930134C5 -:101200002B4B0193E4B20123009304943B463246F6 -:10121000284600F0F3FB00238BF8003000F062F961 -:10122000244A254C1368C31AB3F57A7F31D3106072 -:1012300000F05AF902460B46284600F0B9FC284651 -:1012400000F0DAFB28B3237BDFF890B0002B14BF4B -:10125000032302238BF8053000F044F94FF47A732E -:101260005146B0FBF3F0CBF800005846FFF736FBD1 -:10127000182307300293114B0193C0F3CF0040F2C3 -:101280005513CDE903A0009342464B46284600F093 -:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 -:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 -:1012B0003421002048220020682100204C220020F8 -:1012C000401DA12026812A0BF1C6A7C1D068080FB6 -:1012D0008022002038210020352100202411002008 -:1012E00070B501F0B5FF094E094D30800024286823 -:1012F0003388834208D901F0A7FF2B6804440133E7 -:10130000B4F5D04F2B60F2D370BD00BF7C2200201B -:101310005022002002F03AB800F10060920000F57F -:10132000D04001F0D5BF0000054B1A68054B1B8863 -:101330009B1A834202D9104401F086BF00207047F7 -:10134000502200207C22002038B5074D0446286832 -:10135000204401F07FFF28B928682044BDE83840C8 -:1013600001F08ABF38BD00BF50220020064991F825 -:10137000243033B10023086A81F824300822FFF7B3 -:10138000CBBF0120704700BF54220020022802BFBB -:101390004FF090434FF480129A61704710B50023CC -:1013A000934203D0CC5CC4540133F9E710BD000074 -:1013B00003460246D01A12F9011B0029FAD17047E0 -:1013C00002440346934202D003F8011BFAE7704738 -:1013D0002DE9F8431F4D144695F82420074688460A -:1013E00052BBDFF870909CB395F824302BB92022C3 -:1013F000FF2148462F62FFF7E3FF95F82400C0F174 -:101400000802A24228BF2246D6B24146920005EB0E -:101410008000FFF7C3FF95F82430A41B1E44F6B2EA -:10142000082E17449044E4B285F82460DBD1FFF71E -:101430009DFF0028D7D108E02B6A03EB820383428B -:10144000CFD0FFF793FF0028CBD10020BDE8F88371 -:101450000120FBE7542200200FB4002004B07047A5 -:1014600000B59BB0EFF3098168226846FFF796FF4D -:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E -:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D -:10149000EFF3098168226846FFF780FFEFF30583C9 -:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF -:1014B000FEE700BF00ED00E000B59BB0EFF309814F -:1014C00068226846FFF76AFFEFF30583034B5A6B08 -:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 -:1014E000FEE7000001F08EBF01F064BF30B5094D8A -:1014F0000A4491420DD011F8013B5840082340F3B3 -:101500000004013B2C4013F0FF0384EA5000F6D1A5 -:10151000EFE730BD2083B8ED2DE9F041C56915B97D -:10152000C161BDE8F0814B6823F06047C3F38A4690 -:101530004FEAD37EC3F3807816EA230638BF3E46CF -:10154000AC462B465A68BEEBD27F22F060440AD0EC -:10155000002A18DAA40CB44217D19D420FD10D60B5 -:10156000DEE71346EEE7A74207D102F08044C2F35C -:10157000807242450BD054B1EFE708D2EDE7CCF8CA -:1015800000100B60CDE7B44201D0B442E5D81A6830 -:101590009C46002AE5D11960C3E700002DE9F04719 -:1015A000089D01F007044FEAD508224405F007051D -:1015B00000EBD1004FF47F49944201D1BDE8F087A0 -:1015C00004F0070705F0070A57453E4638BF564660 -:1015D000C6F10806111B8E4228BF0E46E10808EB33 -:1015E000D50E415C13F80EC0B94029FA06F721FA6E -:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 -:10160000010C03F80EC034443544D5E780EA0120CC -:10161000082341F2210201B24000002980B203F107 -:10162000FF33B8BF504013F0FF03F4D17047000000 -:1016300038B50C468D18A54200D138BD14F8011BF1 -:10164000FFF7E4FFF7E7000002684AB113680360A0 -:10165000C388018901339BB29942C38038BF03819B -:101660001046704770B588B0202204460D46684683 -:101670000021FFF7A5FE20460495FFF7E5FF02468F -:1016800058B16B46054608AE1C4603CCB4422860F0 -:101690006960234605F10805F6D1104608B070BD13 -:1016A000082817D909280CD00A280CD00B280CD0F0 -:1016B0000C280CD00D280CD00E2814BF4020302050 -:1016C00070470C2070471020704714207047182076 -:1016D0007047202070470000082817D90C280CD923 -:1016E00010280CD914280CD918280CD920280CD96A -:1016F00030288CBF0F200E207047092070470A2029 -:1017000070470B2070470C2070470D207047000079 -:1017100010B54B6823B9CA8A63F30902CA8210BDA7 -:10172000C4681A681C60C360438A013B43824A60F4 -:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 -:1017400009010629814692460B4630D00020AAB2F4 -:1017500007F119049EB2052E1FFA80F80FD89045A4 -:1017600003F1010306D3FB8A0A4462F30903FB82F7 -:1017700001201AE01AF80060E6540130EAE79045CB -:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 -:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 -:1017A000044638B978606FF00200BDE8F88F4FF05A -:1017B0000008E6E7002606607860ADB24FF0000B47 -:1017C000454510D90AEB0803221D13F8011B91555A -:1017D000B1B208F101081B291FFA88F82BD0454542 -:1017E00006F10106F1D8FB8AC3F30902154465F33B -:1017F0000903BCE7013292B21C462368002BF9D1E1 -:10180000AB1F0B441C21B3FBF1F301339BB29A4293 -:10181000D3D2BBF1000FD0D14846FFF715FF20B956 -:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 -:1018300020600446C1E74545D5D94846FFF704FF77 -:1018400008B92060AFE7C0F800B000262060044669 -:10185000B6E700002DE9F04F2DED028B83B0CDE906 -:101860000013BDF83C5007469146002A00F09280D4 -:101870002DB10E9B002B00F08D80072D32D807F183 -:101880000C00FFF7E1FE044638B96FF00204204671 -:1018900003B0BDEC028BBDE8F08F14220021FFF7EE -:1018A0008FFD0E992A4604F10800FFF777FD681CAA -:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 -:1018C000013814FA80F003F01F0363F03F03037242 -:1018D000009B43F00041616038462146FFF71CFE43 -:1018E0000124D4E700F10C034FF0000808EE103A91 -:1018F0004FF0800A4646444618EE100AFFF7A4FE51 -:1019000083460028C1D014220021FFF759FDC6BB31 -:10191000019BABF8083002200E9B00F108029919D8 -:101920005BFA82F20130C0B2082801D0AE422AD35D -:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E -:1019400002F01F0242EA4812AE4208BF4FF0400ABE -:101950005BFA81F14AEA020A43F0004281F808A0EA -:101960008BF81000CBF8042059463846FFF7D4FD19 -:101970000134AE4224B288F001084FF0000ABBD116 -:1019800085E70020C8E711F801CB02F801CB01364A -:10199000B6B2C7E76FF0010479E70000F8B5154665 -:1019A0000E462822002104461F46FFF709FD069B2C -:1019B0006360B5F5001F079BA76034BF6A094FF647 -:1019C000FF72236204F10C0097B200239A4205D8FB -:1019D0000023036027826382A382F8BD066001337F -:1019E00030462036F2E7000003781BB94BB2002BDB -:1019F000C8BF017070470000007870472DE9F74FAD -:101A0000DDF83C90BDF830500D9E9DF83840BDF893 -:101A10004070804692469B46B9F1000F01D1002FDD -:101A200051D11F2C4FD898F80000B0B9072F47D8D4 -:101A300035F0030347D13A4649464FF6FF70FFF7AA -:101A4000F7FD20F001002D02400445EA0464400C3B -:101A500044EA40244FF6FF7321E040EA0520072FB7 -:101A600040EA0464F6D900254FF6FF73C5F1200063 -:101A7000A5F120022AFA05F10BFA00F001432BFA36 -:101A800002F211431846C9B2FFF7C0FD0835402DD8 -:101A90000346EBD13A464946FFF7CAFD0346CDE976 -:101AA0000097324621464046FFF7D4FE3378013393 -:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B -:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 -:101AD00085B09246DDF848800F9D9DF840209DF826 -:101AE0004490BDF84C7006469B46B8F1000F01D1FA -:101AF000002F48D11F2A46D83378002B46D00C023D -:101B000044EA02649DF8381044EAC93444EA0144C6 -:101B10001C43072F44F0800432D900234FF6FF7294 -:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC -:101B300041EA0C012BFA00F00143C9B210460393AD -:101B4000FFF764FD039B0833402B0246E8D13A4679 -:101B50004146FFF76DFD0346CDE900872A46214641 -:101B60003046FFF777FEB9F1010F06D12B7801332C -:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 -:101B80004FF6FF73E8E76FF00100F6E76FF0030030 -:101B9000F3E70000C06900B104307047C3691A68F8 -:101BA000C261C2681A60C360438A013B43827047C6 -:101BB0002DE9F041D0F81880194E14461D464146D3 -:101BC000002709B9BDE8F081D1E90223A21A65EB2B -:101BD0000303964277EB03031ED283698B420DD138 -:101BE000FFF796FD83691B688361C3680B60438AB6 -:101BF000C1608169013B43828846E2E7FFF788FDC7 -:101C00000B68C8F80030C3680B60438AC160013BB1 -:101C10004382D8F80010D4E788460968D1E700BFAE -:101C200080841E002DE9F04F8BB00D46DDF85090FA -:101C300014469B468046002800F01981B9F1000F38 -:101C400000F01581531E3F2B00F21181012A03D1B0 -:101C5000BBF1000F40F00B810023CDE90833B8F849 -:101C60001430B5EBC30F4FEAC30703D300200BB00A -:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C -:101C8000FFB227461BB9D8F81030002B7AD02F2D81 -:101C90004ED8C5F13006B7424FF000032CBFF6B264 -:101CA0003E4600932946D8F8080008AB3246FFF7B5 -:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 -:101CC00003F10053063BDB000493D8F80C30039378 -:101CD0003021039B13B1BAF1000F2CD1D8F81000BA -:101CE00040B1BAF1000F05D0009608AB5246691A10 -:101CF000FFF754FC38B2002FB8D066070AD00AAB01 -:101D000003EBD401624211F8083C02F007021341D0 -:101D100001F8083C082C3CD9102C40F2B580202C4E -:101D200040F2B780BBF1000F00F09C80082334E044 -:101D3000BA460026C2E7049BE02B28BFE0230693A7 -:101D40000B44AB42059314D95A1B03980096924555 -:101D500034BF5246D2B2691A08AB04300792FFF77B -:101D60001DFC079A1644AAEB020A1544F6B25FFA64 -:101D70008AFA049B069A05999B1A0493039B1B6895 -:101D80000393A6E70093D8F8080008AB3A46294623 -:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F -:101DA000082C12D89DF82030621E23FA02F2D507C3 -:101DB00006D54FF0FF3202FA04F423438DF82030A9 -:101DC0009DF8203089F8003051E7102C12D8BDF86A -:101DD0002030621E23FA02F2D10706D54FF0FF32FF -:101DE00002FA04F42343ADF82030BDF82030A9F8FE -:101DF00000303CE7202C0FD80899631E21FA03F32A -:101E0000DA0705D54FF0FF3202FA04F40C430894C8 -:101E1000089BC9F800302AE7402C2BD0DDE9086583 -:101E2000611EC4F12102A4F1210326FA01F105FA91 -:101E300002F225FA03F311431943CB0712D501220D -:101E4000A4F12003C4F1200102FA03F322FA01F104 -:101E5000A240524243EA010363EB430332432B4364 -:101E6000CDE90823DDE90823C9E90023FFE66FF087 -:101E70000100FCE66FF00800F9E6082CA0D9102C50 -:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD -:101E900083E7BBF1000FBBD004237EE730B5012AF6 -:101EA000144638BF0124402C85B028BF40240025AB -:101EB000012ACDE9025518D81B788DF80830630740 -:101EC0000AD004AB03EBD405624215F8083C02F0DB -:101ED0000702934005F8083C009103462246002182 -:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 -:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D -:101F000000231B680293CDE90223D8E710B5CB6804 -:101F10001BB98B600B618B8210BDC4681A681C6092 -:101F2000C360438A013B4382CA60F0E72DE9F04F6A -:101F3000D1F8008093B018F0800FCDE90323C8F3E7 -:101F4000C01219BFC8F3C03BC8F306264FF0020BFE -:101F50001646B8F1000F04460D4680F2D18118F004 -:101F6000C043059340F0CC810B7B002B00F0C8816F -:101F7000BBF1020F03D00178B14240F0C48108F0F8 -:101F80007F0106916AB3C8F3074A2B44069A93F877 -:101F90000390760646EA0B4646EA82465FEAD91384 -:101FA00046EA0A06079300F0908000220023CDE95C -:101FB0000A23069B009367685B4652460AA920469F -:101FC000B84700287ED0A7699FB9314604F10C00BC -:101FD000FFF748FB0746E0B96FF0020013B0BDE819 -:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A -:101FF000CBE73B699E420DD03F68002FF9D13146B7 -:1020000004F10C00FFF72EFB07460028E4D0A3697B -:102010003B60A761DDE90A2300264FF6FF70C6F199 -:10202000200E22FA06F103FA0EFEA6F1200C23FA86 -:102030000CFC41EA0E0141EA0C01C9B208360992D2 -:102040000893FFF7E3FA402EDDE90832E7D1B882C2 -:10205000FB7D09F01F06C3F384039B1BD7E9022114 -:1020600098B2002BBCBF00F120031BB252EA010062 -:10207000C8F304680FD00398821A049860EB01013A -:10208000A74890424FF000028A4104D3079A002AE1 -:102090005BD0012B23DDFA7D4FEA890302F00302B6 -:1020A00003F07C031343FB7539462046FFF730FBF2 -:1020B000079BA3B9FB7DC3F38402013262F386035D -:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 -:1020D0000C0083E73B699E42BAD03F68F6E719F0EF -:1020E000400F32D0039BBB60049BFB601422002195 -:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 -:102100000C932B7BADF83EA0013BDBB2ADF83C302D -:10211000069B8DF8433094F824308DF840B083F05E -:1021200001038DF844308DF84160A3688DF842803A -:102130000AA920469847FB7DC3F38403013303F0CB -:102140001F039B02FB82002048E7FB7DC9F340127E -:10215000B2EBD31F40F0DA80C3F38403B34240F004 -:10216000D88007992B7B4FEA9912002934D0D207E7 -:1021700041D4032B40F2D080039BBB60049BFB60E7 -:102180002B7BAE1D033BDBB23246394604F10C001B -:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 -:1021A000FB7DC3F38403013303F01F039B02FB8217 -:1021B000032013E7AB883B832A7B033AB88AD2B269 -:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D -:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C -:1021E0003246394604F10C00FFF7A4FA0028D3DB8D -:1021F0002A7B013AE2E7F98AC1F30901013B05298B -:10220000DAB259D8281D002307F11A0C9A4208D9CE -:1022100010F801EB0CF801E0013101330629DBB2C3 -:10222000F4D103990A9104990B91934207F11A0191 -:102230000C9138BF043379680D9134BF55FA83F39C -:1022400000230E93FB8AADF83EA0C3F309031A44A2 -:10225000069B8DF8433094F82430ADF83C2083F091 -:1022600001038DF8443000238DF840B08DF84160B3 -:102270008DF842807B602A7BB88A013A291DFFF7DE -:10228000D7F93B8BB882834203D1A3680AA92046C1 -:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 -:1022A0008403013303F01F039B02FB823B8B9842A4 -:1022B00014BF1120002091E67B68002BB1D00620CE -:1022C00001E01C306346D3F800C0BCF1000FF8D128 -:1022D000091A081D05F1040C00EB030905989DF887 -:1022E000143001EB000EBEF11B0F9AD89A4298D918 -:1022F0001CF8013B09F8013B059B01330593EDE711 -:102300006FF009006AE66FF00A0067E66FF00D00F3 -:1023100064E66FF00E0061E66FF00F005EE600BF4E -:1023200080841E00F0B53D4D3D4FEB6943F00073D6 -:10233000EB61EB693B4B9B6AD3F800623E4046F091 -:102340000106C3F80062D3F800423C4044EA002092 -:1023500040F00100C3F80002002951D00020C3F86A -:102360001C020646C3F80402C3F80C02C3F81402A8 -:1023700003EBC00401300E28C4F84062C4F8446284 -:10238000F6D100274FF0010C9678148816F0010F53 -:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A -:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 -:1023B0000E0EC3F80CE2760742BFD3F81462064350 -:1023C000C3F8146203EBC4045668C4F8406296680C -:1023D000C4F84462D3F81C4201372043B942C3F821 -:1023E0001C0202F10C02CFD1D3F8002222F001022C -:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 -:102400000122C3F84012C3F84412C3F80412C3F8FF -:102410001412C3F80C22C3F81C22E5E70010024096 -:102420000000FFFF80220020184A916A08B58B68DF -:102430008B6013F0010104D013F00C0F18BF4FF4A0 -:102440008031D80506D513F4406F14BF41F4003134 -:1024500041F00201D80306D513F4402F14BF41F414 -:10246000802141F00401D3690BB10848984720232B -:1024700083F311880648002100F038FE002383F31F -:102480001188BDE8084001F0AFB800BF80220020ED -:102490008822002038B5124CA36ADD68AA0712D042 -:1024A0005A6922F002025A61A36913B10121204640 -:1024B0009847202383F311880A48002100F016FE74 -:1024C000002383F31188EB0606D5A36A1021D96097 -:1024D000236A0BB102489847BDE8384001F084B840 -:1024E000802200209022002038B5124CA36A1D697A -:1024F000AA0712D05A6922F010025A61A36913B1D7 -:10250000022120469847202383F311880A4800219E -:1025100000F0ECFD002383F31188EB0606D5A36AD7 -:1025200010211961236A0BB102489847BDE8384071 -:1025300001F05AB8802200209022002038B50F4CBC -:10254000A36A5D685D602A070AD5042222701A68B2 -:1025500022F002021A60636A13B1002120469847F4 -:102560006B0706D5A36A9969236A13B10348090466 -:102570009847BDE8384001F037B800BF80220020FE -:1025800010B50E4C204600F02FFA0D4BA3620B2124 -:10259000132000F009FA0B21142000F005FA0B219A -:1025A000152000F001FA0B21162000F0FDF90022A1 -:1025B000BDE8104011460E20FFF7B4BE8022002077 -:1025C000006400400F4B984210B5044605D10E4BF5 -:1025D000DA6942F00072DA61DB69A36A01221A60EB -:1025E000A36A5A68D20707D5626851681268D96130 -:1025F0001A60064A5A6110BD0121082000F06CFCE7 -:10260000EEE700BF80220020001002405B8701003F -:1026100003291AD8DFE801F0020A0F14836A9B68C5 -:1026200013F0E05F14BF012000207047836A9868B0 -:10263000C0F380607047836A9868C0F3C0607047D9 -:10264000836A9868C0F300707047002070470000EC -:1026500010B5032925D8DFE801F00225292D836A6A -:102660009968C1F30161183103EB011310788406F6 -:102670004CBF54689488C0F300114FEA410148BF31 -:1026800041EAC40100F00F004CBF41F0040141EAEF -:102690004451586041F001019068D2689860DA6056 -:1026A000196010BD836A03F5C073DFE7836A03F521 -:1026B000C873DBE7836A03F5D073D7E701290AD033 -:1026C00002290FD081B9836ADA68920701D11869AB -:1026D00003E001207047836AD86810F0030018BF38 -:1026E00001207047836AF2E70020704710B539B9BE -:1026F000836AD96889071BD11B699C0704D110BD67 -:10270000012915D00229FAD1816AD1F8C031D1F856 -:10271000C441D1F8C8011061D1F8CC01506120202A -:1027200008610869800717D1486940F0100012E07D -:10273000816AD1F8B031D1F8B441D1F8B801106153 -:10274000D1F8BC0150612020C860C868800703D15F -:10275000486940F002004861C3F34000C3F38001C0 -:10276000000140EA4111107920F03000014311715D -:1027700089064BBF91681189DB085B0D4CBF63F381 -:102780001C0163F30A01137948BF916064F30303EA -:1027900013714FEA14234FEA144458BF1181137088 -:1027A0005480ACE7026843681143016003B11847E5 -:1027B00070470000024A136843F0C003136070477B -:1027C00000380140024A136843F0C00313607047A9 -:1027D0000044004037B51D4C1D4D204600F006FB5F -:1027E000009404F114001B490023202200F0C8F9D2 -:1027F0002022009404F13800174B184900F042FAE7 -:10280000174BC4E91735174C0C21252000F0CCF8E4 -:10281000204600F0EBFA04F1140013490094002361 -:10282000202200F0ADF904F13800104B104900945B -:10283000202200F027FA0F4B0C212620C4E917357F -:1028400003B0BDE8304000F0AFB800BFAC220020BC -:102850000051250284230020B5270008C42300204E -:102860000038014018230020A4230020C5270008B9 -:10287000E4230020004400402DE9F047C66D37688E -:10288000F46934622107054618D014F0080118BF16 -:102890008021E20748BF41F02001A30748BF41F073 -:1028A0004001600748BF41F48071202383F3118801 -:1028B000281DFFF777FF002383F31188E2050AD56F -:1028C000202383F311884FF40071281DFFF76AFF5E -:1028D000002383F311884FF020094FF0000A14F011 -:1028E000200838D13B0616D54FF0200905F1380AEB -:1028F000200610D589F31188504600F0F7F900281A -:1029000036DA0821281DFFF74DFF27F080033360DA -:10291000002383F31188790614D5620612D520238B -:1029200083F31188D5E913239A4208D12B6C33B174 -:102930001021281D27F04007FFF734FF37600023E0 -:1029400083F31188E30619D5AA6E1369B3B1BDE804 -:10295000F0475069184789F31188B38C95F86410D3 -:102960002846194000F04EFA8AF31188F469B6E758 -:1029700080B2308588F31188F469B9E7BDE8F08743 -:1029800008B50348FFF778FFBDE8084000F02CBE0B -:10299000AC22002008B50348FFF76EFFBDE80840F1 -:1029A00000F022BE1823002000F1604303F56143CC -:1029B0000901C9B283F80013012200F01F039A40F5 -:1029C00043099B0003F1604303F56143C3F8802191 -:1029D0001A60704700F16040090100F56D40C9B20E -:1029E00001767047FFF7CCBD012300F10802C0E972 -:1029F0000222037000F110020023C0E90422C0E9A2 -:102A00000633C0E9083343607047000010B5202347 -:102A1000044683F31188022303704160FFF7D2FD5F -:102A200004232370002383F3118810BD2DE9F041A6 -:102A30001F4604460D461646202383F3118800F1F5 -:102A400008082378052B0DD029462046FFF7E0FD26 -:102A500040B1204632462946FFF7FAFD002080F3B8 -:102A6000118808E03946404600F024FB0028E8D0F1 -:102A7000002383F31188BDE8F08100002DE9F041C7 -:102A80001F4604460D461646202383F3118800F1A5 -:102A900010082378052B0DD029462046FFF70EFE9F -:102AA00040B1204632462946FFF720FE002080F341 -:102AB000118808E03946404600F0FCFA0028E8D0CA -:102AC000002383F31188BDE8F0810000F8B51546B6 -:102AD00082680669AA420B46816938BF8568761A02 -:102AE000B54204460BD218462A46FEF757FCA369A6 -:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 -:102B000018463246FEF74AFCAF1BE1683A463044AD -:102B1000FEF744FCE3683B44EBE718462A46FEF721 -:102B20003DFCE368E5E7000083689342F7B515468E -:102B3000044638BF8568D0E90460361AB5420BD226 -:102B40002A46FEF72BFC63692B446361A368284681 -:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 -:102B60001DFC0199E068AF1B3A463144FEF716FCA4 -:102B7000E3683B44E9E72A46FEF710FCE368E4E734 -:102B800010B50A440024C361029B8460C0E90000C0 -:102B9000C0E90511C1600261036210BD08B5D0E94A -:102BA0000532934201D1826882B982680132826023 -:102BB0005A1C42611970D0E904329A4224BFC3689A -:102BC0004361002100F086FA002008BD4FF0FF307D -:102BD000FBE7000070B5202304460E4683F31188FE -:102BE000A568A5B1A368A269013BA360531CA361BA -:102BF00015782269934224BFE368A361E3690BB1AE -:102C000020469847002383F31188284607E0314681 -:102C1000204600F04FFA0028E2DA85F3118870BDF3 -:102C20002DE9F74F04460E4617469846D0F81C90FB -:102C30004FF0200A8AF311884FF0000B154665B15A -:102C40002A4631462046FFF741FF034660B9414618 -:102C5000204600F02FFA0028F1D0002383F31188DA -:102C6000781B03B0BDE8F08FB9F1000F03D00190DD -:102C70002046C847019B8BF31188ED1A1E448AF346 -:102C80001188DCE7C0E90511C160C3611144009BF4 -:102C90008260C0E90000016103627047F8B5044634 -:102CA0000D461646202383F31188A768A7B1A368B1 -:102CB000013BA36063695A1C62611D70D4E9043250 -:102CC0009A4224BFE3686361E3690BB120469847E9 -:102CD000002080F3118807E03146204600F0EAF931 -:102CE0000028E2DA87F31188F8BD0000D0E9052357 -:102CF0009A4210B501D182687AB982680132826045 -:102D00005A1C82611C7803699A4224BFC36883619C -:102D1000002100F0DFF9204610BD4FF0FF30FBE747 -:102D20002DE9F74F04460E4617469846D0F81C90FA -:102D30004FF0200A8AF311884FF0000B154665B159 -:102D40002A4631462046FFF7EFFE034660B941466A -:102D5000204600F0AFF90028F1D0002383F311885A -:102D6000781B03B0BDE8F08FB9F1000F03D00190DC -:102D70002046C847019B8BF31188ED1A1E448AF345 -:102D80001188DCE7026843681143016003B118470A -:102D9000704700001430FFF743BF00004FF0FF33CF -:102DA0001430FFF73DBF00003830FFF7B9BF000017 -:102DB0004FF0FF333830FFF7B3BF00001430FFF798 -:102DC00009BF00004FF0FF311430FFF703BF0000D0 -:102DD0003830FFF763BF00004FF0FF323830FFF7A5 -:102DE0005DBF000000207047FFF7F4BC044B036098 -:102DF0000023C0E90233436001230374704700BF1E -:102E0000F43B000838B5C36904460D461BB90421DC -:102E10000844FFF7B7FF294604F11400FFF7BEFE90 -:102E2000002806DA201D4FF48061BDE83840FFF726 -:102E3000A9BF38BD024B0022C3E900339A60704736 -:102E400004240020002303748268054B1B689968E2 -:102E50009142FBD25A68036042601060586070472C -:102E60000424002008B5202383F31188037C032B5E -:102E700005D0042B0DD02BB983F3118808BD43690D -:102E800000221A604FF0FF334361FFF7DBFF00239E -:102E9000F2E7D0E9003213605A60F3E700230374CD -:102EA0008268054B1B6899689142FBD85A68036099 -:102EB000426010605860704704240020054B196977 -:102EC0000874186802681A6053601861012303745B -:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 -:102EE000044610D02B690A4A01A800F01BF92046BD -:102EF000FFF7E4FF049B13B101A800F02FF92B6941 -:102F0000586907B030BDFFF7D9FFF8E70424002067 -:102F1000652E000838B50C4D41612B6981689A68AF -:102F20009142044603D8BDE83840FFF78BBF1846EE -:102F3000FFF7B4FF01232C61014623742046BDE84E -:102F40003840FDF745BB00BF04240020044B1A683D -:102F50001B6990689B68984294BF002001207047CD -:102F60000424002010B5084C236820691A682260E8 -:102F70005460012223611A74FFF790FF0146206913 -:102F8000BDE81040FDF724BB0424002008B5FFF77E -:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 -:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 -:102FB00000F0AAF80A498022204600F031F80123E7 -:102FC00044F8180C037400F0EBFA002383F3118823 -:102FD00062B60448BDE8104000F042B82C2400203E -:102FE0001C3C00082C3C000800F0CAB8EFF311802C -:102FF00020B9EFF30583202282F311887047000087 -:1030000010B530B9EFF30584C4F3080414B180F3AC -:10301000118810BDFFF7BAFF84F31188F9E70000AB -:1030200082600222028270478368A3F17C0243F827 -:103030000C2C026943F83C2C426943F8382C074AAF -:1030400043F81C2CC26843F8102C022203F8082C09 -:10305000002203F8072CA3F118007047E9050008C7 -:1030600010B5202383F31188FFF7DEFF002104460B -:10307000FFF750FF002383F31188204610BD0000A6 -:10308000024B1B6958610F20FFF718BF0424002072 -:10309000202383F31188FFF7F3BF000008B5014632 -:1030A000202383F311880820FFF716FF002383F302 -:1030B000118808BD49B1064B42681B6918605A6007 -:1030C000136043600420FFF707BF4FF0FF307047E5 -:1030D000042400200368984206D01A6802605060F9 -:1030E00059611846FFF7AEBE7047000038B5044678 -:1030F0000D462068844200D138BD036823605C60BF -:103100004561FFF79FFEF4E7054B03F11402C3E9A5 -:1031100005224FF0FF32DA6100221A62704700BFC9 -:103120000424002010B5C0E903230B4A136A536935 -:103130009C68A1420CD85C68816003604460206098 -:1031400058609868411A99604FF0FF33D36110BD01 -:103150001B68091BECE700BF04240020036881689A -:103160009A680A449A60426813605A600023C360F8 -:10317000024B4FF0FF32DA61704700BF0424002099 -:1031800038B50F4C236A22460133236252F8143FAC -:10319000934206D09A68013A9A60202563699A683A -:1031A00002B138BDD3E9001001604860D968DA6027 -:1031B00082F311881869884785F31188EEE700BF0C -:1031C0000424002000207047FEE700007047000044 -:1031D0004FF0FF3070470000BFF34F8F024AD368B3 -:1031E000DB07FCD4704700BF0020024008B5074B46 -:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 -:10320000044A5A6002F188325A6008BD90250020B5 -:10321000002002402301674508B5054B1B7833B9F0 -:10322000FFF7DAFF034A136943F08003136108BD17 -:1032300090250020002002407F289ABF00F58030B2 -:10324000C0020020704700004FF40060704700008B -:10325000802070477F2808B50BD8FFF7EDFF00F5F9 -:1032600000630268013204D104308342F9D10120A5 -:1032700008BD0020FCE700007F2838B5044623D8AD -:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 -:10329000DA6002221A6105462046FFF7CDFF586129 -:1032A0001A6942F040021A614FF40061FFF794FF7F -:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 -:1032C000BDE83840FFF7C6BF002038BD00200240EF -:1032D00012F001032DE9F04704460E46154606D0CC -:1032E000244B40F2BD221A600020BDE8F08781180F -:1032F000214A914204D91F4A40F2C2211160F3E7EA -:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 -:1033100031464FF0010AA61B012D06EB0107884636 -:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E -:103330000030C9F810A03B800024FFF74DFFC9F80A -:1033400010403B8831F8022B9BB29A420FD0094BB8 -:1033500040F2D9221A60094B1F60094B1D60094BCE -:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 -:10337000D2E700BF8C250020000004088025002033 -:10338000882500208425002000200240084908B537 -:103390000B7828B11BB9FFF729FF01230B7008BD7B -:1033A000002BFCD0BDE808400870FFF735BF00BF18 -:1033B0009025002030B583B0FFF718FE0E4B0F4D5F -:1033C0001B6A2A684FF47A7101FB03F3934237BFFB -:1033D0000B4A0B49516814682B602EBFD1E900419C -:1033E000013151601C1941F100010191FFF708FE04 -:1033F0000199204603B030BD04240020942500200C -:103400009825002030B583B0FFF7F0FD114B124D29 -:103410001B6A2A684FF47A7101FB03F3934237BFAA -:103420000E4A0E49516814682B602EBFD1E9004145 -:10343000013151601C1941F100010191FFF7E0FDDC -:1034400001994FF47A7200232046FCF7A9FE03B0DD -:1034500030BD00BF042400209425002098250020C2 -:1034600010B50244064BD2B2904200D110BD441CAC -:1034700000B253F8200041F8040BE0B2F4E700BFBB -:10348000502800400F4B30B51C6A240407D41C6A36 -:1034900044F440741C621C6A44F400441C620A4CEC -:1034A000236843F4807323600244084BD2B29042F5 -:1034B00000D130BD441C00B251F8045B43F82050E9 -:1034C000E0B2F4E7001002400070004050280040D5 -:1034D00007B5012201A90020FFF7C2FF019803B040 -:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 -:1034F000012201A900200194FFF7C4FF02B010BD12 -:1035000070470000074B45F255521A6002225A607C -:1035100040F6FF729A604CF6CC421A60024B0122D0 -:103520001A70704700300040A4250020034B1B7820 -:103530001BB1034B4AF6AA221A607047A42500204B -:1035400000300040044B1A682AB902F1804202F5AB -:103550000432526A1A607047A0250020024B4FF0D7 -:1035600080725A62704700BF0010024008B5FFF732 -:10357000E9FF024B1868C0F3407008BDA025002089 -:10358000EFF3098305494A6B22F001024A6368336D -:1035900083F30988002383F31188704700EF00E06C -:1035A000202080F3118862B60C4B0D4AD96821F4B3 -:1035B000E0610904090C0A43DA60D3F8FC200949E8 -:1035C00042F08072C3F8FC200A6842F001020A60EF -:1035D0001022DA7783F82200704700BF00ED00E088 -:1035E0000003FA05001000E010B5202383F31188D2 -:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 -:103600000984683C4FF08073E361094BDB6B2366F0 -:1036100084F30988FFF79AFC10B1064BA36110BD33 -:10362000054BFBE783F31188F9E700BF00ED00E0ED -:1036300000EF00E0FB050008FE05000870470000F1 -:10364000FEE700000A4B0B480B4A90420BD30B4B92 -:10365000DA1C121AC11E22F003028B4238BF00226C -:103660000021FDF7ADBE53F8041B40F8041BECE746 -:10367000183D0008282600202826002028260020A3 -:10368000704700004B6843608B688360CB68C36001 -:103690000B6943614B6903628B6943620B6803608A -:1036A0007047000008B51B4B9A6A42F4FC029A620C -:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB -:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 -:1036D00002F11C0100F58060FFF7D4FF02F1380110 -:1036E00000F58060FFF7CEFF02F1540100F5806025 -:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D -:1037000002F18C0100F58060FFF7BCFFBDE80840C6 -:1037100000F05AB800100240443C000808B500F020 -:1037200093F9FFF741FCBDE80840FFF70BBF00002D -:103730007047000010B5214CA36A63F4FC03A36238 -:10374000A36A03F4FC03A3624FF0FF32A36A236968 -:1037500022612369002323612169E168E260E26854 -:10376000E360E268E269164942F08052E261E26990 -:103770000A6842F480720A60226A02F44072B2F56A -:10378000407F1EBF4FF4803222622362236A1B04F3 -:1037900007D4236A43F440732362236A43F400434B -:1037A000236200F031F9A369064A43F00103A361E3 -:1037B000A369136843F02003136010BD001002409A -:1037C00000700040000001401E4B1A6842F00102E8 -:1037D0001A601A689007FCD55A6822F003025A60F2 -:1037E0005A6812F00C02FBD1196801F0F901196056 -:1037F0005A601A6842F480321A601A689103FCD544 -:10380000114A5A604FF40452DA6230221A631A687D -:1038100042F080721A601A689201FCD50B4912229C -:103820000A600A6802F00702022AFAD15A6842F0D6 -:1038300002025A605A6802F00C02082AFAD11A6B86 -:103840001A6370470010024000241D00002002404F -:10385000084A08B5516913680B4003F0010353612E -:1038600023B1054A13680BB150689847BDE808407A -:10387000FFF7BABE00040140A8250020084A08B599 -:10388000516913680B4003F00203536123B1054AE9 -:1038900093680BB1D0689847BDE80840FFF7A4BE15 -:1038A00000040140A8250020084A08B551691368A2 -:1038B0000B4003F00403536123B1054A13690BB1B4 -:1038C00050699847BDE80840FFF78EBE00040140EC -:1038D000A8250020084A08B5516913680B4003F079 -:1038E0000803536123B1054A93690BB1D069984726 -:1038F000BDE80840FFF778BE00040140A82500207D -:10390000084A08B5516913680B4003F0100353616E -:1039100023B1054A136A0BB1506A9847BDE80840C5 -:10392000FFF762BE00040140A8250020174B10B528 -:103930005A691C68144004F478725A61A30604D5CD -:10394000134A936A0BB1D06A9847600604D5104AAF -:10395000136B0BB1506B9847210604D50C4A936B3F -:103960000BB1D06B9847E20504D5094A136C0BB133 -:10397000506C9847A30504D5054A936C0BB1D06CE5 -:103980009847BDE81040FFF72FBE00BF000401407C -:10399000A82500201A4B10B55A691C68144004F47D -:1039A0007C425A61620504D5164A136D0BB1506D05 -:1039B0009847230504D5134A936D0BB1D06D9847F2 -:1039C000E00404D50F4A136E0BB1506E9847A10462 -:1039D00004D50C4A936E0BB1D06E9847620404D59F -:1039E000084A136F0BB1506F9847230404D5054A5A -:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F -:103A000000040140A8250020062108B50846FEF75D -:103A1000CBFF06210720FEF7C7FF06210820FEF78F -:103A2000C3FF06210920FEF7BFFF06210A20FEF78B -:103A3000BBFF06211720FEF7B7FFBDE808400621AF -:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 -:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE -:103A6000084000F001B8000000F00EB80023054A3D -:103A700019460133102BC2E9001102F10802F8D1F6 -:103A8000704700BFA82500204FF0E023044A5A6188 -:103A900000229A6107221A6108210B20FEF79ABFC3 -:103AA0003F19010008B5202383F31188FFF79CFA22 -:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 -:103AC0000840FFF791BD000010B501390244904253 -:103AD00001D1002005E0037811F8014FA34201D085 -:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E -:103AF00017780144044603F1FF3C8C42204601D96B -:103B0000002009E00578BD4204F10104F5D10CEB79 -:103B10000405D618A54201D1BDE8F08115F8018D44 -:103B200016F801EDF045F5D0E7E70000034611F87F -:103B3000012B03F8012B002AF9D170476F72672E11 -:103B40006172647570696C6F742E663330335F4DCB -:103B50006174656B475053004E6F20617070207325 -:103B600069670A00426164206677206C656E67743D -:103B7000682025750A0042616420626F6172645F8B -:103B800069642025752073686F756C6420626520F8 -:103B900025750A004261642066772064657363724C -:103BA0006970746F72206C656E6774682025750A81 -:103BB00000426164206170702043524320307825B8 -:103BC0003038783A307825303878203078253038D9 -:103BD000783A3078253038780A00476F6F6420666D -:103BE00069726D776172650A0040A2E4F1646891C0 -:103BF0000600000000000000B12D00089D2D000807 -:103C0000D92D0008C52D0008D12D0008BD2D0008B4 -:103C1000A92D0008952D0008E52D00086D61696E3D -:103C20000000000069646C6500000000243C00088E -:103C3000482400208025002001000000A52F000856 -:103C400000000000A001A82A00000000FAAABEAAF5 -:103C500050001424EFFF0000007700007097090067 -:103C60000000A00000000000AAAAFAAA000050006C -:103C7000FFFF0000000000000077000000000000CF -:103C800000000000AAAAAAAA00000000FFFF00008E -:103C90000000000000000000000000000000000024 -:103CA000AAAAAAAA00000000FFFF0000000000006E -:103CB000000000000000000000000000AAAAAAAA5C -:103CC00000000000FFFF00000000000000000000F6 -:103CD0000000000000000000AAAAAAAA000000003C -:103CE000FFFF00000000000000000000E4C4FF7FB0 -:103CF0000100000000000000EC03000000000000D4 -:103D000000980300000000006400000000000000B4 -:083D1000FE2A0100D2040000AC +:1000000000090020B5040008D52500088D2500084A +:10001000B52500088D250008AD250008B7040008A7 +:10002000B7040008B7040008B7040008C935000881 +:10003000B7040008B7040008B70400087D430008AF +:10004000B7040008B7040008B7040008B7040008A4 +:10005000B7040008B7040008614000088D4000089C +:10006000B9400008E540000811410008B704000845 +:10007000B7040008B7040008B7040008B704000874 +:10008000B7040008B7040008B704000841250008B9 +:100090006D2500087D250008B70400083D410008D3 +:1000A000B7040008B7040008B7040008B704000844 +:1000B000B7040008B7040008B7040008B704000834 +:1000C000B7040008B7040008B7040008B704000824 +:1000D000B70400086D45000881450008B704000812 +:1000E000A5410008B7040008B7040008B7040008D9 +:1000F000B7040008B7040008B7040008B7040008F4 +:10010000B7040008B7040008B7040008B7040008E3 +:10011000B7040008B7040008B7040008B7040008D3 +:10012000B7040008B7040008B7040008B7040008C3 +:10013000B7040008B7040008B7040008B7040008B3 +:10014000B7040008B7040008B7040008B7040008A3 +:10015000B7040008B7040008B7040008B704000893 +:10016000B7040008B7040008B7040008B704000883 +:10017000B7040008B7040008B7040008B704000873 +:10018000B7040008B7040008B7040008B704000863 +:10019000B7040008B7040008B7040008B704000853 +:1001A000291200080000000000000000000000000C +:1001B00053B94AB9002908BF00281CBF4FF0FF31CE +:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA +:1001D00000F006F8DDF804E0DDE9022304B0704722 +:1001E0002DE9F047089D04468E46002B4DD18A42EA +:1001F000944669D9B2FA82F252B101FA02F3C2F11D +:10020000200120FA01F10CFA02FC41EA030E9440AD +:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE +:1002200016E341EA034306FB07F199420AD91CEBA6 +:10023000030306F1FF3080F01F81994240F21C81D8 +:10024000023E63445B1AA4B2B3FBF8F008FB103320 +:1002500044EA034400FB07F7A7420AD91CEB040455 +:1002600000F1FF3380F00A81A74240F20781644425 +:10027000023840EA0640E41B00261DB1D4400023AA +:10028000C5E900433146BDE8F0878B4209D9002D0E +:1002900000F0EF800026C5E9000130463146BDE898 +:1002A000F087B3FA83F6002E4AD18B4202D3824202 +:1002B00000F2F980841A61EB030301209E46002DB1 +:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 +:1002D000002A40F09280A1EB0C014FEA1C471FFA64 +:1002E0008CFE0126200CB1FBF7F307FB131140EA4B +:1002F00001410EFB03F0884208D91CEB010103F118 +:10030000FF3802D2884200F2CB804346091AA4B2D9 +:10031000B1FBF7F007FB101144EA01440EFB00FEAD +:10032000A64508D91CEB040400F1FF3102D2A64512 +:1003300000F2BB800846A4EB0E0440EA03409CE7B1 +:10034000C6F12007B34022FA07FC4CEA030C20FA5E +:1003500007F401FA06F31C43F9404FEA1C4900FA7E +:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB +:1003700040EA014108FB0EF0884202FA06F20BD96E +:100380001CEB010108F1FF3A80F08880884240F2BE +:100390008580A8F102086144091AA4B2B1FBF9F002 +:1003A00009FB101144EA014100FB0EFE8E4508D9FD +:1003B0001CEB010100F1FF346CD28E456AD9023882 +:1003C000614440EA0840A0FB0294A1EB0E01A14267 +:1003D000C846A64656D353D05DB1B3EB080261EBD5 +:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF +:1003F000007100263146BDE8F087C2F12003D840E5 +:100400000CFA02FC21FA03F3914001434FEA1C4726 +:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 +:10042000064300FB0EF69E4204FA02F408D91CEBC8 +:10043000030300F1FF382FD29E422DD902386344C6 +:100440009B1B89B2B3FBF7F607FB163341EA034166 +:1004500006FB0EF38B4208D91CEB010106F1FF38B5 +:1004600016D28B4214D9023E6144C91A46EA0046AC +:1004700038E72E46284605E70646E3E61846F8E63E +:100480004B45A9D2B9EB020864EB0C0E0138A3E787 +:100490004646EAE7204694E74046D1E7D0467BE768 +:1004A000023B614432E7304609E76444023842E7E0 +:1004B000704700BF02E000F000F8FEE772B6374870 +:1004C00080F30888364880F3098836483649086042 +:1004D00040F20000CCF200004EF63471CEF2000182 +:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 +:1004F000F0004EF68851CEF200010860BFF34F8F36 +:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 +:10051000CEF200010860062080F31488BFF36F8FCD +:1005200003F052FC03F0C6FC4FF055301F491B4A44 +:1005300091423CBF41F8040BFAE71D49184A914229 +:100540003CBF41F8040BFAE71A491B4A1B4B9A427D +:100550003EBF51F8040B42F8040BF8E7002018499D +:10056000184A91423CBF41F8040BFAE703F030FC13 +:1005700003F0DCFC144C154DAC4203DA54F8041BB8 +:100580008847F9E700F042F8114C124DAC4203DA0B +:1005900054F8041B8847F9E703F018BC0009002051 +:1005A000001100200000000808ED00E0000100201C +:1005B00000090020784B0008001100207C11002069 +:1005C00080110020583C0020A0010008A401000870 +:1005D000A4010008A40100082DE9F04F2DED108AB8 +:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 +:1005F000002383F311882846A047002003F06EF9FA +:10060000FEE703F0D1F800DFFEE70000F8B500F0E8 +:100610001DFE03F07DFB074603F0CCFB05460028DA +:1006200040D12C4B9F423DD001339F423DD02A4BBD +:1006300027F0FF029A423BD1F8B200F043FC2E466D +:1006400042F2107400F044FC08B10024264601F088 +:10065000B5F888B3032000F045F80024264635B1EC +:100660001E4B9F4203D003F09DFB00242646002032 +:1006700003F058FB1A4B1B6913F0400322D00EB154 +:1006800000F046F800F056FC00F0E2FD01F0AAFF91 +:100690000546CCB101F0A6FF401BA04214D900F0E2 +:1006A00037F8F3E72E460024CCE704460126C9E7D5 +:1006B00006464FF47A74C5E7002CD0D04FF47A7414 +:1006C0000126CCE71C46DDE700F07CFC012003F0AE +:1006D0000BF9DEE7010007B0000008B0263A09B0C8 +:1006E00000040048084B187003280CD8DFE800F01D +:1006F00008050208022000F007BE022000F0FCBD41 +:10070000024B00225A6070478011002084110020A3 +:1007100038B501F053F830B11F4B03221A701F4B4C +:1007200000225A6038BD1E4B1E4A19680131F9D0AB +:1007300004339342F9D11C4C194DD4F80428AA4231 +:10074000F0D31A4B9B6803F1006303F5D0439A4240 +:10075000E8D203F0FBFA03F00DFB002000F092FD5D +:100760000220FFF7BFFF124BDA690022DA61D96974 +:1007700099699A619B6972B64FF0E0233021C3F802 +:10078000085DD4F80038D4F8042881F311889D4618 +:1007900083F308881047C5E78011002084110020EA +:1007A00000680008206800080060000800110020B0 +:1007B00000100240094A136849F2690099B21B0C03 +:1007C00000FB01331360064B186844F2506182B29B +:1007D000000C01FB0200186080B270471411002069 +:1007E0001011002010B500211022044600F0A6FDD3 +:1007F000034B03CB206061601868A06010BD00BF90 +:10080000ACF7FF1F2DE9F041ADF54E7D0DF1340839 +:100810006CAC40F2751207460D460EA80021C8F8D0 +:10082000001000F08BFD4FF4C4720021204600F050 +:1008300085FD01F0D7FE274B4FF47A72B0FBF2F042 +:10084000186093E80700022384E807000DF5E970BB +:100850002382FFF7C7FF4EF603431F49238406A8F0 +:1008600004F0BAF81B2384F832310DF2E32206AB10 +:100870000DF1300C1E4603CE6645106051603346C4 +:1008800002F10802F6D13188B378937011802046C6 +:100890004146012200F09EFD00230393AB7E0293AC +:1008A00005F11903019380B20123CDE9048000937F +:1008B000E97E06A3D3E90023384602F05BFA0DF582 +:1008C0004E7DBDE8F08100BFAFF300809E6AC42179 +:1008D000818A46EE8C110020E84900082DE9F0419C +:1008E0002C4C237ADAB080460D465BBB27A92846FC +:1008F00000F080FE0746002842D19DF89D60C82E7A +:100900003ED801464FF4A662204600F017FD4FF492 +:100910008073C4F8F8314FF40073C4F80C334FF40B +:100920004073C4F8203432460DF19E0104F10900F1 +:1009300000F0F2FC26449DF89C30777223720BB9CC +:10094000EB7E23728122002106AC27A800F0F6FC82 +:100950000122214627A800F089FE00230393AB7EE5 +:10096000029305F1190380B201932823CDE90440D5 +:100970000093E97E05A3D3E90023404602F0FAF98B +:100980005AB0BDE8F08100BFAFF30080264172721B +:10099000DF25D7B7A8320020F0B5254E4FF48A7571 +:1009A00005FB0065F1B096F8D83085F8DC300024FE +:1009B000D822214685F8E8403AA800F0BFFC06F1AD +:1009C000090000F0B3FCD5F8E4308DF8F000C2B2B5 +:1009D00006AF06F109010DF1F100CDE93A3400F05E +:1009E0009BFC394601223AA800F06CFE80B2CDE9AA +:1009F000047008230127CDE9023706F1D8030193DB +:100A000030230093317A0B4807A3D3E9002302F087 +:100A1000B1F9A04206DD01F0E5FDC5F8E000384679 +:100A200071B0F0BD2046FBE778F6339F93CACD8DB9 +:100A3000A8320020A42100202DE9F0411D4D1E4EBA +:100A40001E4F86B0284602F0C1F9034658B3002471 +:100A5000CDE90344ADF81440027B8DF81420996869 +:100A60004068029403AA03C21B68DFF8548043F075 +:100A70000043029301F0B8FD821941F10003009494 +:100A800002A9384601F07CF8A04205DD284602F0B4 +:100A9000A1F988F80040D5E798F80030072B05D871 +:100AA000013388F8003006B0BDE8F081014802F05B +:100AB00091F9F8E7A421002040420F00D82100203E +:100AC000DD37002070B50D4614461E4602F0AEF824 +:100AD00050B9022E10D1012C0ED112A3D3E900235C +:100AE000C5E90023012007E0282C10D005D8012CEF +:100AF00009D0052C0FD0002070BD302CFBD10BA3EA +:100B0000D3E90023ECE70BA3D3E90023E8E70BA329 +:100B1000D3E90023E4E70BA3D3E90023E0E700BF18 +:100B2000AFF30080401DA12026812A0B78F6339F69 +:100B300093CACD8D9E6AC421818A46EE2641727287 +:100B4000DF25D7B7F017304A39059E5638B5054628 +:100B50000E4C0021013500F0B7FBA4F82C55B4F879 +:100B60002C0500F099FB78B1B4F82C0500F0A4FB3B +:100B7000014648B9B4F82C0500F0A6FBB4F82C35B2 +:100B80000133A4F82C35EAE738BD00BFA8320020B5 +:100B900010B50A4B0A4A1A6003F5805393F8602097 +:100BA0003AB9DC6D2CB1204600F082FE204603F0FD +:100BB00053FEBDE81040034800F07ABED821002063 +:100BC000404A0008203200202DE9F04F8FB000AFDE +:100BD00005460C4602F02AF8002849D1237E022B54 +:100BE0001BD1E38A012B18D101F0FCFC0646FFF76C +:100BF000E1FD03464FF4C870DFF8C482B3FBF0F2A6 +:100C000006F5167602FB103316FA83F3C8F80030A7 +:100C1000E37E33B9A34B00221A703C37BD46BDE8D2 +:100C2000F08F07F12401204600F0A2FC0028F4D147 +:100C300007F11400FFF7D6FD97F8264007F11401DD +:100C4000224607F1270003F051FE0028E2D10F2CC5 +:100C500008D8944B1C70D8F80030A3F51673C8F868 +:100C60000030DAE797F82410284601F0D7FFD4E7E0 +:100C7000E38A282B2BD010D8012B23D0052BCCD1E5 +:100C8000BFF34F8F8849894BCA6802F4E06213436F +:100C9000CB60BFF34F8F00BFFDE7302BBDD1844E3B +:100CA000E17E327A9142B8D1607E3146002291F8DD +:100CB000DC50854200F0A5800132042A01F58A71DA +:100CC000F5D1AAE721462846FFF79CFDA5E7214676 +:100CD0002846FFF703FEA0E7B2F8EC507B6005F171 +:100CE00003094FEA99094FEA8902D11DC908A8EB07 +:100CF000C1039D46EB460021584600F01FFB04F15E +:100D0000EE012A463144584600F006FB7B6813B9D1 +:100D1000012000F0B7FA96F8D20000F0BDFA0446C0 +:100D200030B9307200F0D8FA204600F0ABFAB1E0EA +:100D3000D6F8D4203AB996F8D200B6F82C258242DB +:100D400001D8FFF703FFD6F8D4202A44944208D2F2 +:100D500096F8D200B6F82C250130824201D8FFF770 +:100D6000F5FE70685FFA89F2594600F0EFFA08B9AB +:100D7000C54679E0726896F8D2002A447260D6F8C7 +:100D8000D42005EB0209C6F8D49000F085FA81451D +:100D900009D396F8D220D6F8D4000132001B86F889 +:100DA000D220C6F8D400FF2D0FD80024347200F0F2 +:100DB00093FA204600F066FA00F000FD3D4B1881E2 +:100DC00008B9FFF7A5FCC54627E7BB6896F8D90028 +:100DD0000AFB0362FB68D2F8E41082F8E83001F500 +:100DE0008061C2F8E030C2F8E410FFF7D5FDFFF7EC +:100DF00023FE96F8D920013202F0030286F8D920AA +:100E0000B6E74FF48A7A0AFB02F505F1EA013144AC +:100E1000204600F083FCF86000287FF4FEAE3544E5 +:100E2000012285F8E82001F0DDFBD5F8E020D6EDC1 +:100E3000007ADFED216A801A192838BF192040F6A0 +:100E4000B832904228BF1046B8EE677A07EE900A93 +:100E5000F8EEE77A67EEA67ADFED186AE7EE267A13 +:100E6000FCEEE77AC6ED007A96F8D930BB60BA6836 +:100E700073680AFB02F4321992F8E81059B1D2F8FB +:100E8000E4108B42E8463FF427AF002182F8E810D7 +:100E9000C2F8E010C5467368064A9B0A0133138105 +:100EA000BBE600BF9D21002000ED00E00400FA0534 +:100EB000A83200208C110020CDCCCC3D6666663F68 +:100EC000A0210020014B1870704700BF981100202E +:100ED00038B54FF00054134B22689A4220D1124B80 +:100EE000627D12481A70237D03724FF48073C0F83C +:100EF000F8314FF40073C0F80C3300254FF4407301 +:100F0000C0F820340A49C0F8E450C922093000F082 +:100F100003FAE0222946204600F010FA012038BDED +:100F20000020FCE79AAD44C598110020A8320020AB +:100F30001600002037B500F041FC194D19492881F1 +:100F40000223012218486B7101F0EAF90023019392 +:100F5000164B174900931748174B4FF4805201F076 +:100F600035FE164B197811B1124801F057FE01F009 +:100F700039FB0446FFF71EFC4FF4C873B0FBF3F2D5 +:100F800002FB130304F5167010FA83F00C4B186083 +:100F900002F010FF08B10F232B8103B030BD00BF5A +:100FA0008C11002040420F00D8210020C50A000803 +:100FB0009C110020A4210020C90B000898110020DA +:100FC000A02100202DE9F04F2DED028B8EA7D7E94F +:100FD00000670FF23C29D9E90089864C95B00DAD28 +:100FE0009FED828BFFF728FDDFF82CB200230C93D6 +:100FF000ADF83C300D936B6000230DF125028DEDB3 +:10100000008B4FF0010A09A958468DF825308DF85C +:1010100024A001F035F99DF824200023002A40F097 +:10102000AB80204601F002FE0546002847D1DFF8DC +:10103000ECB101F0D7FADBF8003098423FD301F071 +:10104000D1FA0790FFF7B6FB079A4FF4C873B0FBCD +:10105000F3F101FB130302F5167010FA83F0CBF8DD +:101060000000DFF8BCB19BF800100791002914BF05 +:101070002B46534610A88DF83030FFF7B3FB079985 +:10108000C1F11002D2B2062A10AB28BF06221944C1 +:101090000DF13100079200F03FF9079A0CAB039372 +:1010A000182302930132544BD2B2CDE900A304922B +:1010B0003B463246204601F0FFFD8BF8005001F020 +:1010C00091FA4E4A4E4D1368C31AB3F57A7F32D364 +:1010D000106001F089FA02460B46204601F084FEBA +:1010E000204601F0A3FD30B32B7ADFF838A1002BA6 +:1010F00014BF032302238AF8053001F073FA0DF1BF +:10110000400B4FF47A730122B0FBF3F05946CAF852 +:101110000000504600F004FA18230293394B019363 +:1011200080B240F25513CDE903B0009342464B46DE +:10113000204601F0C1FD2B7ACBB101F053FA4FF0FC +:10114000000A83464FF48A7295F8D900504400F0A3 +:10115000030002FB005393F8E81089B30AF1010A77 +:10116000BAF1040FF0D12B7A002B7FF438AF15B011 +:10117000BDEC028BBDE8F08F4FF0904110A84A699A +:1011800082F010024A611946102200F0D7F80DF1E2 +:1011900026030AAA0CA9584600F0F0FD95E80300C2 +:1011A00011AB83E803009DF83C308DF84C300C9B6C +:1011B000109310A9DDE90A23204601F0E9FF1BE79F +:1011C000D3F8E01049B12B68FA2B38BFFA23ABEB08 +:1011D00001010533B1EB430FC0D3FFF7DDFB4FF443 +:1011E0008A720028BAD1BEE7AFF300800000000089 +:1011F00000000000A42100209C210020D8370020FE +:10120000A8320020DC370020401DA12026812A0BB7 +:10121000F1C6A7C1D068080FD8210020A021002066 +:101220009D2100208C11002008B5054800F040FEEB +:10123000BDE80840034A0449002003F007BB00BF93 +:10124000D821002018380020910B000870470000BA +:1012500070B502F013FC094E094D30800024286857 +:101260003388834208D902F005FC2B68044401331B +:10127000B4F5D04F2B60F2D370BD00BF0C38002006 +:10128000E037002002F086BC00F10060920000F51B +:10129000D04002F02DBC0000054B1A68054B1B889E +:1012A0009B1A834202D9104402F0E4BB002070472D +:1012B000E03700200C380020024B1B68184402F075 +:1012C000DFBB00BFE0370020024B1B68184402F070 +:1012D000E9BB00BFE0370020064991F8243033B164 +:1012E0000023086A81F824300822FFF7CDBF0120CF +:1012F000704700BFE4370020022802BF4FF0904340 +:1013000010229A6170470000022802BF4FF09043FC +:101310004FF480129A61704710B50023934203D0B6 +:10132000CC5CC4540133F9E710BD0000034602460B +:10133000D01A12F9011B0029FAD170470244034662 +:10134000934202D003F8011BFAE770472DE9F843F6 +:101350001F4D144695F824200746884652BBDFF8F7 +:1013600070909CB395F824302BB92022FF21484679 +:101370002F62FFF7E3FF95F82400C0F10802A242B4 +:1013800028BF2246D6B24146920005EB8000FFF707 +:10139000C3FF95F82430A41B1E44F6B2082E174450 +:1013A0009044E4B285F82460DBD1FFF795FF002874 +:1013B000D7D108E02B6A03EB82038342CFD0FFF73B +:1013C0008BFF0028CBD10020BDE8F8830120FBE78C +:1013D000E43700202DE9F0470D46044600219046F1 +:1013E000284640F27912FFF7A9FF23462022002168 +:1013F000284601F06FFE231D02222021284601F01D +:1014000069FE631D03222221284601F063FEA31D0D +:1014100003222521284601F05DFE04F10803102275 +:101420002821284601F056FE04F110030822382135 +:10143000284601F04FFE04F11103082240212846FE +:1014400001F048FE04F1120308224821284601F069 +:1014500041FE04F1140320225021284601F03AFEF7 +:1014600004F1180340227021284601F033FE04F1F4 +:1014700020030822B021284601F02CFE04F12103AC +:101480000822B821284601F025FE04F12207C026D3 +:101490003B46314608222846083601F01BFEB6F5C9 +:1014A000A07F07F10107F3D104F13203082231468E +:1014B000284601F00FFE002704F1330A94F8323079 +:1014C0004FEAC7099F4209F5A47615D3B8F1000F7A +:1014D00008D1314604F599730722284601F0FAFD38 +:1014E00009F24F16274694F832213B1B93420CD346 +:1014F000F01DC008BDE8F0870AEB0703082231465B +:10150000284601F0E7FD0137D8E707F233133146EB +:101510000822284601F0DEFD08360137E3E7000027 +:1015200013B504460846002101602346C0F80310A5 +:101530002022019001F0CEFD0198231D02222021DE +:1015400001F0C8FD0198631D0322222101F0C2FDB4 +:101550000198A31D0322252101F0BCFD019804F18F +:1015600008031022282101F0B5FD072002B010BDAC +:10157000F7B50023047F00910E4607221946054661 +:1015800001F06CFC731C0093012200230721284604 +:1015900001F064FCC4B9B31C009305222346082162 +:1015A000284601F05BFC0D243746B278BB1B934202 +:1015B00011D32B7FA88A0734E408BBB9844294BFB7 +:1015C0000020012003B0F0BDAB8ADB00083BDB0844 +:1015D000B3700824E8E7FB1C00932146002308228F +:1015E000284601F03BFC08340137DEE7201A18BF1B +:1015F0000120E7E7F7B50023047F00910E4608229B +:101600001946054601F02AFC731CC4B90822009350 +:1016100011462346284601F021FC1024012372784C +:101620005F1C013B934211D32B7FA88A0734E40847 +:10163000BBB9844294BF0020012003B0F0BDAB8A47 +:10164000DB00083BDB0873700824E7E7F31900931D +:10165000214600230822284601F000FC08343B46BE +:10166000DDE7201A18BF0120E7E70000F8B50E46B5 +:1016700005461446002181223046FFF75FFE2B46C7 +:1016800008220021304601F025FD7CB96B1C0722A1 +:101690000821304601F01EFD0F2401236A785F1CEB +:1016A000013B934204D3E01DC008F8BD0824F4E7D1 +:1016B000EB1921460822304601F00CFD08343B4668 +:1016C000ECE70000F8B50E46054614460021CE2290 +:1016D0003046FFF733FE2B4628220021304601F02A +:1016E000F9FC7CB905F1080308222821304601F0F5 +:1016F000F1FC30242F462A7A7B1B934204D3E01D51 +:10170000C008F8BD2824F5E707F10903214608229F +:10171000304601F0DFFC08340137ECE7F7B5047F11 +:1017200000910E46012310220021054601F096FB90 +:10173000C4B9B31C0093092223461021284601F0A6 +:101740008DFB192437467288BB1B9A4211D82B7F18 +:10175000A88A0734E408BBB9844294BF0020012062 +:1017600003B0F0BDAB8ADB00103BDB0873801024B4 +:10177000E8E73B1D0093214600230822284601F09C +:101780006DFB08340137DEE7201A18BF0120E7E7B8 +:1017900030B5094D0A4491420DD011F8013B584033 +:1017A000082340F30004013B2C4013F0FF0384EABC +:1017B0005000F6D1EFE730BD2083B8EDF7B5364ADB +:1017C000106851686B4603C36A463449344808239D +:1017D00003F09CF8044690BB0A25324A1068516811 +:1017E0006B4603C36A4630492D48082303F08EF840 +:1017F0000446002847D00369B3F5663F43D8B0F8E4 +:101800006620B2F57B7F3ED1284A024402F15C019A +:101810008B4238D35C3B224900209E1AFFF7B8FF69 +:101820003246074604F164010020FFF7B1FFA368C8 +:101830009F4228D1E368984208BF002523E003694E +:10184000B3F5663F26D8428BB2F57B7F20D1174A8D +:10185000024402F110018B4218D3103B10490020C2 +:101860009D1AFFF795FF2A46064604F1180100204D +:10187000FFF78EFFA3689E4202D1E368984201D031 +:101880000D25AAE70025284603B0F0BD1025A4E7E2 +:101890000C25A2E70B25A0E7044A0008DC9703000B +:1018A000006800080D4A0008909703000898FFF7A9 +:1018B00010B5037C044613B9006803F00FF8204606 +:1018C00010BD00000023BFF35B8FC360BFF35B8FCD +:1018D000BFF35B8F8360BFF35B8F7047BFF35B8F9A +:1018E0000068BFF35B8F704770B505460C30FFF79B +:1018F000F5FF05F1080604463046FFF7EFFFA0426A +:1019000006D930466D68FFF7E9FF2544281A70BDF7 +:101910003046FFF7E3FF201AF9E7000070B50546EF +:10192000406898B105F10800FFF7D8FF05F10C06F3 +:1019300004463046FFF7D2FF8442304694BF6D68BC +:101940000025FFF7CBFF013C2C44201A70BD00009E +:1019500038B50C460546FFF7C7FFA04210D305F186 +:101960000800FFF7BBFF04446868B4FBF0F100FB1C +:101970001144BFF35B8F0120AC60BFF35B8F38BDB8 +:101980000020FCE72DE9F041144607460D46FFF71D +:10199000C5FF844228BF0446D4B1B84658F80C6B42 +:1019A0004046FFF79BFF3044286040467E68FFF7C3 +:1019B00095FF331A9C4203D86C600120BDE8F0818A +:1019C0006B60A41B3B68AB602044E8600220F5E735 +:1019D0002046F3E738B50C460546FFF79FFFA042C7 +:1019E00010D305F10C00FFF779FF04446868B4FBDD +:1019F000F0F100FB1144BFF35B8F0120EC60BFF3FB +:101A00005B8F38BD0020FCE72DE9FF418846694621 +:101A10000746FFF7B7FF6C4606B204EBC606002583 +:101A2000B44209D06268206808EB0501FFF774FC36 +:101A3000636808341D44F3E729463846FFF7CAFFB8 +:101A4000284604B0BDE8F081F8B505460C300F46D5 +:101A5000FFF744FF05F1080604463046FFF73EFF56 +:101A6000A042304688BF6C68FFF738FF201A386004 +:101A700020B130462C68FFF731FF2044F8BD00004C +:101A800073B5144606460D46FFF72EFF844228BF65 +:101A900004460190DCB101A93046FFF7D5FF019B58 +:101AA00033B93268C5E90233C5E9002401200CE0EE +:101AB0009C4238BF01942860019868608442F5D93F +:101AC0003368AB60241AEC60022002B070BD20467F +:101AD000FBE700002DE9FF410F466946FFF7D0FF05 +:101AE0006C4600B204EBC0050026AC4209D0D4F825 +:101AF000048054F8081BB8194246FFF70DFC464411 +:101B0000F3E7304604B0BDE8F081000038B5054683 +:101B1000FFF7E0FF044601462846FFF719FF20467D +:101B200038BD0000302383F3118862B6704700008F +:101B3000002383F3118862B67047000010B4026876 +:101B400054681A4623465DF8044B18470120704735 +:101B50000020704700207047704700000020704749 +:101B60000E20704700F5805090F8C800C0F3400088 +:101B70007047000000F5805090F9C90070470000E0 +:101B8000F7B50C68BDF8207014F000541E466FD1F4 +:101B90000B7B082B6CD8FFF7C5FF4569AB685B0171 +:101BA0000CD4AB681B0108D4AC6814F080545DD130 +:101BB000FFF7BEFF204603B0F0BD01240B6804F11F +:101BC000180C002BB8BFDB004FEA0C1CB4BF43F06D +:101BD00004035B0545F80C300B680FFA84FC13F026 +:101BE000804F18BF05EB0C1E05EB0C1C1EBFDEF86A +:101BF000803143F00203CEF880310B7BCCF8843186 +:101C000005EB04158B68C5F88C314B68C5F8883135 +:101C1000DCF8803143F00103CCF8803100EB44154F +:101C200041F268031D4403EB44130344C5E9002655 +:101C300008330D4601F10C0C55F804EB43F804EBA6 +:101C40006545F9D184342D881D8000EB441407F0DC +:101C50000303257925F00B052B432371FFF768FF5C +:101C60000097334600F0E0FC0120A4E70224A5E73A +:101C70004FF0FF309FE7000013B500F5805401914D +:101C8000E06DFFF74BFE1F280AD90199E06D202275 +:101C9000FFF7BAFEA0F120035842584102B010BD30 +:101CA0000020FBE708B500F58050FFF73BFFC06D53 +:101CB000FFF708FEBDE80840FFF73ABF00220260C8 +:101CC000828142608260704710B500220023C0E923 +:101CD00000230023044603810C30FFF7EFFF20466A +:101CE00010BD0000F0B5054600F580500C4690F898 +:101CF000C83013F0040FC3F3800108BF114661F32D +:101D0000820304F1840680F8C83005EB461389B0DD +:101D10001B79D8072ED57AB319072DD46846FFF75B +:101D2000D3FF05EB441303F5835303F1180703AA0C +:101D3000103318685968144603C40833BB4222465E +:101D4000F7D1186820609B88A380DDE90E23CDE9D8 +:101D500000230123ADF808302B686946DB6B284669 +:101D6000984705EB46152B791A075CBF43F008032B +:101D70002B7101E0002AF4D109B0F0BD2DE9F04744 +:101D8000074688B007F5805468469A468846FFF7AC +:101D9000C9FE9146FFF798FFE06DFFF7A5FD1F28EC +:101DA00029D9E06D20226946FFF7B0FE202822D114 +:101DB00003AD444605AB2E4603CE9E4220606160D3 +:101DC000354604F10804F6D130682060B388A3805A +:101DD000DDE90023C9E90023BDF80830AAF8003086 +:101DE000FFF7A6FE4A4653464146384608B0BDE8CE +:101DF000F04700F007BCFFF79BFE002008B0BDE8ED +:101E0000F08700002DE9F84F0023C0E90133254B8E +:101E1000044640F8183B0F46FFF750FF04F1280036 +:101E2000FFF752FF04F1480804F58255464608358D +:101E300030462036FFF748FFAE42F9D104F5805511 +:101E40004FF480534FF00009C5E91339C5F84880B5 +:101E50000123EE6504F5875804F58456C5F85490BF +:101E600085F8583085F86030083608F108084FF0DA +:101E7000000A4FF0000B46E908ABA6F11800FFF787 +:101E80001DFF203646F8289C4645F4D185F8C970D8 +:101E900017B1054800F0A0FB044B63612046BDE884 +:101EA000F88F00BF404A0008184A0008006400404C +:101EB00010B5044B197804464A1C1A70FFF7A2FFAC +:101EC000204610BD143800202DE9F047002950D0DD +:101ED000294B2A4FB7FBF1F599428CBF0A231123F6 +:101EE000581EB5FBF3FC03FB1C53C4B22BB10228F4 +:101EF0000346F5D80020BDE8F0870CF1FF36B6F5B3 +:101F0000806FF7D2C4EBC40E0EF103034FEAE3096E +:101F1000C3F3C703A4EB030809F1010A4FF47A7570 +:101F20005FFA88F009FB05555AFA88F8B5FBF8F511 +:101F3000B5F5617FC1BF0EF1FF33C3F3C703E01AEC +:101F4000C0B25C1C50FA84F40CFB04F4B7FBF4F44C +:101F5000A142CFD1013BDBB20F2BCBD80138C0B2AD +:101F60000728C7D80021107116809170D370012006 +:101F7000C1E70846BFE700BF3F420F0000512502FE +:101F800070B505460E464FF47A746B695B6803F0D2 +:101F90000103B3424FF0010004D001F0A5FC013C65 +:101FA000F3D1204670BD000030B54269936913F04B +:101FB000700F16D000230B4C936103F1840200EBE9 +:101FC000421211794D0709D5890707D5416954F89F +:101FD00023508D60117941F0040111710133032BFD +:101FE000EBD130BD2C4A000873B51D464369164637 +:101FF0009A68D207044609D59A6801219960C2F30C +:102000004002CDE900650021FFF76CFE63699A6824 +:10201000D1050BD59A684FF480719960C2F34022C4 +:10202000CDE9006501212046FFF75CFE63699A68EF +:10203000D2030BD59A684FF480319960C2F34042C5 +:10204000CDE9006502212046FFF74CFE204602B094 +:10205000BDE87040FFF7A8BFF8B5044646690029FF +:102060006CD106F10C07386880076AD006EB0115C1 +:102070003868D5F8B00110F0040FD5F8B0011ABFD8 +:10208000C00840F00040400DA061D5F8B0C11CF080 +:10209000020F1CBF40F08040A061D5F8B40106EBF0 +:1020A000011100F00F0084F82400D1F8B801207766 +:1020B000D1F8B801000A6077D1F8B801000CA07718 +:1020C000D1F8B801000EE077D1F8BC0184F8200007 +:1020D000D1F8BC01000A84F82100D1F8BC01000C41 +:1020E00084F82200D1F8BC11090E84F8231038219D +:1020F000396004F1340004F1180104F1240551F8A9 +:10210000046B40F8046BA942F9D109880180C4E945 +:102110000A2321460023238651F8283B2046DB6B07 +:10212000984704F58052204692F8C83043F00403E3 +:1021300082F8C830BDE8F840FFF736BF06F1100757 +:1021400091E7F8BD10B5044600F04EFA02460B4682 +:1021500052EA030102D0013A63F10003044908681E +:1021600020B12146BDE81040FFF776BF10BD00BF8B +:1021700010380020F8B500F583511E46FFF7D2FC59 +:10218000DFF844C00831002404F1840500EB451554 +:102190002B795F070ED4DB060CD5D1E9007397428B +:1021A000B34107D243695CF824709F602B7943F0F8 +:1021B00004032B710134032C01F12001E4D1BDE8AB +:1021C000F840FFF7B5BC00BF2C4A000808B5FFF780 +:1021D000A9FCFFF7E9FEBDE80840FFF7A9BC000035 +:1021E000F8B543690546986800F0E050B0F1E05F4B +:1021F0000F461FD0E8B1FFF795FC05F58354103466 +:10220000002606F1840305EB43131B791A0706D554 +:102210000136032E04F12004F3D1012007E05B070F +:10222000F6D42146384600F039FA0028F0D1FFF7FD +:102230007FFCF8BD0120FCE700F5805008B5FFF7F2 +:1022400071FCC06DFFF750FBFFF772FC43090CBF38 +:102250000120002008BD0000F8B51D4600231370C2 +:102260000F4606461446FFF7E7FF80F0010038707E +:1022700025B129463046FFF7B3FF2070F8BD0000B6 +:102280002DE9B8410C4615461F46804600F0ACF9D2 +:102290000B462178024609B9287850B14046FFF72D +:1022A00069FFFFF793FF3B462A462146FFF7D4FF1D +:1022B0000120BDE8B881000010B5FFF733FC174BD3 +:1022C000DA6942F00072DA611A6942F000721A614A +:1022D0001A6900F5805422F000721A61FFF728FC99 +:1022E00094F8C830DB0718D4B9B103211320FFF7E5 +:1022F00019FC01F0C7F90321142001F0C3F90321EF +:10230000152001F0BFF994F8C83043F0010384F8B8 +:10231000C830BDE81040FFF70BBC10BD00100240F4 +:102320002DE9F04700F5805588B095F8C930012BAC +:102330000446884616467FD8804F57F823200AB9AE +:1023400047F82300D7F800A0C4F80C802674BAF12F +:10235000000F63D095F8C930012B6FD001212046C2 +:10236000FFF7AAFFFFF7DEFB6269136823F00203A1 +:1023700013606269136843F0010313606369002707 +:102380005F6101212046FFF7D3FBFFF7F9FD00282D +:1023900000F09580E86DFFF795FA04F58359BA4689 +:1023A00009F10809202200216846FEF7C7FF02A8AC +:1023B000FFF784FCCDF818A06A4609EB07030DF17E +:1023C000180E9446BCE80300F44518605960624654 +:1023D00003F10803F5D1DCF80000186020379CF801 +:1023E00004201A71602FDDD195F8C8306FF3820395 +:1023F000002785F8C8306A4641462046ADF800708F +:10240000ADF802708DF80470FFF75EFD636948BB9C +:102410004FF400421A6008B0BDE8F08741F2D000E6 +:1024200002F01CFA814610B15146FFF7EBFCC7F8E9 +:102430000090B9F1000F8DD10020ECE738680368F7 +:102440001B6B98470146002888D13868FFF734FF96 +:102450003868036832465B684146984700287FF435 +:102460007DAFE9E761221A609DF802309DF80320F4 +:102470001B06120402F4702203F040731343BDF8EC +:102480000020C2F3090213439DF804201205022E16 +:1024900002F4E0020CBF4FF00041002113436269D7 +:1024A0000B43D361636913225A616269136823F095 +:1024B0000103136039462046FFF762FD08B96369DE +:1024C000A6E795F8C93093BB6169D1F8002242F0C4 +:1024D0000102C1F800226169D1F8002222F47C5285 +:1024E00022F00E02C1F800226169D1F8002242F404 +:1024F0006062C1F800226269C2F814326269C2F8EF +:102500000432626941F6FF71C2F80C126269C2F8C6 +:1025100040326269C2F8443263690122C3F81C2266 +:102520006269D2F8003223F00103C2F8003295F854 +:10253000C83043F0020385F8C8306CE7103800203B +:1025400008B500F051F850EA0103024602D0421EDD +:1025500061F10001044B186810B10B46FFF744FD10 +:10256000BDE8084001F064B81038002008B500202C +:10257000FFF7E8FDBDE8084001F05AB808B50120B2 +:10258000FFF7E0FDBDE8084001F052B800B59BB090 +:10259000EFF3098168226846FEF7BEFEEFF305837C +:1025A000014B9B6BFEE700BF00ED00E008B5FFF7B5 +:1025B000EDFF000000B59BB0EFF30981682268468B +:1025C000FEF7AAFEEFF30583014B5B6BFEE700BF4E +:1025D00000ED00E0FEE700000FB408B5029801F03E +:1025E00019F9FEE701F02EBB01F004BB13B56C46F0 +:1025F00084E80600031D94E8030083E80500012039 +:1026000002B010BD73B58568019155B11B885B0799 +:1026100007D4D0E900369B6B9847019AC1B2304687 +:10262000A847012002B070BDF0B5866889B00546A4 +:102630000C465EB1BDF838305B070AD4D0E90037EC +:102640009B6B98472246C1B23846B047012009B07B +:10265000F0BD00220023CDE900230023ADF80830AF +:102660000A4603AB01F10806106851681C4603C412 +:102670000832B2422346F7D1106820609288A280C7 +:10268000FFF7B2FF0423ADF808302B68CDE9000155 +:10269000DB6B694628469847D8E7000030B50368E9 +:1026A0000968DD0FB5EBD17F23F0604421F0604273 +:1026B0004FEAD1700BD0002BB8BFA40C0029B8BFD3 +:1026C000920C944202D034BF0120002030BD9442CD +:1026D00005D1C1F38070C3F380738342F6D1944275 +:1026E0002CBF00200120F1E72DE9F041456A15B922 +:1026F0004162BDE8F0814B6823F06047C3F38A462E +:102700004FEAD37EC3F3807816EA230638BF3E46ED +:10271000AC462B465A68BEEBD27F22F060440AD00A +:10272000002A18DAA40CB44217D19D420FD10D60D3 +:10273000DEE71346EEE7A74207D102F08044C2F37A +:10274000807242450BD054B1EFE708D2EDE7CCF8E8 +:1027500000100B60CDE7B44201D0B442E5D81A684E +:102760009C46002AE5D11960C3E700002DE9F04737 +:10277000089D01F007044FEAD508224405F007053B +:1027800000EBD1004FF47F49944201D1BDE8F087BE +:1027900004F0070705F0070A57453E4638BF56467E +:1027A000C6F10806111B8E4228BF0E46E10808EB51 +:1027B000D50E415C13F80EC0B94029FA06F721FA8C +:1027C0000AF1FFB28CEA010147FA0AF739408CEAB4 +:1027D000010C03F80EC034443544D5E780EA0120EB +:1027E000082341F2210201B24000002980B203F126 +:1027F000FF33B8BF504013F0FF03F4D1704700001F +:1028000038B50C468D18A54200D138BD14F8011B0F +:10281000FFF7E4FFF7E7000042684AB1136843603E +:102820004389818901339BB29942438138BF8381B7 +:102830001046704770B588B0202204460D466846A1 +:102840000021FEF77BFD20460495FFF7E5FF0246D9 +:1028500058B16B46054608AE1C4603CCB44228600E +:102860006960234605F10805F6D1104608B070BD31 +:10287000082817D909280CD00A280CD00B280CD00E +:102880000C280CD00D280CD00E2814BF402030206E +:1028900070470C2070471020704714207047182094 +:1028A0007047202070470000082817D90C280CD941 +:1028B00010280CD914280CD918280CD920280CD988 +:1028C00030288CBF0F200E207047092070470A2047 +:1028D00070470B2070470C2070470D207047000098 +:1028E0002DE9F843078C072F04461ED9D0E902983A +:1028F00000254FF6FF73C5F12006A5F1200029FA47 +:1029000005F108FA06F628FA00F031430143C9B28E +:102910001846FFF763FF0835402D0346EBD1E16908 +:102920003A46BDE8F843FFF76BBF4FF6FF70BDE8CE +:10293000F883000010B54B6823B9CA8A63F3090213 +:10294000CA8210BD04691A681C600361C38A013B16 +:10295000C3824A60EFE700002DE9F84F1D46CB8A9D +:102960000F46C3F309010529814692460B4630D034 +:102970000020AAB207F11A049EB2042E1FFA80F8B2 +:102980000FD8904503F1010306D3FB8A0A4462F392 +:102990000903FB8201201AE01AF80060E6540130B6 +:1029A000EAE79045F1D2A1F1050B1C237C68BBFB43 +:1029B000F3F203FB12BB1FFA8BF6002C45D14846FD +:1029C000FFF72AFF044638B978606FF00200BDE8CF +:1029D000F88F4FF00008E6E7002606607860ADB299 +:1029E0004FF0000B454510D90AEB0803221D13F8E0 +:1029F000011B9155B1B208F101081B291FFA88F893 +:102A00002BD0454506F10106F1D8FB8AC3F3090234 +:102A1000154465F30903BCE7013292B21C462368F2 +:102A2000002BF9D16B1F0B441C21B3FBF1F30133D5 +:102A30009BB29A42D3D2BBF1000FD0D14846FFF7E8 +:102A4000EBFE20B9C4F800B0BFE70122E7E7C0F809 +:102A500000B05E4620600446C1E74545D5D94846EA +:102A6000FFF7DAFE08B92060AFE7C0F800B0002633 +:102A700020600446B6E700002DE9F04F2DED028BF3 +:102A80001C4683B05B69019207468846002B00F024 +:102A90009A80238C2BB1E269002A00F09480072BE6 +:102AA00035D807F10C00FFF7B7FE054638B96FF0CF +:102AB0000205284603B0BDEC028BBDE8F08F14225E +:102AC0000021FEF73BFC228CE16905F10800FEF7CE +:102AD00023FC208C013080B2FFF7E6FEFFF7C8FE32 +:102AE000013880B22084013028746369228C1B78FD +:102AF0002A4403F01F0363F03F0348F000411372C0 +:102B0000384669602946FFF7EFFD0125D1E700F15E +:102B10000C034FF0000908EE103A4FF0800A4E46C1 +:102B20004D4618EE100AFFF777FE83460028BED008 +:102B300014220021FEF702FC002E3AD1019BABF8D3 +:102B4000083002220BF1080E1FFA82FC0CF1010082 +:102B5000BCF1060F218C80B201D88E422BD3FFF737 +:102B6000A3FEFFF785FE62691278013802F01F02AA +:102B70008E4208BF4FF0400A42EA49121BFA80F128 +:102B80004AEA020A013048F0004281F808A08BF8B6 +:102B90001000CBF8042059463846FFF7A5FD238CDA +:102BA0000135B3422DB289F001094FF0000AB8D1C6 +:102BB0007FE70022C6E7E169895D0EF80210013661 +:102BC000B6B20132C0E76FF0010572E7F8B51546FD +:102BD0000E463022002104461F46FEF7AFFB069B3F +:102BE0006360B5F5001F079BA76034BF6A094FF605 +:102BF000FF72A36297B2E66104F1100000239A42CB +:102C000006D800230360A782E3822383E360F8BD34 +:102C10000660013330462036F1E7000003781BB927 +:102C20004BB2002BC8BF017070470000007870479E +:102C3000F8B50C46C969074611B9238C002B37D16A +:102C4000257E1F2D34D8387828BB228C072A2CD813 +:102C5000268A36F003032BD14FF6FF70FFF7D0FD25 +:102C600020F001003102400441EA0561400C41EAD4 +:102C700040254FF6FF72234629463846FFF7FCFEF3 +:102C8000002807DD626913780133DBB21F2B88BF90 +:102C900000231370F8BD218A2D0645EA012505435E +:102CA0002046FFF71DFE0246E5E76FF00300F1E75F +:102CB0006FF00100EEE7000070B58AB004461646DA +:102CC0000021282268461D46FEF738FBBDF8383043 +:102CD000ADF810300F9B05939DF840308DF81830FB +:102CE000119B07936946BDF84830ADF82030204667 +:102CF000CDE90265FFF79CFF0AB070BD2DE9F041F8 +:102D0000D36905460C4616460BB9138C5BBB377E60 +:102D10001F2F28D895F80080B8F1000F26D0304634 +:102D2000FFF7DEFD3378210241EAC33141EA0801B1 +:102D3000338A41EA076141EA03410246334641F0E2 +:102D400080012846FFF798FE00280ADD3378012B22 +:102D500007D1726913780133DBB21F2B88BF0023C0 +:102D60001370BDE8F0816FF00100FAE76FF0030027 +:102D7000F7E70000F0B58BB004460D46174600217A +:102D8000282268461E46FEF7D9FA9DF84C305A1E96 +:102D9000534253418DF800309DF84030ADF810306B +:102DA000119B05939DF848308DF81830149B0793BC +:102DB0006A46BDF85430ADF8203029462046CDE9AA +:102DC0000276FFF79BFF0BB0F0BD0000406A00B138 +:102DD00004307047436A1A68426202691A600361EC +:102DE000C38A013BC38270472DE9F041D0F82080AF +:102DF000194E14461D464146002709B9BDE8F08129 +:102E0000D1E90223A21A65EB0303964277EB030391 +:102E10001ED2036A8B420DD1FFF78CFD036A1B683B +:102E2000036203690B60C38A0161016A013BC382CB +:102E30008846E2E7FFF77EFD0B68C8F800300369BB +:102E40000B60C38A0161013BC382D8F80010D4E74C +:102E500088460968D1E700BF80841E002DE9F04F45 +:102E60008BB00D46DDF8509014469B4680460028F6 +:102E700000F01981B9F1000F00F01581531E3F2BAE +:102E800000F21181012A03D1BBF1000F40F00B8148 +:102E90000023CDE90833B8F81430B5EBC30F4FEA7F +:102EA000C30703D300200BB0BDE8F08F2B199F425E +:102EB000D8F80C303ABF7F1BFFB227461BB9D8F8B1 +:102EC0001030002B7AD0272D4ED8C5F12806B742F6 +:102ED0004FF000032CBFF6B23E4600932946D8F8C7 +:102EE000080008AB3246FFF741FCA7EB060A354461 +:102EF0005FFA8AFAB8F8143003F10053053BDB009F +:102F00000493D8F80C3003932821039B13B1BAF132 +:102F1000000F2CD1D8F8100040B1BAF1000F05D045 +:102F2000009608AB5246691AFFF720FC38B2002F12 +:102F3000B8D066070AD00AAB03EBD401624211F89D +:102F4000083C02F00702134101F8083C082C3CD968 +:102F5000102C40F2B580202C40F2B780BBF1000F5E +:102F600000F09C80082334E0BA460026C2E7049BA8 +:102F7000E02B28BFE02306930B44AB42059314D902 +:102F80005A1B03980096924534BF5246D2B2691A32 +:102F900008AB04300792FFF7E9FB079A1644AAEB47 +:102FA000020A1544F6B25FFA8AFA049B069A05995A +:102FB0009B1A0493039B1B680393A6E70093D8F81E +:102FC000080008AB3A462946AEE7BBF1000F13D024 +:102FD0000123B4EBC30F6CD0082C12D89DF820301D +:102FE000621E23FA02F2D50706D54FF0FF3202FA2D +:102FF00004F423438DF820309DF8203089F8003008 +:1030000051E7102C12D8BDF82030621E23FA02F2CC +:10301000D10706D54FF0FF3202FA04F42343ADF88E +:103020002030BDF82030A9F800303CE7202C0FD824 +:103030000899631E21FA03F3DA0705D54FF0FF3232 +:1030400002FA04F40C430894089BC9F800302AE7FC +:10305000402C2BD0DDE90865611EC4F12102A4F1EA +:10306000210326FA01F105FA02F225FA03F31143CE +:103070001943CB0712D50122A4F12003C4F120018A +:1030800002FA03F322FA01F1A240524243EA010399 +:1030900063EB430332432B43CDE90823DDE90823E7 +:1030A000C9E90023FFE66FF00100FCE66FF00800BD +:1030B000F9E6082CA0D9102CB3D9202CEED8C3E700 +:1030C000BBF1000FADD0022383E7BBF1000FBBD0F3 +:1030D00004237EE730B5012A144638BF0124402C72 +:1030E00085B028BF40240025012ACDE9025518D813 +:1030F0001B788DF8083063070AD004AB03EBD405C6 +:10310000624215F8083C02F00702934005F8083CBB +:10311000009103462246002102A8FFF727FB05B0D5 +:1031200030BD082AE4D9102A03D81B88ADF808302E +:10313000E1E7202A8DBFD3E900231B680293CDE984 +:103140000223D8E710B5CB681BB98B600B618B826B +:1031500010BD04691A681C600361C38A013BC38205 +:10316000CA60F0E703064CBFC0F3C03002207047CE +:1031700008B50246FFF7F6FF022806D15306C2F350 +:103180000F2001D100F0030008BDC2F30740FBE7A8 +:103190002DE9F04F93B0CDE903230A6804461046A9 +:1031A000FFF7E0FF022814BFC2F306260026002A1C +:1031B0000D46824680F2F28112F0C04940F0EE8165 +:1031C000097B002900F0EA81022803D02378B3426A +:1031D00040F0E781C2F304630693104602F07F03D8 +:1031E0000593FFF7C5FF059B29444FEA834848EA4A +:1031F0000A4848EA4668CE7800230022CDE9082331 +:10320000F309834648EA0008029367D0059B0093C0 +:1032100002466768534608A92046B847002800F0D0 +:10322000C381276A4FB9414604F10C00FFF702FB46 +:10323000074690B96FF0020054E03B6998450DD005 +:103240003F68002FF9D1414604F10C00FFF7F2FA74 +:1032500007460028EED0236A3B60276297F817C024 +:1032600006F01F08CCF3840CACEB08001FFA80FEBC +:103270000028B8BF0EF12000A8EB0C031FFA83FE54 +:10328000D7E90221B8BF00B2002B0793BEBF0EF1F1 +:1032900020031BB2079352EA010338D0039BDFF8E7 +:1032A00024E39A1A049B4FF0000C63EB010196454E +:1032B0007CEB01032BD36B7B97F81AE0734519D194 +:1032C000029B002B78D0012821DC7868F8B9DFF860 +:1032D000F0C2944570EB010316D337E0276A27B993 +:1032E0006FF00C0013B0BDE8F08F3B699845B5D086 +:1032F0003F68F4E7B24890427CEB010301D3002021 +:10330000F0E7029B002BFAD0079B0F2B17DCFA7D0E +:10331000B30002F0030203F07C031343FB7539464C +:103320002046FFF707FB6B7BBB76029B3BB9FB7D1F +:10333000C3F38402013262F38603FB75D0E76A7B34 +:10334000BB7E9A42DBD1029B002B35D0B309022B06 +:1033500032D0039BBB60049BFB60142200210DA8AC +:10336000FDF7ECFF039B0A93049B0B932B1D0C931F +:103370002B7BADF83EB0013BDBB2ADF83C30069B99 +:103380008DF84230059B8DF8433094F82C308DF841 +:1033900040A083F001038DF844308DF84180A3688C +:1033A0000AA920469847FB7DC3F38403013303F049 +:1033B0001F039B02FB82A2E7FB7DC6F34012B2EB28 +:1033C000D31F40F0F480C3F38403434540F0F28000 +:1033D000029A2B7BB609002A4DD0F2075DD4032B4D +:1033E00040F2EB80039BBB60049BFB602B7BAE1D1C +:1033F000033BDBB23246394604F10C00FFF7ACFA6E +:1034000000280CDA39462046FFF794FAFB7DC3F317 +:103410008403013303F01F039B02FB820AE7DDE90B +:103420000884AB883B834FF6FF73C9F12000A9F1F4 +:10343000200228FA09F104FA00F0014324FA02F20A +:1034400011431846C9B2FFF7C9F909F10809B9F1E2 +:10345000400F0346E9D1B8822A7B033AD2B2314603 +:10346000FFF7CEF9FB7DB882DA43C2F3C01262F3F4 +:10347000C713FB7543E786B92E1D013BDBB232460D +:10348000394604F10C00FFF767FA0028BADB2A7B03 +:10349000B88A013AD2B23146E2E7F98AC1F30901AA +:1034A000013B0429DAB25BD8281D002307F11B0673 +:1034B0009A4208D910F801CB06F801C00131013356 +:1034C0000529DBB2F4D103990A9104990B91934237 +:1034D00007F11B010C9138BF043379680D9134BF9B +:1034E00055FA83F300230E93FB8AADF83EB0C3F385 +:1034F00009031A44069B8DF84230059B8DF8433032 +:1035000094F82C30ADF83C2083F001038DF8443062 +:1035100000238DF840A08DF841807B602A7BB88A1B +:10352000013A291DFFF76CF93B8BB882834203D126 +:10353000A3680AA92046984720460AA9FFF702FE79 +:10354000FB7DBA8AC3F38403013303F01F039B029C +:10355000FB823B8B9A420CBF00206FF01000C1E64B +:103560007B68002BAFD0052001E01C3033461E687D +:10357000002EFAD1091A081D2E1D184401EB090C62 +:10358000BCF11B0F5FFA89F39DD89A429BD916F8BC +:10359000013B00F8013B09F10109EFE76FF0090079 +:1035A000A0E66FF00A009DE66FF00B009AE66FF060 +:1035B0000D0097E66FF00E0094E66FF00F0091E6B5 +:1035C00040420F0080841E00EFF3098305494A6BD7 +:1035D00022F001024A63683383F30988002383F3EE +:1035E0001188704700EF00E0302080F3118862B648 +:1035F0000C4B0D4AD96821F4E0610904090C0A4317 +:10360000DA60D3F8FC20094942F08072C3F8FC204C +:103610000A6842F001020A602022DA7783F8220069 +:10362000704700BF00ED00E00003FA05001000E065 +:1036300010B5302383F311880E4B5B6813F40063DD +:1036400014D0F1EE103AEFF30984683C4FF0807328 +:10365000E361094BDB6B236684F3098800F098F87B +:1036600010B1064BA36110BD054BFBE783F3118836 +:10367000F9E700BF00ED00E000EF00E003060008FE +:103680000606000800F1604303F561430901C9B271 +:1036900083F80013012200F01F039A4043099B00A6 +:1036A00003F1604303F56143C3F880211A6070475A +:1036B00000F16040090100F56D40C9B20176704724 +:1036C00000230375826803691B6899689142FBD2E5 +:1036D0005A680360426010605860704700230375A9 +:1036E000826803691B6899689142FBD85A68036035 +:1036F000426010605860704708B50846302383F375 +:1037000011880B7D032B05D0042B0DD02BB983F32F +:10371000118808BD8B6900221A604FF0FF33836166 +:10372000FFF7CEFF0023F2E7D1E9003213605A60C1 +:10373000F3E70000FFF7C4BF054BD96808751868A8 +:1037400002681A60536001220275D860FCF744BF1A +:103750002038002030B50C4BDD684B1C87B0044688 +:103760000FD02B46094A684600F0FEF82046FFF7C6 +:10377000E3FF009B13B1684600F000F9A86907B0A9 +:1037800030BDFFF7D9FFF9E720380020F9360008EF +:10379000044B1A68DB6890689B68984294BF0020CD +:1037A0000120704720380020084B10B51C68D868ED +:1037B00022681A60536001222275DC60FFF78EFFD9 +:1037C00001462046BDE81040FCF706BF2038002027 +:1037D000044B1A68DB6892689B689A4201D9FFF72C +:1037E000E3BF70472038002038B5074C0749084828 +:1037F000012300252370656000F00AFB022323707B +:1038000085F3118838BD00BF483A0020844A00087B +:103810002038002008B572B6044B186500F0CEF9C8 +:1038200000F092FA024B03221A70FEE720380020C3 +:10383000483A002000F0B4B8EFF3118020B9EFF35C +:103840000583302282F311887047000010B530B92B +:10385000EFF30584C4F3080414B180F3118810BD9C +:10386000FFF7B6FF84F31188F9E700008B600223AD +:1038700008618B82084670478368A3F1840243F88D +:10388000142C026943F8442C426943F8402C094A3D +:1038900043F8242CC26843F8182C022203F80C2C9D +:1038A000002203F80B2C044A43F8102CA3F120004B +:1038B000704700BFF10500082038002008B5FFF769 +:1038C000DBFFBDE80840FFF735BF0000024BDB68B7 +:1038D00098610F20FFF730BF20380020302383F39A +:1038E0001188FFF7F3BF000008B50146302383F3CA +:1038F00011880820FFF72EFF002383F3118808BDED +:10390000064BDB6839B1426818605A601360436047 +:103910000420FFF71FBF4FF0FF3070472038002012 +:103920000368984206D01A68026050609961184690 +:10393000FFF700BF7047000010B50A4C23699A6872 +:1039400091420CD85A6881600360426010609A68A6 +:103950005860511A99604FF0FF33A36110BD1B6886 +:10396000891AECE72038002010B4C0E903230023B3 +:103970005DF8044B4361FFF7DFBF00000368816817 +:103980009A680A449A60426813605A600023036090 +:10399000024B4FF0FF329A61704700BF2038002081 +:1039A00070B5124DEB692A460133EB6152F8103FB6 +:1039B000934206D09A68013A9A6030262C69A3682F +:1039C00003B170BDD4E900210A605160236083F324 +:1039D0001188D4E903312046984786F3118861693C +:1039E0000029EBD02046FFF7A7FFE7E720380020AB +:1039F00000207047FEE70000704700004FF0FF30E6 +:103A000070470000BFF34F8F024AD368DB07FCD436 +:103A1000704700BF0020024008B5074B1B7853B920 +:103A2000FFF7F0FF054B1A69120641BF044A5A60BE +:103A300002F188325A6008BD603A0020002002403E +:103A40002301674508B5054B1B7833B9FFF7DAFF4B +:103A5000034A136943F08003136108BD603A0020F4 +:103A6000002002407F289ABF00F58030C00200206D +:103A7000704700004FF400607047000080207047DE +:103A80007F2808B50BD8FFF7EDFF00F5006302684B +:103A9000013204D104308342F9D1012008BD002055 +:103AA000FCE700007F2810B504461CD8FFF7AAFFEA +:103AB000FFF7B2FF0D4BF322DA6002221A61FFF723 +:103AC000D1FF58611A6942F040021A614FF4006157 +:103AD000FFF798FF00F034F9FFF7B4FF2046BDE888 +:103AE0001040FFF7CDBF002010BD00BF00200240F6 +:103AF0002DE9F84312F00103144606D01F4B40F2A3 +:103B0000F3221A600020BDE8F88385181C4A95420C +:103B100004D91A4A4FF43E711160F3E7FFF77CFFB6 +:103B2000FFF770FFDFF86880451A4FF00109012C9C +:103B300005EB01060F4603D8FFF784FF0120E2E7FB +:103B40003B88C8F8109033800020FFF75BFFC8F86F +:103B50001000338831F8022B9BB29A420CD0074BED +:103B600040F20F321A60074B1E60074B1C60074B78 +:103B70001F60FFF767FFC6E7023CD8E75C3A00200A +:103B800000000408503A0020583A0020543A00201F +:103B900000200240084908B50B7828B11BB9FFF78F +:103BA0003BFF01230B7008BD002BFCD0BDE8084093 +:103BB0000870FFF747BF00BF603A002008B54FF418 +:103BC00020414FF0005000F0BDF8BDE808404FF430 +:103BD00000514FF0805000F0B5B800000846114683 +:103BE00000F05EBE012000F05BBE0000084600F061 +:103BF00075BE000030B583B0FFF71EFE0E4B0F4DB3 +:103C0000DB692A684FF47A7101FB03F3934237BFF3 +:103C10000B4A0B49516814682B602EBFD1E9004153 +:103C2000013151601C1941F100010191FFF70EFEB5 +:103C30000199204603B030BD20380020643A0020AE +:103C4000683A002030B583B0FFF7F6FD114B124DF6 +:103C5000DB692A684FF47A7101FB03F3934237BFA3 +:103C60000E4A0E49516814682B602EBFD1E90041FD +:103C7000013151601C1941F100010191FFF7E6FD8E +:103C800001994FF47A7200232046FCF791FA03B0B1 +:103C900030BD00BF20380020643A0020683A002080 +:103CA00010B50244064BD2B2904200D110BD441C64 +:103CB00000B253F8200041F8040BE0B2F4E700BF73 +:103CC000502800400F4B30B51C6A240407D41C6AEE +:103CD00044F440741C621C6A44F400441C620A4CA4 +:103CE000236843F4807323600244084BD2B29042AD +:103CF00000D130BD441C00B251F8045B43F82050A1 +:103D0000E0B2F4E70010024000700040502800408C +:103D100007B5012201A90020FFF7C2FF019803B0F7 +:103D20005DF804FB13B50446FFF7F2FFA04205D08F +:103D3000012201A900200194FFF7C4FF02B010BDC9 +:103D4000704700007047000070470000074B45F2C5 +:103D500055521A6002225A6040F6FF729A604CF681 +:103D6000CC421A60024B01221A70704700300040AA +:103D7000743A0020034B1B781BB1034B4AF6AA226E +:103D80001A607047743A002000300040044B1A68F3 +:103D90002AB902F1804202F50432526A1A60704771 +:103DA000703A0020024B4FF080725A62704700BF99 +:103DB0000010024008B5FFF7E9FF024B1868C0F396 +:103DC000407008BD703A002070470000FEE7000018 +:103DD0000A4B0B480B4A90420BD30B4BDA1C121ABE +:103DE000C11E22F003028B4238BF00220021FDF7E2 +:103DF000A5BA53F8041B40F8041BECE7F44B000889 +:103E0000583C0020583C0020583C0020FEE70000B1 +:103E100070B51B4B01630025044686B0586085626F +:103E20000E46FFF7E1FB04F11003C4E904334FF041 +:103E3000FF33A361134BE561D969A5600A462B46A0 +:103E4000C4E9082304F13401C4E900440E4AE562E0 +:103E5000256580232046FFF709FD0123E0600B4A1A +:103E60000375009272680192B268CDE90223084B93 +:103E70006846CDE90435FFF721FD06B070BD00BFEF +:103E8000483A002020380020904A0008954A00084F +:103E90000D3E00084B6843608B688360CB68C3604D +:103EA0000B6943614B6903628B6943620B68036072 +:103EB0007047000008B51B4B9A6A42F4FC029A62F4 +:103EC0009A6A22F4FC029A629A6A5A6942F4FC02E3 +:103ED0005A61154A5B6911464FF09040FFF7DAFFCF +:103EE00002F11C0100F58060FFF7D4FF02F13801F8 +:103EF00000F58060FFF7CEFF02F1540100F580600D +:103F0000FFF7C8FF02F1700100F58060FFF7C2FF04 +:103F100002F18C0100F58060FFF7BCFFBDE80840AE +:103F200000F05AB8001002409C4A000808B500F0A2 +:103F300093F9FFF759FCBDE80840FFF727BF0000E1 +:103F40007047000010B5214CA36A63F4FC03A36220 +:103F5000A36A03F4FC03A3624FF0FF32A36A236950 +:103F600022612369002323612169E168E260E2683C +:103F7000E360E268E269164942F08052E261E26978 +:103F80000A6842F480720A60226A02F44072B2F552 +:103F9000407F1EBF4FF4803222622362236A1B04DB +:103FA00007D4236A43F440732362236A43F4004333 +:103FB000236200F031F9A369064A43F00103A361CB +:103FC000A369136843F02003136010BD0010024082 +:103FD00000700040000001401E4B1A6842F00102D0 +:103FE0001A601A689007FCD55A6822F003025A60DA +:103FF0005A6812F00C02FBD1196801F0F90119603E +:104000005A601A6842F480321A601A689103FCD52B +:10401000114A5A604FF40452DA6230221A631A6865 +:1040200042F080721A601A689201FCD50B49122284 +:104030000A600A6802F00702022AFAD15A6842F0BE +:1040400002025A605A6802F00C02082AFAD11A6B6E +:104050001A6370470010024000241D000020024037 +:10406000084A08B5516913680B4003F00103536116 +:1040700023B1054A13680BB150689847BDE8084062 +:10408000FFF7D6BA00040140783A0020084A08B584 +:10409000516913680B4003F00203536123B1054AD1 +:1040A00093680BB1D0689847BDE80840FFF7C0BAE5 +:1040B00000040140783A0020084A08B551691368A5 +:1040C0000B4003F00403536123B1054A13690BB19C +:1040D00050699847BDE80840FFF7AABA00040140BC +:1040E000783A0020084A08B5516913680B4003F07C +:1040F0000803536123B1054A93690BB1D06998470E +:10410000BDE80840FFF794BA00040140783A002067 +:10411000084A08B5516913680B4003F01003536156 +:1041200023B1054A136A0BB1506A9847BDE80840AD +:10413000FFF77EBA00040140783A0020174B10B513 +:104140005A691C68144004F478725A61A30604D5B5 +:10415000134A936A0BB1D06A9847600604D5104A97 +:10416000136B0BB1506B9847210604D50C4A936B27 +:104170000BB1D06B9847E20504D5094A136C0BB11B +:10418000506C9847A30504D5054A936C0BB1D06CCD +:104190009847BDE81040FFF74BBA00BF000401404C +:1041A000783A00201A4B10B55A691C68144004F480 +:1041B0007C425A61620504D5164A136D0BB1506DED +:1041C0009847230504D5134A936D0BB1D06D9847DA +:1041D000E00404D50F4A136E0BB1506E9847A1044A +:1041E00004D50C4A936E0BB1D06E9847620404D587 +:1041F000084A136F0BB1506F9847230404D5054A42 +:10420000936F0BB1D06F9847BDE81040FFF710BA1D +:1042100000040140783A0020062108B50846FFF75F +:1042200031FA06210720FFF72DFA06210820FFF7B3 +:1042300029FA06210920FFF725FA06210A20FFF7AF +:1042400021FA06211720FFF71DFABDE808400621D4 +:104250002820FFF717BA000008B5FFF773FE00F03B +:1042600067F800F03DF8FFF76BFEBDE8084000F08E +:104270005DB80000026843681143016003B118474C +:1042800070470000143000F02FBA00004FF0FF33E9 +:10429000143000F029BA0000383000F0A5BA000050 +:1042A0004FF0FF33383000F09FBA0000143000F0B8 +:1042B000F5B900004FF0FF31143000F0EFB9000005 +:1042C000383000F04FBA00004FF0FF32383000F0C5 +:1042D00049BA0000012914BF6FF013000020704795 +:1042E00000F06CB8044B03600023C0E90233436064 +:1042F00001230374704700BF444B000838B5C369FD +:1043000004460D461BB904210844FFF7B3FF2946B4 +:1043100004F1140000F0A6F9002806DA201D4FF47D +:104320000061BDE83840FFF7A5BF38BD00F00EB80A +:104330000023054A19460133102BC2E9001102F18E +:104340000802F8D1704700BF783A00204FF0E02310 +:10435000044A5A6100229A6107221A6108210B203F +:10436000FFF7A6B93F19010008B5302383F3118880 +:10437000FFF760FA002383F3118808BD08B5FFF743 +:10438000F3FFBDE80840FFF753B900000268436837 +:104390001143016003B1184770470000024A1368D7 +:1043A00043F0C0031360704700380140024A1368AD +:1043B00043F0C003136070470044004037B51D4C04 +:1043C0001D4D2046FFF78EFF009404F114001B4999 +:1043D0000023202200F038F92022009404F1380054 +:1043E000174B184900F0B2F9174BC4E91735174CB1 +:1043F0000C212520FFF746F92046FFF773FF04F153 +:104400001400134900940023202200F01DF904F148 +:104410003800104B10490094202200F097F90F4B00 +:104420000C212620C4E9173503B0BDE83040FFF762 +:1044300029B900BFF83A002000512502D03B0020E6 +:104440009D430008103C002000380140643B0020E0 +:10445000F03B0020AD430008303C00200044004009 +:104460002DE9F047C66D3768F469346221070546C7 +:1044700019D014F0080118BF4FF48071E20748BF4B +:1044800041F02001A30748BF41F04001600748BF49 +:1044900041F08001302383F31188281DFFF776FF58 +:1044A000002383F31188E2050AD5302383F31188B2 +:1044B0004FF48061281DFFF769FF002383F3118803 +:1044C0004FF030094FF0000A14F0200838D13B06B5 +:1044D00016D54FF0300905F1380A200610D589F3BA +:1044E0001188504600F066F9002836DA0821281DA8 +:1044F000FFF74CFF27F080033360002383F311881C +:10450000790614D5620612D5302383F31188D5E9D4 +:1045100013239A4208D12B6C33B11021281D27F0A8 +:104520004007FFF733FF3760002383F31188E3066A +:1045300019D5AA6E1369B3B1BDE8F04750691847A1 +:1045400089F31188B38C95F8641028461940FFF759 +:10455000D5FE8AF31188F469B6E780B2308588F316 +:104560001188F469B9E7BDE8F087000008B5034891 +:10457000FFF776FFBDE80840FFF75AB8F83A002089 +:1045800008B50348FFF76CFFBDE80840FFF750B8D7 +:10459000643B0020F8B5154682680669AA420B46BE +:1045A000816938BF8568761AB54204460BD2184631 +:1045B0002A46FCF7B1FEA3692B44A361A3685B1BE9 +:1045C000A3602846F8BD0CD918463246FCF7A4FE75 +:1045D000AF1BE1683A463044FCF79EFEE3683B447B +:1045E000EBE718462A46FCF797FEE368E5E700008C +:1045F00083689342F7B51546044638BF8568D0E90D +:104600000460361AB5420BD22A46FCF785FE636970 +:104610002B446361A36828465B1BA36003B0F0BD15 +:104620000DD932460191FCF777FE0199E068AF1B86 +:104630003A463144FCF770FEE3683B44E9E72A461A +:10464000FCF76AFEE368E4E710B50A440024C3619E +:10465000029B8460C0E90000C0E90511C1600261ED +:10466000036210BD08B5D0E90532934201D18268DA +:1046700082B98268013282605A1C42611970D0E9A5 +:1046800004329A4224BFC36843610021FFF748F90E +:10469000002008BD4FF0FF30FBE7000070B530236D +:1046A00004460E4683F31188A568A5B1A368A269E4 +:1046B000013BA360531CA36115782269934224BF78 +:1046C000E368A361E3690BB120469847002383F3B5 +:1046D0001188284607E031462046FFF711F90028E7 +:1046E000E2DA85F3118870BD2DE9F74F04460E46D6 +:1046F00017469846D0F81C904FF0300A8AF311887C +:104700004FF0000B154665B12A4631462046FFF7AB +:1047100041FF034660B941462046FFF7F1F8002803 +:10472000F1D0002383F31188781B03B0BDE8F08F2C +:10473000B9F1000F03D001902046C847019B8BF3CD +:104740001188ED1A1E448AF31188DCE7C0E90511CF +:10475000C160C3611144009B8260C0E90000016137 +:1047600003627047F8B504460D461646302383F3BE +:104770001188A768A7B1A368013BA36063695A1CAD +:1047800062611D70D4E904329A4224BFE368636118 +:10479000E3690BB120469847002080F3118807E0B9 +:1047A00031462046FFF7ACF80028E2DA87F311889B +:1047B000F8BD0000D0E905239A4210B501D1826806 +:1047C0007AB98268013282605A1C82611C7803695E +:1047D0009A4224BFC36883610021FFF7A1F82046F5 +:1047E00010BD4FF0FF30FBE72DE9F74F04460E46B2 +:1047F00017469846D0F81C904FF0300A8AF311887B +:104800004FF0000B154665B12A4631462046FFF7AA +:10481000EFFE034660B941462046FFF771F80028D5 +:10482000F1D0002383F31188781B03B0BDE8F08F2B +:10483000B9F1000F03D001902046C847019B8BF3CC +:104840001188ED1A1E448AF31188DCE70B460146F5 +:10485000184600F02DB8000000F040B8012838BF1D +:10486000012010B50446204600F030F830B900F0C1 +:1048700007F808B900F00CF88047F4E710BD000015 +:10488000024B1868BFF35B8F704700BF503C00209D +:1048900008B5062000F084F80120FFF7ABF800000F +:1048A000024B0A4601461868FFF798B91811002014 +:1048B00010B5054C13462CB10A4601460220AFF351 +:1048C000008010BD2046FCE700000000024B0146BE +:1048D0001868FFF787B900BF18110020024B014686 +:1048E0001868FFF783B900BF1811002010B501390F +:1048F0000244904201D1002005E0037811F8014FF5 +:10490000A34201D0181B10BD0130F2E72DE9F041A0 +:10491000A3B1C91A17780144044603F1FF3C8C4245 +:10492000204601D9002009E00578BD4204F10104C8 +:10493000F5D10CEB0405D618A54201D1BDE8F081F4 +:1049400015F8018D16F801EDF045F5D0E7E7000008 +:104950001F2938B504460D4604D9162303604FF0CD +:10496000FF3038BD426C12B152F821304BB92046AD +:1049700000F030F82A4601462046BDE8384000F0F5 +:1049800017B8012B0AD0591C03D11623036001204C +:10499000E7E7002442F82540284698470020E0E752 +:1049A000024B01461868FFF7D3BF00BF1811002063 +:1049B00038B5074D00230446084611462B60FFF723 +:1049C0001DF8431C02D12B6803B1236038BD00BF22 +:1049D000543C0020FFF70CB8034611F8012B03F8F4 +:1049E000012B002AF9D170476F72672E61726475CE +:1049F00070696C6F742E663330332D4D6174656B46 +:104A00004750530040A2E4F1646891060041A3E5D9 +:104A1000F2656992070000004261642043414E49FB +:104A20006661636520696E6465782E008000000011 +:104A30000080000000008000000000000000000076 +:104A40003D1B000821230008812200084D1B00089F +:104A5000811B00087D1D0008511B0008611B000818 +:104A6000551B00085D1B0008591B0008A51C000809 +:104A7000651B0008ED250008751B0008791C00085F +:104A800063300000804A000878380020483A00204F +:104A90006D61696E0069646C65000000A001A82A60 +:104AA00000000000FAAABEAA50001424EFFF000084 +:104AB00000770000709709000000A00000000000CF +:104AC000AAAAFAAA00005000FFFF000000000000A0 +:104AD000007700000000000000000000AAAAAAAAB7 +:104AE00000000000FFFF00000000000000000000C8 +:104AF0000000000000000000AAAAAAAA000000000E +:104B0000FFFF0000000000000000000000000000A7 +:104B100000000000AAAAAAAA00000000FFFF0000EF +:104B20000000000000000000000000000000000085 +:104B3000AAAAAAAA00000000FFFF000000000000CF +:104B40000000000000000000A14200088D420008A3 +:104B5000C9420008B5420008C1420008AD42000841 +:104B60009942000885420008D542000874B6FF7FCC +:104B70000100000000000000EC0300000000000045 +:104B80000098030000000000FE2A0100D20400008B +:104B90001C110020000000000000000000000000C8 +:104BA0000000000000000000000000000000000005 +:104BB00000000000000000000000000000000000F5 +:104BC00000000000000000000000000000000000E5 +:104BD00000000000000000000000000000000000D5 +:104BE00000000000000000000000000000000000C5 +:044BF00000000000C1 :00000001FF diff --git a/Tools/bootloaders/f303-PWM_bl.bin b/Tools/bootloaders/f303-PWM_bl.bin new file mode 100755 index 00000000000000..17ae202d0e3a8a Binary files /dev/null and b/Tools/bootloaders/f303-PWM_bl.bin differ diff --git a/Tools/bootloaders/f303-TempSensor_bl.bin b/Tools/bootloaders/f303-TempSensor_bl.bin new file mode 100755 index 00000000000000..928f635ffa6f97 Binary files /dev/null and b/Tools/bootloaders/f303-TempSensor_bl.bin differ diff --git a/Tools/bootloaders/f303-Universal_bl.bin b/Tools/bootloaders/f303-Universal_bl.bin index 2f1a162da54000..eb9bebcbb2aca6 100755 Binary files a/Tools/bootloaders/f303-Universal_bl.bin and b/Tools/bootloaders/f303-Universal_bl.bin differ diff --git a/Tools/bootloaders/f303-Universal_bl.elf b/Tools/bootloaders/f303-Universal_bl.elf index eaf00e309fdb53..711136577c2da2 100755 Binary files a/Tools/bootloaders/f303-Universal_bl.elf and b/Tools/bootloaders/f303-Universal_bl.elf differ diff --git a/Tools/bootloaders/f303-Universal_bl.hex b/Tools/bootloaders/f303-Universal_bl.hex index 0d4ea718064ac9..feb060e57e8088 100644 --- a/Tools/bootloaders/f303-Universal_bl.hex +++ b/Tools/bootloaders/f303-Universal_bl.hex @@ -1,980 +1,1217 @@ :020000040800F2 -:1000000000090020A5040008E1140008611400089C -:10001000B9140008611400088D140008A704000832 -:10002000A7040008A7040008A704000881350008F9 -:10003000A7040008A7040008A7040008B93A0008AC -:10004000A7040008A7040008A7040008A7040008E4 -:10005000A7040008A7040008513800087D380008EC -:10006000A9380008D538000801390008A70400089D -:10007000A7040008A7040008A7040008A7040008B4 -:10008000A7040008A7040008A70400082924000802 -:1000900095240008E92400083D2500082D390008B2 -:1000A000A7040008A7040008A7040008A704000884 -:1000B000A7040008A7040008A7040008A704000874 -:1000C000A7040008A7040008A7040008A704000864 -:1000D000A70400088129000895290008A704000842 -:1000E00095390008A7040008A7040008A704000821 -:1000F000A7040008A7040008A7040008A704000834 -:10010000A7040008A7040008A7040008A704000823 -:10011000A7040008A7040008A7040008A704000813 -:10012000A7040008A7040008A7040008A704000803 -:10013000A7040008A7040008A7040008A7040008F3 -:10014000A7040008A7040008A7040008A7040008E3 -:10015000A7040008A7040008A7040008A7040008D3 -:10016000A7040008A7040008A7040008A7040008C3 -:10017000A7040008A7040008A7040008A7040008B3 -:10018000A7040008A7040008A7040008A7040008A3 -:10019000A7040008A7040008A7040008A704000893 -:1001A00053B94AB9002908BF00281CBF4FF0FF31DE -:1001B0004FF0FF3000F074B9ADF1080C6DE904CEDA -:1001C00000F006F8DDF804E0DDE9022304B0704732 -:1001D0002DE9F047089D04468E46002B4DD18A42FA -:1001E000944669D9B2FA82F252B101FA02F3C2F12D -:1001F000200120FA01F10CFA02FC41EA030E9440BE -:100200004FEA1C48210CBEFBF8F61FFA8CF708FBDE -:1002100016E341EA034306FB07F199420AD91CEBB6 -:10022000030306F1FF3080F01F81994240F21C81E8 -:10023000023E63445B1AA4B2B3FBF8F008FB103330 -:1002400044EA034400FB07F7A7420AD91CEB040465 -:1002500000F1FF3380F00A81A74240F20781644435 -:10026000023840EA0640E41B00261DB1D4400023BA -:10027000C5E900433146BDE8F0878B4209D9002D1E -:1002800000F0EF800026C5E9000130463146BDE8A8 -:10029000F087B3FA83F6002E4AD18B4202D3824212 -:1002A00000F2F980841A61EB030301209E46002DC1 -:1002B000E0D0C5E9004EDDE702B9FFDEB2FA82F216 -:1002C000002A40F09280A1EB0C014FEA1C471FFA74 -:1002D0008CFE0126200CB1FBF7F307FB131140EA5B -:1002E00001410EFB03F0884208D91CEB010103F128 -:1002F000FF3802D2884200F2CB804346091AA4B2EA -:10030000B1FBF7F007FB101144EA01440EFB00FEBD -:10031000A64508D91CEB040400F1FF3102D2A64522 -:1003200000F2BB800846A4EB0E0440EA03409CE7C1 -:10033000C6F12007B34022FA07FC4CEA030C20FA6E -:1003400007F401FA06F31C43F9404FEA1C4900FA8E -:1003500006F3B1FBF9F8200C1FFA8CFE09FB18110B -:1003600040EA014108FB0EF0884202FA06F20BD97E -:100370001CEB010108F1FF3A80F08880884240F2CE -:100380008580A8F102086144091AA4B2B1FBF9F012 -:1003900009FB101144EA014100FB0EFE8E4508D90D -:1003A0001CEB010100F1FF346CD28E456AD9023892 -:1003B000614440EA0840A0FB0294A1EB0E01A14277 -:1003C000C846A64656D353D05DB1B3EB080261EBE5 -:1003D0000E0101FA07F722FA06F3F1401F43C5E9BF -:1003E000007100263146BDE8F087C2F12003D840F5 -:1003F0000CFA02FC21FA03F3914001434FEA1C4737 -:100400001FFA8CFEB3FBF7F007FB10360B0C43EA28 -:10041000064300FB0EF69E4204FA02F408D91CEBD8 -:10042000030300F1FF382FD29E422DD902386344D6 -:100430009B1B89B2B3FBF7F607FB163341EA034176 -:1004400006FB0EF38B4208D91CEB010106F1FF38C5 -:1004500016D28B4214D9023E6144C91A46EA0046BC -:1004600038E72E46284605E70646E3E61846F8E64E -:100470004B45A9D2B9EB020864EB0C0E0138A3E797 -:100480004646EAE7204694E74046D1E7D0467BE778 -:10049000023B614432E7304609E76444023842E7F0 -:1004A000704700BF02E000F000F8FEE772B63A487D -:1004B00080F30888394880F3098839484EF6085196 -:1004C000CEF20001086040F20000CCF200004EF6CF -:1004D0003471CEF200010860BFF34F8FBFF36F8F0E -:1004E00040F20000C0F2F0004EF68851CEF200015A -:1004F0000860BFF34F8FBFF36F8F4FF00000E1EE46 -:10050000100A4EF63C71CEF200010860062080F31E -:100510001488BFF36F8F03F0B3F803F08FF803F084 -:10052000C1F84FF055301F491B4A91423CBF41F87A -:10053000040BFAE71C49194A91423CBF41F8040BED -:10054000FAE71A491A4A1B4B9A423EBF51F8040B6C -:1005500042F8040BF8E700201749184A91423CBFC3 -:1005600041F8040BFAE703F06DF803F0D7F8144CE8 -:10057000144DAC4203DA54F8041B8847F9E700F045 -:1005800041F8114C114DAC4203DA54F8041B884772 -:10059000F9E703F055B80000000900200011002021 -:1005A000000000080001002000090020003D0008B4 -:1005B00000110020201100202011002028260020FA -:1005C000A0010008A0010008A0010008A001000887 -:1005D0002DE9F04F2DED108AC1F80CD0C3689D466F -:1005E000BDEC108ABDE8F08F002383F31188284604 -:1005F000A047002002F04CFDFEE702F0D1FC00DF36 -:10060000FEE700002DE9F04102F062FF074602F02C -:10061000ADFF054600283ED12B4B9F423BD0013316 -:100620009F423BD0294B27F0FF029A423AD1F8B2C1 -:1006300000F054FAA84642F2107400F059FC08B1D8 -:100640000024A04600F050FA064678B384BB464624 -:1006500035B11F4B9F4203D002F080FF0024264695 -:10066000002002F03FFF1B4B1B6913F0400322D018 -:100670000EB100F031F800F05FFC00F031FE00F048 -:1006800031FF0546CCB100F02DFF401BA04214D92C -:1006900000F022F8F3E7A8460024CEE704464FF026 -:1006A0000108CAE780464FF47A74C6E70446CFE7EC -:1006B0004FF47A74CCE71C46DDE700F0DDFC012046 -:1006C00002F0ECFCDEE700BF010007B0000008B05C -:1006D000263A09B00004004838B51D4A1D4B196878 -:1006E000013134D004339342F9D11B4C194DD4F865 -:1006F0000428AA422BD3194B9B6803F1006303F52E -:10070000D0439A4223D202F0FDFE02F00FFF0020F8 -:1007100000F000FE124B0220187000F037FE114B63 -:10072000DA690022DA61D96999699A619B6972B6BE -:100730004FF0E0232021C3F8085DD4F80038D4F846 -:10074000042881F311889D4683F30888104738BD3B -:100750002068000800680008006000080011002000 -:100760002011002000100240094A136849F2690074 -:1007700099B21B0C00FB01331360064B186844F25E -:10078000506182B2000C01FB0200186080B2704719 -:100790001C1100201811002010B500211022044661 -:1007A00000F00EFE034B03CB206061601868A06070 -:1007B00010BD00BFACF7FF1F2DE9F043224DBBB0C9 -:1007C00000F090FEAB6840F2ED22C31A934232D99A -:1007D00006AFA8602B4628220021384601F05EFBB8 -:1007E00005F10E0000F0E4FD002604465FFA80F9F2 -:1007F00005F10E08F3B2F100994501F1280107D97E -:1008000008EB06030822384601F048FB0136F1E701 -:1008100008230122CDE9023205340C4B0193A4B226 -:1008200030230093CDE9047405A3D3E90023297B89 -:10083000074801F04BF93BB0BDE8F083AFF300800F -:1008400078F6339F93CACD8D682100207521002052 -:100850003C21002070B50D4614461E4601F0CCF830 -:1008600050B9022E10D1012C0ED112A3D3E90023CE -:10087000C5E90023012007E0282C10D005D8012C61 -:1008800009D0052C0FD0002070BD302CFBD10BA35C -:10089000D3E90023ECE70BA3D3E90023E8E70BA39C -:1008A000D3E90023E4E70BA3D3E90023E0E700BF8B -:1008B000AFF30080401DA12026812A0B78F6339FDC -:1008C00093CACD8D9E6AC421818A46EE26417272FA -:1008D000DF25D7B7F017304A39059E5613B50446C1 -:1008E0002346084620220021019001F0D7FA227900 -:1008F0000198032A234628BF032203F8042F20214E -:10090000022201F0CBFA62790198072A234628BF18 -:10091000072203F8052F2221032201F0BFFAA27952 -:100920000198072A234628BF072203F8062F25210E -:10093000032201F0B3FA019804F1080310222821E0 -:1009400001F0ACFA382002B010BD00002DE9F04FE4 -:10095000ADF5037D23AD10AE40F2751280460F4613 -:1009600024A80021296000F02BFD482200213046F8 -:1009700000F026FD00F0B6FD564B4FF47A72B0FB46 -:10098000F2F0186093E80700012386E807000DF1F4 -:1009900062003382FFF700FF4EF60343338407AB58 -:1009A00018464D4903F0C2F82122306429463046EA -:1009B00086F83C20FFF792FF14AB0446014608225C -:1009C000284601F06BFA0822A1180DF151032846C0 -:1009D00001F064FA0DF15203082204F110012846D7 -:1009E00001F05CFA15AB202204F11801284601F051 -:1009F00055FA16AB402204F13801284601F04EFAB0 -:100A000018AB082204F17801284601F047FA0DF1ED -:100A10006103082204F18001284601F03FFA04F145 -:100A2000880A0DF1620904F5847B4B465146082281 -:100A300028460AF1080A01F031FAD34509F1010903 -:100A4000F3D11DAB08225946284601F027FA04F5D8 -:100A500088744FF0000996F834304B450AD9B36BCF -:100A600021464B440822284601F018FA083409F1BF -:100A70000109F0E74FF0000996F83C304B4504EBD4 -:100A8000C90108D9336C08224B44284601F006FA04 -:100A900009F10109F0E700230393BB7E02930731BC -:100AA00007F119030193C1F3CF010123CDE90451EB -:100AB0000093F97E05A3D3E90023404601F006F830 -:100AC0000DF5037DBDE8F08FAFF300809E6AC42171 -:100AD000818A46EE241100203C3B0008014B18702F -:100AE000704700BF30110020F0B5334B1C7B85B040 -:100AF00034B1324B0E221A810024204605B0F0BDDD -:100B00002F4A1068516802AB03C308232D492E48B1 -:100B10000DEB030202F0E8FF054630B9274B2B48E6 -:100B20000A221A8100F098FCE6E70169B1F5663FF8 -:100B300006D9224B26480B221A8100F08DFCDCE7F7 -:100B4000438BB3F57B7F09D01C4A22480C211181CD -:100B50004FF47B72194600F07FFCCEE71E4A024438 -:100B600002F11003994204D2144B1C4810221A813E -:100B7000E3E710398E1A2046134900F0B7FC3246DD -:100B8000074605F11801204600F0B0FCAB689F4213 -:100B900002D1EB6898420AD0084B0D221A810090CE -:100BA000D5E902123B460E4800F056FCA4E70D487A -:100BB00000F052FC0124A0E768210020241100204D -:100BC000F13B0008DC97030000680008603B000868 -:100BD0006C3B00087E3B00080898FFF79C3B000830 -:100BE000B93B0008E23B00082DE9F04FADB006AF7D -:100BF00080460C4600F000FF054600285AD1237EAF -:100C0000022B1BD1E38A012B18D100F06BFC0646A6 -:100C1000FFF7AAFD03464FF4C870DFF8D092B3FB8C -:100C2000F0F206F5167602FB103316FA83F3C9F8D4 -:100C30000030E37E33B9A84B00221A709C37BD46C2 -:100C4000BDE8F08FA38AEEB2013BB34205F1010586 -:100C50000BD93B1D1E44E90000960023082201F039 -:100C6000F801204600F0DEFFECE707F11400FFF783 -:100C700093FD324607F11401381D02F025FF0028CC -:100C8000D9D10F2E08D8944B1E70D9F80030A3F597 -:100C90001673C9F80030D1E7FB1CF87001460093C9 -:100CA00007220346204600F0BDFFF978404600F0D9 -:100CB0009BFEC3E7E38A282B26D010D8012B1ED039 -:100CC000052BBBD1BFF34F8F8449854BCA6802F413 -:100CD000E0621343CB60BFF34F8F00BFFDE7302BC3 -:100CE000ACD1637E7F4D01336A7BDBB29342E94630 -:100CF00003D1E27E2B7B9A4265D0CD469EE721460A -:100D00004046FFF723FE99E7A38A013B9BB2C92B1C -:100D100094D8744D2E7B26BB05F10C03009308225A -:100D200033463146204600F07DFF731CF2B2D900F5 -:100D30001E46A38A013B9A4205DA0E322A440092EB -:100D400000230822EEE700230022C5E90023002348 -:100D5000AB6085F8D730C5F8D8302B7B0BB9E37E74 -:100D60002B73002507F114093B1D0822294648462C -:100D7000C7E90155FD6001F091F83B7A05F1010AE0 -:100D8000AB424FEACA0608D9FB6808222B44314619 -:100D9000484601F083F85546EFE7C6F3CF06E17EFB -:100DA000CDE9049600230393A37E029319342823EC -:100DB0000093019446A3D3E90023404600F086FE49 -:100DC000FFF7FAFC3AE74FF0000807F11403A7F821 -:100DD00014801022009341460123204600F022FF98 -:100DE000A68A023EB6B2F31C9B109B000733DB08B9 -:100DF000A9EBC3039D460DF1180A1FFA88F34FEAC9 -:100E0000C801B34201F110010AD20AEB08030093B2 -:100E100008220023204600F005FF08F10108ECE756 -:100E200095F8D70000F080FAD5F8D83004461BB901 -:100E300095F8D70000F088FAD5F8D83033449C42B2 -:100E400004D295F8D700013000F07EFA4FEA960BF5 -:100E50004FF000081FFA88F18B45D5E9003209D917 -:100E60000AEB880103EB8800012200F0B1FA08F1D7 -:100E70000108EFE7F31842F10002C5E90032D5F8A6 -:100E8000D83095F8D70006EB0308C5F8D88000F0F5 -:100E90004BFA804509D395F8D730D5F8D8000133FF -:100EA000001B85F8D730C5F8D800FF2E08D80023DE -:100EB0002B7300F05BFAFFF717FE08B1FFF70CFC8D -:100EC0002B68094A9B0A013313810023AB6014E7A6 -:100ED00026417272DF25D7B73521002000ED00E0F2 -:100EE0000400FA0568210020241100203821002088 -:100EF00010B54FF000540C4B22689A4211D10B4BA5 -:100F0000627D1A700A48237D03730A49C9220E3094 -:100F100000F044FAE0220021204600F051FA0120BE -:100F200010BD0020FCE700BF9AAD44C53011002081 -:100F300068210020160000202DE9FF41434C0223C8 -:100F400063710023029324250A23581EB5FBF3F690 -:100F50007343D3F12402C1B23ED002280346F4D138 -:100F60009DF80B303A493B485A1E9DF80A30013B28 -:100F70001B0443EA0253BDF80820013A13434B60B7 -:100F800001F044FD00230193334B3449009334486E -:100F9000344B4FF4805200F001FD334B197811B1FE -:100FA0002F4800F021FD00F09DFA0546FFF7DCFB1D -:100FB0004FF4C873B0FBF3F202FB130305F5167090 -:100FC00010FA83F0294B186002F0D0FA08B10F2311 -:100FD000238104B0BDE8F081C1EBC107FB1C4FEADF -:100FE000E30EC3F3C703A1EB030C0EF101084FF4AA -:100FF0007A705FFA8CF50EFB000058FA8CFCB0FB9F -:10100000FCF0B0F5617F07D97B1EC3F3C703C91A93 -:10101000CDB2591E0F2916D86A1E072A8CBF00228E -:101020000122591901FB06601149B1FBF0F1114889 -:10103000814295D1002A93D0ADF808608DF80A302E -:101040008DF80B508CE71346EBE700BF241100200E -:1010500010110020802200205508000834110020C3 -:101060003C210020E90B000830110020382100202D -:101070000051250240420F002DE9F04F90A7D7E91B -:1010800000670FF24429D9E90089874D93B0DFF852 -:1010900040B2864C284600F07DFD0DF1300A0790E5 -:1010A00070B310220021504600F08AF9079B197B8B -:1010B0004FF0000261F303028DF830205868996800 -:1010C0000EAA03C21B680D9A63F31C029DF8303010 -:1010D0000D9243F020038DF830300023524619461C -:1010E000584601F0A3FC079028B9284600F056FDA9 -:1010F000079B2370CEE72378072B3CD8013323705E -:1011000018220021504600F05BF9DFF8C4B100233B -:1011100019465246584601F0B1FC014678BB1022F0 -:1011200008A800F04DF94FF0904209AC536983F0E4 -:101130001003536100F0D8F90B4612A9024611E9D9 -:10114000030084E803009DF83410C1F3030089060E -:101150004CBF0E9CBDF838408DF82C0046BFC4F340 -:101160001C0444F00044C4F30A0408A92846089467 -:1011700000F0DCFECBE7284600F010FDC0E7284673 -:1011800000F03AFC0446002848D1DFF848B100F0EE -:10119000A9F9DBF80030984240D300F0A3F907909A -:1011A000FFF7E2FA079A8DF8204003464FF4C87023 -:1011B00002F51672B3FBF0F101FB103312FA83F360 -:1011C000CBF80030DFF810B19BF8001011B9012303 -:1011D0008DF8203050460791FFF7DEFA0799C1F1EC -:1011E0001004E4B2062C28BF0624224651440DF117 -:1011F000210000F0D3F808AB0393182302930134C5 -:101200002B4B0193E4B20123009304943B463246F6 -:10121000284600F0F3FB00238BF8003000F062F961 -:10122000244A254C1368C31AB3F57A7F31D3106072 -:1012300000F05AF902460B46284600F0B9FC284651 -:1012400000F0DAFB28B3237BDFF890B0002B14BF4B -:10125000032302238BF8053000F044F94FF47A732E -:101260005146B0FBF3F0CBF800005846FFF736FBD1 -:10127000182307300293114B0193C0F3CF0040F2C3 -:101280005513CDE903A0009342464B46284600F093 -:10129000B5FB237B2BB1FFF78FFA237B002B7FF469 -:1012A000F6AE13B0BDE8F08F3C2100204D220020A7 -:1012B0003421002048220020682100204C220020F8 -:1012C000401DA12026812A0BF1C6A7C1D068080FB6 -:1012D0008022002038210020352100202411002008 -:1012E00070B501F0B5FF094E094D30800024286823 -:1012F0003388834208D901F0A7FF2B6804440133E7 -:10130000B4F5D04F2B60F2D370BD00BF7C2200201B -:101310005022002002F03AB800F10060920000F57F -:10132000D04001F0D5BF0000054B1A68054B1B8863 -:101330009B1A834202D9104401F086BF00207047F7 -:10134000502200207C22002038B5074D0446286832 -:10135000204401F07FFF28B928682044BDE83840C8 -:1013600001F08ABF38BD00BF50220020064991F825 -:10137000243033B10023086A81F824300822FFF7B3 -:10138000CBBF0120704700BF54220020022802BFBB -:101390004FF090434FF480129A61704710B50023CC -:1013A000934203D0CC5CC4540133F9E710BD000074 -:1013B00003460246D01A12F9011B0029FAD17047E0 -:1013C00002440346934202D003F8011BFAE7704738 -:1013D0002DE9F8431F4D144695F82420074688460A -:1013E00052BBDFF870909CB395F824302BB92022C3 -:1013F000FF2148462F62FFF7E3FF95F82400C0F174 -:101400000802A24228BF2246D6B24146920005EB0E -:101410008000FFF7C3FF95F82430A41B1E44F6B2EA -:10142000082E17449044E4B285F82460DBD1FFF71E -:101430009DFF0028D7D108E02B6A03EB820383428B -:10144000CFD0FFF793FF0028CBD10020BDE8F88371 -:101450000120FBE7542200200FB4002004B07047A5 -:1014600000B59BB0EFF3098168226846FFF796FF4D -:10147000EFF30583044B9A6BDA6A9A6A9A6A9A6A5E -:101480009A6A9A6A9B6AFEE700ED00E000B59BB09D -:10149000EFF3098168226846FFF780FFEFF30583C9 -:1014A000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6ACF -:1014B000FEE700BF00ED00E000B59BB0EFF309814F -:1014C00068226846FFF76AFFEFF30583034B5A6B08 -:1014D0009A6A9A6A9A6A9A6A9B6AFEE700ED00E045 -:1014E000FEE7000001F08EBF01F064BF30B5094D8A -:1014F0000A4491420DD011F8013B5840082340F3B3 -:101500000004013B2C4013F0FF0384EA5000F6D1A5 -:10151000EFE730BD2083B8ED2DE9F041C56915B97D -:10152000C161BDE8F0814B6823F06047C3F38A4690 -:101530004FEAD37EC3F3807816EA230638BF3E46CF -:10154000AC462B465A68BEEBD27F22F060440AD0EC -:10155000002A18DAA40CB44217D19D420FD10D60B5 -:10156000DEE71346EEE7A74207D102F08044C2F35C -:10157000807242450BD054B1EFE708D2EDE7CCF8CA -:1015800000100B60CDE7B44201D0B442E5D81A6830 -:101590009C46002AE5D11960C3E700002DE9F04719 -:1015A000089D01F007044FEAD508224405F007051D -:1015B00000EBD1004FF47F49944201D1BDE8F087A0 -:1015C00004F0070705F0070A57453E4638BF564660 -:1015D000C6F10806111B8E4228BF0E46E10808EB33 -:1015E000D50E415C13F80EC0B94029FA06F721FA6E -:1015F0000AF1FFB28CEA010147FA0AF739408CEA96 -:10160000010C03F80EC034443544D5E780EA0120CC -:10161000082341F2210201B24000002980B203F107 -:10162000FF33B8BF504013F0FF03F4D17047000000 -:1016300038B50C468D18A54200D138BD14F8011BF1 -:10164000FFF7E4FFF7E7000002684AB113680360A0 -:10165000C388018901339BB29942C38038BF03819B -:101660001046704770B588B0202204460D46684683 -:101670000021FFF7A5FE20460495FFF7E5FF02468F -:1016800058B16B46054608AE1C4603CCB4422860F0 -:101690006960234605F10805F6D1104608B070BD13 -:1016A000082817D909280CD00A280CD00B280CD0F0 -:1016B0000C280CD00D280CD00E2814BF4020302050 -:1016C00070470C2070471020704714207047182076 -:1016D0007047202070470000082817D90C280CD923 -:1016E00010280CD914280CD918280CD920280CD96A -:1016F00030288CBF0F200E207047092070470A2029 -:1017000070470B2070470C2070470D207047000079 -:1017100010B54B6823B9CA8A63F30902CA8210BDA7 -:10172000C4681A681C60C360438A013B43824A60F4 -:10173000EFE700002DE9F84F1D46CB8A0F46C3F3B3 -:1017400009010629814692460B4630D00020AAB2F4 -:1017500007F119049EB2052E1FFA80F80FD89045A4 -:1017600003F1010306D3FB8A0A4462F30903FB82F7 -:1017700001201AE01AF80060E6540130EAE79045CB -:10178000F1D2A1F1060B1C237C68BBFBF3F203FB37 -:1017900012BB1FFA8BF6002C45D14846FFF754FFC9 -:1017A000044638B978606FF00200BDE8F88F4FF05A -:1017B0000008E6E7002606607860ADB24FF0000B47 -:1017C000454510D90AEB0803221D13F8011B91555A -:1017D000B1B208F101081B291FFA88F82BD0454542 -:1017E00006F10106F1D8FB8AC3F30902154465F33B -:1017F0000903BCE7013292B21C462368002BF9D1E1 -:10180000AB1F0B441C21B3FBF1F301339BB29A4293 -:10181000D3D2BBF1000FD0D14846FFF715FF20B956 -:10182000C4F800B0BFE70122E7E7C0F800B05E46A9 -:1018300020600446C1E74545D5D94846FFF704FF77 -:1018400008B92060AFE7C0F800B000262060044669 -:10185000B6E700002DE9F04F2DED028B83B0CDE906 -:101860000013BDF83C5007469146002A00F09280D4 -:101870002DB10E9B002B00F08D80072D32D807F183 -:101880000C00FFF7E1FE044638B96FF00204204671 -:1018900003B0BDEC028BBDE8F08F14220021FFF7EE -:1018A0008FFD0E992A4604F10800FFF777FD681CAA -:1018B000C0B2FFF711FFFFF7F3FE207499F8003074 -:1018C000013814FA80F003F01F0363F03F03037242 -:1018D000009B43F00041616038462146FFF71CFE43 -:1018E0000124D4E700F10C034FF0000808EE103A91 -:1018F0004FF0800A4646444618EE100AFFF7A4FE51 -:1019000083460028C1D014220021FFF759FDC6BB31 -:10191000019BABF8083002200E9B00F108029919D8 -:101920005BFA82F20130C0B2082801D0AE422AD35D -:10193000FFF7D2FEFFF7B4FE99F80020009B411E8E -:1019400002F01F0242EA4812AE4208BF4FF0400ABE -:101950005BFA81F14AEA020A43F0004281F808A0EA -:101960008BF81000CBF8042059463846FFF7D4FD19 -:101970000134AE4224B288F001084FF0000ABBD116 -:1019800085E70020C8E711F801CB02F801CB01364A -:10199000B6B2C7E76FF0010479E70000F8B5154665 -:1019A0000E462822002104461F46FFF709FD069B2C -:1019B0006360B5F5001F079BA76034BF6A094FF647 -:1019C000FF72236204F10C0097B200239A4205D8FB -:1019D0000023036027826382A382F8BD066001337F -:1019E00030462036F2E7000003781BB94BB2002BDB -:1019F000C8BF017070470000007870472DE9F74FAD -:101A0000DDF83C90BDF830500D9E9DF83840BDF893 -:101A10004070804692469B46B9F1000F01D1002FDD -:101A200051D11F2C4FD898F80000B0B9072F47D8D4 -:101A300035F0030347D13A4649464FF6FF70FFF7AA -:101A4000F7FD20F001002D02400445EA0464400C3B -:101A500044EA40244FF6FF7321E040EA0520072FB7 -:101A600040EA0464F6D900254FF6FF73C5F1200063 -:101A7000A5F120022AFA05F10BFA00F001432BFA36 -:101A800002F211431846C9B2FFF7C0FD0835402DD8 -:101A90000346EBD13A464946FFF7CAFD0346CDE976 -:101AA0000097324621464046FFF7D4FE3378013393 -:101AB000DBB21F2B88BF0023337003B0BDE8F08F6B -:101AC0006FF00300F9E76FF00100F6E72DE9F04F42 -:101AD00085B09246DDF848800F9D9DF840209DF826 -:101AE0004490BDF84C7006469B46B8F1000F01D1FA -:101AF000002F48D11F2A46D83378002B46D00C023D -:101B000044EA02649DF8381044EAC93444EA0144C6 -:101B10001C43072F44F0800432D900234FF6FF7294 -:101B2000C3F1200CA3F120002AFA03F10BFA0CFCFC -:101B300041EA0C012BFA00F00143C9B210460393AD -:101B4000FFF764FD039B0833402B0246E8D13A4679 -:101B50004146FFF76DFD0346CDE900872A46214641 -:101B60003046FFF777FEB9F1010F06D12B7801332C -:101B7000DBB21F2B88BF00232B7005B0BDE8F08FB0 -:101B80004FF6FF73E8E76FF00100F6E76FF0030030 -:101B9000F3E70000C06900B104307047C3691A68F8 -:101BA000C261C2681A60C360438A013B43827047C6 -:101BB0002DE9F041D0F81880194E14461D464146D3 -:101BC000002709B9BDE8F081D1E90223A21A65EB2B -:101BD0000303964277EB03031ED283698B420DD138 -:101BE000FFF796FD83691B688361C3680B60438AB6 -:101BF000C1608169013B43828846E2E7FFF788FDC7 -:101C00000B68C8F80030C3680B60438AC160013BB1 -:101C10004382D8F80010D4E788460968D1E700BFAE -:101C200080841E002DE9F04F8BB00D46DDF85090FA -:101C300014469B468046002800F01981B9F1000F38 -:101C400000F01581531E3F2B00F21181012A03D1B0 -:101C5000BBF1000F40F00B810023CDE90833B8F849 -:101C60001430B5EBC30F4FEAC30703D300200BB00A -:101C7000BDE8F08F2B199F42D8F80C303ABF7F1B7C -:101C8000FFB227461BB9D8F81030002B7AD02F2D81 -:101C90004ED8C5F13006B7424FF000032CBFF6B264 -:101CA0003E4600932946D8F8080008AB3246FFF7B5 -:101CB00075FCA7EB060A35445FFA8AFAB8F81430C7 -:101CC00003F10053063BDB000493D8F80C30039378 -:101CD0003021039B13B1BAF1000F2CD1D8F81000BA -:101CE00040B1BAF1000F05D0009608AB5246691A10 -:101CF000FFF754FC38B2002FB8D066070AD00AAB01 -:101D000003EBD401624211F8083C02F007021341D0 -:101D100001F8083C082C3CD9102C40F2B580202C4E -:101D200040F2B780BBF1000F00F09C80082334E044 -:101D3000BA460026C2E7049BE02B28BFE0230693A7 -:101D40000B44AB42059314D95A1B03980096924555 -:101D500034BF5246D2B2691A08AB04300792FFF77B -:101D60001DFC079A1644AAEB020A1544F6B25FFA64 -:101D70008AFA049B069A05999B1A0493039B1B6895 -:101D80000393A6E70093D8F8080008AB3A46294623 -:101D9000AEE7BBF1000F13D00123B4EBC30F6CD03F -:101DA000082C12D89DF82030621E23FA02F2D507C3 -:101DB00006D54FF0FF3202FA04F423438DF82030A9 -:101DC0009DF8203089F8003051E7102C12D8BDF86A -:101DD0002030621E23FA02F2D10706D54FF0FF32FF -:101DE00002FA04F42343ADF82030BDF82030A9F8FE -:101DF00000303CE7202C0FD80899631E21FA03F32A -:101E0000DA0705D54FF0FF3202FA04F40C430894C8 -:101E1000089BC9F800302AE7402C2BD0DDE9086583 -:101E2000611EC4F12102A4F1210326FA01F105FA91 -:101E300002F225FA03F311431943CB0712D501220D -:101E4000A4F12003C4F1200102FA03F322FA01F104 -:101E5000A240524243EA010363EB430332432B4364 -:101E6000CDE90823DDE90823C9E90023FFE66FF087 -:101E70000100FCE66FF00800F9E6082CA0D9102C50 -:101E8000B3D9202CEED8C3E7BBF1000FADD00223AD -:101E900083E7BBF1000FBBD004237EE730B5012AF6 -:101EA000144638BF0124402C85B028BF40240025AB -:101EB000012ACDE9025518D81B788DF80830630740 -:101EC0000AD004AB03EBD405624215F8083C02F0DB -:101ED0000702934005F8083C009103462246002182 -:101EE00002A8FFF75BFB05B030BD082AE4D9102A31 -:101EF00003D81B88ADF80830E1E7202A8DBFD3E96D -:101F000000231B680293CDE90223D8E710B5CB6804 -:101F10001BB98B600B618B8210BDC4681A681C6092 -:101F2000C360438A013B4382CA60F0E72DE9F04F6A -:101F3000D1F8008093B018F0800FCDE90323C8F3E7 -:101F4000C01219BFC8F3C03BC8F306264FF0020BFE -:101F50001646B8F1000F04460D4680F2D18118F004 -:101F6000C043059340F0CC810B7B002B00F0C8816F -:101F7000BBF1020F03D00178B14240F0C48108F0F8 -:101F80007F0106916AB3C8F3074A2B44069A93F877 -:101F90000390760646EA0B4646EA82465FEAD91384 -:101FA00046EA0A06079300F0908000220023CDE95C -:101FB0000A23069B009367685B4652460AA920469F -:101FC000B84700287ED0A7699FB9314604F10C00BC -:101FD000FFF748FB0746E0B96FF0020013B0BDE819 -:101FE000F08FC8F30F2A18F07F0F08BF0AF0030A1A -:101FF000CBE73B699E420DD03F68002FF9D13146B7 -:1020000004F10C00FFF72EFB07460028E4D0A3697B -:102010003B60A761DDE90A2300264FF6FF70C6F199 -:10202000200E22FA06F103FA0EFEA6F1200C23FA86 -:102030000CFC41EA0E0141EA0C01C9B208360992D2 -:102040000893FFF7E3FA402EDDE90832E7D1B882C2 -:10205000FB7D09F01F06C3F384039B1BD7E9022114 -:1020600098B2002BBCBF00F120031BB252EA010062 -:10207000C8F304680FD00398821A049860EB01013A -:10208000A74890424FF000028A4104D3079A002AE1 -:102090005BD0012B23DDFA7D4FEA890302F00302B6 -:1020A00003F07C031343FB7539462046FFF730FBF2 -:1020B000079BA3B9FB7DC3F38402013262F386035D -:1020C000FB7504E06FF00B0088E7A76917B96FF0A4 -:1020D0000C0083E73B699E42BAD03F68F6E719F0EF -:1020E000400F32D0039BBB60049BFB601422002195 -:1020F0000DA8FFF765F9039B0A93049B0B932B1D17 -:102100000C932B7BADF83EA0013BDBB2ADF83C302D -:10211000069B8DF8433094F824308DF840B083F05E -:1021200001038DF844308DF84160A3688DF842803A -:102130000AA920469847FB7DC3F38403013303F0CB -:102140001F039B02FB82002048E7FB7DC9F340127E -:10215000B2EBD31F40F0DA80C3F38403B34240F004 -:10216000D88007992B7B4FEA9912002934D0D207E7 -:1021700041D4032B40F2D080039BBB60049BFB60E7 -:102180002B7BAE1D033BDBB23246394604F10C001B -:10219000FFF7D0FA00280DDA20463946FFF7B8FAE3 -:1021A000FB7DC3F38403013303F01F039B02FB8217 -:1021B000032013E7AB883B832A7B033AB88AD2B269 -:1021C0003146FFF735FAFB7DB882DA43C2F3C0121D -:1021D00062F3C713FB75B6E76AB92E1D013BDBB28C -:1021E0003246394604F10C00FFF7A4FA0028D3DB8D -:1021F0002A7B013AE2E7F98AC1F30901013B05298B -:10220000DAB259D8281D002307F11A0C9A4208D9CE -:1022100010F801EB0CF801E0013101330629DBB2C3 -:10222000F4D103990A9104990B91934207F11A0191 -:102230000C9138BF043379680D9134BF55FA83F39C -:1022400000230E93FB8AADF83EA0C3F309031A44A2 -:10225000069B8DF8433094F82430ADF83C2083F091 -:1022600001038DF8443000238DF840B08DF84160B3 -:102270008DF842807B602A7BB88A013A291DFFF7DE -:10228000D7F93B8BB882834203D1A3680AA92046C1 -:10229000984720460AA9FFF739FEFB7DB88AC3F3A9 -:1022A0008403013303F01F039B02FB823B8B9842A4 -:1022B00014BF1120002091E67B68002BB1D00620CE -:1022C00001E01C306346D3F800C0BCF1000FF8D128 -:1022D000091A081D05F1040C00EB030905989DF887 -:1022E000143001EB000EBEF11B0F9AD89A4298D918 -:1022F0001CF8013B09F8013B059B01330593EDE711 -:102300006FF009006AE66FF00A0067E66FF00D00F3 -:1023100064E66FF00E0061E66FF00F005EE600BF4E -:1023200080841E00F0B53D4D3D4FEB6943F00073D6 -:10233000EB61EB693B4B9B6AD3F800623E4046F091 -:102340000106C3F80062D3F800423C4044EA002092 -:1023500040F00100C3F80002002951D00020C3F86A -:102360001C020646C3F80402C3F80C02C3F81402A8 -:1023700003EBC00401300E28C4F84062C4F8446284 -:10238000F6D100274FF0010C9678148816F0010F53 -:1023900018BFD3F804E20CFA04F01CBF40EA0E0E9A -:1023A000C3F804E216F0020F1EBFD3F80CE240EAB5 -:1023B0000E0EC3F80CE2760742BFD3F81462064350 -:1023C000C3F8146203EBC4045668C4F8406296680C -:1023D000C4F84462D3F81C4201372043B942C3F821 -:1023E0001C0202F10C02CFD1D3F8002222F001022C -:1023F000C3F80022EB6923F00073EB61EB69F0BDD9 -:102400000122C3F84012C3F84412C3F80412C3F8FF -:102410001412C3F80C22C3F81C22E5E70010024096 -:102420000000FFFF80220020184A916A08B58B68DF -:102430008B6013F0010104D013F00C0F18BF4FF4A0 -:102440008031D80506D513F4406F14BF41F4003134 -:1024500041F00201D80306D513F4402F14BF41F414 -:10246000802141F00401D3690BB10848984720232B -:1024700083F311880648002100F038FE002383F31F -:102480001188BDE8084001F0AFB800BF80220020ED -:102490008822002038B5124CA36ADD68AA0712D042 -:1024A0005A6922F002025A61A36913B10121204640 -:1024B0009847202383F311880A48002100F016FE74 -:1024C000002383F31188EB0606D5A36A1021D96097 -:1024D000236A0BB102489847BDE8384001F084B840 -:1024E000802200209022002038B5124CA36A1D697A -:1024F000AA0712D05A6922F010025A61A36913B1D7 -:10250000022120469847202383F311880A4800219E -:1025100000F0ECFD002383F31188EB0606D5A36AD7 -:1025200010211961236A0BB102489847BDE8384071 -:1025300001F05AB8802200209022002038B50F4CBC -:10254000A36A5D685D602A070AD5042222701A68B2 -:1025500022F002021A60636A13B1002120469847F4 -:102560006B0706D5A36A9969236A13B10348090466 -:102570009847BDE8384001F037B800BF80220020FE -:1025800010B50E4C204600F02FFA0D4BA3620B2124 -:10259000132000F009FA0B21142000F005FA0B219A -:1025A000152000F001FA0B21162000F0FDF90022A1 -:1025B000BDE8104011460E20FFF7B4BE8022002077 -:1025C000006400400F4B984210B5044605D10E4BF5 -:1025D000DA6942F00072DA61DB69A36A01221A60EB -:1025E000A36A5A68D20707D5626851681268D96130 -:1025F0001A60064A5A6110BD0121082000F06CFCE7 -:10260000EEE700BF80220020001002405B8701003F -:1026100003291AD8DFE801F0020A0F14836A9B68C5 -:1026200013F0E05F14BF012000207047836A9868B0 -:10263000C0F380607047836A9868C0F3C0607047D9 -:10264000836A9868C0F300707047002070470000EC -:1026500010B5032925D8DFE801F00225292D836A6A -:102660009968C1F30161183103EB011310788406F6 -:102670004CBF54689488C0F300114FEA410148BF31 -:1026800041EAC40100F00F004CBF41F0040141EAEF -:102690004451586041F001019068D2689860DA6056 -:1026A000196010BD836A03F5C073DFE7836A03F521 -:1026B000C873DBE7836A03F5D073D7E701290AD033 -:1026C00002290FD081B9836ADA68920701D11869AB -:1026D00003E001207047836AD86810F0030018BF38 -:1026E00001207047836AF2E70020704710B539B9BE -:1026F000836AD96889071BD11B699C0704D110BD67 -:10270000012915D00229FAD1816AD1F8C031D1F856 -:10271000C441D1F8C8011061D1F8CC01506120202A -:1027200008610869800717D1486940F0100012E07D -:10273000816AD1F8B031D1F8B441D1F8B801106153 -:10274000D1F8BC0150612020C860C868800703D15F -:10275000486940F002004861C3F34000C3F38001C0 -:10276000000140EA4111107920F03000014311715D -:1027700089064BBF91681189DB085B0D4CBF63F381 -:102780001C0163F30A01137948BF916064F30303EA -:1027900013714FEA14234FEA144458BF1181137088 -:1027A0005480ACE7026843681143016003B11847E5 -:1027B00070470000024A136843F0C003136070477B -:1027C00000380140024A136843F0C00313607047A9 -:1027D0000044004037B51D4C1D4D204600F006FB5F -:1027E000009404F114001B490023202200F0C8F9D2 -:1027F0002022009404F13800174B184900F042FAE7 -:10280000174BC4E91735174C0C21252000F0CCF8E4 -:10281000204600F0EBFA04F1140013490094002361 -:10282000202200F0ADF904F13800104B104900945B -:10283000202200F027FA0F4B0C212620C4E917357F -:1028400003B0BDE8304000F0AFB800BFAC220020BC -:102850000051250284230020B5270008C42300204E -:102860000038014018230020A4230020C5270008B9 -:10287000E4230020004400402DE9F047C66D37688E -:10288000F46934622107054618D014F0080118BF16 -:102890008021E20748BF41F02001A30748BF41F073 -:1028A0004001600748BF41F48071202383F3118801 -:1028B000281DFFF777FF002383F31188E2050AD56F -:1028C000202383F311884FF40071281DFFF76AFF5E -:1028D000002383F311884FF020094FF0000A14F011 -:1028E000200838D13B0616D54FF0200905F1380AEB -:1028F000200610D589F31188504600F0F7F900281A -:1029000036DA0821281DFFF74DFF27F080033360DA -:10291000002383F31188790614D5620612D520238B -:1029200083F31188D5E913239A4208D12B6C33B174 -:102930001021281D27F04007FFF734FF37600023E0 -:1029400083F31188E30619D5AA6E1369B3B1BDE804 -:10295000F0475069184789F31188B38C95F86410D3 -:102960002846194000F04EFA8AF31188F469B6E758 -:1029700080B2308588F31188F469B9E7BDE8F08743 -:1029800008B50348FFF778FFBDE8084000F02CBE0B -:10299000AC22002008B50348FFF76EFFBDE80840F1 -:1029A00000F022BE1823002000F1604303F56143CC -:1029B0000901C9B283F80013012200F01F039A40F5 -:1029C00043099B0003F1604303F56143C3F8802191 -:1029D0001A60704700F16040090100F56D40C9B20E -:1029E00001767047FFF7CCBD012300F10802C0E972 -:1029F0000222037000F110020023C0E90422C0E9A2 -:102A00000633C0E9083343607047000010B5202347 -:102A1000044683F31188022303704160FFF7D2FD5F -:102A200004232370002383F3118810BD2DE9F041A6 -:102A30001F4604460D461646202383F3118800F1F5 -:102A400008082378052B0DD029462046FFF7E0FD26 -:102A500040B1204632462946FFF7FAFD002080F3B8 -:102A6000118808E03946404600F024FB0028E8D0F1 -:102A7000002383F31188BDE8F08100002DE9F041C7 -:102A80001F4604460D461646202383F3118800F1A5 -:102A900010082378052B0DD029462046FFF70EFE9F -:102AA00040B1204632462946FFF720FE002080F341 -:102AB000118808E03946404600F0FCFA0028E8D0CA -:102AC000002383F31188BDE8F0810000F8B51546B6 -:102AD00082680669AA420B46816938BF8568761A02 -:102AE000B54204460BD218462A46FEF757FCA369A6 -:102AF0002B44A361A3685B1BA3602846F8BD0CD9D7 -:102B000018463246FEF74AFCAF1BE1683A463044AD -:102B1000FEF744FCE3683B44EBE718462A46FEF721 -:102B20003DFCE368E5E7000083689342F7B515468E -:102B3000044638BF8568D0E90460361AB5420BD226 -:102B40002A46FEF72BFC63692B446361A368284681 -:102B50005B1BA36003B0F0BD0DD932460191FEF7B7 -:102B60001DFC0199E068AF1B3A463144FEF716FCA4 -:102B7000E3683B44E9E72A46FEF710FCE368E4E734 -:102B800010B50A440024C361029B8460C0E90000C0 -:102B9000C0E90511C1600261036210BD08B5D0E94A -:102BA0000532934201D1826882B982680132826023 -:102BB0005A1C42611970D0E904329A4224BFC3689A -:102BC0004361002100F086FA002008BD4FF0FF307D -:102BD000FBE7000070B5202304460E4683F31188FE -:102BE000A568A5B1A368A269013BA360531CA361BA -:102BF00015782269934224BFE368A361E3690BB1AE -:102C000020469847002383F31188284607E0314681 -:102C1000204600F04FFA0028E2DA85F3118870BDF3 -:102C20002DE9F74F04460E4617469846D0F81C90FB -:102C30004FF0200A8AF311884FF0000B154665B15A -:102C40002A4631462046FFF741FF034660B9414618 -:102C5000204600F02FFA0028F1D0002383F31188DA -:102C6000781B03B0BDE8F08FB9F1000F03D00190DD -:102C70002046C847019B8BF31188ED1A1E448AF346 -:102C80001188DCE7C0E90511C160C3611144009BF4 -:102C90008260C0E90000016103627047F8B5044634 -:102CA0000D461646202383F31188A768A7B1A368B1 -:102CB000013BA36063695A1C62611D70D4E9043250 -:102CC0009A4224BFE3686361E3690BB120469847E9 -:102CD000002080F3118807E03146204600F0EAF931 -:102CE0000028E2DA87F31188F8BD0000D0E9052357 -:102CF0009A4210B501D182687AB982680132826045 -:102D00005A1C82611C7803699A4224BFC36883619C -:102D1000002100F0DFF9204610BD4FF0FF30FBE747 -:102D20002DE9F74F04460E4617469846D0F81C90FA -:102D30004FF0200A8AF311884FF0000B154665B159 -:102D40002A4631462046FFF7EFFE034660B941466A -:102D5000204600F0AFF90028F1D0002383F311885A -:102D6000781B03B0BDE8F08FB9F1000F03D00190DC -:102D70002046C847019B8BF31188ED1A1E448AF345 -:102D80001188DCE7026843681143016003B118470A -:102D9000704700001430FFF743BF00004FF0FF33CF -:102DA0001430FFF73DBF00003830FFF7B9BF000017 -:102DB0004FF0FF333830FFF7B3BF00001430FFF798 -:102DC00009BF00004FF0FF311430FFF703BF0000D0 -:102DD0003830FFF763BF00004FF0FF323830FFF7A5 -:102DE0005DBF000000207047FFF7F4BC044B036098 -:102DF0000023C0E90233436001230374704700BF1E -:102E0000FC3B000838B5C36904460D461BB90421D4 -:102E10000844FFF7B7FF294604F11400FFF7BEFE90 -:102E2000002806DA201D4FF48061BDE83840FFF726 -:102E3000A9BF38BD024B0022C3E900339A60704736 -:102E400004240020002303748268054B1B689968E2 -:102E50009142FBD25A68036042601060586070472C -:102E60000424002008B5202383F31188037C032B5E -:102E700005D0042B0DD02BB983F3118808BD43690D -:102E800000221A604FF0FF334361FFF7DBFF00239E -:102E9000F2E7D0E9003213605A60F3E700230374CD -:102EA0008268054B1B6899689142FBD85A68036099 -:102EB000426010605860704704240020054B196977 -:102EC0000874186802681A6053601861012303745B -:102ED000FDF77EBB0424002030B54B1C0B4D87B0A2 -:102EE000044610D02B690A4A01A800F01BF92046BD -:102EF000FFF7E4FF049B13B101A800F02FF92B6941 -:102F0000586907B030BDFFF7D9FFF8E70424002067 -:102F1000652E000838B50C4D41612B6981689A68AF -:102F20009142044603D8BDE83840FFF78BBF1846EE -:102F3000FFF7B4FF01232C61014623742046BDE84E -:102F40003840FDF745BB00BF04240020044B1A683D -:102F50001B6990689B68984294BF002001207047CD -:102F60000424002010B5084C236820691A682260E8 -:102F70005460012223611A74FFF790FF0146206913 -:102F8000BDE81040FDF724BB0424002008B5FFF77E -:102F9000DDFF18B1BDE80840FFF7E4BF08BD000041 -:102FA000FFF7E0BFFEE7000010B50C4CFFF742FF53 -:102FB00000F0AAF80A498022204600F031F80123E7 -:102FC00044F8180C037400F0EBFA002383F3118823 -:102FD00062B60448BDE8104000F042B82C2400203E -:102FE000243C0008343C000800F0CAB8EFF311801C -:102FF00020B9EFF30583202282F311887047000087 -:1030000010B530B9EFF30584C4F3080414B180F3AC -:10301000118810BDFFF7BAFF84F31188F9E70000AB -:1030200082600222028270478368A3F17C0243F827 -:103030000C2C026943F83C2C426943F8382C074AAF -:1030400043F81C2CC26843F8102C022203F8082C09 -:10305000002203F8072CA3F118007047E9050008C7 -:1030600010B5202383F31188FFF7DEFF002104460B -:10307000FFF750FF002383F31188204610BD0000A6 -:10308000024B1B6958610F20FFF718BF0424002072 -:10309000202383F31188FFF7F3BF000008B5014632 -:1030A000202383F311880820FFF716FF002383F302 -:1030B000118808BD49B1064B42681B6918605A6007 -:1030C000136043600420FFF707BF4FF0FF307047E5 -:1030D000042400200368984206D01A6802605060F9 -:1030E00059611846FFF7AEBE7047000038B5044678 -:1030F0000D462068844200D138BD036823605C60BF -:103100004561FFF79FFEF4E7054B03F11402C3E9A5 -:1031100005224FF0FF32DA6100221A62704700BFC9 -:103120000424002010B5C0E903230B4A136A536935 -:103130009C68A1420CD85C68816003604460206098 -:1031400058609868411A99604FF0FF33D36110BD01 -:103150001B68091BECE700BF04240020036881689A -:103160009A680A449A60426813605A600023C360F8 -:10317000024B4FF0FF32DA61704700BF0424002099 -:1031800038B50F4C236A22460133236252F8143FAC -:10319000934206D09A68013A9A60202563699A683A -:1031A00002B138BDD3E9001001604860D968DA6027 -:1031B00082F311881869884785F31188EEE700BF0C -:1031C0000424002000207047FEE700007047000044 -:1031D0004FF0FF3070470000BFF34F8F024AD368B3 -:1031E000DB07FCD4704700BF0020024008B5074B46 -:1031F0001B7853B9FFF7F0FF054B1A69120641BF60 -:10320000044A5A6002F188325A6008BD90250020B5 -:10321000002002402301674508B5054B1B7833B9F0 -:10322000FFF7DAFF034A136943F08003136108BD17 -:1032300090250020002002407F289ABF00F58030B2 -:10324000C0020020704700004FF40060704700008B -:10325000802070477F2808B50BD8FFF7EDFF00F5F9 -:1032600000630268013204D104308342F9D10120A5 -:1032700008BD0020FCE700007F2838B5044623D8AD -:10328000FFF7B4FEFFF7A8FFFFF7B0FF0F4BF322E5 -:10329000DA6002221A6105462046FFF7CDFF586129 -:1032A0001A6942F040021A614FF40061FFF794FF7F -:1032B00000F026F92846FFF7AFFFFFF7A1FE2046F2 -:1032C000BDE83840FFF7C6BF002038BD00200240EF -:1032D00012F001032DE9F04704460E46154606D0CC -:1032E000244B40F2BD221A600020BDE8F08781180F -:1032F000214A914204D91F4A40F2C2211160F3E7EA -:10330000FFF774FEFFF772FFFFF766FFDFF87890B4 -:1033100031464FF0010AA61B012D06EB0107884636 -:1033200005D8FFF779FFFFF76BFE0120DDE7B8F85E -:103330000030C9F810A03B800024FFF74DFFC9F80A -:1033400010403B8831F8022B9BB29A420FD0094BB8 -:1033500040F2D9221A60094B1F60094B1D60094BCE -:10336000C3F80080FFF758FFFFF74AFEBCE7023DB5 -:10337000D2E700BF8C250020000004088025002033 -:10338000882500208425002000200240084908B537 -:103390000B7828B11BB9FFF729FF01230B7008BD7B -:1033A000002BFCD0BDE808400870FFF735BF00BF18 -:1033B0009025002030B583B0FFF718FE0E4B0F4D5F -:1033C0001B6A2A684FF47A7101FB03F3934237BFFB -:1033D0000B4A0B49516814682B602EBFD1E900419C -:1033E000013151601C1941F100010191FFF708FE04 -:1033F0000199204603B030BD04240020942500200C -:103400009825002030B583B0FFF7F0FD114B124D29 -:103410001B6A2A684FF47A7101FB03F3934237BFAA -:103420000E4A0E49516814682B602EBFD1E9004145 -:10343000013151601C1941F100010191FFF7E0FDDC -:1034400001994FF47A7200232046FCF7A9FE03B0DD -:1034500030BD00BF042400209425002098250020C2 -:1034600010B50244064BD2B2904200D110BD441CAC -:1034700000B253F8200041F8040BE0B2F4E700BFBB -:10348000502800400F4B30B51C6A240407D41C6A36 -:1034900044F440741C621C6A44F400441C620A4CEC -:1034A000236843F4807323600244084BD2B29042F5 -:1034B00000D130BD441C00B251F8045B43F82050E9 -:1034C000E0B2F4E7001002400070004050280040D5 -:1034D00007B5012201A90020FFF7C2FF019803B040 -:1034E0005DF804FB13B50446FFF7F2FFA04205D0D8 -:1034F000012201A900200194FFF7C4FF02B010BD12 -:1035000070470000074B45F255521A6002225A607C -:1035100040F6FF729A604CF6CC421A60024B0122D0 -:103520001A70704700300040A4250020034B1B7820 -:103530001BB1034B4AF6AA221A607047A42500204B -:1035400000300040044B1A682AB902F1804202F5AB -:103550000432526A1A607047A0250020024B4FF0D7 -:1035600080725A62704700BF0010024008B5FFF732 -:10357000E9FF024B1868C0F3407008BDA025002089 -:10358000EFF3098305494A6B22F001024A6368336D -:1035900083F30988002383F31188704700EF00E06C -:1035A000202080F3118862B60C4B0D4AD96821F4B3 -:1035B000E0610904090C0A43DA60D3F8FC200949E8 -:1035C00042F08072C3F8FC200A6842F001020A60EF -:1035D0001022DA7783F82200704700BF00ED00E088 -:1035E0000003FA05001000E010B5202383F31188D2 -:1035F0000E4B5B6813F4006314D0F1EE103AEFF356 -:103600000984683C4FF08073E361094BDB6B2366F0 -:1036100084F30988FFF79AFC10B1064BA36110BD33 -:10362000054BFBE783F31188F9E700BF00ED00E0ED -:1036300000EF00E0FB050008FE05000870470000F1 -:10364000FEE700000A4B0B480B4A90420BD30B4B92 -:10365000DA1C121AC11E22F003028B4238BF00226C -:103660000021FDF7ADBE53F8041B40F8041BECE746 -:10367000203D00082826002028260020282600209B -:10368000704700004B6843608B688360CB68C36001 -:103690000B6943614B6903628B6943620B6803608A -:1036A0007047000008B51B4B9A6A42F4FC029A620C -:1036B0009A6A22F4FC029A629A6A5A6942F4FC02FB -:1036C0005A61154A5B6911464FF09040FFF7DAFFE7 -:1036D00002F11C0100F58060FFF7D4FF02F1380110 -:1036E00000F58060FFF7CEFF02F1540100F5806025 -:1036F000FFF7C8FF02F1700100F58060FFF7C2FF1D -:1037000002F18C0100F58060FFF7BCFFBDE80840C6 -:1037100000F05AB8001002404C3C000808B500F018 -:1037200093F9FFF741FCBDE80840FFF70BBF00002D -:103730007047000010B5214CA36A63F4FC03A36238 -:10374000A36A03F4FC03A3624FF0FF32A36A236968 -:1037500022612369002323612169E168E260E26854 -:10376000E360E268E269164942F08052E261E26990 -:103770000A6842F480720A60226A02F44072B2F56A -:10378000407F1EBF4FF4803222622362236A1B04F3 -:1037900007D4236A43F440732362236A43F400434B -:1037A000236200F031F9A369064A43F00103A361E3 -:1037B000A369136843F02003136010BD001002409A -:1037C00000700040000001401E4B1A6842F00102E8 -:1037D0001A601A689007FCD55A6822F003025A60F2 -:1037E0005A6812F00C02FBD1196801F0F901196056 -:1037F0005A601A6842F480321A601A689103FCD544 -:10380000114A5A604FF40452DA6230221A631A687D -:1038100042F080721A601A689201FCD50B4912229C -:103820000A600A6802F00702022AFAD15A6842F0D6 -:1038300002025A605A6802F00C02082AFAD11A6B86 -:103840001A6370470010024000241D00002002404F -:10385000084A08B5516913680B4003F0010353612E -:1038600023B1054A13680BB150689847BDE808407A -:10387000FFF7BABE00040140A8250020084A08B599 -:10388000516913680B4003F00203536123B1054AE9 -:1038900093680BB1D0689847BDE80840FFF7A4BE15 -:1038A00000040140A8250020084A08B551691368A2 -:1038B0000B4003F00403536123B1054A13690BB1B4 -:1038C00050699847BDE80840FFF78EBE00040140EC -:1038D000A8250020084A08B5516913680B4003F079 -:1038E0000803536123B1054A93690BB1D069984726 -:1038F000BDE80840FFF778BE00040140A82500207D -:10390000084A08B5516913680B4003F0100353616E -:1039100023B1054A136A0BB1506A9847BDE80840C5 -:10392000FFF762BE00040140A8250020174B10B528 -:103930005A691C68144004F478725A61A30604D5CD -:10394000134A936A0BB1D06A9847600604D5104AAF -:10395000136B0BB1506B9847210604D50C4A936B3F -:103960000BB1D06B9847E20504D5094A136C0BB133 -:10397000506C9847A30504D5054A936C0BB1D06CE5 -:103980009847BDE81040FFF72FBE00BF000401407C -:10399000A82500201A4B10B55A691C68144004F47D -:1039A0007C425A61620504D5164A136D0BB1506D05 -:1039B0009847230504D5134A936D0BB1D06D9847F2 -:1039C000E00404D50F4A136E0BB1506E9847A10462 -:1039D00004D50C4A936E0BB1D06E9847620404D59F -:1039E000084A136F0BB1506F9847230404D5054A5A -:1039F000936F0BB1D06F9847BDE81040FFF7F4BD4F -:103A000000040140A8250020062108B50846FEF75D -:103A1000CBFF06210720FEF7C7FF06210820FEF78F -:103A2000C3FF06210920FEF7BFFF06210A20FEF78B -:103A3000BBFF06211720FEF7B7FFBDE808400621AF -:103A40002820FEF7B1BF000008B5FFF773FE00F0B5 -:103A50000DF8FEF7C7FFFFF7C7F9FFF769FEBDE8EE -:103A6000084000F001B8000000F00EB80023054A3D -:103A700019460133102BC2E9001102F10802F8D1F6 -:103A8000704700BFA82500204FF0E023044A5A6188 -:103A900000229A6107221A6108210B20FEF79ABFC3 -:103AA0003F19010008B5202383F31188FFF79CFA22 -:103AB000002383F3118808BD08B5FFF7F3FFBDE8C5 -:103AC0000840FFF791BD000010B501390244904253 -:103AD00001D1002005E0037811F8014FA34201D085 -:103AE000181B10BD0130F2E72DE9F041A3B1C91A4E -:103AF00017780144044603F1FF3C8C42204601D96B -:103B0000002009E00578BD4204F10104F5D10CEB79 -:103B10000405D618A54201D1BDE8F08115F8018D44 -:103B200016F801EDF045F5D0E7E70000034611F87F -:103B3000012B03F8012B002AF9D170476F72672E11 -:103B40006172647570696C6F742E61705F706572FC -:103B50006970685F756E6976657273616C000000EC -:103B60004E6F20617070207369670A0042616420A3 -:103B70006677206C656E6774682025750A0042615F -:103B80006420626F6172645F6964202575207368C8 -:103B90006F756C642062652025750A00426164209F -:103BA00066772064657363726970746F72206C65E8 -:103BB0006E6774682025750A004261642061707028 -:103BC00020435243203078253038783A30782530F9 -:103BD0003878203078253038783A30782530387881 -:103BE0000A00476F6F64206669726D776172650ABB -:103BF0000040A2E4F16468910600000000000000AB -:103C0000B12D00089D2D0008D92D0008C52D0008F4 -:103C1000D12D0008BD2D0008A92D0008952D000804 -:103C2000E52D00086D61696E0000000069646C6537 -:103C3000000000002C3C00084824002080250020C3 -:103C400001000000A52F000800000000A001A82A24 -:103C500000000000FAAABEAA50001424EFFF0000E2 -:103C600000770000709709000100000000000000CC -:103C7000AAAAAAAA01000000FFFF0000000000009D -:103C8000000000000000000000000000AAAAAAAA8C -:103C900000000000FFFF0000000000000000000026 -:103CA0000000000000000000AAAAAAAA000000006C -:103CB000FFFF000000000000000000000000000006 -:103CC00000000000AAAAAAAA00000000FFFF00004E -:103CD00000000000000000000000000000000000E4 -:103CE000AAAAAAAA00000000FFFF0000000000002E -:103CF00000000000DCC4FF7F0100000000000000A5 -:103D0000EC03000000000000009803000000000029 -:103D10006400000000000000FE2A0100D204000040 +:1000000000090020B5040008CD250008852500085A +:10001000AD25000885250008A5250008B7040008BF +:10002000B7040008B7040008B7040008C135000889 +:10003000B7040008B7040008B704000875430008B7 +:10004000B7040008B7040008B7040008B7040008A4 +:10005000B7040008B70400085940000885400008AC +:10006000B1400008DD40000809410008B70400085D +:10007000B7040008B7040008B7040008B704000874 +:10008000B7040008B7040008B704000839250008C1 +:100090006525000875250008B704000835410008EB +:1000A000B7040008B7040008B7040008B704000844 +:1000B000B7040008B7040008B7040008B704000834 +:1000C000B7040008B7040008B7040008B704000824 +:1000D000B70400086545000879450008B704000822 +:1000E0009D410008B7040008B7040008B7040008E1 +:1000F000B7040008B7040008B7040008B7040008F4 +:10010000B7040008B7040008B7040008B7040008E3 +:10011000B7040008B7040008B7040008B7040008D3 +:10012000B7040008B7040008B7040008B7040008C3 +:10013000B7040008B7040008B7040008B7040008B3 +:10014000B7040008B7040008B7040008B7040008A3 +:10015000B7040008B7040008B7040008B704000893 +:10016000B7040008B7040008B7040008B704000883 +:10017000B7040008B7040008B7040008B704000873 +:10018000B7040008B7040008B7040008B704000863 +:10019000B7040008B7040008B7040008B704000853 +:1001A0002112000800000000000000000000000014 +:1001B00053B94AB9002908BF00281CBF4FF0FF31CE +:1001C0004FF0FF3000F074B9ADF1080C6DE904CECA +:1001D00000F006F8DDF804E0DDE9022304B0704722 +:1001E0002DE9F047089D04468E46002B4DD18A42EA +:1001F000944669D9B2FA82F252B101FA02F3C2F11D +:10020000200120FA01F10CFA02FC41EA030E9440AD +:100210004FEA1C48210CBEFBF8F61FFA8CF708FBCE +:1002200016E341EA034306FB07F199420AD91CEBA6 +:10023000030306F1FF3080F01F81994240F21C81D8 +:10024000023E63445B1AA4B2B3FBF8F008FB103320 +:1002500044EA034400FB07F7A7420AD91CEB040455 +:1002600000F1FF3380F00A81A74240F20781644425 +:10027000023840EA0640E41B00261DB1D4400023AA +:10028000C5E900433146BDE8F0878B4209D9002D0E +:1002900000F0EF800026C5E9000130463146BDE898 +:1002A000F087B3FA83F6002E4AD18B4202D3824202 +:1002B00000F2F980841A61EB030301209E46002DB1 +:1002C000E0D0C5E9004EDDE702B9FFDEB2FA82F206 +:1002D000002A40F09280A1EB0C014FEA1C471FFA64 +:1002E0008CFE0126200CB1FBF7F307FB131140EA4B +:1002F00001410EFB03F0884208D91CEB010103F118 +:10030000FF3802D2884200F2CB804346091AA4B2D9 +:10031000B1FBF7F007FB101144EA01440EFB00FEAD +:10032000A64508D91CEB040400F1FF3102D2A64512 +:1003300000F2BB800846A4EB0E0440EA03409CE7B1 +:10034000C6F12007B34022FA07FC4CEA030C20FA5E +:1003500007F401FA06F31C43F9404FEA1C4900FA7E +:1003600006F3B1FBF9F8200C1FFA8CFE09FB1811FB +:1003700040EA014108FB0EF0884202FA06F20BD96E +:100380001CEB010108F1FF3A80F08880884240F2BE +:100390008580A8F102086144091AA4B2B1FBF9F002 +:1003A00009FB101144EA014100FB0EFE8E4508D9FD +:1003B0001CEB010100F1FF346CD28E456AD9023882 +:1003C000614440EA0840A0FB0294A1EB0E01A14267 +:1003D000C846A64656D353D05DB1B3EB080261EBD5 +:1003E0000E0101FA07F722FA06F3F1401F43C5E9AF +:1003F000007100263146BDE8F087C2F12003D840E5 +:100400000CFA02FC21FA03F3914001434FEA1C4726 +:100410001FFA8CFEB3FBF7F007FB10360B0C43EA18 +:10042000064300FB0EF69E4204FA02F408D91CEBC8 +:10043000030300F1FF382FD29E422DD902386344C6 +:100440009B1B89B2B3FBF7F607FB163341EA034166 +:1004500006FB0EF38B4208D91CEB010106F1FF38B5 +:1004600016D28B4214D9023E6144C91A46EA0046AC +:1004700038E72E46284605E70646E3E61846F8E63E +:100480004B45A9D2B9EB020864EB0C0E0138A3E787 +:100490004646EAE7204694E74046D1E7D0467BE768 +:1004A000023B614432E7304609E76444023842E7E0 +:1004B000704700BF02E000F000F8FEE772B6374870 +:1004C00080F30888364880F3098836483649086042 +:1004D00040F20000CCF200004EF63471CEF2000182 +:1004E0000860BFF34F8FBFF36F8F40F20000C0F280 +:1004F000F0004EF68851CEF200010860BFF34F8F36 +:10050000BFF36F8F4FF00000E1EE100A4EF63C7122 +:10051000CEF200010860062080F31488BFF36F8FCD +:1005200003F04EFC03F0C2FC4FF055301F491B4A4C +:1005300091423CBF41F8040BFAE71D49184A914229 +:100540003CBF41F8040BFAE71A491B4A1B4B9A427D +:100550003EBF51F8040B42F8040BF8E7002018499D +:10056000184A91423CBF41F8040BFAE703F02CFC17 +:1005700003F0D8FC144C154DAC4203DA54F8041BBC +:100580008847F9E700F042F8114C124DAC4203DA0B +:1005900054F8041B8847F9E703F014BC0009002055 +:1005A000001100200000000808ED00E0000100201C +:1005B00000090020704B0008001100207C11002071 +:1005C00080110020583C0020A0010008A401000870 +:1005D000A4010008A40100082DE9F04F2DED108AB8 +:1005E000C1F80CD0C3689D46BDEC108ABDE8F08F01 +:1005F000002383F311882846A047002003F06AF9FE +:10060000FEE703F0CDF800DFFEE70000F8B500F0EC +:1006100019FE03F079FB074603F0C8FB05460028E6 +:1006200040D12C4B9F423DD001339F423DD02A4BBD +:1006300027F0FF029A423BD1F8B200F03FFC2E4671 +:1006400042F2107400F040FC08B10024264601F08C +:10065000B1F888B3032000F045F80024264635B1F0 +:100660001E4B9F4203D003F099FB00242646002036 +:1006700003F054FB1A4B1B6913F0400322D00EB158 +:1006800000F046F800F052FC00F0DEFD01F0A6FF9D +:100690000546CCB101F0A2FF401BA04214D900F0E6 +:1006A00037F8F3E72E460024CCE704460126C9E7D5 +:1006B00006464FF47A74C5E7002CD0D04FF47A7414 +:1006C0000126CCE71C46DDE700F078FC012003F0B2 +:1006D00007F9DEE7010007B0000008B0263A09B0CC +:1006E00000040048084B187003280CD8DFE800F01D +:1006F00008050208022000F003BE022000F0F8BD49 +:10070000024B00225A6070478011002084110020A3 +:1007100038B501F04FF830B11F4B03221A701F4B50 +:1007200000225A6038BD1E4B1E4A19680131F9D0AB +:1007300004339342F9D11C4C194DD4F80428AA4231 +:10074000F0D31A4B9B6803F1006303F5D0439A4240 +:10075000E8D203F0F7FA03F009FB002000F08EFD69 +:100760000220FFF7BFFF124BDA690022DA61D96974 +:1007700099699A619B6972B64FF0E0233021C3F802 +:10078000085DD4F80038D4F8042881F311889D4618 +:1007900083F308881047C5E78011002084110020EA +:1007A00000680008206800080060000800110020B0 +:1007B00000100240094A136849F2690099B21B0C03 +:1007C00000FB01331360064B186844F2506182B29B +:1007D000000C01FB0200186080B270471411002069 +:1007E0001011002010B500211022044600F0A2FDD7 +:1007F000034B03CB206061601868A06010BD00BF90 +:10080000ACF7FF1F2DE9F041ADF5507D0DF13C082F +:100810006EAC40F2751207460D4610A80021C8F8CC +:10082000001000F087FD4FF4C4720021204600F054 +:1008300081FD01F0D3FE254B4FF47A72B0FBF2F04C +:10084000186093E80700022384E807000DF5ED70B7 +:100850002382FFF7C7FF4EF603431D49238407A8F1 +:1008600004F0B6F81C2384F832310DF2EB226B440D +:100870000DF1340C1E4603CE6645106051603346C0 +:1008800002F10802F6D1306810604146012220468C +:1008900000F09CFD00230393AB7E029305F1190346 +:1008A000019380B20123CDE904800093E97E05A382 +:1008B000D3E90023384602F059FA0DF5507DBDE822 +:1008C000F08100BF9E6AC421818A46EE8C1100200F +:1008D000E04900082DE9F0412C4C237ADAB080463B +:1008E0000D465BBB27A9284600F080FE074600287E +:1008F00042D19DF89D60C82E3ED801464FF4A662B5 +:10090000204600F017FD4FF48073C4F8F8314FF41F +:100910000073C4F80C334FF44073C4F820343246EB +:100920000DF19E0104F1090000F0F2FC26449DF84F +:100930009C30777223720BB9EB7E237281220021E7 +:1009400006AC27A800F0F6FC0122214627A800F0FB +:1009500089FE00230393AB7E029305F1190380B255 +:1009600001932823CDE904400093E97E05A3D3E950 +:100970000023404602F0FAF95AB0BDE8F08100BF0A +:10098000AFF3008026417272DF25D7B7A83200206E +:10099000F0B5254E4FF48A7505FB0065F1B096F869 +:1009A000D83085F8DC300024D822214685F8E8408C +:1009B0003AA800F0BFFC06F1090000F0B3FCD5F83E +:1009C000E4308DF8F000C2B206AF06F109010DF176 +:1009D000F100CDE93A3400F09BFC394601223AA8F7 +:1009E00000F06CFE80B2CDE9047008230127CDE948 +:1009F000023706F1D803019330230093317A0B4874 +:100A000007A3D3E9002302F0B1F9A04206DD01F00B +:100A1000E5FDC5F8E000384671B0F0BD2046FBE7C3 +:100A200078F6339F93CACD8DA8320020A4210020F0 +:100A30002DE9F0411D4D1E4E1E4F86B0284602F096 +:100A4000C1F9034658B30024CDE90344ADF814407E +:100A5000027B8DF8142099684068029403AA03C2AF +:100A60001B68DFF8548043F00043029301F0B8FDA7 +:100A7000821941F10003009402A9384601F07CF884 +:100A8000A04205DD284602F0A1F988F80040D5E72C +:100A900098F80030072B05D8013388F8003006B0ED +:100AA000BDE8F081014802F091F9F8E7A4210020A7 +:100AB00040420F00D8210020DD37002070B50D46E0 +:100AC00014461E4602F0AEF850B9022E10D1012C89 +:100AD0000ED112A3D3E90023C5E90023012007E0CA +:100AE000282C10D005D8012C09D0052C0FD00020BF +:100AF00070BD302CFBD10BA3D3E90023ECE70BA393 +:100B0000D3E90023E8E70BA3D3E90023E4E70BA331 +:100B1000D3E90023E0E700BFAFF30080401DA12030 +:100B200026812A0B78F6339F93CACD8D9E6AC42105 +:100B3000818A46EE26417272DF25D7B7F017304A18 +:100B400039059E5638B505460E4C0021013500F09A +:100B5000B7FBA4F82C55B4F82C0500F099FB78B13C +:100B6000B4F82C0500F0A4FB014648B9B4F82C05F4 +:100B700000F0A6FBB4F82C350133A4F82C35EAE7D5 +:100B800038BD00BFA832002010B50A4B0A4A1A60CF +:100B900003F5805393F860203AB9DC6D2CB1204600 +:100BA00000F082FE204603F053FEBDE810400348EB +:100BB00000F07ABED82100203C4A000820320020F4 +:100BC0002DE9F04F8FB000AF05460C4602F02AF831 +:100BD000002849D1237E022B1BD1E38A012B18D197 +:100BE00001F0FCFC0646FFF7E5FD03464FF4C87034 +:100BF000DFF8C482B3FBF0F206F5167602FB103381 +:100C000016FA83F3C8F80030E37E33B9A34B002211 +:100C10001A703C37BD46BDE8F08F07F1240120462D +:100C200000F0A2FC0028F4D107F11400FFF7DAFD70 +:100C300097F8264007F11401224607F1270003F038 +:100C400051FE0028E2D10F2C08D8944B1C70D8F824 +:100C50000030A3F51673C8F80030DAE797F82410CF +:100C6000284601F0D7FFD4E7E38A282B2BD010D8F1 +:100C7000012B23D0052BCCD1BFF34F8F8849894B53 +:100C8000CA6802F4E0621343CB60BFF34F8F00BF2A +:100C9000FDE7302BBDD1844EE17E327A9142B8D14E +:100CA000607E3146002291F8DC50854200F0A5803C +:100CB0000132042A01F58A71F5D1AAE721462846B6 +:100CC000FFF7A0FDA5E721462846FFF703FEA0E7B2 +:100CD000B2F8EC507B6005F103094FEA99094FEA3D +:100CE0008902D11DC908A8EBC1039D46EB4600212E +:100CF000584600F01FFB04F1EE012A4631445846E5 +:100D000000F006FB7B6813B9012000F0B7FA96F8F3 +:100D1000D20000F0BDFA044630B9307200F0D8FAC3 +:100D2000204600F0ABFAB1E0D6F8D4203AB996F8F4 +:100D3000D200B6F82C25824201D8FFF703FFD6F87F +:100D4000D4202A44944208D296F8D200B6F82C2532 +:100D50000130824201D8FFF7F5FE70685FFA89F230 +:100D6000594600F0EFFA08B9C54679E0726896F87E +:100D7000D2002A447260D6F8D42005EB0209C6F8E6 +:100D8000D49000F085FA814509D396F8D220D6F8A0 +:100D9000D4000132001B86F8D220C6F8D400FF2D03 +:100DA0000FD80024347200F093FA204600F066FA5F +:100DB00000F000FD3D4B188108B9FFF7A9FCC546BE +:100DC00027E7BB6896F8D9000AFB0362FB68D2F8F4 +:100DD000E41082F8E83001F58061C2F8E030C2F832 +:100DE000E410FFF7D5FDFFF723FE96F8D920013276 +:100DF00002F0030286F8D920B6E74FF48A7A0AFB9C +:100E000002F505F1EA013144204600F083FCF86068 +:100E100000287FF4FEAE3544012285F8E82001F079 +:100E2000DDFBD5F8E020D6ED007ADFED216A801AEF +:100E3000192838BF192040F6B832904228BF104612 +:100E4000B8EE677A07EE900AF8EEE77A67EEA67AD0 +:100E5000DFED186AE7EE267AFCEEE77AC6ED007A57 +:100E600096F8D930BB60BA6873680AFB02F432198D +:100E700092F8E81059B1D2F8E4108B42E8463FF4FA +:100E800027AF002182F8E810C2F8E010C546736869 +:100E9000064A9B0A01331381BBE600BF9D21002057 +:100EA00000ED00E00400FA05A83200208C110020BB +:100EB000CDCCCC3D6666663FA0210020014B18706A +:100EC000704700BF9811002038B54FF00054134B05 +:100ED00022689A4220D1124B627D12481A70237DFB +:100EE00003724FF48073C0F8F8314FF40073C0F808 +:100EF0000C3300254FF44073C0F820340A49C0F881 +:100F0000E450C922093000F003FAE02229462046C5 +:100F100000F010FA012038BD0020FCE79AAD44C56E +:100F200098110020A83200201600002037B500F0EC +:100F300041FC194D194928810223012218486B717F +:100F400001F0EAF900230193164B17490093174863 +:100F5000174B4FF4805201F035FE164B197811B142 +:100F6000124801F057FE01F039FB0446FFF722FC5E +:100F70004FF4C873B0FBF3F202FB130304F51670D1 +:100F800010FA83F00C4B186002F010FF08B10F2329 +:100F90002B8103B030BD00BF8C11002040420F00F8 +:100FA000D8210020BD0A00089C110020A4210020A7 +:100FB000C10B000898110020A02100202DE9F04F5E +:100FC0002DED028B8EA7D7E900670FF23C29D9E9F6 +:100FD0000089864C95B00DAD9FED828BFFF728FD03 +:100FE000DFF82CB200230C93ADF83C300D936B600E +:100FF00000230DF125028DED008B4FF0010A09A9A8 +:1010000058468DF825308DF824A001F035F99DF86B +:1010100024200023002A40F0AB80204601F002FE8D +:101020000546002847D1DFF8ECB101F0D7FADBF82C +:10103000003098423FD301F0D1FA0790FFF7BAFB96 +:10104000079A4FF4C873B0FBF3F101FB130302F5E9 +:10105000167010FA83F0CBF80000DFF8BCB19BF8F3 +:1010600000100791002914BF2B46534610A88DF895 +:101070003030FFF7B7FB0799C1F11002D2B2062A50 +:1010800010AB28BF062219440DF13100079200F081 +:101090003FF9079A0CAB0393182302930132544B88 +:1010A000D2B2CDE900A304923B463246204601F07D +:1010B000FFFD8BF8005001F091FA4E4A4E4D136837 +:1010C000C31AB3F57A7F32D3106001F089FA024671 +:1010D0000B46204601F084FE204601F0A3FD30B30C +:1010E0002B7ADFF838A1002B14BF032302238AF8E0 +:1010F000053001F073FA0DF1400B4FF47A730122C1 +:10110000B0FBF3F05946CAF80000504600F004FA6C +:1011100018230293394B019380B240F25513CDE965 +:1011200003B0009342464B46204601F0C1FD2B7AA6 +:10113000CBB101F053FA4FF0000A83464FF48A72A4 +:1011400095F8D900504400F0030002FB005393F8D7 +:10115000E81089B30AF1010ABAF1040FF0D12B7A31 +:10116000002B7FF438AF15B0BDEC028BBDE8F08FDB +:101170004FF0904110A84A6982F010024A61194666 +:10118000102200F0D7F80DF126030AAA0CA9584640 +:1011900000F0F0FD95E8030011AB83E803009DF833 +:1011A0003C308DF84C300C9B109310A9DDE90A23DC +:1011B000204601F0E9FF1BE7D3F8E01049B12B68A6 +:1011C000FA2B38BFFA23ABEB01010533B1EB430F28 +:1011D000C0D3FFF7DDFB4FF48A720028BAD1BEE717 +:1011E000AFF300800000000000000000A4210020F8 +:1011F0009C210020D8370020A8320020DC370020B6 +:10120000401DA12026812A0BF1C6A7C1D068080F76 +:10121000D8210020A02100209D2100208C11002039 +:1012200008B5054800F040FEBDE80840034A0449FF +:10123000002003F007BB00BFD82100201838002091 +:10124000890B00087047000070B502F013FC094ECE +:10125000094D3080002428683388834208D902F081 +:1012600005FC2B6804440133B4F5D04F2B60F2D356 +:1012700070BD00BF0C380020E037002002F086BCB3 +:1012800000F10060920000F5D04002F02DBC00009B +:10129000054B1A68054B1B889B1A834202D91044E0 +:1012A00002F0E4BB00207047E03700200C3800203B +:1012B000024B1B68184402F0DFBB00BFE037002080 +:1012C000024B1B68184402F0E9BB00BFE037002066 +:1012D000064991F8243033B10023086A81F824309C +:1012E0000822FFF7CDBF0120704700BFE437002080 +:1012F000022802BF4FF0904310229A61704700000D +:10130000022802BF4FF090434FF480129A61704759 +:1013100010B50023934203D0CC5CC4540133F9E7E9 +:1013200010BD000003460246D01A12F9011B002925 +:10133000FAD1704702440346934202D003F8011BDE +:10134000FAE770472DE9F8431F4D144695F824201D +:101350000746884652BBDFF870909CB395F824305E +:101360002BB92022FF2148462F62FFF7E3FF95F8B3 +:101370002400C0F10802A24228BF2246D6B241464C +:10138000920005EB8000FFF7C3FF95F82430A41B03 +:101390001E44F6B2082E17449044E4B285F8246047 +:1013A000DBD1FFF795FF0028D7D108E02B6A03EBCC +:1013B00082038342CFD0FFF78BFF0028CBD10020E0 +:1013C000BDE8F8830120FBE7E43700202DE9F04772 +:1013D0000D46044600219046284640F27912FFF758 +:1013E000A9FF234620220021284601F06FFE231D7D +:1013F00002222021284601F069FE631D03222221DA +:10140000284601F063FEA31D03222521284601F092 +:101410005DFE04F1080310222821284601F056FE43 +:1014200004F1100308223821284601F04FFE04F190 +:10143000110308224021284601F048FE04F112035E +:1014400008224821284601F041FE04F1140320221D +:101450005021284601F03AFE04F118034022702181 +:10146000284601F033FE04F120030822B02128466B +:1014700001F02CFE04F121030822B821284601F0D6 +:1014800025FE04F12207C0263B46314608222846A5 +:10149000083601F01BFEB6F5A07F07F10107F3D176 +:1014A00004F1320308223146284601F00FFE0027DE +:1014B00004F1330A94F832304FEAC7099F4209F524 +:1014C000A47615D3B8F1000F08D1314604F599730D +:1014D0000722284601F0FAFD09F24F16274694F834 +:1014E00032213B1B93420CD3F01DC008BDE8F087AE +:1014F0000AEB070308223146284601F0E7FD0137D1 +:10150000D8E707F2331331460822284601F0DEFD02 +:1015100008360137E3E7000013B50446084600210A +:1015200001602346C0F803102022019001F0CEFD97 +:101530000198231D0222202101F0C8FD0198631D9E +:101540000322222101F0C2FD0198A31D03222521BF +:1015500001F0BCFD019804F108031022282101F0DC +:10156000B5FD072002B010BDF7B50023047F009140 +:101570000E4607221946054601F06CFC731C0093C9 +:10158000012200230721284601F064FCC4B9B31CE2 +:101590000093052223460821284601F05BFC0D2418 +:1015A0003746B278BB1B934211D32B7FA88A0734EE +:1015B000E408BBB9844294BF0020012003B0F0BD11 +:1015C000AB8ADB00083BDB08B3700824E8E7FB1CB0 +:1015D0000093214600230822284601F03BFC0834F2 +:1015E0000137DEE7201A18BF0120E7E7F7B500232F +:1015F000047F00910E4608221946054601F02AFC98 +:10160000731CC4B90822009311462346284601F0F2 +:1016100021FC1024012372785F1C013B934211D3FB +:101620002B7FA88A0734E408BBB9844294BF00200A +:10163000012003B0F0BDAB8ADB00083BDB08737010 +:101640000824E7E7F31900932146002308222846DF +:1016500001F000FC08343B46DDE7201A18BF0120EA +:10166000E7E70000F8B50E46054614460021812242 +:101670003046FFF75FFE2B4608220021304601F07E +:1016800025FD7CB96B1C07220821304601F01EFDA8 +:101690000F2401236A785F1C013B934204D3E01DB1 +:1016A000C008F8BD0824F4E7EB19214608223046AB +:1016B00001F00CFD08343B46ECE70000F8B50E469F +:1016C000054614460021CE223046FFF733FE2B4656 +:1016D00028220021304601F0F9FC7CB905F108030D +:1016E00008222821304601F0F1FC30242F462A7AC6 +:1016F0007B1B934204D3E01DC008F8BD2824F5E706 +:1017000007F1090321460822304601F0DFFC0834C6 +:101710000137ECE7F7B5047F00910E460123102254 +:101720000021054601F096FBC4B9B31C00930922C1 +:1017300023461021284601F08DFB19243746728874 +:10174000BB1B9A4211D82B7FA88A0734E408BBB987 +:10175000844294BF0020012003B0F0BDAB8ADB00BF +:10176000103BDB0873801024E8E73B1D0093214603 +:1017700000230822284601F06DFB08340137DEE71C +:10178000201A18BF0120E7E730B5094D0A449142FD +:101790000DD011F8013B5840082340F30004013BF1 +:1017A0002C4013F0FF0384EA5000F6D1EFE730BD80 +:1017B0002083B8EDF7B5364A106851686B4603C30D +:1017C0006A4634493448082303F09CF8044690BB29 +:1017D0000A25324A106851686B4603C36A4630498D +:1017E0002D48082303F08EF80446002847D00369EB +:1017F000B3F5663F43D8B0F86620B2F57B7F3ED1A3 +:10180000284A024402F15C018B4238D35C3B2249F6 +:1018100000209E1AFFF7B8FF3246074604F1640124 +:101820000020FFF7B1FFA3689F4228D1E3689842E8 +:1018300008BF002523E00369B3F5663F26D8428B35 +:10184000B2F57B7F20D1174A024402F110018B428E +:1018500018D3103B104900209D1AFFF795FF2A4628 +:10186000064604F118010020FFF78EFFA3689E4290 +:1018700002D1E368984201D00D25AAE70025284649 +:1018800003B0F0BD1025A4E70C25A2E70B25A0E7C7 +:10189000004A0008DC97030000680008094A0008B5 +:1018A000909703000898FFF710B5037C044613B91E +:1018B000006803F00FF8204610BD00000023BFF3BE +:1018C0005B8FC360BFF35B8FBFF35B8F8360BFF33E +:1018D0005B8F7047BFF35B8F0068BFF35B8F704710 +:1018E00070B505460C30FFF7F5FF05F10806044614 +:1018F0003046FFF7EFFFA04206D930466D68FFF78C +:10190000E9FF2544281A70BD3046FFF7E3FF201A8F +:10191000F9E7000070B50546406898B105F1080088 +:10192000FFF7D8FF05F10C0604463046FFF7D2FF5B +:101930008442304694BF6D680025FFF7CBFF013C21 +:101940002C44201A70BD000038B50C460546FFF740 +:10195000C7FFA04210D305F10800FFF7BBFF044406 +:101960006868B4FBF0F100FB1144BFF35B8F01200A +:10197000AC60BFF35B8F38BD0020FCE72DE9F04180 +:10198000144607460D46FFF7C5FF844228BF0446AC +:10199000D4B1B84658F80C6B4046FFF79BFF304473 +:1019A000286040467E68FFF795FF331A9C4203D8B3 +:1019B0006C600120BDE8F0816B60A41B3B68AB60EC +:1019C0002044E8600220F5E72046F3E738B50C46EE +:1019D0000546FFF79FFFA04210D305F10C00FFF76B +:1019E00079FF04446868B4FBF0F100FB1144BFF3D5 +:1019F0005B8F0120EC60BFF35B8F38BD0020FCE7FC +:101A00002DE9FF41884669460746FFF7B7FF6C4658 +:101A100006B204EBC6060025B44209D0626820680D +:101A200008EB0501FFF774FC636808341D44F3E715 +:101A300029463846FFF7CAFF284604B0BDE8F081C2 +:101A4000F8B505460C300F46FFF744FF05F10806D0 +:101A500004463046FFF73EFFA042304688BF6C6820 +:101A6000FFF738FF201A386020B130462C68FFF7A6 +:101A700031FF2044F8BD000073B5144606460D46FC +:101A8000FFF72EFF844228BF04460190DCB101A974 +:101A90003046FFF7D5FF019B33B93268C5E9023301 +:101AA000C5E9002401200CE09C4238BF0194286065 +:101AB000019868608442F5D93368AB60241AEC6001 +:101AC000022002B070BD2046FBE700002DE9FF4177 +:101AD0000F466946FFF7D0FF6C4600B204EBC00525 +:101AE0000026AC4209D0D4F8048054F8081BB81979 +:101AF0004246FFF70DFC4644F3E7304604B0BDE82C +:101B0000F081000038B50546FFF7E0FF04460146C6 +:101B10002846FFF719FF204638BD0000302383F325 +:101B2000118862B670470000002383F3118862B603 +:101B30007047000010B4026854681A4623465DF8E6 +:101B4000044B184701207047002070470020704761 +:101B500070470000002070470E20704700F580504D +:101B600090F8C800C0F340007047000000F58050B6 +:101B700090F9C90070470000F7B50C68BDF82070F7 +:101B800014F000541E466FD10B7B082B6CD8FFF766 +:101B9000C5FF4569AB685B010CD4AB681B0108D479 +:101BA000AC6814F080545DD1FFF7BEFF204603B04F +:101BB000F0BD01240B6804F1180C002BB8BFDB004A +:101BC0004FEA0C1CB4BF43F004035B0545F80C302E +:101BD0000B680FFA84FC13F0804F18BF05EB0C1E46 +:101BE00005EB0C1C1EBFDEF8803143F00203CEF87B +:101BF00080310B7BCCF8843105EB04158B68C5F87C +:101C00008C314B68C5F88831DCF8803143F0010332 +:101C1000CCF8803100EB441541F268031D4403EB1E +:101C200044130344C5E9002608330D4601F10C0CAA +:101C300055F804EB43F804EB6545F9D184342D885D +:101C40001D8000EB441407F00303257925F00B05F4 +:101C50002B432371FFF768FF0097334600F0E0FC49 +:101C60000120A4E70224A5E74FF0FF309FE7000022 +:101C700013B500F580540191E06DFFF74BFE1F286E +:101C80000AD90199E06D2022FFF7BAFEA0F12003E6 +:101C90005842584102B010BD0020FBE708B500F5DE +:101CA0008050FFF73BFFC06DFFF708FEBDE808401E +:101CB000FFF73ABF00220260828142608260704773 +:101CC00010B500220023C0E900230023044603814D +:101CD0000C30FFF7EFFF204610BD0000F0B50546C1 +:101CE00000F580500C4690F8C83013F0040FC3F391 +:101CF000800108BF114661F3820304F1840680F875 +:101D0000C83005EB461389B01B79D8072ED57AB3B6 +:101D100019072DD46846FFF7D3FF05EB441303F5ED +:101D2000835303F1180703AA10331868596814463F +:101D300003C40833BB422246F7D1186820609B8851 +:101D4000A380DDE90E23CDE900230123ADF808309F +:101D50002B686946DB6B2846984705EB46152B79BF +:101D60001A075CBF43F008032B7101E0002AF4D18D +:101D700009B0F0BD2DE9F047074688B007F580545B +:101D800068469A468846FFF7C9FE9146FFF798FFD6 +:101D9000E06DFFF7A5FD1F2829D9E06D20226946D7 +:101DA000FFF7B0FE202822D103AD444605AB2E46F6 +:101DB00003CE9E4220606160354604F10804F6D1EE +:101DC00030682060B388A380DDE90023C9E90023DF +:101DD000BDF80830AAF80030FFF7A6FE4A46534681 +:101DE0004146384608B0BDE8F04700F007BCFFF7B1 +:101DF0009BFE002008B0BDE8F08700002DE9F84FF9 +:101E00000023C0E90133254B044640F8183B0F4638 +:101E1000FFF750FF04F12800FFF752FF04F14808D4 +:101E200004F582554646083530462036FFF748FF10 +:101E3000AE42F9D104F580554FF480534FF00009BC +:101E4000C5E91339C5F848800123EE6504F58758C4 +:101E500004F58456C5F8549085F8583085F86030FC +:101E6000083608F108084FF0000A4FF0000B46E969 +:101E700008ABA6F11800FFF71DFF203646F8289C96 +:101E80004645F4D185F8C97017B1054800F0A0FBAC +:101E9000044B63612046BDE8F88F00BF3C4A000850 +:101EA000144A00080064004010B5044B1978044639 +:101EB0004A1C1A70FFF7A2FF204610BD14380020FC +:101EC0002DE9F047002950D0294B2A4FB7FBF1F5F7 +:101ED00099428CBF0A231123581EB5FBF3FC03FB68 +:101EE0001C53C4B22BB102280346F5D80020BDE82C +:101EF000F0870CF1FF36B6F5806FF7D2C4EBC40E55 +:101F00000EF103034FEAE309C3F3C703A4EB03088D +:101F100009F1010A4FF47A755FFA88F009FB05555B +:101F20005AFA88F8B5FBF8F5B5F5617FC1BF0EF137 +:101F3000FF33C3F3C703E01AC0B25C1C50FA84F449 +:101F40000CFB04F4B7FBF4F4A142CFD1013BDBB2AC +:101F50000F2BCBD80138C0B20728C7D80021107189 +:101F600016809170D3700120C1E70846BFE700BF1B +:101F70003F420F000051250270B505460E464FF452 +:101F80007A746B695B6803F00103B3424FF00100A0 +:101F900004D001F0A5FC013CF3D1204670BD000047 +:101FA00030B54269936913F0700F16D000230B4CC3 +:101FB000936103F1840200EB421211794D0709D5B8 +:101FC000890707D5416954F823508D60117941F094 +:101FD000040111710133032BEBD130BD284A0008F5 +:101FE00073B51D46436916469A68D207044609D55B +:101FF0009A6801219960C2F34002CDE90065002191 +:10200000FFF76CFE63699A68D1050BD59A684FF4A7 +:1020100080719960C2F34022CDE90065012120461C +:10202000FFF75CFE63699A68D2030BD59A684FF498 +:1020300080319960C2F34042CDE90065022120461B +:10204000FFF74CFE204602B0BDE87040FFF7A8BF86 +:10205000F8B50446466900296CD106F10C073868CA +:1020600080076AD006EB01153868D5F8B00110F08A +:10207000040FD5F8B0011ABFC00840F00040400D71 +:10208000A061D5F8B0C11CF0020F1CBF40F0804029 +:10209000A061D5F8B40106EB011100F00F0084F83F +:1020A0002400D1F8B8012077D1F8B801000A607790 +:1020B000D1F8B801000CA077D1F8B801000EE07794 +:1020C000D1F8BC0184F82000D1F8BC01000A84F8E2 +:1020D0002100D1F8BC01000C84F82200D1F8BC1119 +:1020E000090E84F823103821396004F1340004F11A +:1020F000180104F1240551F8046B40F8046BA9425F +:10210000F9D109880180C4E90A23214600232386E6 +:1021100051F8283B2046DB6B984704F58052204657 +:1021200092F8C83043F0040382F8C830BDE8F840A4 +:10213000FFF736BF06F1100791E7F8BD10B504466A +:1021400000F04EFA02460B4652EA030102D0013A71 +:1021500063F100030449086820B12146BDE810403E +:10216000FFF776BF10BD00BF10380020F8B500F5AE +:1021700083511E46FFF7D2FCDFF844C0083100242B +:1021800004F1840500EB45152B795F070ED4DB06BF +:102190000CD5D1E900739742B34107D243695CF88B +:1021A00024709F602B7943F004032B710134032CBE +:1021B00001F12001E4D1BDE8F840FFF7B5BC00BF54 +:1021C000284A000808B5FFF7A9FCFFF7E9FEBDE8BB +:1021D0000840FFF7A9BC0000F8B5436905469868B8 +:1021E00000F0E050B0F1E05F0F461FD0E8B1FFF71C +:1021F00095FC05F583541034002606F1840305EBA5 +:1022000043131B791A0706D50136032E04F1200467 +:10221000F3D1012007E05B07F6D42146384600F0F1 +:1022200039FA0028F0D1FFF77FFCF8BD0120FCE768 +:1022300000F5805008B5FFF771FCC06DFFF750FB4B +:10224000FFF772FC43090CBF0120002008BD00000D +:10225000F8B51D46002313700F4606461446FFF7D7 +:10226000E7FF80F00100387025B129463046FFF7BE +:10227000B3FF2070F8BD00002DE9B8410C461546AB +:102280001F46804600F0ACF90B462178024609B99A +:10229000287850B14046FFF769FFFFF793FF3B46B0 +:1022A0002A462146FFF7D4FF0120BDE8B88100008F +:1022B00010B5FFF733FC174BDA6942F00072DA61B0 +:1022C0001A6942F000721A611A6900F5805422F00E +:1022D00000721A61FFF728FC94F8C830DB0718D4A5 +:1022E000B9B103211320FFF719FC01F0C7F903214D +:1022F000142001F0C3F90321152001F0BFF994F86F +:10230000C83043F0010384F8C830BDE81040FFF73F +:102310000BBC10BD001002402DE9F04700F58055C0 +:1023200088B095F8C930012B0446884616467FD8F8 +:10233000804F57F823200AB947F82300D7F800A0A8 +:10234000C4F80C802674BAF1000F63D095F8C93038 +:10235000012B6FD001212046FFF7AAFFFFF7DEFB1C +:102360006269136823F0020313606269136843F023 +:1023700001031360636900275F6101212046FFF7B5 +:10238000D3FBFFF7F9FD002800F09580E86DFFF71B +:1023900095FA04F58359BA4609F10809202200216B +:1023A0006846FEF7C7FF02A8FFF784FCCDF818A027 +:1023B0006A4609EB07030DF1180E9446BCE80300CA +:1023C000F44518605960624603F10803F5D1DCF862 +:1023D0000000186020379CF804201A71602FDDD1AE +:1023E00095F8C8306FF38203002785F8C8306A4635 +:1023F00041462046ADF80070ADF802708DF80470CB +:10240000FFF75EFD636948BB4FF400421A6008B0F5 +:10241000BDE8F08741F2D00002F01CFA814610B10D +:102420005146FFF7EBFCC7F80090B9F1000F8DD1D2 +:102430000020ECE7386803681B6B984701460028CA +:1024400088D13868FFF734FF3868036832465B6824 +:102450004146984700287FF47DAFE9E761221A6082 +:102460009DF802309DF803201B06120402F470222E +:1024700003F040731343BDF80020C2F30902134375 +:102480009DF804201205022E02F4E0020CBF4FF06A +:1024900000410021134362690B43D3616369132236 +:1024A0005A616269136823F00103136039462046BC +:1024B000FFF762FD08B96369A6E795F8C93093BBD9 +:1024C0006169D1F8002242F00102C1F8002261697D +:1024D000D1F8002222F47C5222F00E02C1F8002230 +:1024E0006169D1F8002242F46062C1F80022626999 +:1024F000C2F814326269C2F80432626941F6FF71AF +:10250000C2F80C126269C2F840326269C2F8443201 +:1025100063690122C3F81C226269D2F8003223F0F9 +:102520000103C2F8003295F8C83043F0020385F881 +:10253000C8306CE71038002008B500F051F850EAB8 +:102540000103024602D0421E61F10001044B1868EB +:1025500010B10B46FFF744FDBDE8084001F064B838 +:102560001038002008B50020FFF7E8FDBDE808405E +:1025700001F05AB808B50120FFF7E0FDBDE80840BA +:1025800001F052B800B59BB0EFF3098168226846AC +:10259000FEF7BEFEEFF30583014B9B6BFEE700BF2A +:1025A00000ED00E008B5FFF7EDFF000000B59BB0BF +:1025B000EFF3098168226846FEF7AAFEEFF3058370 +:1025C000014B5B6BFEE700BF00ED00E0FEE70000A3 +:1025D0000FB408B5029801F019F9FEE701F02EBB1F +:1025E00001F004BB13B56C4684E80600031D94E8B3 +:1025F000030083E80500012002B010BD73B58568B3 +:10260000019155B11B885B0707D4D0E900369B6B5D +:102610009847019AC1B23046A847012002B070BD68 +:10262000F0B5866889B005460C465EB1BDF8383015 +:102630005B070AD4D0E900379B6B98472246C1B2AA +:102640003846B047012009B0F0BD00220023CDE993 +:1026500000230023ADF808300A4603AB01F1080659 +:10266000106851681C4603C40832B2422346F7D1B1 +:10267000106820609288A280FFF7B2FF0423ADF8B3 +:1026800008302B68CDE90001DB6B69462846984786 +:10269000D8E7000030B503680968DD0FB5EBD17FDE +:1026A00023F0604421F060424FEAD1700BD0002B40 +:1026B000B8BFA40C0029B8BF920C944202D034BF1A +:1026C0000120002030BD944205D1C1F38070C3F3D6 +:1026D00080738342F6D194422CBF00200120F1E7A1 +:1026E0002DE9F041456A15B94162BDE8F0814B68BA +:1026F00023F06047C3F38A464FEAD37EC3F3807862 +:1027000016EA230638BF3E46AC462B465A68BEEB57 +:10271000D27F22F060440AD0002A18DAA40CB44216 +:1027200017D19D420FD10D60DEE71346EEE7A742B9 +:1027300007D102F08044C2F3807242450BD054B1FD +:10274000EFE708D2EDE7CCF800100B60CDE7B4421C +:1027500001D0B442E5D81A689C46002AE5D1196038 +:10276000C3E700002DE9F047089D01F007044FEA98 +:10277000D508224405F0070500EBD1004FF47F494E +:10278000944201D1BDE8F08704F0070705F0070A7D +:1027900057453E4638BF5646C6F10806111B8E42C5 +:1027A00028BF0E46E10808EBD50E415C13F80EC0B9 +:1027B000B94029FA06F721FA0AF1FFB28CEA0101C1 +:1027C00047FA0AF739408CEA010C03F80EC034448A +:1027D0003544D5E780EA0120082341F2210201B205 +:1027E0004000002980B203F1FF33B8BF504013F01E +:1027F000FF03F4D17047000038B50C468D18A54290 +:1028000000D138BD14F8011BFFF7E4FFF7E7000023 +:1028100042684AB1136843604389818901339BB29E +:102820009942438138BF83811046704770B588B0A4 +:10283000202204460D4668460021FEF77BFD204617 +:102840000495FFF7E5FF024658B16B46054608AE12 +:102850001C4603CCB44228606960234605F1080594 +:10286000F6D1104608B070BD082817D909280CD039 +:102870000A280CD00B280CD00C280CD00D280CD01A +:102880000E2814BF4020302070470C2070471020C5 +:1028900070471420704718207047202070470000B0 +:1028A000082817D90C280CD910280CD914280CD9B1 +:1028B00018280CD920280CD930288CBF0F200E20C6 +:1028C0007047092070470A2070470B2070470C2082 +:1028D00070470D20704700002DE9F843078C072F43 +:1028E00004461ED9D0E9029800254FF6FF73C5F1C2 +:1028F0002006A5F1200029FA05F108FA06F628FAC3 +:1029000000F031430143C9B21846FFF763FF0835B1 +:10291000402D0346EBD1E1693A46BDE8F843FFF7A5 +:102920006BBF4FF6FF70BDE8F883000010B54B6831 +:1029300023B9CA8A63F30902CA8210BD04691A68FE +:102940001C600361C38A013BC3824A60EFE7000059 +:102950002DE9F84F1D46CB8A0F46C3F3090105291F +:10296000814692460B4630D00020AAB207F11A04E5 +:102970009EB2042E1FFA80F80FD8904503F1010390 +:1029800006D3FB8A0A4462F30903FB8201201AE0A2 +:102990001AF80060E6540130EAE79045F1D2A1F15F +:1029A000050B1C237C68BBFBF3F203FB12BB1FFA75 +:1029B0008BF6002C45D14846FFF72AFF044638B96C +:1029C00078606FF00200BDE8F88F4FF00008E6E78E +:1029D000002606607860ADB24FF0000B454510D977 +:1029E0000AEB0803221D13F8011B9155B1B208F13F +:1029F00001081B291FFA88F82BD0454506F101066E +:102A0000F1D8FB8AC3F30902154465F30903BCE757 +:102A1000013292B21C462368002BF9D16B1F0B4484 +:102A20001C21B3FBF1F301339BB29A42D3D2BBF129 +:102A3000000FD0D14846FFF7EBFE20B9C4F800B034 +:102A4000BFE70122E7E7C0F800B05E462060044619 +:102A5000C1E74545D5D94846FFF7DAFE08B92060F9 +:102A6000AFE7C0F800B0002620600446B6E70000DB +:102A70002DE9F04F2DED028B1C4683B05B6901926E +:102A800007468846002B00F09A80238C2BB1E26920 +:102A9000002A00F09480072B35D807F10C00FFF7CF +:102AA000B7FE054638B96FF00205284603B0BDEC05 +:102AB000028BBDE8F08F14220021FEF73BFC228C34 +:102AC000E16905F10800FEF723FC208C013080B29B +:102AD000FFF7E6FEFFF7C8FE013880B22084013020 +:102AE00028746369228C1B782A4403F01F0363F067 +:102AF0003F0348F000411372384669602946FFF7EA +:102B0000EFFD0125D1E700F10C034FF0000908EEBD +:102B1000103A4FF0800A4E464D4618EE100AFFF765 +:102B200077FE83460028BED014220021FEF702FC67 +:102B3000002E3AD1019BABF8083002220BF1080EAF +:102B40001FFA82FC0CF10100BCF1060F218C80B24F +:102B500001D88E422BD3FFF7A3FEFFF785FE6269F3 +:102B60001278013802F01F028E4208BF4FF0400A6F +:102B700042EA49121BFA80F14AEA020A013048F09F +:102B8000004281F808A08BF81000CBF804205946C9 +:102B90003846FFF7A5FD238C0135B3422DB289F0ED +:102BA00001094FF0000AB8D17FE70022C6E7E169CA +:102BB000895D0EF802100136B6B20132C0E76FF03F +:102BC000010572E7F8B515460E463022002104468D +:102BD0001F46FEF7AFFB069B6360B5F5001F079B22 +:102BE000A76034BF6A094FF6FF72A36297B2E6612D +:102BF00004F1100000239A4206D800230360A78244 +:102C0000E3822383E360F8BD06600133304620365B +:102C1000F1E7000003781BB94BB2002BC8BF01706D +:102C20007047000000787047F8B50C46C969074640 +:102C300011B9238C002B37D1257E1F2D34D838783D +:102C400028BB228C072A2CD8268A36F003032BD1E6 +:102C50004FF6FF70FFF7D0FD20F001003102400475 +:102C600041EA0561400C41EA40254FF6FF722346D8 +:102C700029463846FFF7FCFE002807DD6269137815 +:102C80000133DBB21F2B88BF00231370F8BD218AEC +:102C90002D0645EA012505432046FFF71DFE0246A5 +:102CA000E5E76FF00300F1E76FF00100EEE70000E9 +:102CB00070B58AB0044616460021282268461D4693 +:102CC000FEF738FBBDF83830ADF810300F9B059398 +:102CD0009DF840308DF81830119B07936946BDF878 +:102CE0004830ADF820302046CDE90265FFF79CFF63 +:102CF0000AB070BD2DE9F041D36905460C46164671 +:102D00000BB9138C5BBB377E1F2F28D895F800803A +:102D1000B8F1000F26D03046FFF7DEFD33782102F0 +:102D200041EAC33141EA0801338A41EA076141EAD5 +:102D300003410246334641F080012846FFF798FEE2 +:102D400000280ADD3378012B07D17269137801332B +:102D5000DBB21F2B88BF00231370BDE8F0816FF03A +:102D60000100FAE76FF00300F7E70000F0B58BB061 +:102D700004460D4617460021282268461E46FEF7E7 +:102D8000D9FA9DF84C305A1E534253418DF8003009 +:102D90009DF84030ADF81030119B05939DF84830F8 +:102DA0008DF81830149B07936A46BDF85430ADF87F +:102DB000203029462046CDE90276FFF79BFF0BB075 +:102DC000F0BD0000406A00B104307047436A1A68E1 +:102DD000426202691A600361C38A013BC382704781 +:102DE0002DE9F041D0F82080194E14461D46414689 +:102DF000002709B9BDE8F081D1E90223A21A65EBE9 +:102E00000303964277EB03031ED2036A8B420DD174 +:102E1000FFF78CFD036A1B68036203690B60C38ABA +:102E20000161016A013BC3828846E2E7FFF77EFD4C +:102E30000B68C8F8003003690B60C38A0161013B6D +:102E4000C382D8F80010D4E788460968D1E700BFEC +:102E500080841E002DE9F04F8BB00D46DDF85090B8 +:102E600014469B468046002800F01981B9F1000FF6 +:102E700000F01581531E3F2B00F21181012A03D16E +:102E8000BBF1000F40F00B810023CDE90833B8F807 +:102E90001430B5EBC30F4FEAC30703D300200BB0C8 +:102EA000BDE8F08F2B199F42D8F80C303ABF7F1B3A +:102EB000FFB227461BB9D8F81030002B7AD0272D47 +:102EC0004ED8C5F12806B7424FF000032CBFF6B22A +:102ED0003E4600932946D8F8080008AB3246FFF773 +:102EE00041FCA7EB060A35445FFA8AFAB8F81430B9 +:102EF00003F10053053BDB000493D8F80C30039337 +:102F00002821039B13B1BAF1000F2CD1D8F810007F +:102F100040B1BAF1000F05D0009608AB5246691ACD +:102F2000FFF720FC38B2002FB8D066070AD00AABF2 +:102F300003EBD401624211F8083C02F0070213418E +:102F400001F8083C082C3CD9102C40F2B580202C0C +:102F500040F2B780BBF1000F00F09C80082334E002 +:102F6000BA460026C2E7049BE02B28BFE023069365 +:102F70000B44AB42059314D95A1B03980096924513 +:102F800034BF5246D2B2691A08AB04300792FFF739 +:102F9000E9FB079A1644AAEB020A1544F6B25FFA57 +:102FA0008AFA049B069A05999B1A0493039B1B6853 +:102FB0000393A6E70093D8F8080008AB3A462946E1 +:102FC000AEE7BBF1000F13D00123B4EBC30F6CD0FD +:102FD000082C12D89DF82030621E23FA02F2D50781 +:102FE00006D54FF0FF3202FA04F423438DF8203067 +:102FF0009DF8203089F8003051E7102C12D8BDF828 +:103000002030621E23FA02F2D10706D54FF0FF32BC +:1030100002FA04F42343ADF82030BDF82030A9F8BB +:1030200000303CE7202C0FD80899631E21FA03F3E7 +:10303000DA0705D54FF0FF3202FA04F40C43089486 +:10304000089BC9F800302AE7402C2BD0DDE9086541 +:10305000611EC4F12102A4F1210326FA01F105FA4F +:1030600002F225FA03F311431943CB0712D50122CB +:10307000A4F12003C4F1200102FA03F322FA01F1C2 +:10308000A240524243EA010363EB430332432B4322 +:10309000CDE90823DDE90823C9E90023FFE66FF045 +:1030A0000100FCE66FF00800F9E6082CA0D9102C0E +:1030B000B3D9202CEED8C3E7BBF1000FADD002236B +:1030C00083E7BBF1000FBBD004237EE730B5012AB4 +:1030D000144638BF0124402C85B028BF4024002569 +:1030E000012ACDE9025518D81B788DF808306307FE +:1030F0000AD004AB03EBD405624215F8083C02F099 +:103100000702934005F8083C00910346224600213F +:1031100002A8FFF727FB05B030BD082AE4D9102A22 +:1031200003D81B88ADF80830E1E7202A8DBFD3E92A +:1031300000231B680293CDE90223D8E710B5CB68C2 +:103140001BB98B600B618B8210BD04691A681C600F +:103150000361C38A013BC382CA60F0E703064CBF28 +:10316000C0F3C0300220704708B50246FFF7F6FFF3 +:10317000022806D15306C2F30F2001D100F003004C +:1031800008BDC2F30740FBE72DE9F04F93B0CDE94E +:1031900003230A6804461046FFF7E0FF022814BF25 +:1031A000C2F306260026002A0D46824680F2F281EE +:1031B00012F0C04940F0EE81097B002900F0EA815D +:1031C000022803D02378B34240F0E781C2F30463BE +:1031D0000693104602F07F030593FFF7C5FF059B9A +:1031E00029444FEA834848EA0A4848EA4668CE78C4 +:1031F00000230022CDE90823F309834648EA0008AA +:10320000029367D0059B009302466768534608A95E +:103210002046B847002800F0C381276A4FB94146CD +:1032200004F10C00FFF702FB074690B96FF00200B3 +:1032300054E03B6998450DD03F68002FF9D14146D5 +:1032400004F10C00FFF7F2FA07460028EED0236ADB +:103250003B60276297F817C006F01F08CCF3840C78 +:10326000ACEB08001FFA80FE0028B8BF0EF120006A +:10327000A8EB0C031FFA83FED7E90221B8BF00B206 +:10328000002B0793BEBF0EF120031BB2079352EA37 +:10329000010338D0039BDFF824E39A1A049B4FF014 +:1032A000000C63EB010196457CEB01032BD36B7B98 +:1032B00097F81AE0734519D1029B002B78D00128AA +:1032C00021DC7868F8B9DFF8F0C2944570EB0103AF +:1032D00016D337E0276A27B96FF00C0013B0BDE8AA +:1032E000F08F3B699845B5D03F68F4E7B24890420B +:1032F0007CEB010301D30020F0E7029B002BFAD006 +:10330000079B0F2B17DCFA7DB30002F0030203F0DA +:103310007C031343FB7539462046FFF707FB6B7BA5 +:10332000BB76029B3BB9FB7DC3F38402013262F39F +:103330008603FB75D0E76A7BBB7E9A42DBD1029B9A +:10334000002B35D0B309022B32D0039BBB60049B0A +:10335000FB60142200210DA8FDF7ECFF039B0A93EC +:10336000049B0B932B1D0C932B7BADF83EB0013BC4 +:10337000DBB2ADF83C30069B8DF84230059B8DF8F2 +:10338000433094F82C308DF840A083F001038DF881 +:1033900044308DF84180A3680AA920469847FB7DF8 +:1033A000C3F38403013303F01F039B02FB82A2E7F4 +:1033B000FB7DC6F34012B2EBD31F40F0F480C3F3A1 +:1033C0008403434540F0F280029A2B7BB609002A21 +:1033D0004DD0F2075DD4032B40F2EB80039BBB6022 +:1033E000049BFB602B7BAE1D033BDBB232463946B0 +:1033F00004F10C00FFF7ACFA00280CDA394620463D +:10340000FFF794FAFB7DC3F38403013303F01F033A +:103410009B02FB820AE7DDE90884AB883B834FF619 +:10342000FF73C9F12000A9F1200228FA09F104FA7A +:1034300000F0014324FA02F211431846C9B2FFF723 +:10344000C9F909F10809B9F1400F0346E9D1B88279 +:103450002A7B033AD2B23146FFF7CEF9FB7DB88220 +:10346000DA43C2F3C01262F3C713FB7543E786B9B0 +:103470002E1D013BDBB23246394604F10C00FFF74A +:1034800067FA0028BADB2A7BB88A013AD2B2314601 +:10349000E2E7F98AC1F30901013B0429DAB25BD8FA +:1034A000281D002307F11B069A4208D910F801CB0A +:1034B00006F801C0013101330529DBB2F4D10399CB +:1034C0000A9104990B91934207F11B010C9138BFAB +:1034D000043379680D9134BF55FA83F300230E93BA +:1034E000FB8AADF83EB0C3F309031A44069B8DF87E +:1034F0004230059B8DF8433094F82C30ADF83C20D9 +:1035000083F001038DF8443000238DF840A08DF83E +:1035100041807B602A7BB88A013A291DFFF76CF94C +:103520003B8BB882834203D1A3680AA920469847FF +:1035300020460AA9FFF702FEFB7DBA8AC3F3840383 +:10354000013303F01F039B02FB823B8B9A420CBFAB +:1035500000206FF01000C1E67B68002BAFD0052083 +:1035600001E01C3033461E68002EFAD1091A081DEE +:103570002E1D184401EB090CBCF11B0F5FFA89F3F7 +:103580009DD89A429BD916F8013B00F8013B09F1FE +:103590000109EFE76FF00900A0E66FF00A009DE671 +:1035A0006FF00B009AE66FF00D0097E66FF00E00DB +:1035B00094E66FF00F0091E640420F0080841E00F9 +:1035C000EFF3098305494A6B22F001024A6368332D +:1035D00083F30988002383F31188704700EF00E02C +:1035E000302080F3118862B60C4B0D4AD96821F463 +:1035F000E0610904090C0A43DA60D3F8FC200949A8 +:1036000042F08072C3F8FC200A6842F001020A60AE +:103610002022DA7783F82200704700BF00ED00E037 +:103620000003FA05001000E010B5302383F3118881 +:103630000E4B5B6813F4006314D0F1EE103AEFF315 +:103640000984683C4FF08073E361094BDB6B2366B0 +:1036500084F3098800F098F810B1064BA36110BDFF +:10366000054BFBE783F31188F9E700BF00ED00E0AD +:1036700000EF00E0030600080606000800F16043C2 +:1036800003F561430901C9B283F80013012200F078 +:103690001F039A4043099B0003F1604303F5614314 +:1036A000C3F880211A60704700F16040090100F5FD +:1036B0006D40C9B2017670470023037582680369C3 +:1036C0001B6899689142FBD25A680360426010609F +:1036D0005860704700230375826803691B68996806 +:1036E0009142FBD85A68036042601060586070478E +:1036F00008B50846302383F311880B7D032B05D0D2 +:10370000042B0DD02BB983F3118808BD8B690022DF +:103710001A604FF0FF338361FFF7CEFF0023F2E71B +:10372000D1E9003213605A60F3E70000FFF7C4BF2D +:10373000054BD9680875186802681A605360012241 +:103740000275D860FCF748BF2038002030B50C4B1C +:10375000DD684B1C87B004460FD02B46094A6846EB +:1037600000F0FEF82046FFF7E3FF009B13B1684628 +:1037700000F000F9A86907B030BDFFF7D9FFF9E7FD +:1037800020380020F1360008044B1A68DB68906886 +:103790009B68984294BF0020012070472038002089 +:1037A000084B10B51C68D86822681A605360012263 +:1037B0002275DC60FFF78EFF01462046BDE8104011 +:1037C000FCF70ABF20380020044B1A68DB689268B7 +:1037D0009B689A4201D9FFF7E3BF70472038002069 +:1037E00038B5074C07490848012300252370656058 +:1037F00000F00AFB0223237085F3118838BD00BF57 +:10380000483A0020804A00082038002008B572B6E7 +:10381000044B186500F0CEF900F092FA024B032237 +:103820001A70FEE720380020483A002000F0B4B8B3 +:10383000EFF3118020B9EFF30583302282F3118872 +:103840007047000010B530B9EFF30584C4F30804E5 +:1038500014B180F3118810BDFFF7B6FF84F311880F +:10386000F9E700008B60022308618B8208467047ED +:103870008368A3F1840243F8142C026943F8442CB2 +:10388000426943F8402C094A43F8242CC26843F8A3 +:10389000182C022203F80C2C002203F80B2C044AEB +:1038A00043F8102CA3F12000704700BFF105000879 +:1038B0002038002008B5FFF7DBFFBDE80840FFF720 +:1038C00035BF0000024BDB6898610F20FFF730BF67 +:1038D00020380020302383F31188FFF7F3BF000066 +:1038E00008B50146302383F311880820FFF72EFF27 +:1038F000002383F3118808BD064BDB6839B14268A9 +:1039000018605A60136043600420FFF71FBF4FF038 +:10391000FF307047203800200368984206D01A68AC +:103920000260506099611846FFF700BF70470000C1 +:1039300010B50A4C23699A6891420CD85A68816084 +:103940000360426010609A685860511A99604FF0A5 +:10395000FF33A36110BD1B68891AECE720380020F3 +:1039600010B4C0E9032300235DF8044B4361FFF763 +:10397000DFBF0000036881689A680A449A60426861 +:1039800013605A6000230360024B4FF0FF329A61CC +:10399000704700BF2038002070B5124DEB692A46F1 +:1039A0000133EB6152F8103F934206D09A68013A16 +:1039B0009A6030262C69A36803B170BDD4E9002158 +:1039C0000A605160236083F31188D4E903312046F3 +:1039D000984786F3118861690029EBD02046FFF7EC +:1039E000A7FFE7E72038002000207047FEE700002F +:1039F000704700004FF0FF3070470000BFF34F8F5B +:103A0000024AD368DB07FCD4704700BF00200240A5 +:103A100008B5074B1B7853B9FFF7F0FF054B1A6940 +:103A2000120641BF044A5A6002F188325A6008BD4A +:103A3000603A0020002002402301674508B5054B8D +:103A40001B7833B9FFF7DAFF034A136943F08003A9 +:103A5000136108BD603A0020002002407F289ABF11 +:103A600000F58030C0020020704700004FF4006075 +:103A700070470000802070477F2808B50BD8FFF7FB +:103A8000EDFF00F500630268013204D10430834287 +:103A9000F9D1012008BD0020FCE700007F2810B507 +:103AA00004461CD8FFF7AAFFFFF7B2FF0D4BF32225 +:103AB000DA6002221A61FFF7D1FF58611A6942F0F9 +:103AC00040021A614FF40061FFF798FF00F034F9EB +:103AD000FFF7B4FF2046BDE81040FFF7CDBF002040 +:103AE00010BD00BF002002402DE9F84312F0010391 +:103AF000144606D01F4B40F2F3221A600020BDE8A6 +:103B0000F88385181C4A954204D91A4A4FF43E712D +:103B10001160F3E7FFF77CFFFFF770FFDFF86880C5 +:103B2000451A4FF00109012C05EB01060F4603D899 +:103B3000FFF784FF0120E2E73B88C8F8109033804C +:103B40000020FFF75BFFC8F81000338831F8022B24 +:103B50009BB29A420CD0074B40F20F321A60074BCF +:103B60001E60074B1C60074B1F60FFF767FFC6E72F +:103B7000023CD8E75C3A002000000408503A0020DC +:103B8000583A0020543A002000200240084908B565 +:103B90000B7828B11BB9FFF73BFF01230B7008BD61 +:103BA000002BFCD0BDE808400870FFF747BF00BFFE +:103BB000603A002008B54FF420414FF0005000F06B +:103BC000BDF8BDE808404FF400514FF0805000F0C0 +:103BD000B5B800000846114600F05EBE012000F0B6 +:103BE0005BBE0000084600F075BE000030B583B033 +:103BF000FFF71EFE0E4B0F4DDB692A684FF47A71FA +:103C000001FB03F3934237BF0B4A0B495168146819 +:103C10002B602EBFD1E90041013151601C1941F1E7 +:103C200000010191FFF70EFE0199204603B030BD5F +:103C300020380020643A0020683A002030B583B074 +:103C4000FFF7F6FD114B124DDB692A684FF47A71CC +:103C500001FB03F3934237BF0E4A0E4951681468C3 +:103C60002B602EBFD1E90041013151601C1941F197 +:103C700000010191FFF7E6FD01994FF47A720023EC +:103C80002046FCF795FA03B030BD00BF2038002075 +:103C9000643A0020683A002010B50244064BD2B2C4 +:103CA000904200D110BD441C00B253F8200041F8EE +:103CB000040BE0B2F4E700BF502800400F4B30B5D2 +:103CC0001C6A240407D41C6A44F440741C621C6AF5 +:103CD00044F400441C620A4C236843F4807323605C +:103CE0000244084BD2B2904200D130BD441C00B215 +:103CF00051F8045B43F82050E0B2F4E700100240B2 +:103D0000007000405028004007B5012201A90020A2 +:103D1000FFF7C2FF019803B05DF804FB13B504463A +:103D2000FFF7F2FFA04205D0012201A90020019473 +:103D3000FFF7C4FF02B010BD7047000070470000DD +:103D400070470000074B45F255521A6002225A6034 +:103D500040F6FF729A604CF6CC421A60024B012288 +:103D60001A70704700300040743A0020034B1B78F3 +:103D70001BB1034B4AF6AA221A607047743A00201E +:103D800000300040044B1A682AB902F1804202F563 +:103D90000432526A1A607047703A0020024B4FF0AA +:103DA00080725A62704700BF0010024008B5FFF7EA +:103DB000E9FF024B1868C0F3407008BD703A00205C +:103DC00070470000FEE700000A4B0B480B4A904288 +:103DD0000BD30B4BDA1C121AC11E22F003028B42CA +:103DE00038BF00220021FDF7A5BA53F8041B40F8A4 +:103DF000041BECE7EC4B0008583C0020583C00202A +:103E0000583C0020FEE7000070B51B4B0163002505 +:103E1000044686B0586085620E46FFF7E1FB04F168 +:103E20001003C4E904334FF0FF33A361134BE56182 +:103E3000D969A5600A462B46C4E9082304F1340178 +:103E4000C4E900440E4AE562256580232046FFF759 +:103E500009FD0123E0600B4A03750092726801922C +:103E6000B268CDE90223084B6846CDE90435FFF777 +:103E700021FD06B070BD00BF483A00202038002068 +:103E80008C4A0008914A0008053E00084B684360D0 +:103E90008B688360CB68C3600B6943614B690362C5 +:103EA0008B6943620B6803607047000008B51B4BC9 +:103EB0009A6A42F4FC029A629A6A22F4FC029A62BA +:103EC0009A6A5A6942F4FC025A61154A5B691146C2 +:103ED0004FF09040FFF7DAFF02F11C0100F580601F +:103EE000FFF7D4FF02F1380100F58060FFF7CEFF45 +:103EF00002F1540100F58060FFF7C8FF02F1700184 +:103F000000F58060FFF7C2FF02F18C0100F58060D0 +:103F1000FFF7BCFFBDE8084000F05AB800100240AF +:103F2000984A000808B500F093F9FFF759FCBDE87E +:103F30000840FFF727BF00007047000010B5214C74 +:103F4000A36A63F4FC03A362A36A03F4FC03A36201 +:103F50004FF0FF32A36A23692261236900232361A2 +:103F60002169E168E260E268E360E268E2691649BB +:103F700042F08052E261E2690A6842F480720A60AB +:103F8000226A02F44072B2F5407F1EBF4FF48032C5 +:103F900022622362236A1B0407D4236A43F440731A +:103FA0002362236A43F40043236200F031F9A369DA +:103FB000064A43F00103A361A369136843F0200399 +:103FC000136010BD0010024000700040000001406E +:103FD0001E4B1A6842F001021A601A689007FCD55D +:103FE0005A6822F003025A605A6812F00C02FBD1A0 +:103FF000196801F0F90119605A601A6842F48032B8 +:104000001A601A689103FCD5114A5A604FF40452A1 +:10401000DA6230221A631A6842F080721A601A68F3 +:104020009201FCD50B4912220A600A6802F00702CD +:10403000022AFAD15A6842F002025A605A6802F023 +:104040000C02082AFAD11A6B1A637047001002405A +:1040500000241D0000200240084A08B55169136879 +:104060000B4003F00103536123B1054A13680BB100 +:1040700050689847BDE80840FFF7D6BA00040140F1 +:10408000783A0020084A08B5516913680B4003F0DC +:104090000203536123B1054A93680BB1D068984776 +:1040A000BDE80840FFF7C0BA00040140783A00209C +:1040B000084A08B5516913680B4003F004035361C3 +:1040C00023B1054A13690BB150699847BDE8084010 +:1040D000FFF7AABA00040140783A0020084A08B560 +:1040E000516913680B4003F00803536123B1054A7B +:1040F00093690BB1D0699847BDE80840FFF794BABF +:1041000000040140783A0020084A08B55169136854 +:104110000B4003F01003536123B1054A136A0BB13E +:10412000506A9847BDE80840FFF77EBA0004014096 +:10413000783A0020174B10B55A691C68144004F4F3 +:1041400078725A61A30604D5134A936A0BB1D06AF8 +:104150009847600604D5104A136B0BB1506B984713 +:10416000210604D50C4A936B0BB1D06B9847E2053E +:1041700004D5094A136C0BB1506C9847A30504D5BC +:10418000054A936C0BB1D06C9847BDE81040FFF71F +:104190004BBA00BF00040140783A00201A4B10B51A +:1041A0005A691C68144004F47C425A61620504D5C3 +:1041B000164A136D0BB1506D9847230504D5134A69 +:1041C000936D0BB1D06D9847E00404D50F4A136E80 +:1041D0000BB1506E9847A10404D50C4A936E0BB1F5 +:1041E000D06E9847620404D5084A136F0BB1506F24 +:1041F0009847230404D5054A936F0BB1D06F9847B5 +:10420000BDE81040FFF710BA00040140783A0020E2 +:10421000062108B50846FFF731FA06210720FFF707 +:104220002DFA06210820FFF729FA06210920FFF7B9 +:1042300025FA06210A20FFF721FA06211720FFF7A9 +:104240001DFABDE8084006212820FFF717BA000034 +:1042500008B5FFF773FE00F067F800F03DF8FFF7D0 +:104260006BFEBDE8084000F05DB8000002684368DE +:104270001143016003B1184770470000143000F08B +:104280002FBA00004FF0FF33143000F029BA0000BD +:10429000383000F0A5BA00004FF0FF33383000F09E +:1042A0009FBA0000143000F0F5B900004FF0FF3164 +:1042B000143000F0EFB90000383000F04FBA0000C1 +:1042C0004FF0FF32383000F049BA0000012914BF26 +:1042D0006FF013000020704700F06CB8044B0360CF +:1042E0000023C0E90233436001230374704700BF19 +:1042F000404B000838B5C36904460D461BB904217C +:104300000844FFF7B3FF294604F1140000F0A6F9B2 +:10431000002806DA201D4FF40061BDE83840FFF7A1 +:10432000A5BF38BD00F00EB80023054A1946013379 +:10433000102BC2E9001102F10802F8D1704700BF4A +:10434000783A00204FF0E023044A5A6100229A6133 +:1043500007221A6108210B20FFF7A6B93F190100B7 +:1043600008B5302383F31188FFF760FA002383F345 +:10437000118808BD08B5FFF7F3FFBDE80840FFF757 +:1043800053B90000026843681143016003B1184744 +:1043900070470000024A136843F0C003136070477F +:1043A00000380140024A136843F0C00313607047AD +:1043B0000044004037B51D4C1D4D2046FFF78EFFD1 +:1043C000009404F114001B490023202200F038F966 +:1043D0002022009404F13800174B184900F0B2F97C +:1043E000174BC4E91735174C0C212520FFF746F968 +:1043F0002046FFF773FF04F11400134900940023D3 +:10440000202200F01DF904F13800104B10490094EF +:10441000202200F097F90F4B0C212620C4E9173514 +:1044200003B0BDE83040FFF729B900BFF83A0020DB +:1044300000512502D03B002095430008103C00208D +:1044400000380140643B0020F03B0020A5430008F9 +:10445000303C0020004400402DE9F047C66D37682D +:10446000F46934622107054619D014F0080118BF19 +:104470004FF48071E20748BF41F02001A30748BF15 +:1044800041F04001600748BF41F08001302383F3D1 +:104490001188281DFFF776FF002383F31188E205BA +:1044A0000AD5302383F311884FF48061281DFFF76C +:1044B00069FF002383F311884FF030094FF0000AA1 +:1044C00014F0200838D13B0616D54FF0300905F11D +:1044D000380A200610D589F31188504600F066F995 +:1044E000002836DA0821281DFFF74CFF27F080034B +:1044F0003360002383F31188790614D5620612D540 +:10450000302383F31188D5E913239A4208D12B6C09 +:1045100033B11021281D27F04007FFF733FF376024 +:10452000002383F31188E30619D5AA6E1369B3B18A +:10453000BDE8F0475069184789F31188B38C95F8A6 +:10454000641028461940FFF7D5FE8AF31188F469F4 +:10455000B6E780B2308588F31188F469B9E7BDE821 +:10456000F087000008B50348FFF776FFBDE8084074 +:10457000FFF75AB8F83A002008B50348FFF76CFF78 +:10458000BDE80840FFF750B8643B0020F8B5154679 +:1045900082680669AA420B46816938BF8568761A27 +:1045A000B54204460BD218462A46FCF7B1FEA36971 +:1045B0002B44A361A3685B1BA3602846F8BD0CD9FC +:1045C00018463246FCF7A4FEAF1BE1683A46304479 +:1045D000FCF79EFEE3683B44EBE718462A46FCF7EF +:1045E00097FEE368E5E7000083689342F7B5154658 +:1045F000044638BF8568D0E90460361AB5420BD24C +:104600002A46FCF785FE63692B446361A36828464C +:104610005B1BA36003B0F0BD0DD932460191FCF7DE +:1046200077FE0199E068AF1B3A463144FCF770FE13 +:10463000E3683B44E9E72A46FCF76AFEE368E4E7FF +:1046400010B50A440024C361029B8460C0E90000E5 +:10465000C0E90511C1600261036210BD08B5D0E96F +:104660000532934201D1826882B982680132826048 +:104670005A1C42611970D0E904329A4224BFC368BF +:1046800043610021FFF748F9002008BD4FF0FF30DB +:10469000FBE7000070B5302304460E4683F3118813 +:1046A000A568A5B1A368A269013BA360531CA361DF +:1046B00015782269934224BFE368A361E3690BB1D3 +:1046C00020469847002383F31188284607E03146A7 +:1046D0002046FFF711F90028E2DA85F3118870BD52 +:1046E0002DE9F74F04460E4617469846D0F81C9021 +:1046F0004FF0300A8AF311884FF0000B154665B170 +:104700002A4631462046FFF741FF034660B941463D +:104710002046FFF7F1F80028F1D0002383F3118839 +:10472000781B03B0BDE8F08FB9F1000F03D0019002 +:104730002046C847019B8BF31188ED1A1E448AF36B +:104740001188DCE7C0E90511C160C3611144009B19 +:104750008260C0E90000016103627047F8B5044659 +:104760000D461646302383F31188A768A7B1A368C6 +:10477000013BA36063695A1C62611D70D4E9043275 +:104780009A4224BFE3686361E3690BB1204698470E +:10479000002080F3118807E031462046FFF7ACF88F +:1047A0000028E2DA87F31188F8BD0000D0E905237C +:1047B0009A4210B501D182687AB98268013282606A +:1047C0005A1C82611C7803699A4224BFC3688361C2 +:1047D0000021FFF7A1F8204610BD4FF0FF30FBE7A6 +:1047E0002DE9F74F04460E4617469846D0F81C9020 +:1047F0004FF0300A8AF311884FF0000B154665B16F +:104800002A4631462046FFF7EFFE034660B941468F +:104810002046FFF771F80028F1D0002383F31188B8 +:10482000781B03B0BDE8F08FB9F1000F03D0019001 +:104830002046C847019B8BF31188ED1A1E448AF36A +:104840001188DCE70B460146184600F02DB8000041 +:1048500000F040B8012838BF012010B504462046BA +:1048600000F030F830B900F007F808B900F00CF8A3 +:104870008047F4E710BD0000024B1868BFF35B8F60 +:10488000704700BF503C002008B5062000F084F8B7 +:104890000120FFF7ABF80000024B0A4601461868FA +:1048A000FFF798B91811002010B5054C13462CB12C +:1048B0000A4601460220AFF3008010BD2046FCE707 +:1048C00000000000024B01461868FFF787B900BFDF +:1048D00018110020024B01461868FFF783B900BF8A +:1048E0001811002010B501390244904201D1002076 +:1048F00005E0037811F8014FA34201D0181B10BD49 +:104900000130F2E72DE9F041A3B1C91A177801444B +:10491000044603F1FF3C8C42204601D9002009E007 +:104920000578BD4204F10104F5D10CEB0405D6185D +:10493000A54201D1BDE8F08115F8018D16F801ED11 +:10494000F045F5D0E7E700001F2938B504460D46CD +:1049500004D9162303604FF0FF3038BD426C12B10A +:1049600052F821304BB9204600F030F82A46014673 +:104970002046BDE8384000F017B8012B0AD0591C7A +:1049800003D1162303600120E7E7002442F8254005 +:10499000284698470020E0E7024B01461868FFF7D9 +:1049A000D3BF00BF1811002038B5074D00230446BF +:1049B000084611462B60FFF71DF8431C02D12B68F7 +:1049C00003B1236038BD00BF543C0020FFF70CB892 +:1049D000034611F8012B03F8012B002AF9D1704787 +:1049E0006F72672E6172647570696C6F742E6633B6 +:1049F00030332D556E6976657273616C000000006E +:104A000040A2E4F1646891060041A3E5F265699271 +:104A1000070000004261642043414E4966616365BE +:104A200020696E6465782E00800000000080000020 +:104A3000000080000000000000000000351B00089E +:104A40001923000879220008451B0008791B00087B +:104A5000751D0008491B0008591B00084D1B000864 +:104A6000551B0008511B00089D1C00085D1B000819 +:104A7000E52500086D1B0008711C0008633000006C +:104A80007C4A000878380020483A00206D61696E41 +:104A90000069646C65000000A001A82A0000000005 +:104AA000FAAABEAA50001424EFFF0000007700000D +:104AB000709709000100000000000000AAAAAAAA3D +:104AC00001000000FFFF00000000000000000000E7 +:104AD0000000000000000000AAAAAAAA000000002E +:104AE000FFFF0000000000000000000000000000C8 +:104AF00000000000AAAAAAAA00000000FFFF000010 +:104B000000000000000000000000000000000000A5 +:104B1000AAAAAAAA00000000FFFF000000000000EF +:104B2000000000000000000000000000AAAAAAAADD +:104B300000000000FFFF0000000000000000000077 +:104B4000000000009942000885420008C1420008A8 +:104B5000AD420008B9420008A54200089142000891 +:104B60007D420008CD42000878B6FF7F01000000BA +:104B7000EC030000000000000098030000000000AB +:104B8000FE2A0100D20400001C11002000000000D9 +:104B90000000000000000000000000000000000015 +:104BA0000000000000000000000000000000000005 +:104BB00000000000000000000000000000000000F5 +:104BC00000000000000000000000000000000000E5 +:104BD00000000000000000000000000000000000D5 +:0C4BE000000000000000000000000000C9 :00000001FF diff --git a/Tools/bootloaders/f405-MatekAirspeed_bl.bin b/Tools/bootloaders/f405-MatekAirspeed_bl.bin index 3a2276329c3e05..75eac16a24a4ac 100755 Binary files a/Tools/bootloaders/f405-MatekAirspeed_bl.bin and b/Tools/bootloaders/f405-MatekAirspeed_bl.bin differ diff --git a/Tools/bootloaders/f405-MatekAirspeed_bl.hex b/Tools/bootloaders/f405-MatekAirspeed_bl.hex index 2b5ee851433a77..989d82a4d68cb8 100644 --- a/Tools/bootloaders/f405-MatekAirspeed_bl.hex +++ b/Tools/bootloaders/f405-MatekAirspeed_bl.hex @@ -1,1509 +1,1741 @@ :020000040800F2 -:1000000000070020E5040008E11B0008611B000850 -:10001000B91B0008611B00088D1B0008E7040008DD -:10002000E7040008E7040008E70400082547000883 -:10003000E7040008E7040008E7040008E7040008F4 -:10004000E7040008E7040008E7040008E7040008E4 -:10005000E7040008E7040008C1570008ED5700084E -:10006000195800084558000871580008E7040008AE -:10007000E7040008E7040008E7040008E7040008B4 -:10008000E7040008E7040008E7040008E52E00087C -:10009000512F0008A52F0008F92F00089D580008CF -:1000A000E7040008E7040008E7040008E704000884 -:1000B00035560008E7040008E7040008E7040008D4 -:1000C000E7040008E7040008E7040008E704000864 -:1000D000E7040008E7040008E7040008E704000854 -:1000E00005590008E7040008E7040008E7040008D1 -:1000F000E7040008E7040008E7040008E704000834 -:10010000E7040008E7040008E7040008E704000823 -:10011000E7040008E7040008E7040008E704000813 -:10012000E7040008E7040008E7040008E704000803 -:10013000E7040008E7040008E7040008E7040008F3 -:10014000E7040008E7040008E70400085D4E000823 -:10015000E7040008E7040008E7040008E7040008D3 -:10016000E7040008E7040008E7040008E7040008C3 -:10017000E7040008E7040008E7040008E7040008B3 -:10018000E7040008E7040008E7040008E7040008A3 -:10019000E7040008E7040008E7040008E704000893 -:1001A000E7040008E7040008E7040008E704000883 -:1001B000E7040008E7040008E7040008E704000873 -:1001C000E7040008E7040008E7040008E704000863 -:1001D000E7040008E7040008E7040008E704000853 -:1001E00053B94AB9002908BF00281CBF4FF0FF319E -:1001F0004FF0FF3000F074B9ADF1080C6DE904CE9A -:1002000000F006F8DDF804E0DDE9022304B07047F1 -:100210002DE9F047089D04468E46002B4DD18A42B9 -:10022000944669D9B2FA82F252B101FA02F3C2F1EC -:10023000200120FA01F10CFA02FC41EA030E94407D -:100240004FEA1C48210CBEFBF8F61FFA8CF708FB9E -:1002500016E341EA034306FB07F199420AD91CEB76 -:10026000030306F1FF3080F01F81994240F21C81A8 -:10027000023E63445B1AA4B2B3FBF8F008FB1033F0 -:1002800044EA034400FB07F7A7420AD91CEB040425 -:1002900000F1FF3380F00A81A74240F207816444F5 -:1002A000023840EA0640E41B00261DB1D44000237A -:1002B000C5E900433146BDE8F0878B4209D9002DDE -:1002C00000F0EF800026C5E9000130463146BDE868 -:1002D000F087B3FA83F6002E4AD18B4202D38242D2 -:1002E00000F2F980841A61EB030301209E46002D81 -:1002F000E0D0C5E9004EDDE702B9FFDEB2FA82F2D6 -:10030000002A40F09280A1EB0C014FEA1C471FFA33 -:100310008CFE0126200CB1FBF7F307FB131140EA1A -:1003200001410EFB03F0884208D91CEB010103F1E7 -:10033000FF3802D2884200F2CB804346091AA4B2A9 -:10034000B1FBF7F007FB101144EA01440EFB00FE7D -:10035000A64508D91CEB040400F1FF3102D2A645E2 -:1003600000F2BB800846A4EB0E0440EA03409CE781 -:10037000C6F12007B34022FA07FC4CEA030C20FA2E -:1003800007F401FA06F31C43F9404FEA1C4900FA4E -:1003900006F3B1FBF9F8200C1FFA8CFE09FB1811CB -:1003A00040EA014108FB0EF0884202FA06F20BD93E -:1003B0001CEB010108F1FF3A80F08880884240F28E -:1003C0008580A8F102086144091AA4B2B1FBF9F0D2 -:1003D00009FB101144EA014100FB0EFE8E4508D9CD -:1003E0001CEB010100F1FF346CD28E456AD9023852 -:1003F000614440EA0840A0FB0294A1EB0E01A14237 -:10040000C846A64656D353D05DB1B3EB080261EBA4 -:100410000E0101FA07F722FA06F3F1401F43C5E97E -:10042000007100263146BDE8F087C2F12003D840B4 -:100430000CFA02FC21FA03F3914001434FEA1C47F6 -:100440001FFA8CFEB3FBF7F007FB10360B0C43EAE8 -:10045000064300FB0EF69E4204FA02F408D91CEB98 -:10046000030300F1FF382FD29E422DD90238634496 -:100470009B1B89B2B3FBF7F607FB163341EA034136 -:1004800006FB0EF38B4208D91CEB010106F1FF3885 -:1004900016D28B4214D9023E6144C91A46EA00467C -:1004A00038E72E46284605E70646E3E61846F8E60E -:1004B0004B45A9D2B9EB020864EB0C0E0138A3E757 -:1004C0004646EAE7204694E74046D1E7D0467BE738 -:1004D000023B614432E7304609E76444023842E7B0 -:1004E000704700BF02E000F000F8FEE772B63A483D -:1004F00080F30888394880F3098839484EF6085156 -:10050000CEF20001086040F20000CCF200004EF68E -:100510003471CEF200010860BFF34F8FBFF36F8FCD -:1005200040F20000C0F2F0004EF68851CEF2000119 -:100530000860BFF34F8FBFF36F8F4FF00000E1EE05 -:10054000100A4EF63C71CEF200010860062080F3DE -:100550001488BFF36F8F04F065F904F041F904F0DB -:10056000CDFF4FF055301F491B4A91423CBF41F827 -:10057000040BFAE71C49194A91423CBF41F8040BAD -:10058000FAE71A491A4A1B4B9A423EBF51F8040B2C -:1005900042F8040BF8E700201749184A91423CBF83 -:1005A00041F8040BFAE704F01FF904F0FBFF144CC8 -:1005B000144DAC4203DA54F8041B8847F9E700F005 -:1005C00041F8114C114DAC4203DA54F8041B884732 -:1005D000F9E704F007B9000000070020002300201D -:1005E000000000080001002000070020D85D00087E -:1005F00000230020542300205823002028400020FE -:10060000E0010008E0010008E0010008E001000846 -:100610002DE9F04F2DED108AC1F80CD0C3689D462E -:10062000BDEC108ABDE8F08F002383F311882846C3 -:10063000A047002003F000FCFEE703F07BFB00DF97 -:10064000FEE70000F8B504F00BF8074604F056F892 -:100650000546B8BB204B9F4234D001339F4234D073 -:100660001E4B27F0FF029A4232D1F8B200F03AFE58 -:100670002E4642F2107400F03BFE08B100242646DC -:1006800001F0F6FB20B1032000F07CF800242646A0 -:1006900035B1134B9F4203D004F028F800242646BE -:1006A000002003F0E7FF0EB100F082F801F02EFA0F -:1006B00000F07CFE01F0B8F8204600F0DFF800F012 -:1006C00077F8F9E72E460024D5E704460126D2E75D -:1006D000064641F28834CEE7010007B0000008B0BA -:1006E000263A09B008B501F071F8A0F1200358428C -:1006F000584108BD07B541F21203022101A8ADF827 -:10070000043001F081F803B05DF804FB38B5202314 -:1007100083F311881748C3680BB103F013FC164A22 -:10072000144800234FF47A7103F0D0FB002383F3C5 -:100730001188124C236813B12368013B236063685E -:1007400013B16368013B63600D4D2B7833B9636867 -:100750007BB9022001F054F9322363602B78032B1C -:1007600007D163682BB9022001F04AF94FF47A737C -:10077000636038BD582300200D0700087424002052 -:100780006C230020084B187003280CD8DFE800F019 -:1007900008050208022001F029B9022001F01CB965 -:1007A000024B00225A6070476C2300207424002002 -:1007B00010B501F05DFB30B1294B03221A70294BB3 -:1007C00000225A6010BD284B284A1C461968013186 -:1007D000F8D004339342F9D16268254B9A42F1D99B -:1007E000244B9B6803F1006303F580339A42E9D2FE -:1007F00003F050FF03F062FF002001F02FF8022009 -:10080000FFF7C0FF1C4B1A6C00221A64196E1A669F -:10081000196E596C5A64596E5A665A6E5A6942F08A -:1008200080025A615A6922F080025A615A691A6933 -:1008300042F000521A611A6922F000521A611B69D3 -:1008400072B64FF0E0232021C3F8084DD4E90032FE -:1008500081F311889D4683F308881047B2E700BFF3 -:100860006C230020742400200000010820000108EF -:10087000FFFF000800230020003802402DE9F04F60 -:1008800093B0AC4B00902022FF210AA89D6801F094 -:10089000E7F8A94A1378A3B9A8480121C3601170E9 -:1008A000202383F31188C3680BB103F04BFBA44AE8 -:1008B000A24800234FF47A7103F008FB002383F36E -:1008C0001188009B13B19F4B009A1A609E4A009CAE -:1008D0001378032B1EBF002313709A4A4FF0000AAF -:1008E00018BF5360D3465646D146012001F07EF82A -:1008F00024B1944B1B68002B00F01582002000F0FF -:1009000065FF0390039B002B01DA00F003FE039BBD -:10091000002BEDDB012001F05FF8039B213B162B40 -:10092000E3D801A252F823F085090008AD090008B8 -:10093000410A0008EB080008EB080008EB08000873 -:10094000CB0A00089B0C0008B50B0008170C000828 -:100950003F0C0008650C0008EB080008770C000845 -:10096000EB080008E90C0008250A0008EB0800085D -:100970002D0D000891090008250A0008EB08000861 -:10098000170C00080220FFF7ADFE002840F0F581AB -:10099000009B0221BAF1000F08BF1C4605A841F2D6 -:1009A0001233ADF8143000F02FFF9EE74FF47A7049 -:1009B00000F00CFF071EEBDB0220FFF793FE002880 -:1009C000E6D0013F052F00F2DA81DFE807F0030AE5 -:1009D0000D10133605230593042105A800F014FF1C -:1009E00017E054480421F9E758480421F6E758482D -:1009F0000421F3E74FF01C08404600F031FF08F1F6 -:100A000004080590042105A800F0FEFEB8F12C0FA3 -:100A1000F2D1012000FA07F747EA0B0B5FFA8BFBD4 -:100A20004FF0000901F068F826B10BF00B030B2B17 -:100A300008BF0024FFF75EFE57E746480421CDE7D4 -:100A4000002EA5D00BF00B030B2BA1D10220FFF73A -:100A500049FE074600289BD0012000F0FFFE02203F -:100A6000FFF790FE00265FFA86F8404600F006FF8A -:100A7000044690B10021404600F010FF01360028E6 -:100A8000F1D1BA46044641F21213022105A8ADF88D -:100A900014303E4600F0B8FE27E70120FFF772FE53 -:100AA0002546244B9B68AB4207D9284600F0D8FE68 -:100AB000013040F067810435F3E7234B00251D70BA -:100AC000204BBA465D603E46ACE7002E3FF460AF77 -:100AD0000BF00B030B2B7FF45BAF0220FFF752FEF2 -:100AE000322000F073FEB0F10008FFF651AF18F0AD -:100AF00003077FF44DAF0F4A926808EB050393425A -:100B00003FF646AFB8F5807F3FF742AF124B0193F7 -:100B1000B84523DD4FF47A7000F058FE0390039A35 -:100B2000002AFFF635AF019B039A03F8012B01372A -:100B3000EDE700BF00230020702400205823002090 -:100B40000D070008742400206C23002004230020DB -:100B5000082300200C23002070230020C820FFF76A -:100B6000C1FD074600283FF413AF1F2D11D8C5F172 -:100B7000200242450AAB25F0030028BF42468349C4 -:100B80000192184400F046FF019A8048FF2100F0CE -:100B900067FF4FEAA8037D490193C8F387022846FF -:100BA00000F066FF064600283FF46DAF019B05EBA1 -:100BB000830537E70220FFF795FD00283FF4E8AEF4 -:100BC00000F098FE00283FF4E3AE0027B846704BD3 -:100BD0009B68BB4218D91F2F11D80A9B01330ED036 -:100BE00027F0030312AA134453F8203C0593404610 -:100BF000042205A901F0F4F804378046E7E73846F7 -:100C000000F02EFE0590F2E7CDF81480042105A82F -:100C100000F0FAFD06E70023642104A8049300F025 -:100C2000E9FD00287FF4B4AE0220FFF75BFD002849 -:100C30003FF4AEAE049800F045FE0590E6E70023D1 -:100C4000642104A8049300F0D5FD00287FF4A0AE31 -:100C50000220FFF747FD00283FF49AAE049800F009 -:100C600041FEEAE70220FFF73DFD00283FF490AE89 -:100C700000F050FEE1E70220FFF734FD00283FF4CA -:100C800087AE05A9142000F04BFE0421074604900E -:100C900004A800F0B9FD3946B9E7322000F096FD0E -:100CA000071EFFF675AEBB077FF472AE384A926836 -:100CB00007EB090393423FF66BAE0220FFF712FDEC -:100CC00000283FF465AE27F003074F44B9453FF4D1 -:100CD000A9AE484600F0C4FD0421059005A800F027 -:100CE00093FD09F10409F1E74FF47A70FFF7FAFC7C -:100CF00000283FF44DAE00F0FDFD002844D00A9BD3 -:100D000001330BD008220AA9002000F0B1FE002810 -:100D10003AD02022FF210AA800F0A2FEFFF7EAFC49 -:100D20001C4803F08FF813B0BDE8F08F002E3FF49D -:100D30002FAE0BF00B030B2B7FF42AAE00236421A4 -:100D400005A8059300F056FD074600287FF420AE65 -:100D50000220FFF7C7FC804600283FF419AEFFF7DA -:100D6000C9FC41F2883003F06DF8059800F0F6FEFA -:100D7000464600F0C1FE3C46B7E5064652E64FF057 -:100D8000000905E6BA467EE637467CE67023002079 -:100D900000230020A0860100094A136849F2690077 -:100DA00099B21B0C00FB01331360064B186844F228 -:100DB000506182B2000C01FB0200186080B27047E3 -:100DC000202300201C23002010B5002110220446FF -:100DD00000F046FE034B03CB206061601868A06002 -:100DE00010BD00BF107AFF1F2DE9F041ADF5507D19 -:100DF0000DF13C086EAC40F2751207460D4610A886 -:100E00000021C8F8001000F02BFE4FF4C47200213E -:100E1000204600F025FE00F0E5FE254B4FF47A72E7 -:100E2000B0FBF2F0186093E80700012384E80700A4 -:100E30000DF5ED702382FFF7C7FF4FF203631D49E5 -:100E4000238406A804F00AFE202384F832310DF230 -:100E5000EB2606AB0DF1380C1A4603CA624530602A -:100E60007160134606F10806F6D14146012220467C -:100E700000F0BCFE00230393AB7E029305F119033F -:100E8000019380B20123CDE904800093E97E06A39B -:100E9000D3E90023384601F043FB0DF5507DBDE852 -:100EA000F08100BFAFF300809E6AC421818A46EEC4 -:100EB0007C2400206C5A00082DE9F043224DBBB081 -:100EC00000F090FEAB6840F2ED22C31A934232D993 -:100ED00006AFA8602B4628220021384601F008FD05 -:100EE00005F10E0000F0B4FD002604465FFA80F91B -:100EF00005F10E08F3B2F100994501F1280107D977 -:100F000008EB06030822384601F0F2FC0136F1E74F -:100F100008230122CDE9023205340C4B0193A4B21F -:100F200030230093CDE9047405A3D3E90023297B82 -:100F3000074801F0F5FA3BB0BDE8F083AFF300805D -:100F400078F6339F93CACD8DC0340020CD34002075 -:100F500094340020F0B58B8A013B9BB2C92BC9B0F9 -:100F600006460C4647D8274D2F7B27BB05F10C03BF -:100F7000009308223B463946204601F07DFB7B1C4E -:100F8000FAB2D9001F46A38A013B9A4205DA0E3213 -:100F90002A44009200230822EEE700230022C5E93C -:100FA00000230023AB6085F8D730C5F8D8302B7B01 -:100FB0000BB9E37E2B738122002106AD27A800F038 -:100FC0004FFD0122294627A800F0DEFE00230393EF -:100FD000A37E029304F1190380B201932823CDE983 -:100FE0000450E17E0093304604A3D3E9002301F0CE -:100FF00097FAFFF761FF49B0F0BD00BF264172725A -:10100000DF25D7B7C034002070B50D4614461E4604 -:1010100001F01CFA50B9022E10D1012C0ED112A3EE -:10102000D3E90023C5E90023012007E0282C10D0D4 -:1010300005D8012C09D0052C0FD0002070BD302C14 -:10104000FBD10BA3D3E90023ECE70BA3D3E90023E7 -:10105000E8E70BA3D3E90023E4E70BA3D3E90023DC -:10106000E0E700BFAFF30080401DA12026812A0BDE -:1010700078F6339F93CACD8D9E6AC421818A46EE4D -:1010800026417272DF25D7B7F017304A39059E56D0 -:101090002DE9F04F8DB002AF80460D4601F0D6F934 -:1010A000044600285CD12B7E022B1BD1EB8A012B3E -:1010B00018D100F097FD0646FFF76EFE03464FF489 -:1010C000C870DFF81C92B3FBF0F206F5167602FB4F -:1010D000103316FA83F3C9F80030EB7E33B97B4B3B -:1010E00000221A702C37BD46BDE8F08FAB8AE6B2FD -:1010F000013BB34204F101040CD907F108031E447B -:10110000E10000960023082201F0F801284601F0D2 -:10111000B3FAEBE707F11800FFF756FE324607F186 -:10112000180107F1080004F067FC0028D7D10F2E42 -:1011300008D8664B1E70D9F80030A3F51673C9F8AD -:101140000030CFE7FB1DF8710146009307220346EC -:10115000284601F091FAF979404601F06FF9C1E7AC -:10116000EB8A282B26D010D8012B1ED0052BB9D105 -:10117000BFF34F8F5649574BCA6802F4E0621343DE -:10118000CB60BFF34F8F00BFFDE7302BAAD16B7E42 -:10119000514C0133627BDBB29342E94603D1EA7ED4 -:1011A000237B9A420BD0CD469CE729464046FFF769 -:1011B0001BFE97E729464046FFF7CCFE92E74FF02B -:1011C000000807F11803A7F8188010220093414681 -:1011D0000123284601F050FAAE8A023EB6B2F31C53 -:1011E0009B109B000733DB08A9EBC3039D460DF161 -:1011F000080A1FFA88F34FEAC8019E4201F1100164 -:101200000AD90AEB0803009308220023284601F0BC -:1012100033FA08F10108ECE794F8D70000F02EFB50 -:10122000D4F8D810054619B994F8D70000F036FB69 -:10123000D4F8D83033449D4205D294F8D700002129 -:10124000013000F02BFB4FEA960B4FF000081FFA1D -:1012500088F18B45D4E9003209D90AEB880103EB08 -:101260008800012200F004FC08F10108EFE7F31800 -:1012700042F10002C4E90032D4F8D83094F8D70023 -:1012800006EB0308C4F8D88000F0F8FA804509D3CB -:1012900094F8D730D4F8D8000133401B84F8D73005 -:1012A000C4F8D800FF2E0D4D09D80023237300F099 -:1012B00021FB00F0DDFD288108B9FFF779FA2368EA -:1012C0009B0A01332B810023A3606CE78D3400203F -:1012D00000ED00E00400FA05C03400207C2400206A -:1012E00090340020014B1870704700BF8824002004 -:1012F00030B54FF00054244B22689A4285B007D095 -:1013000003F006FA0446A8B90024204605B030BD13 -:101310001E4B627D1A701E48237D03731D49C9222E -:101320000E3000F077FB2046E022002100F098FB11 -:101330000124EAE7184A194D136C43F00073136453 -:10134000AA6D174B9A42DFD12B6E013B7E2BDBD867 -:10135000144A07CA01AB83E807001846032100F0CE -:1013600055FD6B6D83424FF00003CDD12A6D8A424B -:1013700001BFAB65054B2A6E1A7003BF0A4BEA6DBD -:101380001A601C46C1E700BF9AAD44C588240020FE -:10139000C0340020160000200038024000660040E3 -:1013A0005041A0B058660040182300202DE9FF47A7 -:1013B0004C4C00F05DFD02236371002302934A4B05 -:1013C0002081D3F800C0BCF57A7F12D3474B484F39 -:1013D000B7FBFCF69C458CBF0A231123581EB6FBB5 -:1013E000F3F503FB1562C1B2002A3ED00228034682 -:1013F000F4D89DF80B303F493F485A1E9DF80A30FB -:10140000013B1B0443EA0253BDF80820013A134391 -:101410004B6001F053FF00230193384B3849009390 -:101420003848394B4FF4805200F0E2FF374B1978BF -:1014300011B1344801F002F800F0D4FB0546FFF783 -:10144000ABFC4FF4C873B0FBF3F202FB130305F5DA -:10145000167010FA83F02E4B186003F04FF908B1A4 -:101460000F23238104B0BDE8F0876B1EB3F5806FB6 -:10147000BFD2C1EBC10E0EF103034FEAE309C3F380 -:10148000C703A1EB030809F1010A4FF47A705FFA70 -:1014900088F609FB00005AFA88F8B0FBF8F0B0F5BE -:1014A000617F08D90EF1FF33C3F3C703C91ACEB267 -:1014B000591E0F2914D8721E072A8CBF0022012240 -:1014C000991901FB0551B7FBF1F7BC4591D1002AF1 -:1014D0008FD0ADF808508DF80A308DF80B6088E792 -:1014E0001346EDE77C240020182300203F420F0024 -:1014F00080DE800210230020D8350020091000086B -:101500008C240020943400209110000888240020AE -:10151000903400202DE9F04F91A7D7E900670FF232 -:101520004829D9E90089874D93B0DFF844B2864C49 -:10153000284601F059F80DF1300A079070B31022D7 -:101540000021504600F08CFA079B197B4FF00002F7 -:1015500061F303028DF83020586899680EAA03C21F -:101560001B680D9A63F31C029DF830300D9243F016 -:1015700020038DF83030002352461946584601F0BA -:10158000ADFE079028B9284601F032F8079B23707A -:10159000CEE72378072B3CD8013323701822002193 -:1015A000504600F05DFADFF8C8B1684C00231946D8 -:1015B0005246584601F0BAFE014670BB102208A8F8 -:1015C00000F04EFA636983F48043636100F00CFB22 -:1015D0000B4612A9024611E903000DF1240C8CE818 -:1015E00003009DF83410C1F3030089064CBF0E9927 -:1015F000BDF838C08DF82C0046BFC1F31C0C4CF070 -:101600000041CCF30A010891284608A901F0B8F975 -:10161000CCE7284600F0ECFFC0E7284600F016FFB4 -:101620000446002848D1DFF84CB100F0DBFADBF8C3 -:101630000030984240D300F0D5FA0790FFF7ACFB9A -:10164000079A8DF8204003464FF4C87002F51672D1 -:10165000B3FBF0F101FB103312FA83F3CBF8003047 -:10166000DFF814B19BF8001011B901238DF8203078 -:1016700050460791FFF7A8FB0799C1F11004E4B2A7 -:10168000062C28BF0624224651440DF1210000F00B -:10169000C1F908AB03931823029301342C4B019337 -:1016A000E4B20123009304943B463246284600F0FE -:1016B000CFFE00238BF8003000F094FA254A264C28 -:1016C0001368C31AB3F57A7F30D3106000F08CFA38 -:1016D00002460B46284600F095FF284600F0B6FE6D -:1016E00020B3237BDFF894B0002B14BF0323022325 -:1016F0008BF8053000F076FA4FF47A730122B0FBD4 -:10170000F3F05146CBF80000584600F015FB1823C3 -:101710000293124B019380B240F25513CDE903A01E -:10172000009342464B46284600F092FE237B2BB1A5 -:10173000FFF7C2FB237B002B7FF4F7AE13B0BDE8AD -:10174000F08F00BF94340020A53500200000024037 -:101750008C340020A0350020C0340020A4350020A7 -:10176000401DA12026812A0BF1C6A7C1D068080F11 -:10177000D8350020903400208D3400207C240020B7 -:1017800070B50F4B1B780133DBB2012B0C4611D81F -:101790000C4D29684FF47A730E6AA2FB033201469E -:1017A00022462846B047844204D1074B00221A70D3 -:1017B000012070BD4FF4FA7002F044FB0020F8E7FE -:1017C00024230020C0370020D435002007B5002393 -:1017D000024601210DF107008DF80730FFF7D0FF19 -:1017E00020B19DF8070003B05DF804FB4FF0FF3017 -:1017F000F9E700000A4608B50421FFF7C1FF80F0B1 -:101800000100C0B2404208BD30B4054C2368DD6918 -:10181000044B0A46AC460146204630BC604700BF38 -:10182000C0370020A086010070B502F0BBFD094E54 -:10183000094D3080002428683388834208D902F09B -:10184000ABFD2B6804440133B4F5803F2B60F2D329 -:1018500070BD00BFD6350020A835002002F064BE60 -:1018600000F1006000F580300068704700F1006012 -:10187000920000F5803002F0E3BD0000054B1A68CD -:10188000054B1B889B1A834202D9104402F084BD89 -:1018900000207047A8350020D635002038B5084D07 -:1018A000044629B128682044BDE8384002F094BDC0 -:1018B0002868204402F078FD0028F3D038BD00BF2E -:1018C000A835002010F003030AD1B0F5047F05D23B -:1018D00000F10050A0F51040D0F8003818467047CD -:1018E0000023FBE700F10050A0F51040D0F8100AEB -:1018F00070470000064991F8243033B10023086A8C -:1019000081F824300822FFF7B1BF0120704700BFE3 -:10191000AC350020014B1868704700BF002004E080 -:1019200070B52A4B1B68C3F30B0204461B0C62B153 -:1019300040F21340824230D040F2194082422ED011 -:1019400040F2214082422CD10322214D0C2000FB89 -:101950000252556842F20102934224D0B3F5805FEF -:1019600023D041F20102934221D041F2030293427B -:101970001FD041F20702934214BF3F233123013CA1 -:101980000C44013D0A46A24215D215F9016F501CC4 -:101990009EB100F8016C0246F5E70122D5E702226C -:1019A000D3E70C4DD6E73323E9E74123E7E75A2392 -:1019B000E5E75923E3E7104605E02C25844215703E -:1019C00001D9901C5370401A70BD00BF002004E084 -:1019D000BC5A0008905A0008022802BF024B4FF080 -:1019E00080429A61704700BF00000240022802BF97 -:1019F000024B4FF480429A61704700BF00000240E2 -:101A0000022801BF024A536983F48043536170473F -:101A10000000024010B50023934203D0CC5CC454B4 -:101A20000133F9E710BD000010B5013810F9013F8E -:101A30003BB191F900409C4203D11AB10131013A06 -:101A4000F4E71AB191F90020981A10BD1046FCE78E -:101A500003460246D01A12F9011B0029FAD1704739 -:101A600002440346934202D003F8011BFAE7704791 -:101A70002DE9F8431F4D144695F824200746884663 -:101A800052BBDFF870909CB395F824302BB920221C -:101A9000FF2148462F62FFF7E3FF95F82400C0F1CD -:101AA0000802A24228BF2246D6B24146920005EB68 -:101AB0008000FFF7AFFF95F82430A41B1E44F6B258 -:101AC000082E17449044E4B285F82460DBD1FFF778 -:101AD00011FF0028D7D108E02B6A03EB8203834271 -:101AE000CFD0FFF707FF0028CBD10020BDE8F88357 -:101AF0000120FBE7AC350020024B1A78024B1A702C -:101B0000704700BFD43500202423002010B50F4CAF -:101B10000F4801F0ADFC21460D4801F0D5FC2468CA -:101B20000C48626DD2F8043843F00203C2F804385E -:101B300002F088F90849204601F0CCFD626DD2F828 -:101B4000043823F00203C2F8043810BDC45B000857 -:101B5000C037002040420F00CC5B000870470000F7 -:101B600000B59BB0EFF3098168226846FFF752FF8A -:101B7000EFF30583044B9A6BDA6A9A6A9A6A9A6A57 -:101B80009A6A9A6A9B6AFEE700ED00E000B59BB096 -:101B9000EFF3098168226846FFF73CFFEFF3058306 -:101BA000044B9A6B9A6A9A6A9A6A9A6A9A6A9B6AC8 -:101BB000FEE700BF00ED00E000B59BB0EFF3098148 -:101BC00068226846FFF726FFEFF30583034B5A6B45 -:101BD0009A6A9A6A9A6A9A6A9B6AFEE700ED00E03E -:101BE000FEE7000002F0DABC02F0B2BC2DE9F047DB -:101BF0000D46044600219046284640F27912FFF730 -:101C00002FFF234620220021284600F071FE231DCD -:101C100002222021284600F06BFE631D03222221B0 -:101C2000284600F065FEA31D03222521284600F06A -:101C30005FFE04F1080310222821284600F058FE18 -:101C400004F1100308223821284600F051FE04F167 -:101C5000110308224021284600F04AFE04F1120335 -:101C600008224821284600F043FE04F114032022F4 -:101C70005021284600F03CFE04F118034022702158 -:101C8000284600F035FE04F120030822B021284642 -:101C900000F02EFE04F121030822B821284600F0AE -:101CA00027FE04F12207C0263B463146082228467B -:101CB000083600F01DFEB6F5A07F07F10107F3D14D -:101CC00004F1320308223146284600F011FE0027B5 -:101CD00004F1330A94F832304FEAC7099F4209F5FC -:101CE000A47615D3B8F1000F08D1314604F59973E5 -:101CF0000722284600F0FCFD09F24F16274694F80B -:101D000032213B1B93420CD3F01DC008BDE8F08785 -:101D10000AEB070308223146284600F0E9FD0137A7 -:101D2000D8E707F2331331460822284600F0E0FDD9 -:101D300008360137E3E7000013B5044608460021E2 -:101D400001602346C0F803102022019000F0D0FD6E -:101D50000198231D0222202100F0CAFD0198631D75 -:101D60000322222100F0C4FD0198A31D0322252196 -:101D700000F0BEFD019804F108031022282100F0B4 -:101D8000B7FD072002B010BDF8B50E460546144653 -:101D9000002181223046FFF763FE2B4608220021F6 -:101DA000304600F0A5FD7CB96B1C072208213046A7 -:101DB00000F09EFD0F2401236A785F1C013B9342D3 -:101DC00004D3E01DC008F8BD0824F4E7EB19214650 -:101DD0000822304600F08CFD08343B46ECE700005A -:101DE00030B5094D0A4491420DD011F8013B5840DD -:101DF000082340F30004013B2C4013F0FF0384EA66 -:101E00005000F6D1EFE730BD2083B8EDF7B54FF0C5 -:101E1000FF33DFF854C0DFF854E000EB81011A46CD -:101E200088421CD050F8044B019401AF042417F8E9 -:101E3000015B82EA05620825DB18164605F1FF35CD -:101E40005241002EBCBF83EA0C0382EA0E0215F059 -:101E5000FF05F1D1013C14F0FF04E8D1E0E7D843DD -:101E6000D14303B0F0BD00BF9336EAA9EBE1F042E5 -:101E700073B5384A106851686B4603C36A463649E1 -:101E80003648082303F0C8FD044670B9344A106888 -:101E900051686B4603C36A4632493048082303F051 -:101EA000BBFD044630BB0A2022E00369B3F5702F66 -:101EB000ECD8418B40F2F6329142E7D12A4A0244F3 -:101EC00002F110018B42E1D3103B244900209D1AFE -:101ED000FFF786FF2A46064604F118010020FFF7A7 -:101EE0007FFFA3689E42D1D1E3689842CED1002003 -:101EF00002B070BD0369B3F5702F22D8B0F8661038 -:101F000040F2F63291421ED1174A024402F15C01BE -:101F10008B421AD35C3B114900209D1AFFF760FFEA -:101F20002A46064604F164010020FFF759FFA26823 -:101F3000964203460BD1E068834214BF0D20002077 -:101F4000D6E70B20D4E70C20D2E71020D0E70D20F5 -:101F5000CEE700BFEC5A0008DCFF0E0000000108CD -:101F6000F55A000890FF0E000800FFF72DE9F04138 -:101F7000C56915B9C161BDE8F0814B6823F06047C0 -:101F8000C3F38A464FEAD37EC3F3807816EA23066A -:101F900038BF3E46AC462B465A68BEEBD27F22F095 -:101FA00060440AD0002A18DAA40CB44217D19D422A -:101FB0000FD10D60DEE71346EEE7A74207D102F02E -:101FC0008044C2F3807242450BD054B1EFE708D28F -:101FD000EDE7CCF800100B60CDE7B44201D0B4427D -:101FE000E5D81A689C46002AE5D11960C3E70000CD -:101FF0002DE9F047089D01F007044FEAD508224477 -:1020000005F0070500EBD1004FF47F49944201D160 -:10201000BDE8F08704F0070705F0070A57453E467C -:1020200038BF5646C6F10806111B8E4228BF0E4621 -:10203000E10808EBD50E415C13F80EC0B94029FA4F -:1020400006F721FA0AF1FFB28CEA010147FA0AF712 -:1020500039408CEA010C03F80EC034443544D5E70E -:1020600080EA0120082341F2210201B24000002948 -:1020700080B203F1FF33B8BF504013F0FF03F4D137 -:102080007047000038B50C468D18A54200D138BD08 -:1020900014F8011BFFF7E4FFF7E7000002684AB1FC -:1020A00013680360C388018901339BB29942C380DE -:1020B00038BF03811046704770B588B020220446AF -:1020C0000D4668460021FFF7CBFC20460495FFF73C -:1020D000E5FF024658B16B46054608AE1C4603CCE8 -:1020E000B44228606960234605F10805F6D1104620 -:1020F00008B070BD082817D909280CD00A280CD0C0 -:102100000B280CD00C280CD00D280CD00E2814BF96 -:102110004020302070470C2070471020704714205A -:10212000704718207047202070470000082817D9F2 -:102130000C280CD910280CD914280CD918280CD923 -:1021400020280CD930288CBF0F200E207047092082 -:1021500070470A2070470B2070470C2070470D20F5 -:102160007047000010B54B6823B9CA8A63F30902AF -:10217000CA8210BDC4681A681C60C360438A013BF0 -:1021800043824A60EFE700002DE9F84F1D46CB8AF5 -:102190000F46C3F309010529814692460B4630D00C -:1021A0000020AAB207F11A049EB2042E1FFA80F88A -:1021B0000FD8904503F1010306D3FB8A0A4462F36A -:1021C0000903FB8201201AE01AF80060E65401308E -:1021D000EAE79045F1D2A1F1050B1C237C68BBFB1B -:1021E000F3F203FB12BB1FFA8BF6002C45D14846D5 -:1021F000FFF754FF044638B978606FF00200BDE87D -:10220000F88F4FF00008E6E7002606607860ADB270 -:102210004FF0000B454510D90AEB0803221D13F8B7 -:10222000011B9155B1B208F101081B291FFA88F86A -:102230002BD0454506F10106F1D8FB8AC3F309020C -:10224000154465F30903BCE7013292B21C462368CA -:10225000002BF9D16B1F0B441C21B3FBF1F30133AD -:102260009BB29A42D3D2BBF1000FD0D14846FFF7C0 -:1022700015FF20B9C4F800B0BFE70122E7E7C0F8B6 -:1022800000B05E4620600446C1E74545D5D94846C2 -:10229000FFF704FF08B92060AFE7C0F800B00026E0 -:1022A00020600446B6E700002DE9F04F2DED028BCB -:1022B00083B0CDE90013BDF83C5007469146002A93 -:1022C00000F092802DB10E9B002B00F08D80072D29 -:1022D00032D807F10C00FFF7E1FE044638B96FF081 -:1022E0000204204603B0BDEC028BBDE8F08F14223F -:1022F0000021FFF7B5FB0E992A4604F10800FFF70D -:1023000089FB681CC0B2FFF711FFFFF7F3FE2074D2 -:1023100099F80030013814FA80F003F01F0363F0DD -:102320003F030372009B43F0004161603846214641 -:10233000FFF71CFE0124D4E700F10C034FF0000866 -:1023400008EE103A4FF0800A4646444618EE100A4E -:10235000FFF7A4FE83460028C1D014220021FFF716 -:102360007FFBC6BB019BABF8083002200E9B00F13F -:10237000080299195BFA82F20130C0B2082801D034 -:10238000AE422AD3FFF7D2FEFFF7B4FE99F8002041 -:10239000009B411E02F01F0242EA4812AE4208BFF3 -:1023A0004FF0400A5BFA81F14AEA020A43F0004228 -:1023B00081F808A08BF81000CBF804205946384665 -:1023C000FFF7D4FD0134AE4224B288F001084FF08B -:1023D000000ABBD185E70020C8E711F801CB02F85D -:1023E00001CB0136B6B2C7E76FF0010479E7000010 -:1023F000F8B515460E462822002104461F46FFF771 -:102400002FFB069B6360B5F5001F079BA76034BFD9 -:102410006A094FF6FF72236204F10C0097B20023A1 -:102420009A4205D80023036027826382A382F8BD05 -:102430000660013330462036F2E7000003781BB90E -:102440004BB2002BC8BF0170704700000078704786 -:102450002DE9F74FDDF83C90BDF830500D9E9DF80A -:102460003840BDF84070804692469B46B9F1000F57 -:1024700001D1002F51D11F2C4FD898F80000B0B9CE -:10248000072F47D835F0030347D13A4649464FF660 -:10249000FF70FFF7F7FD20F001002D02400445EA30 -:1024A0000464400C44EA40244FF6FF7321E040EA04 -:1024B0000520072F40EA0464F6D900254FF6FF7384 -:1024C000C5F12000A5F120022AFA05F10BFA00F06F -:1024D00001432BFA02F211431846C9B2FFF7C0FDBF -:1024E0000835402D0346EBD13A464946FFF7CAFD71 -:1024F0000346CDE90097324621464046FFF7D4FE19 -:1025000033780133DBB21F2B88BF0023337003B055 -:10251000BDE8F08F6FF00300F9E76FF00100F6E718 -:102520002DE9F04F85B09246DDF848800F9D9DF86B -:1025300040209DF84490BDF84C7006469B46B8F18B -:10254000000F01D1002F48D11F2A46D83378002B25 -:1025500046D00C0244EA02649DF8381044EAC934BB -:1025600044EA01441C43072F44F0800432D900237D -:102570004FF6FF72C3F1200CA3F120002AFA03F1F9 -:102580000BFA0CFC41EA0C012BFA00F00143C9B232 -:1025900010460393FFF764FD039B0833402B02466C -:1025A000E8D13A464146FFF76DFD0346CDE9008785 -:1025B0002A4621463046FFF777FEB9F1010F06D1D2 -:1025C0002B780133DBB21F2B88BF00232B7005B0A3 -:1025D000BDE8F08F4FF6FF73E8E76FF00100F6E714 -:1025E0006FF00300F3E70000C06900B104307047EA -:1025F000C3691A68C261C2681A60C360438A013B3A -:10260000438270472DE9F041D0F81880194E1446E6 -:102610001D464146002709B9BDE8F081D1E90223F2 -:10262000A21A65EB0303964277EB03031ED283697C -:102630008B420DD1FFF796FD83691B688361C368E8 -:102640000B60438AC1608169013B43828846E2E7AF -:10265000FFF788FD0B68C8F80030C3680B60438A39 -:10266000C160013B4382D8F80010D4E7884609686E -:10267000D1E700BF80841E002DE9F04F8BB00D46DE -:10268000DDF8509014469B468046002800F01981E2 -:10269000B9F1000F00F01581531E3F2B00F211819C -:1026A000012A03D1BBF1000F40F00B810023CDE9DB -:1026B0000833B8F81430B5EBC30F4FEAC30703D3A0 -:1026C00000200BB0BDE8F08F2B199F42D8F80C30DA -:1026D0003ABF7F1BFFB227461BB9D8F81030002B3A -:1026E0007AD0272D4ED8C5F12806B7424FF0000307 -:1026F0002CBFF6B23E4600932946D8F8080008AB36 -:102700003246FFF775FCA7EB060A35445FFA8AFAF2 -:10271000B8F8143003F10053053BDB000493D8F8FC -:102720000C3003932821039B13B1BAF1000F2CD175 -:10273000D8F8100040B1BAF1000F05D0009608ABF0 -:102740005246691AFFF754FC38B2002FB8D066071A -:102750000AD00AAB03EBD401624211F8083C02F044 -:102760000702134101F8083C082C3CD9102C40F218 -:10277000B580202C40F2B780BBF1000F00F09C80A8 -:10278000082334E0BA460026C2E7049BE02B28BFAA -:10279000E02306930B44AB42059314D95A1B0398CC -:1027A0000096924534BF5246D2B2691A08AB043043 -:1027B0000792FFF71DFC079A1644AAEB020A15447C -:1027C000F6B25FFA8AFA049B069A05999B1A04935B -:1027D000039B1B680393A6E70093D8F8080008AB97 -:1027E0003A462946AEE7BBF1000F13D00123B4EB04 -:1027F000C30F6CD0082C12D89DF82030621E23FA2B -:1028000002F2D50706D54FF0FF3202FA04F4234353 -:102810008DF820309DF8203089F8003051E7102CD9 -:1028200012D8BDF82030621E23FA02F2D10706D575 -:102830004FF0FF3202FA04F42343ADF82030BDF824 -:102840002030A9F800303CE7202C0FD80899631EEF -:1028500021FA03F3DA0705D54FF0FF3202FA04F448 -:102860000C430894089BC9F800302AE7402C2BD071 -:10287000DDE90865611EC4F12102A4F1210326FAF5 -:1028800001F105FA02F225FA03F311431943CB07CC -:1028900012D50122A4F12003C4F1200102FA03F3AE -:1028A00022FA01F1A240524243EA010363EB4303DF -:1028B00032432B43CDE90823DDE90823C9E900238E -:1028C000FFE66FF00100FCE66FF00800F9E6082C67 -:1028D000A0D9102CB3D9202CEED8C3E7BBF1000F40 -:1028E000ADD0022383E7BBF1000FBBD004237EE70A -:1028F00030B5012A144638BF0124402C85B028BFCA -:1029000040240025012ACDE9025518D81B788DF8FE -:10291000083063070AD004AB03EBD405624215F814 -:10292000083C02F00702934005F8083C009103467A -:102930002246002102A8FFF75BFB05B030BD082A44 -:10294000E4D9102A03D81B88ADF80830E1E7202A23 -:102950008DBFD3E900231B680293CDE90223D8E79A -:1029600010B5CB681BB98B600B618B8210BDC4683E -:102970001A681C60C360438A013B4382CA60F0E767 -:102980002DE9F04F95B0CDE904230B6804460D46C0 -:102990001806C3F3C01147BFC3F3C03BC3F30626F9 -:1029A0004FF0020B0E46002B80F2018213F0C0495B -:1029B00040F0FD812A7B002A00F0F981BBF1020F73 -:1029C00003D02078B04240F0F581C3F30460089052 -:1029D00003F07F00069069B3C3F3074A2A44069BBD -:1029E00092F80380760646EA0B4646EA83460022C2 -:1029F0000023CDE90A235FEAD81346EA0A060393C7 -:102A00006CD0069B009367685B4652460AA9204635 -:102A1000B847002800F0D181A76997B9314604F181 -:102A20000C00FFF749FB0746D8B96FF0020015B05C -:102A3000BDE8F08FC3F30F2A590608BF0AF0030A56 -:102A4000CCE73B699E420DD03F68002FF9D131465B -:102A500004F10C00FFF730FB07460028E5D0A3691E -:102A60003B60A761FE7D08F01F03C6F38406F01AE1 -:102A70001FFA80FC0028B8BF0CF120000793A3EBDD -:102A800006031FFA83FCD7E90221B8BF00B2002B6E -:102A90000993BEBF0CF120031BB2099352EA010354 -:102AA00033D0049EDFF8D0C2B21A059E66EB010156 -:102AB0000026944576EB010327D395F80DE097F8AF -:102AC0001AC0E64514D1039B002B76D001281CDCEC -:102AD000A848904276EB010314D336E0A76917B9F2 -:102AE0006FF00C00A3E73B699E42BBD03F68F6E75E -:102AF000A048904276EB010301D3002097E7039BA7 -:102B0000002BFAD0099B0F2B18DCFA7D4FEA8803C3 -:102B100002F0030203F07C031343FB7539462046A1 -:102B2000FFF720FB6B7BBB76039B3BB9FB7DC3F3BD -:102B30008402013262F38603FB75D1E76A7BBB7EB8 -:102B40009A42DAD1039B002B37D04FEA9813022B1D -:102B500033D0049BBB60059BFB60142200210FA8AF -:102B6000FEF77EFF049B0C93059B0D932B1D0E938C -:102B70002B7BADF846A0013BDBB2ADF84430079BA0 -:102B80008DF84930089B8DF84A30069B8DF84B3004 -:102B900094F824308DF848B083F001038DF84C3060 -:102BA0000CA9A36820469847FB7DC3F38403013337 -:102BB00003F01F039B02FB829FE7FB7DC8F34012DB -:102BC000B2EBD31F40F0FC80079AC3F38403934217 -:102BD00040F0F98003992B7B4FEA981200294ED0E0 -:102BE000D2075ED4032B40F2F180049BBB60059BAF -:102BF000FB602B7BAE1D033BDBB23246394604F152 -:102C00000C00FFF7C1FA00280DDA20463946FFF71D -:102C1000A9FAFB7DC3F38403013303F01F039B0276 -:102C2000FB82032003E7DDE90A84AB883B834FF690 -:102C3000FF73C9F12000A9F1200228FA09F104FA72 -:102C400000F0014324FA02F211431846C9B2FFF71B -:102C500007FA09F10809B9F1400F0346E9D1B88232 -:102C60002A7B033AD2B23146FFF70CFAFB7DB882D9 -:102C7000DA43C2F3C01262F3C713FB753DE782B9B2 -:102C80002E1D013BDBB23246394604F10C00FFF742 -:102C90007BFA0028B9DB2A7BB88A013AD2B23146E6 -:102CA000E2E7F98AC1F30901013B0429DAB25BD8F2 -:102CB000281D002307F11B069A4208D910F801CB02 -:102CC00006F801C0013101330529DBB2F4D10499C2 -:102CD0000C9105990D91934207F11B010E9138BF9C -:102CE000043379680F9134BF55FA83F300231093AE -:102CF000FB8AADF846A0C3F309031A44079B8DF87D -:102D00004930089B8DF84A30069B8DF84B3094F87B -:102D10002430ADF8442083F001038DF84C300023BB -:102D20008DF848B07B602A7BB88A013A291DFFF7ED -:102D3000A9F93B8BB882834203D1A3680CA9204632 -:102D4000984720460CA9FFF70BFEFB7DB88AC3F31A -:102D50008403013303F01F039B02FB823B8B9842E9 -:102D600014BF1120002062E67B68002BAFD0052045 -:102D700006E000BF40420F0080841E001C30334636 -:102D80001E68002EFAD1091A081D2E1D184401EBE9 -:102D9000090CBCF11B0F5FFA89F398D89A4296D9B7 -:102DA00016F8013B00F8013B09F10109EFE76FF06C -:102DB00009003CE66FF00A0039E66FF00B0036E6DA -:102DC0006FF00D0033E66FF00E0030E66FF00F008D -:102DD0002DE600BF404BF0B51C6C404E44F0007433 -:102DE0001C641D6E45F000751D661B6E3C4B9B6A96 -:102DF000D3F80052354045F00105C3F80052D3F82E -:102E00000042344044EA002040F00100C3F80002D0 -:102E1000002952D00020C3F81C020546C3F8040262 -:102E2000C3F80C02C3F8140203EBC00401301C28E1 -:102E3000C4F84052C4F84452F6D100254FF0010CBA -:102E400096781488F70748BFD3F804720CFA04F098 -:102E500044BF0743C3F80472B70742BFD3F80C72EC -:102E60000743C3F80C72760742BFD3F814620643D7 -:102E7000C3F8146203EBC4045668C4F84062966851 -:102E8000C4F84462D3F81C4201352043A942C3F878 -:102E90001C0202F10C02D3D1D3F8002222F001026D -:102EA000C3F800220C4B1A6C22F000721A641A6EDE -:102EB00022F000721A661B6EF0BD0122C3F84012A8 -:102EC000C3F84412C3F80412C3F81412C3F80C2256 -:102ED000C3F81C22E0E700BF003802400000FFFFFB -:102EE000D8350020184A916A08B58B688B6013F0BA -:102EF000010104D013F00C0F18BF4FF48031D80536 -:102F000006D513F4406F14BF41F4003141F00201C3 -:102F1000D80306D513F4402F14BF41F4802141F0AB -:102F20000401D3690BB108489847202383F3118823 -:102F30000648002100F0AEFF002383F31188BDE8AE -:102F4000084001F023BC00BFD8350020E035002048 -:102F500038B5124CA36ADD68AA0712D05A6922F06C -:102F600002025A61A36913B1012120469847202328 -:102F700083F311880A48002100F08CFF002383F3BB -:102F80001188EB0606D5A36A1021D960236A0BB11C -:102F900002489847BDE8384001F0F8BBD83500201A -:102FA000E835002038B5124CA36A1D69AA0712D073 -:102FB0005A6922F010025A61A36913B10221204616 -:102FC0009847202383F311880A48002100F062FF0C -:102FD000002383F31188EB0606D5A36A102119613B -:102FE000236A0BB102489847BDE8384001F0CEBBD8 -:102FF000D8350020E835002038B50F4CA36A5D684D -:103000005D602A070AD5042222701A6822F00202A3 -:103010001A60636A13B10021204698476B0706D5F2 -:10302000A36A9969236A13B1034809049847BDE864 -:10303000384001F0ABBB00BFD835002010B50E4CB6 -:10304000204600F029F90D4BA3620B21132000F05C -:103050000BF90B21142000F007F90B21152000F0CB -:1030600003F90B21162000F0FFF80022BDE8104004 -:1030700011460E20FFF7AEBED83500200064004098 -:10308000114B984210B5044609D1104B1A6C42F00E -:1030900000721A641A6E42F000721A661B6EA36AFE -:1030A00001221A60A36A5A68D20707D5626851687C -:1030B0001268D9611A60064A5A6110BD01210820C0 -:1030C00000F0D4FDEEE700BFD83500200038024004 -:1030D0005B87010003291AD8DFE801F0020A0F1408 -:1030E000836A9B6813F0E05F14BF012000207047E3 -:1030F000836A9868C0F380607047836A9868C0F3F9 -:10310000C0607047836A9868C0F300707047002001 -:103110007047000010B5032925D8DFE801F002252B -:10312000292D836A9968C1F30161183103EB0113FA -:10313000107884064CBF54689488C0F300114FEA9D -:10314000410148BF41EAC40100F00F004CBF41F00B -:10315000040141EA4451586041F001019068D2688D -:103160009860DA60196010BD836A03F5C073DFE709 -:10317000836A03F5C873DBE7836A03F5D073D7E787 -:1031800001290AD002290FD081B9836ADA6892072F -:1031900001D1186903E001207047836AD86810F0F4 -:1031A000030018BF01207047836AF2E700207047D0 -:1031B00010B539B9836AD96889071BD11B699C0787 -:1031C00004D110BD012915D00229FAD1816AD1F8A4 -:1031D000C031D1F8C441D1F8C8011061D1F8CC0197 -:1031E0005061202008610869800717D1486940F0C4 -:1031F000100012E0816AD1F8B031D1F8B441D1F8B1 -:10320000B8011061D1F8BC0150612020C860C868C5 -:10321000800703D1486940F002004861C3F34000D1 -:10322000C3F38001000140EA4111107920F0300021 -:103230000143117189064BBF91681189DB085B0D51 -:103240004CBF63F31C0163F30A01137948BF91601B -:1032500064F3030313714FEA14234FEA144458BF75 -:10326000118113705480ACE700F1604303F56143B2 -:103270000901C9B283F80013012200F01F039A402C -:1032800043099B0003F1604303F56143C3F88021C8 -:103290001A607047FFF7D2BE012300F10802C0E9AF -:1032A0000222037000F110020023C0E90422C0E9E9 -:1032B0000633C0E9083343607047000010B520238F -:1032C000044683F31188022303704160FFF7D8FEA0 -:1032D00004232370002383F3118810BD2DE9F041EE -:1032E0001F4604460D461646202383F3118800F13D -:1032F00008082378052B0DD029462046FFF7EAFE63 -:1033000040B1204632462946FFF704FF002080F3F3 -:10331000118808E03946404600F0A0FD0028E8D0BA -:10332000002383F31188BDE8F08100002DE9F0410E -:103330001F4604460D461646202383F3118800F1EC -:1033400010082378052B0DD029462046FFF718FFDB -:1033500040B1204632462946FFF72AFF002080F37D -:10336000118808E03946404600F078FD0028E8D092 -:10337000002383F31188BDE8F081000002684368F0 -:103380001143016003B118477047000013B5446B47 -:10339000D4F894341A681178042915D1217C0229B3 -:1033A00012D11979128901238B4013420CD101A942 -:1033B00004F14C0001F0A8FFD4F89444019B21795A -:1033C0000246206800F0CEF902B010BD143001F0C2 -:1033D0002BBF00004FF0FF33143001F025BF000079 -:1033E0004C3001F0FDBF00004FF0FF334C3001F0D6 -:1033F000F7BF0000143001F0F9BE00004FF0FF31BC -:10340000143001F0F3BE00004C3001F0C9BF0000E1 -:103410004FF0FF324C3001F0C3BF00000020704776 -:1034200010B5D0F894341A6811780429044617D1DD -:10343000017C022914D15979528901238B4013420E -:103440000ED1143001F08CFE024648B1D4F89444F9 -:103450004FF4807361792068BDE8104000F070B9C6 -:1034600010BD0000406BFFF7DBBF0000704700009D -:103470007FB5124B036000234360C0E9023301258E -:1034800002260F4B057404460290019300F184025A -:10349000294600964FF48073143001F03DFE094B2D -:1034A0000294CDE9006304F523724FF4807329463A -:1034B00004F14C0001F004FF04B070BD005B000893 -:1034C000653400088D3300080B68202282F31188D0 -:1034D0000A7903EB820290614A79093243F82200AB -:1034E0008A7912B103EB8203986102230374C0F856 -:1034F0009414002383F311887047000038B5037FCC -:10350000044613B190F85430ABB9201D01250221B7 -:10351000FFF734FF04F1140025776FF0010100F08C -:10352000B9FC84F8545004F14C006FF00101BDE87F -:10353000384000F0AFBC38BD10B50121044604305E -:10354000FFF71CFF0023237784F8543010BD0000E0 -:1035500038B504460025143001F0F6FD04F14C00A6 -:10356000257701F0C5FE201D84F854500121FFF796 -:1035700005FF2046BDE83840FFF752BF90F84430C1 -:1035800003F06003202B07D190F84520212A4FF04B -:10359000000303D81F2A06D800207047222AFBD137 -:1035A000C0E90E3303E0034A82630722C263036467 -:1035B000012070472523002037B5D0F894341A68CD -:1035C0001178042904461AD1017C022917D11979EE -:1035D000128901238B40134211D100F14C0528467A -:1035E00001F046FF58B101A9284601F08DFED4F83C -:1035F0009444019B21790246206800F0B3F803B09F -:1036000030BD0000F0B500EB810385B09E69044633 -:103610000D46FEB1202383F3118804EB8507301D8E -:103620000821FFF7ABFEFB685B691B6806F14C00E5 -:103630001BB1019001F076FE019803A901F064FE30 -:10364000024648B1039B2946204600F08BF8002330 -:1036500083F3118805B0F0BDFB685A691268002A2F -:10366000F5D01B8A013B1340F1D104F14402EAE793 -:10367000093138B550F82140DCB1202383F311889B -:10368000D4F894241368527903EB8203DB689B69B6 -:103690005D6845B104216018FFF770FE294604F10A -:1036A000140001F067FD2046FFF7BAFE002383F304 -:1036B000118838BD7047000001F02AB9012303705A -:1036C0000023C0E90133C36183620362C3624362C2 -:1036D0000363704738B50446202383F3118800251F -:1036E000C0E90355C0E90555416001F021F9022305 -:1036F000237085F3118838BD70B500EB8103054652 -:103700005069DA600E46144618B110220021FEF707 -:10371000A7F9A06918B110220021FEF7A1F93146DE -:103720002846BDE8704001F0CDB90000826802F083 -:10373000011282600022C0E90422826101F04EBAC7 -:10374000F0B400EB81044789E4680125A4698D4049 -:103750003D43458123600023A2606360F0BC01F01B -:1037600069BA0000F0B400EB81040789E468012520 -:1037700064698D403D43058123600023A26063603E -:10378000F0BC01F0E3BA000070B502230025044646 -:103790000370C0E90255C0E90455C564856180F82D -:1037A000345001F02BF963681B6823B12946204689 -:1037B000BDE87040184770BD037880F8503005238D -:1037C000037043681B6810B504460BB10421984789 -:1037D0000023A36010BD000090F8502043680270E1 -:1037E0001B680BB1052118477047000070B590F8B1 -:1037F0003430044613B1002380F8343004F144021D -:10380000204601F00DFA63689B68B3B994F8443020 -:1038100013F0600535D00021204601F05FFC002147 -:10382000204601F051FC63681B6813B10621204655 -:103830009847062384F8343070BD20469847002806 -:10384000E4D0B4F84A30E26B9A4288BFE36394F95B -:103850004430E56B002B4FF0200380F20381002DF4 -:1038600000F0F280092284F8342083F311880021CB -:10387000D4E90E232046FFF775FF002383F3118858 -:10388000DAE794F8452003F07F0343EA022340F28D -:103890000232934200F0C58021D8B3F5807F48D032 -:1038A0000DD8012B3FD0022B00F09380002BB2D11A -:1038B00004F14C02A2630222E2632364C1E7B3F580 -:1038C000817F00F09B80B3F5407FA4D194F846300F -:1038D000012BA0D1B4F84C3043F0020332E0B3F531 -:1038E000006F4DD017D8B3F5A06F31D0A3F5C063EA -:1038F000012B90D8636894F846205E6894F84710CE -:10390000B4F848302046B047002884D04368A36309 -:103910000368E3631AE0B3F5106F36D040F6024255 -:1039200093427FF478AF5C4BA3630223E3630023ED -:10393000C3E794F84630012B7FF46DAFB4F84C30F8 -:1039400023F00203C4E90E55A4F84C30256478E74F -:10395000B4F84430B3F5A06F0ED194F8463084F833 -:103960004E30204601F0A2F863681B6813B10121B4 -:1039700020469847032323700023C4E90E339CE7B5 -:1039800004F14F03A3630123C3E72378042B10D171 -:10399000202383F311882046FFF7C8FE85F31188A2 -:1039A0000321636884F84F5021701B680BB12046D7 -:1039B000984794F84630002BDED084F84F3004232B -:1039C000237063681B68002BD6D0022120469847DD -:1039D000D2E794F848301D0603F00F0120460AD5BF -:1039E00001F010F9012804D002287FF414AF2B4B0A -:1039F0009AE72B4B98E701F0F7F8F3E794F8463095 -:103A0000002B7FF408AF94F8483013F00F01B3D0C7 -:103A10001A06204602D501F075FBADE701F068FB00 -:103A2000AAE794F84630002B7FF4F5AE94F84830BE -:103A300013F00F01A0D01B06204602D501F04EFB6B -:103A40009AE701F041FB97E7142284F8342083F3CE -:103A500011882B462A4629462046FFF771FE85F33A -:103A60001188E9E65DB1152284F8342083F31188CA -:103A70000021D4E90E232046FFF762FEFDE60B226B -:103A800084F8342083F311882B462A4629462046A1 -:103A9000FFF768FEE3E700BF305B0008285B000823 -:103AA0002C5B000838B590F834300446002B3ED02B -:103AB000063BDAB20F2A34D80F2B32D8DFE803F0F6 -:103AC000373131082232313131313131313137370B -:103AD000C56BB0F84A309D4214D2C3681B8AB5FB4F -:103AE000F3F203FB12556DB9202383F311882B46A3 -:103AF0002A462946FFF736FE85F311880A2384F803 -:103B000034300EE0142384F83430202383F31188FA -:103B100000231A4619462046FFF712FE002383F3BE -:103B2000118838BD036C03B198470023E7E70021F3 -:103B3000204601F0D3FA0021204601F0C5FA63685F -:103B40001B6813B10621204698470623D7E70000DB -:103B500010B590F83430142B044629D017D8062B12 -:103B600005D001D81BB110BD093B022BFBD80021A9 -:103B7000204601F0B3FA0021204601F0A5FA63685F -:103B80001B6813B1062120469847062319E0152B20 -:103B9000E9D10B2380F83430202383F311880023EC -:103BA0001A461946FFF7DEFD002383F31188DAE792 -:103BB000C3689B695B68002BD5D1036C03B1984740 -:103BC000002384F83430CEE7024B0022C3E90033EF -:103BD0009A60704704360020002303748268054B06 -:103BE0001B6899689142FBD25A680360426010607A -:103BF000586070470436002008B5202383F31188ED -:103C0000037C032B05D0042B0DD02BB983F3118833 -:103C100008BD436900221A604FF0FF334361FFF78C -:103C2000DBFF0023F2E7D0E9003213605A60F3E7CC -:103C3000002303748268054B1B6899689142FBD886 -:103C40005A68036042601060586070470436002074 -:103C5000054B19690874186802681A605360186186 -:103C600001230374FCF7D4BC0436002030B54B1C90 -:103C70000B4D87B0044610D02B690A4A01A800F00A -:103C800025F92046FFF7E4FF049B13B101A800F0DB -:103C900059F92B69586907B030BDFFF7D9FFF8E72C -:103CA00004360020F93B000838B50C4D41612B6902 -:103CB00081689A689142044603D8BDE83840FFF70E -:103CC0008BBF1846FFF7B4FF01232C610146237414 -:103CD0002046BDE83840FCF79BBC00BF04360020FE -:103CE000044B1A681B6990689B68984294BF002037 -:103CF000012070470436002010B5084C2368206965 -:103D00001A6822605460012223611A74FFF790FF41 -:103D100001462069BDE81040FCF77ABC043600205B -:103D200008B5FFF7DDFF18B1BDE80840FFF7E4BFB5 -:103D300008BD0000FFF7E0BFFEE7000010B50C4C27 -:103D4000FFF742FF00F0B4F80A498022204600F055 -:103D50003BF8012344F8180C037400F0F3FC002333 -:103D600083F3118862B60448BDE8104000F04CB8F7 -:103D70002C360020345B0008445B000800F01CB9BE -:103D8000EFF3118020B9EFF30583202282F311882D -:103D90007047000010B530B9EFF30584C4F3080490 -:103DA00014B180F3118810BDFFF7BAFF84F31188B6 -:103DB000F9E70000034A516853685B1A9842FBD840 -:103DC000704700BF001000E082600222028270474C -:103DD0008368A3F17C0243F80C2C026943F83C2C65 -:103DE000426943F8382C074A43F81C2CC26843F850 -:103DF000102C022203F8082C002203F8072CA3F150 -:103E0000180070472906000810B5202383F3118895 -:103E1000FFF7DEFF00210446FFF746FF002383F390 -:103E20001188204610BD0000024B1B6958610F200D -:103E3000FFF70EBF04360020202383F31188FFF71D -:103E4000F3BF000008B50146202383F31188082042 -:103E5000FFF70CFF002383F3118808BD49B1064B1F -:103E600042681B6918605A60136043600420FFF7C2 -:103E7000FDBE4FF0FF3070470436002003689842C3 -:103E800006D01A680260506059611846FFF7A4BE58 -:103E90007047000038B504460D462068844200D1C2 -:103EA00038BD036823605C604561FFF795FEF4E769 -:103EB000054B03F11402C3E905224FF0FF31002244 -:103EC000C3E90712704700BF0436002070B51C4ECE -:103ED000C0E9032305460C4601F0FCFA334653F8CB -:103EE000142F9A420DD13062C5E901242A600A2CB0 -:103EF0002CBF00190A30C6E90555BDE8704001F035 -:103F0000D7BA316A431AE31838BF1C469368A342F4 -:103F100002D9081901F0DAFA73699A6894420CD848 -:103F20005A68AC602B606A6015609A685D60121B0D -:103F30009A604FF0FF33F36170BD1B68A41AECE781 -:103F40000436002038B51B4C636998420DD0D0E987 -:103F5000003213605A6000228168C2609A680A4485 -:103F60009A604FF0FF33E36138BD2246036842F8A0 -:103F7000143F002193425A60C16003D1BDE838402C -:103F800001F09EBA9A688168256A0A449A6001F035 -:103F9000A1FA63699A68411B8A42E5D9AB181D1AD8 -:103FA000092D206A98BF01F10A02BDE8384010448B -:103FB00001F08CBA043600202DE9F041184C00279E -:103FC00004F11406656901F085FA236AAA68C11A2A -:103FD0008A4215D813442362D5E9003213605A602F -:103FE0006369D5F80C80EF60B34201D101F068FA43 -:103FF00087F311882869C047202383F31188E1E7FC -:104000006169B14209D013441B1ABDE8F0410A2B83 -:104010002CBFC0180A3001F059BABDE8F08100BFCA -:104020000436002000207047FEE7000070470000C3 -:104030004FF0FF307047000002290CD0032904D054 -:104040000129074818BF00207047032A05D80548F2 -:1040500000EBC2007047044870470020704700BF63 -:10406000285C000834230020DC5B000870B59AB09F -:104070000546084601A9144600F0C2F801A8FDF75C -:10408000E7FC431C5B00C5E90034002223700323D6 -:104090006370C6B201AB02341046D1B28E4204F155 -:1040A000020401D81AB070BD13F8011B04F8021CF9 -:1040B00004F8010C0132F0E708B5202383F31188DE -:1040C0000348FFF779FA002383F3118808BD00BF86 -:1040D000C037002090F8443003F01F02012A07D1B6 -:1040E00090F845200B2A03D10023C0E90E3315E0D8 -:1040F00003F06003202B08D1B0F848302BB990F8BA -:104100004520212A03D81F2A04D8FFF737BA222ACC -:10411000EBD0FAE7034A82630722C26303640120FB -:10412000704700BF2C23002007B5052917D8DFE80A -:1041300001F0191603191920202383F31188104A5E -:1041400001900121FFF7D8FA01980E4A0221FFF7EA -:10415000D3FA0D48FFF7FCF9002383F3118803B06D -:104160005DF804FB202383F311880748FFF7C6F9A5 -:10417000F2E7202383F311880348FFF7DDF9EBE72B -:104180007C5B0008A05B0008C037002038B50C4DF0 -:104190000C4C0D492A4604F10800FFF767FF05F1B2 -:1041A000CA0204F110000949FFF760FF05F5CA7261 -:1041B00004F118000649BDE83840FFF757BF00BFBB -:1041C000883C0020342300205C5B0008665B00080C -:1041D000715B000870B5044608460D46FDF738FCD3 -:1041E000C6B22046013403780BB9184670BD32467A -:1041F0002946FDF719FC0028F3D10120F6E700005D -:104200002DE9F04705460C46FDF722FC2B49C6B2C6 -:104210002846FFF7DFFF08B10B36F6B228492846DB -:10422000FFF7D8FF08B11036F6B2632E0BD8DFF8CF -:104230008C80DFF88C90234FDFF894A02E7846B95D -:104240002670BDE8F08729462046BDE8F04701F01A -:1042500005BC252E2ED1072241462846FDF7E4FB5A -:1042600070B9194B224603F1100153F8040B42F8C0 -:10427000040B8B42F9D11B88138007351234DDE71C -:10428000082249462846FDF7CFFB98B90F4BA21CE0 -:10429000197809090232C95D02F8041C13F8011BE0 -:1042A00001F00F015345C95D02F8031CF0D1183429 -:1042B0000835C3E704F8016B0135BFE7485C000827 -:1042C000715B0008635C0008505C0008107AFF1FF7 -:1042D0001C7AFF1FBFF34F8F024AD368DB03FCD465 -:1042E000704700BF003C024008B5094B1B7873B90A -:1042F000FFF7F0FF074B1A69002ABFBF064A5A6052 -:1043000002F188325A601A6822F480621A6008BD8D -:10431000E63E0020003C02402301674508B50B4BF8 -:104320001B7893B9FFF7D6FF094B1A6942F0004298 -:104330001A611A6842F480521A601A6822F4805294 -:104340001A601A6842F480621A6008BDE63E0020D6 -:10435000003C02400B28F0B516D80C4C0C492378D1 -:104360007BB90C4D0E460C234FF0006255F8047BD0 -:1043700046F8042B013B13F0FF033A44F6D1012326 -:10438000237051F82000F0BD0020FCE7183F00200A -:10439000E83E0020745C0008014B53F82000704791 -:1043A000745C00080C2070470B2810B5044601D936 -:1043B000002010BDFFF7CEFF064B53F82430184401 -:1043C000C21A0BB90120F4E712680132F0D1043BA4 -:1043D000F6E700BF745C00080B2838B5044628D8FF -:1043E000FFF7CEFCFFF776FFFFF77EFF124AF323BD -:1043F000D360E300DBB243F4007343F002031361C4 -:10440000136943F48033136105462046FFF762FFCA -:10441000FFF7A0FF094B53F8241000F039F92846A4 -:10442000FFF77CFFFFF7B6FC2046BDE83840FFF7FA -:10443000BBBF002038BD00BF003C0240745C0008D8 -:1044400012F001032DE9F04105460E4614464BD10A -:104450008218B2F1016F61D8314B1B6813F0010370 -:104460005CD0304FFFF78CFCFFF73EFFF323FB607F -:10447000FFF730FF314640F20128032C18D824F012 -:104480000104284E0C446D1A40F20118A142336910 -:1044900005EB01072AD123F001033361FFF73EFF4B -:1044A000FFF778FC0120BDE8F081043C0435E4E727 -:1044B000AB07E4D13B6923F440733B613B6943EABA -:1044C00008033B6151F8046B2E60BFF34F8FFFF779 -:1044D00001FF2B689E42E8D03B6923F001033B615A -:1044E000FFF71CFFFFF756FC0020DCE723F44073C6 -:1044F0003361336943EA080333610B883B80BFF3C0 -:104500004F8FFFF7E7FE3F8831F8023BBFB2BB4257 -:10451000BCD0336923F001033361E1E71846C2E7F9 -:1045200000380240003C0240084908B50B7828B129 -:104530001BB9FFF7D9FE01230B7008BD002BFCD07F -:10454000BDE808400870FFF7E9BE00BFE63E002066 -:1045500070B582B0FFF714FC0E4E054600F0BAFFAE -:104560003268904237BF0C4A0B49516814682EBF1D -:10457000D1E90041013151600419034641F10001C4 -:10458000284601913360FFF705FC0199204602B0EF -:1045900070BD00BF1C3F0020203F002070B582B0DE -:1045A000FFF7EEFB104E054600F094FF3268904294 -:1045B00037BF0E4A0D49516814682EBFD1E900413A -:1045C00001315160041941F100010346284601916F -:1045D0003360FFF7DFFB01994FF47A720023204626 -:1045E000FBF7FEFD02B070BD1C3F0020203F002005 -:1045F00010B50244064BD2B2904200D110BD441C0B -:1046000000B253F8200041F8040BE0B2F4E700BF19 -:10461000502800400F4B30B51C6F240407D41C6F8A -:1046200044F400741C671C6F44F400441C670A4C7B -:10463000236843F4807323600244084BD2B2904253 -:1046400000D130BD441C00B251F8045B43F8205047 -:10465000E0B2F4E70038024000700040502800400B -:1046600007B5012201A90020FFF7C2FF019803B09E -:104670005DF804FB13B50446FFF7F2FFA04205D036 -:10468000012201A900200194FFF7C4FF02B010BD70 -:1046900070470000074B45F255521A6002225A60DB -:1046A00040F6FF729A604CF6CC421A60024B01222F -:1046B0001A707047003000402C3F0020034B1B78DD -:1046C0001BB1034B4AF6AA221A6070472C3F002008 -:1046D00000300040034B1A681AB9034AD2F8742814 -:1046E0001A607047283F002000300240024B4FF014 -:1046F0008072C3F8742870470030024008B5FFF795 -:10470000E9FF024B1868C0F3407008BD283F002045 -:1047100008B5FFF7DFFF024B1868C0F3007008BD53 -:10472000283F0020EFF3098305494A6B22F001027C -:104730004A63683383F30988002383F31188704741 -:1047400000EF00E0202080F3118862B60C4B0D4A88 -:10475000D96821F4E0610904090C0A43DA60D3F84E -:10476000FC20094942F08072C3F8FC200A6842F03C -:1047700001020A601022DA7783F82200704700BF36 -:1047800000ED00E00003FA05001000E010B5202362 -:1047900083F311880E4B5B6813F4006314D0F1EEC1 -:1047A000103AEFF30984683C4FF08073E361094BE2 -:1047B000DB6B236684F30988FFF792FA10B1064B8E -:1047C000A36110BD054BFBE783F31188F9E700BF38 -:1047D00000ED00E000EF00E03B0600083E060008A8 -:1047E00070470000FEE700000A4B0B480B4A90425E -:1047F0000BD30B4BDA1C121AC11E22F003028B42A0 -:1048000038BF00220021FDF72BB953F8041B40F8F4 -:10481000041BECE72C5E0008284000202840002004 -:10482000284000207047000070B5D0E915439E680D -:1048300000224FF0FF3504EB42135101D3F8000979 -:104840000028BEBFD3F8000940F08040C3F800093B -:10485000D3F8000B0028BEBFD3F8000B40F0804017 -:10486000C3F8000B013263189642C3F80859C3F825 -:10487000085BE0D24FF00113C4F81C3870BD000093 -:104880001D4B03EB80022DE9F043D2F80CC05D6DA7 -:10489000DCF81420461CD2F800E005EB063605EBE8 -:1048A0004018516871450AD3D5F83438012202FA0C -:1048B00000F023EA0000C5F83408BDE8F083BCF836 -:1048C0001040AEEB0103A34228BF2346D8F8184995 -:1048D000A4B2B3EB840FF0D89468A4F1040959F89A -:1048E000047F3760A4EB09071F44042FF7D81C444A -:1048F0000B4494605360D4E7303F0020890141F0BD -:104900002001016103699B06FCD41220FFF752BA13 -:1049100010B5054C2046FEF7D1FE4FF0A04363656D -:10492000024BA36510BD00BF303F0020C85C0008EB -:1049300070B50378012B054650D12A4B446D98423F -:104940001BD1294B5A6B42F080025A635A6D42F0D8 -:1049500080025A655A6D5A6942F080025A615A695A -:1049600022F080025A610E2143205B69FEF77CFC35 -:104970001E4BE3601E4BC4F800380023C4F8003E11 -:10498000C02323606E6D4FF40413A3633369002BBF -:10499000FCDA012333610C20FFF70CFA3369DB07E3 -:1049A000FCD41220FFF706FA3369002BFCDA00264C -:1049B000A6602846FFF738FF6B68C4F81068DB680C -:1049C000C4F81468C4F81C684BB90A4BA3614FF0D3 -:1049D000FF336361A36843F00103A36070BD064B1E -:1049E000F4E700BF303F0020003802404014004090 -:1049F00003002002003C30C0083C30C0F8B5446DD4 -:104A0000054600212046FFF779FFA96D00234FF0EE -:104A100001128F68C4F834384FF00066C4F81C28BF -:104A20004FF0FF3004EB431201339F42C2F800699C -:104A3000C2F8006BC2F80809C2F8080BF2D20B6882 -:104A40006A6DEB65636210231361166916F0100638 -:104A5000FBD11220FFF7AEF9D4F8003823F4FE633F -:104A6000C4F80038A36943F4402343F01003A36162 -:104A70000923C4F81038C4F814380A4BEB604FF01F -:104A8000C043C4F8103B084BC4F8003BC4F810699D -:104A9000C4F80039EB6D03F1100243F48013EA65AA -:104AA000A362F8BDA45C000840800010426D90F83D -:104AB0004E10D2F8003823F4FE6343EA0113C2F823 -:104AC000003870472DE9F84300EB8103456DDA6843 -:104AD000166806F00306731E022B05EB41130C4605 -:104AE00080460FFA81F94FEA41104FF00001C3F8F8 -:104AF000101B4FF0010104F1100398BFB60401FA36 -:104B000003F391698EBF334E06F1805606F50046D9 -:104B100000293AD0578A04F15801490137436F50B0 -:104B2000D5F81C180B43C5F81C382B180021C3F806 -:104B3000101953690127611EA7409BB3138A928BFA -:104B40009B08012A88BF5343D8F85C20981842EA92 -:104B5000034301F1400205EB8202C8F85C002146E4 -:104B600053602846FFF7CAFE08EB8900C3681B8A1A -:104B700043EA8453483464011E432E51D5F81C384F -:104B80001F43C5F81C78BDE8F88305EB4917D7F833 -:104B9000001B21F40041C7F8001BD5F81C1821EABE -:104BA0000303C0E704F13F0305EB83030A4A5A609D -:104BB00028462146FFF7A2FE05EB4910D0F8003940 -:104BC00023F40043C0F80039D5F81C3823EA07075E -:104BD000D7E700BF0080001000040002826D126859 -:104BE000C265FFF721BE00005831436D49015B5893 -:104BF00013F4004004D013F4001F0CBF0220012066 -:104C0000704700004831436D49015B5813F4004080 -:104C100004D013F4001F0CBF0220012070470000D5 -:104C200000EB8101CB68196A0B6813604B68536015 -:104C30007047000000EB810330B5DD68AA69136896 -:104C4000D36019B9402B84BF402313606B8A14686A -:104C5000426D1C44013CB4FBF3F46343033323F083 -:104C6000030302EB411043EAC44343F0C043C0F8DE -:104C7000103B2B6803F00303012B09B20ED1D2F8CD -:104C8000083802EB411013F4807FD0F8003B14BFCA -:104C900043F0805343F00053C0F8003B02EB411255 -:104CA000D2F8003B43F00443C2F8003B30BD0000A3 -:104CB0002DE9F041244D6E6D06EB40130446D3F808 -:104CC000087BC3F8087B38070AD5D6F814381907CB -:104CD00006D505EB84032146DB6828465B689847C8 -:104CE000FA071FD5D6F81438DB071BD505EB84036C -:104CF000D968CCB98B69488A5A68B2FBF0F600FBD8 -:104D000016228AB91868DA6890420DD2121AC3E9DD -:104D10000024202383F311880B482146FFF78AFFE4 -:104D200084F31188BDE8F081012303FA04F26B8952 -:104D300023EA02036B81CB68002BF3D021460248A3 -:104D4000BDE8F041184700BF303F002000EB810371 -:104D500070B5DD68436D6C692668E6604A0156BB34 -:104D60001A444FF40020C2F810092A6802F0030226 -:104D7000012A0AB20ED1D3F8080803EB421410F44A -:104D8000807FD4F8000914BF40F0805040F00050FC -:104D9000C4F8000903EB4212D2F8000940F00440C5 -:104DA000C2F80009D3F83408012202FA01F10143E4 -:104DB000C3F8341870BD19B9402E84BF402020605C -:104DC00020682E8A8419013CB4FBF6F440EAC44002 -:104DD00040F000501A44C6E7F8B504461E48456D39 -:104DE00005EB4413D3F80869C3F80869F10717D530 -:104DF000D5F81038DA0713D500EB8403D9684B696E -:104E00001F68DA68974218D2D21B00271A605F60C9 -:104E1000202383F311882146FFF798FF87F3118839 -:104E2000330617D5D5F834280123A340134211D0F7 -:104E30002046BDE8F840FFF723BD012303FA04F242 -:104E4000038923EA020303818B68002BE8D0214603 -:104E50009847E5E7F8BD00BF303F00202DE9F74F48 -:104E6000984C666D7569B3691D4015F4805875617D -:104E700007D02046FEF788FC03B0BDE8F04FFFF7EF -:104E800085BC002D12DAD6F8003E8E489F071EBF63 -:104E9000D6F8003E23F00303C6F8003ED6F80438E7 -:104EA00023F00103C6F80438FEF796FC280505D563 -:104EB0008448FFF7B9FC8348FEF77EFCA9040CD5B3 -:104EC000D6F8083813F0060FF36823F470530CBFBC -:104ED00043F4105343F4A053F3602A0704D56368E6 -:104EE000DB680BB177489847EB0274D4AF0227D543 -:104EF000D4F85490DFF8CCB100274FF0010A09EB49 -:104F00004712D2F8003B03F44023B3F5802F11D1B0 -:104F1000D2F8003B002B0DDA62890AFA07F322EA85 -:104F20000303638104EB8703DB68DB6813B1394655 -:104F300058469847A36D01379B68FFB29F42DED960 -:104F4000E80617D5676D3A6AC2F30A1002F00F033C -:104F500002F4F012B2F5802F00F08880B2F5402FF5 -:104F600008D104EB83030022DB681B6A07F5805736 -:104F700090426DD12903D6F8184813D5E20302D523 -:104F80000020FFF795FEA30302D50120FFF790FE56 -:104F9000670302D50220FFF78BFE260302D503200C -:104FA000FFF786FE6D037FF567AFE00702D50020AF -:104FB000FFF712FFA10702D50120FFF70DFF6207DF -:104FC00002D50220FFF708FF23077FF555AF032026 -:104FD000FFF702FF50E7636DDFF8E8B001930027A9 -:104FE0004FF0010AA36D9B685FFA87F999453FF678 -:104FF0007DAF019B03EB4913D3F8002902F4402253 -:10500000B2F5802F22D1D3F80029002A1EDAD3F876 -:10501000002942F09042C3F80029D3F80029002A61 -:10502000FBDB606D4946FFF769FC22890AFA09F348 -:1050300022EA0303238104EB8903DB689B6813B135 -:105040004946584698474846FFF71AFC0137C9E7D2 -:10505000910708BFD7F80080072A98BF03F8018B93 -:1050600002F1010298BF4FEA182881E7023304EBEE -:10507000830207F580575268D2F818C0DCF8082080 -:10508000DCE9001CA1EB0C0C002188420AD104EBE6 -:10509000830463689B699A6802449A605A68024470 -:1050A0005A6067E711F0030F08BFD7F800808C45FE -:1050B00088BF02F8018B01F1010188BF4FEA18286F -:1050C000E3E700BF303F0020436D03EB4111D1F80F -:1050D000003B43F40013C1F8003B7047436D03EB02 -:1050E0004111D1F8003943F40013C1F80039704779 -:1050F000436D03EB4111D1F8003B23F40013C1F8D9 -:10510000003B7047436D03EB4111D1F8003923F4A4 -:105110000013C1F80039704730B5039C01720433A5 -:1051200004FB0325C0E90653049B03630021059B90 -:10513000C160C0E90000C0E90422C0E90842C0E93A -:105140000A11436330BD0000416A0022C0E9041126 -:10515000C0E90A22C2606FF00101FEF79BBE0000A9 -:10516000D0E90432934201D1C2680AB9181D7047D0 -:105170000020704703691960C2680132C260C269C9 -:10518000134482690361934224BF436A036100218F -:10519000FEF774BE38B504460D46E3683BB162695C -:1051A000131D1268A3621344E362002007E0237A10 -:1051B00033B929462046FEF751FE0028EDDA38BD06 -:1051C0006FF00100FBE70000C368C269013BC360E8 -:1051D0004369134482694361934224BF436A436134 -:1051E00000238362036B03B11847704770B5202317 -:1051F000044683F31188866A3EB9FFF7CBFF054664 -:1052000018B186F31188284670BDA36AE26A13F8C4 -:10521000015BA362934202D32046FFF7D5FF002330 -:1052200083F31188EFE700002DE9F84F04460E469E -:10523000174698464FF0200989F311880025AA46A1 -:10524000D4F828B0BBF1000F09D141462046FFF742 -:10525000A1FF20B18BF311882846BDE8F88FD4E96F -:105260000A12A7EB050B521A934528BF9346BBF1D0 -:10527000400F1BD9334601F1400251F8040B43F8AB -:10528000040B9142F9D1A36A40334036A362403502 -:10529000D4E90A239A4202D32046FFF795FF8AF306 -:1052A0001188BD42D8D289F31188C9E730465A46E1 -:1052B000FCF7B0FBA36A5B445E44A3625D44E7E78E -:1052C00010B5029C0172043304FB0321C0E90613EC -:1052D0000023C0E90A33039B0363049BC460C0E955 -:1052E0000000C0E90422C0E90842436310BD000089 -:1052F000026AC260426AC0E904220022C0E90A22AE -:105300006FF00101FEF7C6BDD0E904239A4201D136 -:10531000C26822B9184650F8043B0B607047002061 -:1053200070470000C368C2690133C3604369134416 -:1053300082694361934224BF436A43610021FEF7BF -:105340009DBD000038B504460D46E3683BB12369B6 -:105350001A1DA262E2691344E362002007E0237A87 -:1053600033B929462046FEF779FD0028EDDA38BD2D -:105370006FF00100FBE7000003691960C268013AA1 -:10538000C260C269134482690361934224BF436AC5 -:10539000036100238362036B03B118477047000069 -:1053A00070B520230D460446114683F31188866AA2 -:1053B0002EB9FFF7C7FF10B186F3118870BDA36A3D -:1053C0001D70A36AE26A01339342A36204D3E169C8 -:1053D00020460439FFF7D0FF002080F31188EDE765 -:1053E0002DE9F84F04460D46904699464FF0200AA5 -:1053F0008AF311880026B346A76A4FB9494620466A -:10540000FFF7A0FF20B187F311883046BDE8F88F81 -:10541000D4E90A073A1AA8EB0607974228BF1746AD -:10542000402F1BD905F1400355F8042B40F8042BFD -:105430009D42F9D1A36A4033A3624036D4E90A23DE -:105440009A4204D3E16920460439FFF795FF8BF3B4 -:1054500011884645D9D28AF31188CDE729463A46C4 -:10546000FCF7D8FAA36A3B443D44A3623E44E5E717 -:10547000D0E904239A4217D1C3689BB1836A8BB1E8 -:10548000043B9B1A0ED01360C368013BC360C36921 -:105490001A44836902619A4224BF436A036100236C -:1054A00083620123184670470023FBE700F088B8A9 -:1054B0004FF08043002258631A610222DA6070477D -:1054C0004FF080430022DA60704700004FF08043C5 -:1054D000586370474FF08043586A70474B68436089 -:1054E0008B688360CB68C3600B6943614B6903625F -:1054F0008B6943620B6803607047000008B5264B58 -:1055000026481A6940F2FF110A431A611A6922F407 -:10551000FF7222F001021A611A691A6B0A431A63B8 -:105520001A6D0A431A651E4A1B6D1146FFF7D6FF16 -:1055300002F11C0100F58060FFF7D0FF02F1380195 -:1055400000F58060FFF7CAFF02F1540100F58060AA -:10555000FFF7C4FF02F1700100F58060FFF7BEFFA6 -:1055600002F18C0100F58060FFF7B8FF02F1A8019D -:1055700000F58060FFF7B2FF02F1C40100F5806022 -:10558000FFF7ACFF02F1E00100F58060FFF7A6FF36 -:10559000BDE8084000F09AB8003802400000024020 -:1055A000D45C000808B500F007FAFEF7C7FBFFF768 -:1055B00091F8BDE80840FEF7E9BD00007047000023 -:1055C000104B1A6C42F001021A641A6E42F001028A -:1055D0001A660D4A1B6E936843F0010393604FF007 -:1055E000804353229A624FF0FF32DA6200229A61BE -:1055F0005A63DA605A6001225A6108211A601C203D -:10560000FDF732BE00380240002004E04FF0804237 -:1056100008B51169D3680B40D9B2C9439B07116122 -:1056200007D5202383F31188FEF7A8FB002383F31B -:10563000118808BD08B5FFF7E9FFBDE80840FFF78E -:10564000A5B800001F4B1A696FEAC2526FEAD25226 -:105650001A611A69C2F308021A614FF0FF301A6921 -:105660005A69586100215A6959615A691A6A62F087 -:1056700080521A621A6A02F080521A621A6A5A6AD0 -:1056800058625A6A59625A6A1A6C42F080521A6415 -:105690001A6E42F080521A661A6E0B4A106840F475 -:1056A00080701060186F00F44070B0F5007F1EBF6E -:1056B0004FF4803018671967536823F40073536000 -:1056C00000F05AB90038024000700040334B4FF0F0 -:1056D00080521A64324A4FF4404111601A6842F015 -:1056E00001021A601A689107FCD59A6822F0030239 -:1056F0009A602A4B9A6812F00C02FBD1196801F0EB -:10570000F90119609A601A6842F480321A601A68C6 -:105710009203FCD55A6F42F001025A671F4B5A6F31 -:105720009007FCD51F4A5A601A6842F080721A60CE -:105730001B4A53685904FCD5184B1A689201FCD5D2 -:10574000194A9A60194B1A68194B9A42194B21D180 -:10575000194A1168194A91421CD140F205121A6087 -:10576000144A136803F00F03052BFAD10B4B9A6808 -:1057700042F002029A609A6802F00C02082AFAD1FA -:105780005A6C42F480425A645A6E42F480425A661D -:105790005B6E704740F20572E1E700BF00380240DF -:1057A000007000400854400700948838002004E04E -:1057B00011640020003C024000ED00E041C20F41B6 -:1057C000084A08B5516913680B4003F0010353619F -:1057D00023B1054A13680BB150689847BDE80840EB -:1057E000FEF7D4BF003C0140A83F0020084A08B59E -:1057F000516913680B4003F00203536123B1054A5A -:1058000093680BB1D0689847BDE80840FEF7BEBF6B -:10581000003C0140A83F0020084A08B551691368C0 -:105820000B4003F00403536123B1054A13690BB124 -:1058300050699847BDE80840FEF7A8BF003C01400A -:10584000A83F0020084A08B5516913680B4003F0CF -:105850000803536123B1054A93690BB1D069984796 -:10586000BDE80840FEF792BF003C0140A83F002081 -:10587000084A08B5516913680B4003F010035361DF -:1058800023B1054A136A0BB1506A9847BDE8084036 -:10589000FEF77CBF003C0140A83F0020174B10B52D -:1058A0005A691C68144004F478725A61A30604D53E -:1058B000134A936A0BB1D06A9847600604D5104A20 -:1058C000136B0BB1506B9847210604D50C4A936BB0 -:1058D0000BB1D06B9847E20504D5094A136C0BB1A4 -:1058E000506C9847A30504D5054A936C0BB1D06C56 -:1058F0009847BDE81040FEF749BF00BF003C01409B -:10590000A83F00201A4B10B55A691C68144004F4D3 -:105910007C425A61620504D5164A136D0BB1506D75 -:105920009847230504D5134A936D0BB1D06D984762 -:10593000E00404D50F4A136E0BB1506E9847A104D2 -:1059400004D50C4A936E0BB1D06E9847620404D50F -:10595000084A136F0BB1506F9847230404D5054ACA -:10596000936F0BB1D06F9847BDE81040FEF70EBFA4 -:10597000003C0140A83F0020062108B50846FDF77D -:1059800073FC06210720FDF76FFC06210820FDF7B8 -:105990006BFC06210920FDF767FC06210A20FDF7B4 -:1059A00063FC06211720FDF75FFCBDE808400621D7 -:1059B0002820FDF759BC000008B5FFF743FE00F0B2 -:1059C0000DF8FDF767FCFDF777FEFDF74FFDFFF7DC -:1059D000F5FDBDE80840FFF769BD00000023054A5A -:1059E00019460133102BC2E9001102F10802F8D167 -:1059F000704700BFA83F002010B501390244904213 -:105A000001D1002005E0037811F8014FA34201D035 -:105A1000181B10BD0130F2E72DE9F041A3B1C91AFE -:105A200017780144044603F1FF3C8C42204601D91B -:105A3000002009E00578BD4204F10104F5D10CEB2A -:105A40000405D618A54201D1BDE8F08115F8018DF5 -:105A500016F801EDF045F5D0E7E70000034611F830 -:105A6000012B03F8012B002AF9D170476F72672EC2 -:105A70006172647570696C6F742E663430355F4D79 -:105A80006174656B41697273706565640000000044 -:105A900053544D3332463F3F3F00000053544D3383 -:105AA00032463430780053544D3332463432780025 -:105AB00053544D33324634343658580000000000F9 -:105AC000905A00083F000000130400009C5A000890 -:105AD0003F00000019040000A65A00083F00000023 -:105AE00021040000B05A00083F00000040A2E4F189 -:105AF000646891060041A3E5F26569920700000021 -:105B000000000000E9330008D53300081134000814 -:105B1000FD33000809340008F5330008E1330008BC -:105B2000CD3300081D340008000000000100000013 -:105B3000000000006D61696E0000000069646C6522 -:105B4000000000003C5B000848360020C037002001 -:105B500001000000393D000800000000417264753A -:105B600050696C6F740025424F415244252D424CC0 -:105B7000002553455249414C250000000200000019 -:105B800000000000053600087136000840004000A3 -:105B9000583C0020683C002002000000000000008B -:105BA0000300000000000000B536000800000000FF -:105BB00010000000783C0020000000000100000000 -:105BC00000000000303F00200101020029410008D0 -:105BD00039400008D5400008B940000843000000E3 -:105BE000E45B000809024300020100C0320904001E -:105BF000000102020100052400100105240100013A -:105C0000042402020524060001070582030800FFA0 -:105C100009040100020A000000070501024000001B -:105C2000070581024000000012000000305C0008FF -:105C30001201100102000040091241570002010246 -:105C4000030100000403090425424F41524425008A -:105C5000663430352D4D6174656B416972737065C2 -:105C60006564003031323334353637383941424398 -:105C70004445460000400000004000000040000095 -:105C800000400000000001000000020000000200CF -:105C900000000200000002000000020000000200FC -:105CA0000000020000000000ED370008A53A0008DF -:105CB000513B000840004000903F0020903F0020F2 -:105CC00001000000A03F0020800000004001000013 -:105CD00003000000AA01A81200000000AAAAAAAAB4 -:105CE00055011400FFBF00008877000070A70A006C -:105CF00000000A0100000000AAAAAAAA00000001F0 -:105D0000FFFF000000000000990000000000A01646 -:105D100000000000AAAAAAA600005011FFDF0000A0 -:105D200000000000007708002000000000000000D4 -:105D3000AAAAAAAA10000000FFFF000000080000A5 -:105D4000000000000000000000000000AAAAAAAAAB -:105D500000000000FFFF0000000000000000000045 -:105D60000000000000000000AAAAAAAA000000008B -:105D7000FFFF000000000000000000000000000025 -:105D800000000000AAAAAAAA00000000FFFF00006D -:105D90000000000000000000000000000000000003 -:105DA0000A000000000000000300000000000000E6 -:105DB00000000000000000000000000000000000E3 -:105DC00000000000000000000000000000000000D3 -:105DD00040A4FF7F01000000F60300000000000067 -:105DE00000000F0000000000640000000000000040 -:105DF00040420F00FE2A0100D2040000FF0096007E -:105E000000000008009600000000080004000000E8 -:105E1000445C0008000000000000000000000000DA -:0C5E200000000000000000000000000076 +:1000000000070020F5040008A92E0008612E000852 +:10001000892E0008612E0008812E0008F7040008D0 +:10002000F7040008F7040008F70400089D3E0008E4 +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F70400086D64000895640008C0 +:10006000BD640008E56400080D650008F704000899 +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F7040008152E00081C +:10009000412E0008512E0008F704000835650008BD +:1000A000F7040008F7040008F7040008F704000844 +:1000B00009660008F7040008F7040008F7040008C0 +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008F7040008F7040008F704000814 +:1000E00099650008F7040008F7040008F704000801 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008615A0008E3 +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E0005D18000800000000000000000000000092 +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600004F046FF05F02AFE4FF055301F491B4AA4 +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE704F024FFDB +:1005B00005F058FE144C154DAC4203DA54F8041BF8 +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E704F00CBF000700201B +:1005E000002300200000000808ED00E000010020CA +:1005F00000070020F86B000800230020B023002033 +:10060000B023002048560020E0010008E401000863 +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002004F0E6F940 +:10064000FEE704F03FF900DFFEE70000F8B501F037 +:1006500017F904F067FE074604F0B6FE0546B8BB7E +:10066000204B9F4234D001339F4234D01E4B27F0A1 +:10067000FF029A4232D1F8B200F00EFF2E4642F24B +:10068000107400F00FFF08B10024264601F0FAFCB8 +:1006900020B1032000F07CF80024264635B1134B2E +:1006A0009F4203D004F088FE00242646002004F078 +:1006B00043FE0EB100F082F801F094FA00F05EFF04 +:1006C00001F044F9204600F0D5F800F077F8F9E79A +:1006D0002E460024D5E704460126D2E7064641F21D +:1006E0008834CEE7010007B0000008B0263A09B010 +:1006F00008B501F0FDF8A0F120035842584108BDAB +:1007000007B541F21203022101A8ADF8043001F04F +:100710000DF903B05DF804FB38B5302383F311887D +:10072000174803680BB104F03DFA164A1448002339 +:100730004FF47A7104F02CFA002383F31188124CE1 +:10074000236813B12368013B2360636813B16368B6 +:10075000013B63600D4D2B7833B963687BB9022090 +:1007600001F0BAF9322363602B78032B07D1636859 +:100770002BB9022001F0B0F94FF47A73636038BDF1 +:10078000B023002019070008D0240020C82300202F +:10079000084B187003280CD8DFE800F008050208A1 +:1007A000022001F08FB9022001F082B9024B002231 +:1007B0005A607047C8230020D024002010B501F0F3 +:1007C00061FC30B1244B03221A70244B00225A6082 +:1007D00010BD234B234A1C4619680131F8D004335D +:1007E0009342F9D16268204B9A42F1D91F4B9B6822 +:1007F00003F1006303F580339A42E9D204F0B0FDBF +:1008000004F0C2FD002001F0BBF80220FFF7C0FF9A +:10081000174B1A6C00221A64196E1A66196E596CFD +:100820005A64596E5A665A6E1A6942F000521A6139 +:100830001A6922F000521A611B6972B64FF0E02368 +:100840003021C3F8084DD4E9003281F311889D4668 +:1008500083F308881047BBE7C8230020D02400207A +:100860000000010820000108FFFF0008002300200D +:10087000003802402DE9F04F93B0AC4B009020229D +:10088000FF210AA89D6801F057F9A94A1378A3B976 +:10089000A848012103601170302383F31188036895 +:1008A0000BB104F07FF9A44AA24800234FF47A71F7 +:1008B00004F06EF9002383F31188009B13B19F4B62 +:1008C000009A1A609E4A009C1378032B1EBF0023D7 +:1008D00013709A4A4FF0000A18BF5360D346564629 +:1008E000D146012001F0EEF824B1944B1B68002B97 +:1008F00000F01582002000F0FBFF0390039B002B0B +:1009000001DA00F083FE039B002BEDDB012001F0F8 +:10091000CFF8039B213B162BE3D801A252F823F01A +:100920007D090008A5090008390A0008E308000845 +:10093000E3080008E3080008C30A0008930C000855 +:10094000AD0B00080F0C0008370C00085D0C000808 +:10095000E30800086F0C0008E3080008E10C000839 +:100960001D0A0008E3080008250D00088909000891 +:100970001D0A0008E30800080F0C00080220FFF71A +:10098000B7FE002840F0F581009B0221BAF1000F6C +:1009900008BF1C4605A841F21233ADF8143000F030 +:1009A000C5FF9EE74FF47A7000F0A2FF071EEBDB55 +:1009B0000220FFF79DFE0028E6D0013F052F00F240 +:1009C000DA81DFE807F0030A0D10133605230593DB +:1009D000042105A800F0AAFF17E054480421F9E714 +:1009E00058480421F6E758480421F3E74FF01C0863 +:1009F000404600F0C7FF08F104080590042105A84F +:100A000000F094FFB8F12C0FF2D1012000FA07F7A3 +:100A100047EA0B0B5FFA8BFB4FF0000901F0D8F8A7 +:100A200026B10BF00B030B2B08BF0024FFF768FE69 +:100A300057E746480421CDE7002EA5D00BF00B0365 +:100A40000B2BA1D10220FFF753FE074600289BD0B5 +:100A5000012000F095FF0220FFF79AFE00261FFA02 +:100A600086F8404600F09CFF044690B100214046C5 +:100A700000F0AEFF01360028F1D1BA46044641F23B +:100A80001213022105A8ADF814303E4600F04EFFC7 +:100A900027E70120FFF77CFE2546244B9B68AB42ED +:100AA00007D9284600F06EFF013040F06781043519 +:100AB000F3E7234B00251D70204BBA465D603E4690 +:100AC000ACE7002E3FF460AF0BF00B030B2B7FF471 +:100AD0005BAF0220FFF75CFE322000F009FFB0F1AF +:100AE0000008FFF651AF18F003077FF44DAF0F4A2F +:100AF000926808EB050393423FF646AFB8F5807F56 +:100B00003FF742AF124B0193B84523DD4FF47A70A3 +:100B100000F0EEFE0390039A002AFFF635AF019B2A +:100B2000039A03F8012B0137EDE700BF00230020F3 +:100B3000CC240020B023002019070008D024002076 +:100B4000C823002004230020082300200C230020B9 +:100B5000CC230020C820FFF7CBFD074600283FF438 +:100B600013AF1F2D11D8C5F1200242450AAB25F065 +:100B7000030028BF424683490192184400F0B6FFA3 +:100B8000019A8048FF2100F0D7FF4FEAA8037D4972 +:100B90000193C8F38702284600F0D6FF06460028D6 +:100BA0003FF46DAF019B05EB830537E70220FFF7AC +:100BB0009FFD00283FF4E8AE00F02AFF00283FF434 +:100BC000E3AE0027B846704B9B68BB4218D91F2F75 +:100BD00011D80A9B01330ED027F0030312AA134445 +:100BE00053F8203C05934046042205A901F002FA7F +:100BF00004378046E7E7384600F0C4FE0590F2E788 +:100C0000CDF81480042105A800F090FE06E700232B +:100C1000642104A8049300F07FFE00287FF4B4AEA2 +:100C20000220FFF765FD00283FF4AEAE049800F007 +:100C3000D7FE0590E6E70023642104A8049300F0A2 +:100C40006BFE00287FF4A0AE0220FFF751FD0028C4 +:100C50003FF49AAE049800F0D3FEEAE70220FFF7D3 +:100C600047FD00283FF490AE00F0E2FEE1E70220ED +:100C7000FFF73EFD00283FF487AE05A9142000F0E1 +:100C8000DDFE04210746049004A800F04FFE39461B +:100C9000B9E7322000F02CFE071EFFF675AEBB0749 +:100CA0007FF472AE384A926807EB090393423FF62D +:100CB0006BAE0220FFF71CFD00283FF465AE27F065 +:100CC00003074F44B9453FF4A9AE484600F05AFE29 +:100CD0000421059005A800F029FE09F10409F1E7B7 +:100CE0004FF47A70FFF704FD00283FF44DAE00F09A +:100CF0008FFE002844D00A9B01330BD008220AA99A +:100D0000002000F021FF00283AD02022FF210AA86D +:100D100000F012FFFFF7F4FC1C4803F07DFE13B057 +:100D2000BDE8F08F002E3FF42FAE0BF00B030B2B22 +:100D30007FF42AAE0023642105A8059300F0ECFDA2 +:100D4000074600287FF420AE0220FFF7D1FC804642 +:100D500000283FF419AEFFF7D3FC41F2883003F0CE +:100D60005BFE059800F066FF464600F031FF3C460A +:100D7000B7E5064652E64FF0000905E6BA467EE6BC +:100D800037467CE6CC23002000230020A08601000B +:100D9000094A136849F2690099B21B0C00FB013340 +:100DA0001360064B186844F2506182B2000C01FBDC +:100DB0000200186080B2704718230020142300201E +:100DC00010B500211022044600F0B6FE034B03CB01 +:100DD000206061601868A06010BD00BF107AFF1F1E +:100DE0002DE9F041ADF5507D0DF13C086EAC40F2BF +:100DF000751207460D4610A80021C8F8001000F033 +:100E00009BFE4FF4C4720021204600F095FE02F0D4 +:100E100053F8254B4FF47A72B0FBF2F0186093E868 +:100E20000700022384E807000DF5ED702382FFF729 +:100E3000C7FF4FF203631D49238406A805F0F4FCA5 +:100E4000202384F832310DF2EB2606AB0DF1380C7D +:100E50001A4603CA624530607160134606F10806FF +:100E6000F6D141460122204600F0E6FE002303931E +:100E7000AB7E029305F11903019380B20123CDE902 +:100E800004800093E97E06A3D3E90023384602F0EC +:100E9000DBFB0DF5507DBDE8F08100BFAFF30080B6 +:100EA0009E6AC421818A46EED82400203868000852 +:100EB0002DE9F0412C4C237ADAB080460D465BBB1D +:100EC00027A9284600F0C8FF0746002842D19DF810 +:100ED0009D60C82E3ED801464FF4A662204600F021 +:100EE0002BFE4FF48073C4F8F8314FF40073C4F84C +:100EF0000C334FF44073C4F8203432460DF19E0198 +:100F000004F1090000F0F2FD26449DF89C30777250 +:100F100023720BB9EB7E23728122002106AC27A835 +:100F200000F00AFE0122214627A800F0D1FF00238D +:100F30000393AB7E029305F1190380B2019328233A +:100F4000CDE904400093E97E05A3D3E900234046A0 +:100F500002F07AFB5AB0BDE8F08100BFAFF3008029 +:100F600026417272DF25D7B7F0450020F0B5254E37 +:100F70004FF48A7505FB0065F1B096F8D83085F816 +:100F8000DC300024D822214685F8E8403AA800F059 +:100F9000D3FD06F1090000F0C7FDD5F8E4308DF867 +:100FA000F000C2B206AF06F109010DF1F100CDE982 +:100FB0003A3400F09BFD394601223AA800F0B4FF14 +:100FC00080B2CDE9047008230127CDE9023706F18C +:100FD000D803019330230093317A0B4807A3D3E958 +:100FE000002302F031FBA04206DD01F065FFC5F8E9 +:100FF000E000384671B0F0BD2046FBE778F6339F3D +:1010000093CACD8DF0450020F03400202DE9F04149 +:101010001D4D1E4E1E4F86B0284602F041FB034672 +:1010200058B30024CDE90344ADF81440027B8DF899 +:10103000142099684068029403AA03C21B68DFF871 +:10104000548043F00043029301F038FF821941F1CC +:101050000003009402A9384601F0FAF9A04205DD28 +:10106000284602F021FB88F80040D5E798F80030C8 +:10107000072B05D8013388F8003006B0BDE8F081B1 +:10108000014802F011FBF8E7F034002040420F0065 +:1010900020350020254B002070B50D4614461E4615 +:1010A00002F02EFA50B9022E10D1012C0ED112A34B +:1010B000D3E90023C5E90023012007E0282C10D044 +:1010C00005D8012C09D0052C0FD0002070BD302C84 +:1010D000FBD10BA3D3E90023ECE70BA3D3E9002357 +:1010E000E8E70BA3D3E90023E4E70BA3D3E900234C +:1010F000E0E700BFAFF30080401DA12026812A0B4E +:1011000078F6339F93CACD8D9E6AC421818A46EEBC +:1011100026417272DF25D7B7F017304A39059E563F +:1011200038B505460E4C0021013500F051FCA4F8FD +:101130002C55B4F82C0500F033FC78B1B4F82C052C +:1011400000F03EFC014648B9B4F82C0500F040FC24 +:10115000B4F82C350133A4F82C35EAE738BD00BFCC +:10116000F045002010B50A4B0A4A1A6003F5805377 +:1011700093F860203AB9DC6D2CB1204601F000F8FC +:10118000204605F091FABDE81040034800F0F8BF92 +:1011900020350020F8680008684500202DE9F04F50 +:1011A0008FB000AF05460C4602F0AAF9002849D1DD +:1011B000237E022B1BD1E38A012B18D101F07CFE88 +:1011C0000646FFF7E5FD03464FF4C870DFF8C4821A +:1011D000B3FBF0F206F5167602FB103316FA83F332 +:1011E000C8F80030E37E33B9A34B00221A703C37B5 +:1011F000BD46BDE8F08F07F12401204600F0EAFD6E +:101200000028F4D107F11400FFF7DAFD97F8264023 +:1012100007F11401224607F1270005F08FFA002894 +:10122000E2D10F2C08D8944B1C70D8F80030A3F5ED +:101230001673C8F80030DAE797F82410284602F051 +:1012400057F9D4E7E38A282B2BD010D8012B23D0D1 +:10125000052BCCD1BFF34F8F8849894BCA6802F464 +:10126000E0621343CB60BFF34F8F00BFFDE7302B2D +:10127000BDD1844EE17E327A9142B8D1607E314652 +:10128000002291F8DC50854200F0A5800132042A4A +:1012900001F58A71F5D1AAE721462846FFF7A0FD9E +:1012A000A5E721462846FFF703FEA0E7B2F8EC5079 +:1012B0007B6005F103094FEA99094FEA8902D11DC4 +:1012C000C908A8EBC1039D46EB460021584600F033 +:1012D00033FC04F1EE012A463144584600F006FC86 +:1012E0007B6813B9012000F04BFB96F8D20000F0A8 +:1012F00057FB044630B9307200F08AFB204600F0FC +:101300003FFBB1E0D6F8D4203AB996F8D200B6F84F +:101310002C25824201D8FFF703FFD6F8D4202A44B7 +:10132000944208D296F8D200B6F82C2501308242B9 +:1013300001D8FFF7F5FE70685FFA89F2594600F0B0 +:1013400003FC08B9C54679E0726896F8D2002A44D1 +:101350007260D6F8D42005EB0209C6F8D49000F0EC +:101360001FFB814509D396F8D220D6F8D40001326C +:10137000001B86F8D220C6F8D400FF2D0FD8002419 +:10138000347200F045FB204600F0FAFA00F07AFED5 +:101390003D4B188108B9FFF711FAC54627E7BB682E +:1013A00096F8D9000AFB0362FB68D2F8E41082F8D1 +:1013B000E83001F58061C2F8E030C2F8E410FFF7D0 +:1013C000D5FDFFF723FE96F8D920013202F0030283 +:1013D00086F8D920B6E74FF48A7A0AFB02F505F1C0 +:1013E000EA013144204600F0CBFDF86000287FF48C +:1013F000FEAE3544012285F8E82001F05DFDD5F808 +:10140000E020D6ED007ADFED216A801A192838BF76 +:10141000192040F6B832904228BF1046B8EE677ADD +:1014200007EE900AF8EEE77A67EEA67ADFED186A23 +:10143000E7EE267AFCEEE77AC6ED007A96F8D93028 +:10144000BB60BA6873680AFB02F4321992F8E810BC +:1014500059B1D2F8E4108B42E8463FF427AF00219F +:1014600082F8E810C2F8E010C5467368064A9B0A85 +:1014700001331381BBE600BFE934002000ED00E03A +:101480000400FA05F0450020D8240020CDCCCC3D46 +:101490006666663FEC340020014B1870704700BF51 +:1014A000E424002030B54FF000542B4B22689A42C0 +:1014B00085B007D003F092FF044620BB00242046ED +:1014C00005B030BD254B627D25481A70237D03721F +:1014D0004FF48073C0F8F8314FF40073C0F80C3348 +:1014E00000254FF44073C0F820341E49C0F8E45082 +:1014F000C922093000F0FAFA2046E022294600F01D +:101500001BFB0124DBE7184A184D136C43F00073F2 +:101510001364AA6D164B9A42D0D12B6E013B7E2BE1 +:10152000CCD8144A07CA01AB83E807001846032148 +:1015300000F076FD6B6D83424FF00003BED12A6D43 +:101540008A4201BFAB65054B2A6E1A7003BF0A4B76 +:10155000EA6D1A601C46B2E79AAD44C5E424002047 +:10156000F0450020160000200038024000660040D0 +:101570005041A0B0586600401023002037B51A4DE6 +:1015800000F080FD02236B71184B28811968184800 +:10159000012201F02FFB00230193164B1649009303 +:1015A0001648174B4FF4805201F07AFF154B19780B +:1015B00011B1124801F09CFF01F07EFC0446FFF7D8 +:1015C000E7FB4FF4C873B0FBF3F202FB130304F51F +:1015D000167010FA83F00C4B186003F0F5FE08B19A +:1015E0000F232B8103B030BDD8240020102300200E +:1015F0002035002099100008E8240020F034002055 +:101600009D110008E4240020EC3400202DE9F04F67 +:101610002DED028B0FF23829D9E90089834C93B064 +:101620000BAE9FED7E8BFFF7F1FC814FDFF828A218 +:1016300000230A93ADF834300B9373604FF0000B26 +:101640005B468DED008B01250DF11D0207A9384683 +:101650008DF81C508DF81DB001F07CFA9DF81C30FF +:10166000002B40F0A580204601F04AFF06460028E6 +:1016700045D1704F01F020FC3B6898423FD301F008 +:101680001BFC8246FFF784FB4FF4C873B0FBF3F2F8 +:1016900002FB13030AF5167010FA83F03860664FE8 +:1016A00097F800B0CBF1100ABBF1000F14BF33461E +:1016B0002B465FFA8AFA0EA88DF82830FFF780FBD8 +:1016C000BAF1060F28BF4FF0060A0EAB03EB0B0171 +:1016D00052460DF1290000F009FA0AAB03931823D2 +:1016E00002930AF10102554BD2B2CDE900530492A4 +:1016F00020464CA3D3E9002301F048FF3E7001F0DF +:10170000DBFB4F4A4F4D1368C31AB3F57A7F2ED3D4 +:10171000106001F0D3FB02460B46204601F0CEFFDD +:10172000204601F0EDFE10B32B7A474E002B14BF7C +:1017300003230223737101F0BFFB0EAF4FF47A73E2 +:101740000122B0FBF3F039463060304600F01AFB5E +:10175000182302933D4B019380B240F25513CDE91B +:101760000370009342464B46204601F00FFF2B7A50 +:1017700093B101F0A1FB002607464FF48A7A95F851 +:10178000D900304400F003000AFB005393F8E8202E +:1017900092B30136042EF2D1C82003F03DF92B7A22 +:1017A000002B7FF43DAF13B0BDEC028BBDE8F08F92 +:1017B000DAF8143083F48043CAF814305946102202 +:1017C0000EA800F0B9F90DF11E0308AA0AA93846BF +:1017D00000F03CFF96E803000FAB83E803009DF8A0 +:1017E00034308DF844300A9B0E930EA9DDE90823AE +:1017F000204602F037F921E7D3F8E02042B12B6808 +:10180000FA2B38BFFA23BA1A0533B2EB430FC0D311 +:10181000FFF7ACFB0028BCD1BEE700BF0000000012 +:1018200000000000401DA12026812A0BF03400207A +:1018300020350020EC340020E9340020E83400207A +:10184000204B0020F0450020D8240020244B00200D +:10185000F1C6A7C1D068080F0000024008B50548CE +:1018600000F08EFFBDE80840034A0449002004F060 +:1018700015BF00BF20350020604B00206511000817 +:101880007047000070B50F4B1B780133DBB2012BA2 +:101890000C4611D80C4D29684FF47A730E6AA2FBDE +:1018A0000332014622462846B047844204D1074B02 +:1018B00000221A70012070BD4FF4FA7003F0ACF8EA +:1018C0000020F8E71C230020D84D0020544B0020B6 +:1018D00070B504464FF47A76412C254628BF412541 +:1018E00006FB05F003F098F8641BF5D170BD00000D +:1018F00007B50023024601210DF107008DF80730DE +:10190000FFF7C0FF20B19DF8070003B05DF804FBAE +:101910004FF0FF30F9E700000A4608B50421FFF751 +:10192000B1FF80F00100C0B2404208BD30B4054CA8 +:101930002368DD69044B0A46AC460146204630BCAC +:10194000604700BFD84D0020A086010070B503F0AD +:1019500083FB094E094D3080002428683388834278 +:1019600008D903F073FB2B6804440133B4F5803FBE +:101970002B60F2D370BD00BF564B0020284B0020D7 +:1019800003F018BC00F1006000F58030006870477B +:1019900000F10060920000F5803003F0A3BB00006E +:1019A000054B1A68054B1B889B1A834202D91044C9 +:1019B00003F04CBB00207047284B0020564B002002 +:1019C000024B1B68184403F049BB00BF284B0020A2 +:1019D000024B1B68184403F059BB00BF284B002082 +:1019E00010F003030AD1B0F5047F05D200F10050D6 +:1019F000A0F51040D0F80038184670470023FBE7E8 +:101A000000F10050A0F51040D0F8100A7047000017 +:101A1000064991F8243033B10023086A81F8243054 +:101A20000822FFF7B5BF0120704700BF2C4B0020F4 +:101A3000014B1868704700BF002004E070B5194BD7 +:101A40001D68194B0138C5F30B0408442D0C042202 +:101A50001E88A6420BD15C680A46013C82421346AE +:101A60000FD214F9016F4EB102F8016BF6E7013A9B +:101A700003F10803ECD181420B4602D22C2203F879 +:101A8000012B0A4A05241688AE4204D1984284BF2D +:101A9000967803F8016B013C02F10402F3D1581A65 +:101AA00070BD00BF002004E09C6800088868000842 +:101AB000022802BF024B4FF080429A61704700BF7C +:101AC00000000240022802BF024B4FF480429A619C +:101AD000704700BF00000240022801BF024A53695C +:101AE00083F48043536170470000024010B5002327 +:101AF000934203D0CC5CC4540133F9E710BD00001D +:101B000010B5013810F9013F3BB191F900409C42FA +:101B100003D11AB10131013AF4E71AB191F9002069 +:101B2000981A10BD1046FCE703460246D01A12F977 +:101B3000011B0029FAD1704702440346934202D0A8 +:101B400003F8011BFAE770472DE9F8431F4D1446CF +:101B500095F824200746884652BBDFF870909CB366 +:101B600095F824302BB92022FF2148462F62FFF739 +:101B7000E3FF95F82400C0F10802A24228BF2246E4 +:101B8000D6B24146920005EB8000FFF7AFFF95F813 +:101B90002430A41B1E44F6B2082E17449044E4B22D +:101BA00085F82460DBD1FFF733FF0028D7D108E0A8 +:101BB0002B6A03EB82038342CFD0FFF729FF002873 +:101BC000CBD10020BDE8F8830120FBE72C4B00209F +:101BD000024B1A78024B1A70704700BF544B00201A +:101BE0001C23002010B5104C104802F045FA214685 +:101BF0000E4802F06DFA2468626DD2F8043843F0A2 +:101C00000203C2F804384FF47A70FFF761FE084906 +:101C1000204602F063FB626DD2F8043823F0020321 +:101C2000C2F8043810BD00BFE4690008D84D002098 +:101C3000EC690008704700002DE9F0470D460446A6 +:101C400000219046284640F27912FFF775FF23469F +:101C500020220021284601F0A7FE231D0222202178 +:101C6000284601F0A1FE631D03222221284601F02F +:101C70009BFEA31D03222521284601F095FE04F1B9 +:101C8000080310222821284601F08EFE04F11003DB +:101C900008223821284601F087FE04F111030822AA +:101CA0004021284601F080FE04F112030822482159 +:101CB000284601F079FE04F1140320225021284621 +:101CC00001F072FE04F1180340227021284601F051 +:101CD0006BFE04F120030822B021284601F064FEC7 +:101CE00004F121030822B821284601F05DFE04F129 +:101CF0002207C0263B46314608222846083601F016 +:101D000053FEB6F5A07F07F10107F3D104F13203CA +:101D100008223146284601F047FE002704F1330A25 +:101D200094F832304FEAC7099F4209F5A47615D3DB +:101D3000B8F1000F08D1314604F5997307222846FF +:101D400001F032FE09F24F16274694F832213B1B70 +:101D500093420CD3F01DC008BDE8F0870AEB0703DF +:101D600008223146284601F01FFE0137D8E707F266 +:101D7000331331460822284601F016FE0836013793 +:101D8000E3E7000013B5044608460021016023463E +:101D9000C0F803102022019001F006FE0198231DD7 +:101DA0000222202101F000FE0198631D032222215E +:101DB00001F0FAFD0198A31D0322252101F0F4FD95 +:101DC000019804F108031022282101F0EDFD0720FD +:101DD00002B010BDF7B50023047F00910E46072224 +:101DE0001946054601F0A4FC731C00930122002350 +:101DF0000721284601F09CFCC4B9B31C00930522BE +:101E000023460821284601F093FC0D243746B2787A +:101E1000BB1B934211D32B7FA88A0734E408BBB9BC +:101E2000844294BF0020012003B0F0BDAB8ADB00E8 +:101E3000083BDB08B3700824E8E7FB1C009321464D +:101E400000230822284601F073FC08340137DEE73E +:101E5000201A18BF0120E7E7F7B50023047F00919F +:101E60000E4608221946054601F062FC731CC4B9EF +:101E70000822009311462346284601F059FC1024FD +:101E8000012372785F1C013B934211D32B7FA88AF8 +:101E90000734E408BBB9844294BF0020012003B09A +:101EA000F0BDAB8ADB00083BDB0873700824E7E772 +:101EB000F3190093214600230822284601F038FC3C +:101EC00008343B46DDE7201A18BF0120E7E7000091 +:101ED000F8B50E4605461446002181223046FFF72C +:101EE0002BFE2B4608220021304601F05DFD7CB917 +:101EF0006B1C07220821304601F056FD0F240123F8 +:101F00006A785F1C013B934204D3E01DC008F8BD12 +:101F10000824F4E7EB1921460822304601F044FD7D +:101F200008343B46ECE70000F8B50E46054614467B +:101F30000021CE223046FFF7FFFD2B46282200214C +:101F4000304601F031FD7CB905F108030822282153 +:101F5000304601F029FD30242F462A7A7B1B93421C +:101F600004D3E01DC008F8BD2824F5E707F10903F4 +:101F700021460822304601F017FD08340137ECE70E +:101F8000F7B5047F00910E4601231022002105467B +:101F900001F0CEFBC4B9B31C0093092223461021E3 +:101FA000284601F0C5FB192437467288BB1B9A42AC +:101FB00011D82B7FA88A0734E408BBB9844294BFA8 +:101FC0000020012003B0F0BDAB8ADB00103BDB0832 +:101FD00073801024E8E73B1D00932146002308226C +:101FE000284601F0A5FB08340137DEE7201A18BFA8 +:101FF0000120E7E730B5094D0A4491420DD011F8B0 +:10200000013B5840082340F30004013B2C4013F0EF +:10201000FF0384EA5000F6D1EFE730BD2083B8ED2E +:10202000F7B54FF0FF33DFF854C0DFF854E000EBB2 +:1020300081011A4688421CD050F8044B019401AF2C +:10204000042417F8015B82EA05620825DB181646AE +:1020500005F1FF355241002EBCBF83EA0C0382EA32 +:102060000E0215F0FF05F1D1013C14F0FF04E8D198 +:10207000E0E7D843D14303B0F0BD00BF9336EAA9EF +:10208000EBE1F042F7B5384A106851686B4603C37C +:102090006A4636493648082304F060FB04460028A7 +:1020A00033D10A25334A106851686B4603C36A4628 +:1020B00031492F48082304F051FB0446002849D039 +:1020C0000369B3F5702F45D8B0F8661040F2F632C8 +:1020D00091423FD1294A024402F15C018B4239D33B +:1020E0005C3B234900209E1AFFF784FF32460746D7 +:1020F00004F164010020FFF77DFFA3689F4229D10E +:10210000E368984208BF002524E00369B3F5702F07 +:1021100027D8418B40F2F632914220D1174A02442F +:1021200002F110018B4218D3103B114900209D1A77 +:10213000FFF760FF2A46064604F118010020FFF76A +:1021400059FFA3689E4202D1E368984201D00D2551 +:10215000A8E70025284603B0F0BD1025A2E70C250E +:10216000A0E70B259EE700BFBC680008DCFF0E005F +:1021700000000108C568000890FF0E000800FFF786 +:1021800010B5037C044613B9006804F0CFFA20466A +:1021900010BD00000023BFF35B8FC360BFF35B8FF4 +:1021A000BFF35B8F8360BFF35B8F7047BFF35B8FC1 +:1021B0000068BFF35B8F704770B505460C30FFF7C2 +:1021C000F5FF05F1080604463046FFF7EFFFA04291 +:1021D00006D930466D68FFF7E9FF2544281A70BD1F +:1021E0003046FFF7E3FF201AF9E7000070B5054617 +:1021F000406898B105F10800FFF7D8FF05F10C061B +:1022000004463046FFF7D2FF8442304694BF6D68E3 +:102210000025FFF7CBFF013C2C44201A70BD0000C5 +:1022200038B50C460546FFF7C7FFA04210D305F1AD +:102230000800FFF7BBFF04446868B4FBF0F100FB43 +:102240001144BFF35B8F0120AC60BFF35B8F38BDDF +:102250000020FCE72DE9F041144607460D46FFF744 +:10226000C5FF844228BF0446D4B1B84658F80C6B69 +:102270004046FFF79BFF3044286040467E68FFF7EA +:1022800095FF331A9C4203D86C600120BDE8F081B1 +:102290006B60A41B3B68AB602044E8600220F5E75C +:1022A0002046F3E738B50C460546FFF79FFFA042EE +:1022B00010D305F10C00FFF779FF04446868B4FB04 +:1022C000F0F100FB1144BFF35B8F0120EC60BFF322 +:1022D0005B8F38BD0020FCE72DE9FF418846694649 +:1022E0000746FFF7B7FF6C4606B204EBC6060025AB +:1022F000B44209D06268206808EB0501FFF7F6FBDD +:10230000636808341D44F3E729463846FFF7CAFFDF +:10231000284604B0BDE8F081F8B505460C300F46FC +:10232000FFF744FF05F1080604463046FFF73EFF7D +:10233000A042304688BF6C68FFF738FF201A38602B +:1023400020B130462C68FFF731FF2044F8BD000073 +:1023500073B5144606460D46FFF72EFF844228BF8C +:1023600004460190DCB101A93046FFF7D5FF019B7F +:1023700033B93268C5E90233C5E9002401200CE015 +:102380009C4238BF01942860019868608442F5D966 +:102390003368AB60241AEC60022002B070BD2046A6 +:1023A000FBE700002DE9FF410F466946FFF7D0FF2C +:1023B0006C4600B204EBC0050026AC4209D0D4F84C +:1023C000048054F8081BB8194246FFF78FFB4644B7 +:1023D000F3E7304604B0BDE8F081000038B50546AB +:1023E000FFF7E0FF044601462846FFF719FF2046A5 +:1023F00038BD0000302383F3118862B670470000B7 +:10240000002383F3118862B67047000010B402689D +:1024100054681A4623465DF8044B1847012070475C +:102420000020704700207047704700000020704770 +:102430000E20704700F5805090F8C800C0F34000AF +:102440007047000000F5805090F9C9007047000007 +:10245000F7B50C68BDF8207014F000541E466FD11B +:102460000B7B082B6CD8FFF7C5FF4569AB685B0198 +:102470000CD4AB681B0108D4AC6814F080545DD157 +:10248000FFF7BEFF204603B0F0BD01240B6804F146 +:10249000180C002BB8BFDB004FEA0C1CB4BF43F094 +:1024A00004035B0545F80C300B680FFA84FC13F04D +:1024B000804F18BF05EB0C1E05EB0C1C1EBFDEF891 +:1024C000803143F00203CEF880310B7BCCF88431AD +:1024D00005EB04158B68C5F88C314B68C5F888315D +:1024E000DCF8803143F00103CCF8803100EB441577 +:1024F00041F268031D4403EB44130344C5E900267D +:1025000008330D4601F10C0C55F804EB43F804EBCD +:102510006545F9D184342D881D8000EB441407F003 +:102520000303257925F00B052B432371FFF768FF83 +:102530000097334600F0E2FC0120A4E70224A5E75F +:102540004FF0FF309FE7000013B500F58054019174 +:10255000E06DFFF74BFE1F280AD90199E06D20229C +:10256000FFF7BAFEA0F120035842584102B010BD57 +:102570000020FBE708B500F58050FFF73BFFC06D7A +:10258000FFF708FEBDE80840FFF73ABF00220260EF +:10259000828142608260704710B500220023C0E94A +:1025A00000230023044603810C30FFF7EFFF204691 +:1025B00010BD0000F0B5054600F580500C4690F8BF +:1025C000C83013F0040FC3F3800108BF114661F354 +:1025D000820304F1840680F8C83005EB461389B005 +:1025E0001B79D8072ED57AB319072DD46846FFF783 +:1025F000D3FF05EB441303F5835303F1180703AA34 +:10260000103318685968144603C40833BB42224685 +:10261000F7D1186820609B88A380DDE90E23CDE9FF +:1026200000230123ADF808302B686946DB6B284690 +:10263000984705EB46152B791A075CBF43F0080352 +:102640002B7101E0002AF4D109B0F0BD2DE9F0476B +:10265000074688B007F5805468469A468846FFF7D3 +:10266000C9FE9146FFF798FFE06DFFF7A5FD1F2813 +:1026700029D9E06D20226946FFF7B0FE202822D13B +:1026800003AD444605AB2E4603CE9E4220606160FA +:10269000354604F10804F6D130682060B388A38081 +:1026A000DDE90023C9E90023BDF80830AAF80030AD +:1026B000FFF7A6FE4A4653464146384608B0BDE8F5 +:1026C000F04700F009BCFFF79BFE002008B0BDE812 +:1026D000F08700002DE9F84F0023C0E90133254BB6 +:1026E000044640F8183B0F46FFF750FF04F128005E +:1026F000FFF752FF04F1480804F5825546460835B5 +:1027000030462036FFF748FFAE42F9D104F5805538 +:102710004FF480534FF00009C5E91339C5F84880DC +:102720000123EE6504F5875804F58456C5F85490E6 +:1027300085F8583085F86030083608F108084FF001 +:10274000000A4FF0000B46E908ABA6F11800FFF7AE +:102750001DFF203646F8289C4645F4D185F8C970FF +:1027600017B1054800F0A2FB044B63612046BDE8A9 +:10277000F88F00BFF8680008D068000800640040C7 +:1027800010B5044B197804464A1C1A70FFF7A2FFD3 +:10279000204610BD5C4B00202DE9F047002950D0A9 +:1027A000294B2A4FB7FBF1F599428CBF0A2311231D +:1027B000581EB5FBF3FC03FB1C53C4B22BB102281B +:1027C0000346F5D80020BDE8F0870CF1FF36B6F5DA +:1027D000806FF7D2C4EBC40E0EF103034FEAE30996 +:1027E000C3F3C703A4EB030809F1010A4FF47A7598 +:1027F0005FFA88F009FB05555AFA88F8B5FBF8F539 +:10280000B5F5617FC1BF0EF1FF33C3F3C703E01A13 +:10281000C0B25C1C50FA84F40CFB04F4B7FBF4F473 +:10282000A142CFD1013BDBB20F2BCBD80138C0B2D4 +:102830000728C7D80021107116809170D37001202D +:10284000C1E70846BFE700BF3F420F0080DE8002BD +:1028500070B505460E464FF47A746B695B6803F0F9 +:102860000103B34207D04FF47A7002F0D5F8013C6F +:10287000F3D1204670BD0120FCE7000030B542696D +:10288000936913F0700F16D000230B4C936103F182 +:10289000840200EB421211794D0709D5890707D54B +:1028A000416954F823508D60117941F00401117190 +:1028B0000133032BEBD130BDE468000873B51D462E +:1028C000436916469A68D207044609D59A680121D9 +:1028D0009960C2F34002CDE900650021FFF76AFE6E +:1028E00063699A68D1050BD59A684FF48071996035 +:1028F000C2F34022CDE9006501212046FFF75AFED0 +:1029000063699A68D2030BD59A684FF48031996055 +:10291000C2F34042CDE9006502212046FFF74AFE9E +:10292000204602B0BDE87040FFF7A8BFF8B50446E6 +:10293000466900296CD106F10C07386880076AD017 +:1029400006EB01153868D5F8B00110F0040FD5F882 +:10295000B0011ABFC00840F00040400DA061D5F89A +:10296000B0C11CF0020F1CBF40F08040A061D5F840 +:10297000B40106EB011100F00F0084F82400D1F837 +:10298000B8012077D1F8B801000A6077D1F8B80112 +:10299000000CA077D1F8B801000EE077D1F8BC01A7 +:1029A00084F82000D1F8BC01000A84F82100D1F895 +:1029B000BC01000C84F82200D1F8BC11090E84F887 +:1029C00023103821396004F1340004F1180104F1B6 +:1029D000240551F8046B40F8046BA942F9D1098829 +:1029E0000180C4E90A2321460023238651F8283BAD +:1029F0002046DB6B984704F58052204692F8C83099 +:102A000043F0040382F8C830BDE8F840FFF736BF52 +:102A100006F1100791E7F8BD10B5044600F04EFA34 +:102A200002460B4652EA030102D0013A63F1000369 +:102A30000449086820B12146BDE81040FFF776BF81 +:102A400010BD00BF584B0020F8B500F583511E465D +:102A5000FFF7D0FCDFF844C00831002404F18405FE +:102A600000EB45152B795F070ED4DB060CD5D1E9B9 +:102A700000739742B34107D243695CF824709F60AA +:102A80002B7943F004032B710134032C01F1200155 +:102A9000E4D1BDE8F840FFF7B3BC00BFE46800082C +:102AA00008B5FFF7A7FCFFF7E9FEBDE80840FFF710 +:102AB000A7BC0000F8B543690546986800F0E050EF +:102AC000B0F1E05F0F461FD0E8B1FFF793FC05F5CA +:102AD00083541034002606F1840305EB43131B795D +:102AE0001A0706D50136032E04F12004F3D1012084 +:102AF00007E05B07F6D42146384600F039FA002893 +:102B0000F0D1FFF77DFCF8BD0120FCE700F5805017 +:102B100008B5FFF76FFCC06DFFF74EFBFFF770FCC9 +:102B200043090CBF0120002008BD0000F8B51D4678 +:102B3000002313700F4606461446FFF7E7FF80F0A8 +:102B40000100387025B129463046FFF7B3FF2070E9 +:102B5000F8BD00002DE9B8410C4615461F468046D9 +:102B600000F0ACF90B462178024609B9287850B13B +:102B70004046FFF769FFFFF793FF3B462A46214691 +:102B8000FFF7D4FF0120BDE8B881000010B5FFF7C2 +:102B900031FC174B1A6C42F000721A641A6A42F048 +:102BA00000721A621A6A00F5805422F000721A62EA +:102BB000FFF726FC94F8C830DB0718D4B9B103211D +:102BC0001320FFF717FC01F0C7F90321142001F0CF +:102BD000C3F90321152001F0BFF994F8C83043F080 +:102BE000010384F8C830BDE81040FFF709BC10BDF0 +:102BF000003802402DE9F04700F5805588B095F87F +:102C0000C930012B0446884616467FD8804F57F8B6 +:102C100023200AB947F82300D7F800A0C4F80C8095 +:102C20002674BAF1000F63D095F8C930012B6FD02C +:102C300001212046FFF7AAFFFFF7DCFB626913685A +:102C400023F0020313606269136843F00103136009 +:102C5000636900275F6101212046FFF7D1FBFFF781 +:102C6000F7FD002800F09580E86DFFF793FA04F572 +:102C70008359BA4609F10809202200216846FEF767 +:102C80005BFF02A8FFF782FCCDF818A06A4609EBAB +:102C900007030DF1180E9446BCE80300F4451860D4 +:102CA0005960624603F10803F5D1DCF800001860B2 +:102CB00020379CF804201A71602FDDD195F8C830B8 +:102CC0006FF38203002785F8C8306A4641462046E4 +:102CD000ADF80070ADF802708DF80470FFF75CFD80 +:102CE000636948BB4FF400421A6008B0BDE8F08742 +:102CF00041F2D00003F0DAFC814610B15146FFF7F3 +:102D0000E9FCC7F80090B9F1000F8DD10020ECE785 +:102D1000386803681B6B98470146002888D13868DB +:102D2000FFF734FF3868036832465B6841469847CE +:102D300000287FF47DAFE9E761221A609DF8023038 +:102D40009DF803201B06120402F4702203F0407366 +:102D50001343BDF80020C2F3090213439DF8042079 +:102D60001205022E02F4E0020CBF4FF000410021D8 +:102D7000134362690B43D361636913225A61626929 +:102D8000136823F00103136039462046FFF760FD06 +:102D900008B96369A6E795F8C93093BB6169D1F8B2 +:102DA000002242F00102C1F800226169D1F800223C +:102DB00022F47C5222F00E02C1F800226169D1F89F +:102DC000002242F46062C1F800226269C2F8143243 +:102DD0006269C2F80432626941F6FF71C2F80C12EE +:102DE0006269C2F840326269C2F844326369012202 +:102DF000C3F81C226269D2F8003223F00103C2F842 +:102E0000003295F8C83043F0020385F8C8306CE70B +:102E1000584B002008B500F051F850EA0103024673 +:102E200002D0421E61F10001044B186810B10B463C +:102E3000FFF744FDBDE8084001F064B8584B00209E +:102E400008B50020FFF7E8FDBDE8084001F05AB8DA +:102E500008B50120FFF7E0FDBDE8084001F052B8D9 +:102E600000B59BB0EFF3098168226846FEF73EFE8D +:102E7000EFF30583014B9B6BFEE700BF00ED00E025 +:102E800008B5FFF7EDFF000000B59BB0EFF3098137 +:102E900068226846FEF72AFEEFF30583014B5B6B61 +:102EA000FEE700BF00ED00E0FEE700000FB408B54C +:102EB000029801F03DFDFEE702F0D2B902F0AAB996 +:102EC00013B56C4684E80600031D94E8030083E80C +:102ED0000500012002B010BD73B58568019155B1A0 +:102EE0001B885B0707D4D0E900369B6B9847019A93 +:102EF000C1B23046A847012002B070BDF0B5866867 +:102F000089B005460C465EB1BDF838305B070AD47F +:102F1000D0E900379B6B98472246C1B23846B0478C +:102F2000012009B0F0BD00220023CDE900230023D9 +:102F3000ADF808300A4603AB01F108061068516885 +:102F40001C4603C40832B2422346F7D11068206001 +:102F50009288A280FFF7B2FF0423ADF808302B68F7 +:102F6000CDE90001DB6B694628469847D8E70000A9 +:102F700030B503680968DD0FB5EBD17F23F06044FD +:102F800021F060424FEAD1700BD0002BB8BFA40CE7 +:102F90000029B8BF920C944202D034BF0120002017 +:102FA00030BD944205D1C1F38070C3F38073834276 +:102FB000F6D194422CBF00200120F1E72DE9F04129 +:102FC000456A15B94162BDE8F0814B6823F060475E +:102FD000C3F38A464FEAD37EC3F3807816EA23060A +:102FE00038BF3E46AC462B465A68BEEBD27F22F035 +:102FF00060440AD0002A18DAA40CB44217D19D42CA +:103000000FD10D60DEE71346EEE7A74207D102F0CD +:103010008044C2F3807242450BD054B1EFE708D22E +:10302000EDE7CCF800100B60CDE7B44201D0B4421C +:10303000E5D81A689C46002AE5D11960C3E700006C +:103040002DE9F047089D01F007044FEAD508224416 +:1030500005F0070500EBD1004FF47F49944201D100 +:10306000BDE8F08704F0070705F0070A57453E461C +:1030700038BF5646C6F10806111B8E4228BF0E46C1 +:10308000E10808EBD50E415C13F80EC0B94029FAEF +:1030900006F721FA0AF1FFB28CEA010147FA0AF7B2 +:1030A00039408CEA010C03F80EC034443544D5E7AE +:1030B00080EA0120082341F2210201B240000029E8 +:1030C00080B203F1FF33B8BF504013F0FF03F4D1D7 +:1030D0007047000038B50C468D18A54200D138BDA8 +:1030E00014F8011BFFF7E4FFF7E7000042684AB15C +:1030F000136843604389818901339BB299424381BC +:1031000038BF83811046704770B588B020220446CE +:103110000D4668460021FEF70FFD20460495FFF797 +:10312000E5FF024658B16B46054608AE1C4603CC87 +:10313000B44228606960234605F10805F6D11046BF +:1031400008B070BD082817D909280CD00A280CD05F +:103150000B280CD00C280CD00D280CD00E2814BF36 +:103160004020302070470C207047102070471420FA +:10317000704718207047202070470000082817D992 +:103180000C280CD910280CD914280CD918280CD9C3 +:1031900020280CD930288CBF0F200E207047092022 +:1031A00070470A2070470B2070470C2070470D2095 +:1031B000704700002DE9F843078C072F04461ED9FD +:1031C000D0E9029800254FF6FF73C5F12006A5F15E +:1031D000200029FA05F108FA06F628FA00F0314332 +:1031E0000143C9B21846FFF763FF0835402D034677 +:1031F000EBD1E1693A46BDE8F843FFF76BBF4FF604 +:10320000FF70BDE8F883000010B54B6823B9CA8A87 +:1032100063F30902CA8210BD04691A681C60036165 +:10322000C38A013BC3824A60EFE700002DE9F84FF3 +:103230001D46CB8A0F46C3F30901052981469246F4 +:103240000B4630D00020AAB207F11A049EB2042E19 +:103250001FFA80F80FD8904503F1010306D3FB8ACB +:103260000A4462F30903FB8201201AE01AF80060A5 +:10327000E6540130EAE79045F1D2A1F1050B1C2399 +:103280007C68BBFBF3F203FB12BB1FFA8BF6002C2E +:1032900045D14846FFF72AFF044638B978606FF0F9 +:1032A0000200BDE8F88F4FF00008E6E70026066050 +:1032B0007860ADB24FF0000B454510D90AEB08031A +:1032C000221D13F8011B9155B1B208F101081B2909 +:1032D0001FFA88F82BD0454506F10106F1D8FB8A84 +:1032E000C3F30902154465F30903BCE7013292B246 +:1032F0001C462368002BF9D16B1F0B441C21B3FB28 +:10330000F1F301339BB29A42D3D2BBF1000FD0D17B +:103310004846FFF7EBFE20B9C4F800B0BFE7012232 +:10332000E7E7C0F800B05E4620600446C1E74545C7 +:10333000D5D94846FFF7DAFE08B92060AFE7C0F8F4 +:1033400000B0002620600446B6E700002DE9F04FEB +:103350002DED028B1C4683B05B69019207468846BF +:10336000002B00F09A80238C2BB1E269002A00F038 +:103370009480072B35D807F10C00FFF7B7FE054600 +:1033800038B96FF00205284603B0BDEC028BBDE8EA +:10339000F08F14220021FEF7CFFB228CE16905F1AA +:1033A0000800FEF7A3FB208C013080B2FFF7E6FE99 +:1033B000FFF7C8FE013880B22084013028746369A9 +:1033C000228C1B782A4403F01F0363F03F0348F06C +:1033D00000411372384669602946FFF7EFFD012569 +:1033E000D1E700F10C034FF0000908EE103A4FF05E +:1033F000800A4E464D4618EE100AFFF777FE8346C8 +:103400000028BED014220021FEF796FB002E3AD1F0 +:10341000019BABF8083002220BF1080E1FFA82FC68 +:103420000CF10100BCF1060F218C80B201D88E4254 +:103430002BD3FFF7A3FEFFF785FE626912780138F0 +:1034400002F01F028E4208BF4FF0400A42EA4912C2 +:103450001BFA80F14AEA020A013048F0004281F882 +:1034600008A08BF81000CBF8042059463846FFF727 +:10347000A5FD238C0135B3422DB289F001094FF02F +:10348000000AB8D17FE70022C6E7E169895D0EF83E +:1034900002100136B6B20132C0E76FF0010572E7E3 +:1034A000F8B515460E463022002104461F46FEF7A9 +:1034B00043FB069B6360B5F5001F079BA76034BF05 +:1034C0006A094FF6FF72A36297B2E66104F1100039 +:1034D00000239A4206D800230360A782E382238355 +:1034E000E360F8BD0660013330462036F1E70000A6 +:1034F00003781BB94BB2002BC8BF017070470000A6 +:1035000000787047F8B50C46C969074611B9238C95 +:10351000002B37D1257E1F2D34D8387828BB228C3C +:10352000072A2CD8268A36F003032BD14FF6FF70DA +:10353000FFF7D0FD20F001003102400441EA0561AF +:10354000400C41EA40254FF6FF7223462946384693 +:10355000FFF7FCFE002807DD626913780133DBB258 +:103560001F2B88BF00231370F8BD218A2D0645EA62 +:10357000012505432046FFF71DFE0246E5E76FF0F3 +:103580000300F1E76FF00100EEE7000070B58AB0CC +:10359000044616460021282268461D46FEF7CCFA4E +:1035A000BDF83830ADF810300F9B05939DF84030D2 +:1035B0008DF81830119B07936946BDF84830ADF877 +:1035C00020302046CDE90265FFF79CFF0AB070BDB0 +:1035D0002DE9F041D36905460C4616460BB9138C0C +:1035E0005BBB377E1F2F28D895F80080B8F1000FFD +:1035F00026D03046FFF7DEFD3378210241EAC331A1 +:1036000041EA0801338A41EA076141EA034102467F +:10361000334641F080012846FFF798FE00280ADD76 +:103620003378012B07D1726913780133DBB21F2B7A +:1036300088BF00231370BDE8F0816FF00100FAE746 +:103640006FF00300F7E70000F0B58BB004460D46BD +:1036500017460021282268461E46FEF76DFA9DF89F +:103660004C305A1E534253418DF800309DF8403083 +:10367000ADF81030119B05939DF848308DF8183047 +:10368000149B07936A46BDF85430ADF820302946A4 +:103690002046CDE90276FFF79BFF0BB0F0BD00009E +:1036A000406A00B104307047436A1A684262026996 +:1036B0001A600361C38A013BC38270472DE9F04160 +:1036C000D0F82080194E14461D464146002709B9FE +:1036D000BDE8F081D1E90223A21A65EB030396420B +:1036E00077EB03031ED2036A8B420DD1FFF78CFDEB +:1036F000036A1B68036203690B60C38A0161016A84 +:10370000013BC3828846E2E7FFF77EFD0B68C8F8FD +:10371000003003690B60C38A0161013BC382D8F8A2 +:103720000010D4E788460968D1E700BF80841E00F6 +:103730002DE9F04F8BB00D46DDF8509014469B46B6 +:103740008046002800F01981B9F1000F00F01581C2 +:10375000531E3F2B00F21181012A03D1BBF1000F50 +:1037600040F00B810023CDE90833B8F81430B5EBF5 +:10377000C30F4FEAC30703D300200BB0BDE8F08F9F +:103780002B199F42D8F80C303ABF7F1BFFB2274657 +:103790001BB9D8F81030002B7AD0272D4ED8C5F1A0 +:1037A0002806B7424FF000032CBFF6B23E46009306 +:1037B0002946D8F8080008AB3246FFF741FCA7EBD2 +:1037C000060A35445FFA8AFAB8F8143003F1005358 +:1037D000053BDB000493D8F80C3003932821039BAE +:1037E00013B1BAF1000F2CD1D8F8100040B1BAF1E2 +:1037F000000F05D0009608AB5246691AFFF720FC6F +:1038000038B2002FB8D066070AD00AAB03EBD40158 +:10381000624211F8083C02F00702134101F8083C2B +:10382000082C3CD9102C40F2B580202C40F2B780F7 +:10383000BBF1000F00F09C80082334E0BA4600265C +:10384000C2E7049BE02B28BFE02306930B44AB4266 +:10385000059314D95A1B03980096924534BF5246DB +:10386000D2B2691A08AB04300792FFF7E9FB079A56 +:103870001644AAEB020A1544F6B25FFA8AFA049BD0 +:10388000069A05999B1A0493039B1B680393A6E76A +:103890000093D8F8080008AB3A462946AEE7BBF1DA +:1038A000000F13D00123B4EBC30F6CD0082C12D837 +:1038B0009DF82030621E23FA02F2D50706D54FF09C +:1038C000FF3202FA04F423438DF820309DF82030B3 +:1038D00089F8003051E7102C12D8BDF82030621E54 +:1038E00023FA02F2D10706D54FF0FF3202FA04F4B0 +:1038F0002343ADF82030BDF82030A9F800303CE774 +:10390000202C0FD80899631E21FA03F3DA0705D596 +:103910004FF0FF3202FA04F40C430894089BC9F8F4 +:1039200000302AE7402C2BD0DDE90865611EC4F188 +:103930002102A4F1210326FA01F105FA02F225FA87 +:1039400003F311431943CB0712D50122A4F120033D +:10395000C4F1200102FA03F322FA01F1A24052421B +:1039600043EA010363EB430332432B43CDE90823CE +:10397000DDE90823C9E90023FFE66FF00100FCE65A +:103980006FF00800F9E6082CA0D9102CB3D9202C30 +:10399000EED8C3E7BBF1000FADD0022383E7BBF144 +:1039A000000FBBD004237EE730B5012A144638BF90 +:1039B0000124402C85B028BF40240025012ACDE9F0 +:1039C000025518D81B788DF8083063070AD004AB6D +:1039D00003EBD405624215F8083C02F0070293405D +:1039E00005F8083C009103462246002102A8FFF793 +:1039F00027FB05B030BD082AE4D9102A03D81B885C +:103A0000ADF80830E1E7202A8DBFD3E900231B6819 +:103A10000293CDE90223D8E710B5CB681BB98B60C0 +:103A20000B618B8210BD04691A681C600361C38A34 +:103A3000013BC382CA60F0E703064CBFC0F3C0304D +:103A40000220704708B50246FFF7F6FF022806D1AC +:103A50005306C2F30F2001D100F0030008BDC2F3EA +:103A60000740FBE72DE9F04F93B0CDE903230A6847 +:103A700004461046FFF7E0FF022814BFC2F30626F3 +:103A80000026002A0D46824680F2F28112F0C049DB +:103A900040F0EE81097B002900F0EA81022803D082 +:103AA0002378B34240F0E781C2F3046306931046E3 +:103AB00002F07F030593FFF7C5FF059B29444FEAFA +:103AC000834848EA0A4848EA4668CE78002300223C +:103AD000CDE90823F309834648EA0008029367D03A +:103AE000059B009302466768534608A92046B847DD +:103AF000002800F0C381276A4FB9414604F10C0049 +:103B0000FFF702FB074690B96FF0020054E03B69F3 +:103B100098450DD03F68002FF9D1414604F10C00C3 +:103B2000FFF7F2FA07460028EED0236A3B602762CF +:103B300097F817C006F01F08CCF3840CACEB080014 +:103B40001FFA80FE0028B8BF0EF12000A8EB0C037E +:103B50001FFA83FED7E90221B8BF00B2002B0793FA +:103B6000BEBF0EF120031BB2079352EA010338D007 +:103B7000039BDFF824E39A1A049B4FF0000C63EBDD +:103B8000010196457CEB01032BD36B7B97F81AE080 +:103B9000734519D1029B002B78D0012821DC78686D +:103BA000F8B9DFF8F0C2944570EB010316D337E0A3 +:103BB000276A27B96FF00C0013B0BDE8F08F3B699E +:103BC0009845B5D03F68F4E7B24890427CEB0103DA +:103BD00001D30020F0E7029B002BFAD0079B0F2BAC +:103BE00017DCFA7DB30002F0030203F07C031343F9 +:103BF000FB7539462046FFF707FB6B7BBB76029BC4 +:103C00003BB9FB7DC3F38402013262F38603FB758B +:103C1000D0E76A7BBB7E9A42DBD1029B002B35D07A +:103C2000B309022B32D0039BBB60049BFB601422C0 +:103C300000210DA8FDF780FF039B0A93049B0B93C3 +:103C40002B1D0C932B7BADF83EB0013BDBB2ADF8E6 +:103C50003C30069B8DF84230059B8DF8433094F83C +:103C60002C308DF840A083F001038DF844308DF89E +:103C70004180A3680AA920469847FB7DC3F38403CB +:103C8000013303F01F039B02FB82A2E7FB7DC6F317 +:103C90004012B2EBD31F40F0F480C3F384034345DA +:103CA00040F0F280029A2B7BB609002A4DD0F20731 +:103CB0005DD4032B40F2EB80039BBB60049BFB6055 +:103CC0002B7BAE1D033BDBB23246394604F10C00C0 +:103CD000FFF7ACFA00280CDA39462046FFF794FAD1 +:103CE000FB7DC3F38403013303F01F039B02FB82BC +:103CF0000AE7DDE90884AB883B834FF6FF73C9F11F +:103D00002000A9F1200228FA09F104FA00F0014389 +:103D100024FA02F211431846C9B2FFF7C9F909F1B2 +:103D20000809B9F1400F0346E9D1B8822A7B033A6A +:103D3000D2B23146FFF7CEF9FB7DB882DA43C2F347 +:103D4000C01262F3C713FB7543E786B92E1D013B12 +:103D5000DBB23246394604F10C00FFF767FA00285F +:103D6000BADB2A7BB88A013AD2B23146E2E7F98A55 +:103D7000C1F30901013B0429DAB25BD8281D0023F5 +:103D800007F11B069A4208D910F801CB06F801C0CA +:103D9000013101330529DBB2F4D103990A91049969 +:103DA0000B91934207F11B010C9138BF04337968E2 +:103DB0000D9134BF55FA83F300230E93FB8AADF8BF +:103DC0003EB0C3F309031A44069B8DF84230059BAD +:103DD0008DF8433094F82C30ADF83C2083F001038B +:103DE0008DF8443000238DF840A08DF841807B6031 +:103DF0002A7BB88A013A291DFFF76CF93B8BB88200 +:103E0000834203D1A3680AA92046984720460AA9FD +:103E1000FFF702FEFB7DBA8AC3F38403013303F08C +:103E20001F039B02FB823B8B9A420CBF00206FF06A +:103E30001000C1E67B68002BAFD0052001E01C30EC +:103E400033461E68002EFAD1091A081D2E1D18448B +:103E500001EB090CBCF11B0F5FFA89F39DD89A4264 +:103E60009BD916F8013B00F8013B09F10109EFE786 +:103E70006FF00900A0E66FF00A009DE66FF00B00FE +:103E80009AE66FF00D0097E66FF00E0094E66FF083 +:103E90000F0091E640420F0080841E00EFF309837B +:103EA00005494A6B22F001024A63683383F30988AB +:103EB000002383F31188704700EF00E0302080F387 +:103EC000118862B60C4B0D4AD96821F4E0610904EF +:103ED000090C0A43DA60D3F8FC20094942F08072E9 +:103EE000C3F8FC200A6842F001020A602022DA7757 +:103EF00083F82200704700BF00ED00E00003FA05E0 +:103F0000001000E010B5302383F311880E4B5B687E +:103F100013F4006314D0F1EE103AEFF30984683C17 +:103F20004FF08073E361094BDB6B236684F30988F0 +:103F300000F0BCFC10B1064BA36110BD054BFBE7C4 +:103F400083F31188F9E700BF00ED00E000EF00E027 +:103F5000430600084606000800F1604303F561438C +:103F60000901C9B283F80013012200F01F039A402F +:103F700043099B0003F1604303F56143C3F88021CB +:103F80001A607047026843681143016003B1184723 +:103F90007047000013B5446BD4F894341A68117854 +:103FA000042915D1217C022912D119791289012302 +:103FB0008B4013420CD101A904F14C0001F0BAFF6F +:103FC000D4F89444019B21790246206800F0D0F98E +:103FD00002B010BD143001F03DBF00004FF0FF33C0 +:103FE000143001F037BF00004C3002F00FB8000071 +:103FF0004FF0FF334C3002F009B80000143001F0EC +:104000000BBF00004FF0FF31143001F005BF00007E +:104010004C3001F0DBBF00004FF0FF324C3001F0BC +:10402000D5BF00000020704710B5D0F894341A684E +:1040300011780429044617D1017C022914D1597939 +:10404000528901238B4013420ED1143001F09EFEA1 +:10405000024648B1D4F894444FF4807361792068E3 +:10406000BDE8104000F072B910BD0000406BFFF7D2 +:10407000DBBF0000704700007FB5124B03600023D8 +:104080004360C0E90233012502260F4B0574044644 +:104090000290019300F18402294600964FF4807348 +:1040A000143001F04FFE094B0294CDE9006304F592 +:1040B00023724FF48073294604F14C0001F016FF7F +:1040C00004B070BD386900086D400008953F0008D5 +:1040D0000B68302282F311880A7903EB8202906127 +:1040E0004A79093243F822008A7912B103EB82033C +:1040F00098610223C0F894140374002080F311889F +:104100007047000038B5037F044613B190F854306F +:10411000ABB9201D01250221FFF734FF04F1140083 +:1041200025776FF0010100F09FFC84F8545004F1F2 +:104130004C006FF00101BDE8384000F095BC38BD7F +:1041400010B5012104460430FFF71CFF002323773C +:1041500084F8543010BD000038B5044600251430F2 +:1041600001F008FE04F14C00257701F0D7FE201D78 +:1041700084F854500121FFF705FF2046BDE8384080 +:10418000FFF752BF90F8443003F06003202B07D1B3 +:1041900090F84520212A4FF0000303D81F2A06D8A3 +:1041A00000207047222AFBD1C0E90E3303E0034A06 +:1041B00082630722C2630364012070471D2300202D +:1041C00037B5D0F894341A681178042904461AD106 +:1041D000017C022917D11979128901238B401342DE +:1041E00011D100F14C05284601F058FF58B101A942 +:1041F000284601F09FFED4F89444019B21790246A1 +:10420000206800F0B5F803B030BD0000F0B500EB59 +:10421000810385B09E6904460D46FEB1302383F3C9 +:10422000118804EB8507301D0821FFF7ABFEFB6802 +:104230005B691B6806F14C001BB1019001F088FE20 +:10424000019803A901F076FE024648B1039B294676 +:10425000204600F08DF8002383F3118805B0F0BDEF +:10426000FB685A691268002AF5D01B8A013B13408B +:10427000F1D104F14402EAE7093138B550F82140A0 +:10428000DCB1302383F31188D4F894241368527975 +:1042900003EB8203DB689B695D6845B1042160180C +:1042A000FFF770FE294604F1140001F079FD204665 +:1042B000FFF7BAFE002383F3118838BD7047000072 +:1042C00001F0EEB8012303700023C0E90133C3619C +:1042D00083620362C36243620363704738B5044676 +:1042E000302383F311880025C0E90355C0E9055543 +:1042F000416001F0E5F80223237085F31188284618 +:1043000038BD000070B500EB810305465069DA60E6 +:104310000E46144618B110220021FDF70DFCA069CD +:1043200018B110220021FDF707FC31462846BDE8F0 +:10433000704001F08FB90000826802F001128260C3 +:104340000022C0E90422826101F010BAF0B400EB4F +:1043500081044789E4680125A4698D403D43458176 +:1043600023600023A2606360F0BC01F02BBA000060 +:10437000F0B400EB81040789E468012564698D408D +:104380003D43058123600023A2606360F0BC01F01F +:10439000A5BA000070B50223002504460370C0E9E9 +:1043A0000255C0E90455C564856180F8345001F0B8 +:1043B000EDF863681B6823B129462046BDE87040CC +:1043C000184770BD0378052B10B504460AD080F855 +:1043D00050300523037043681B680BB104219847D4 +:1043E0000023A36010BD00000178052906D190F8D4 +:1043F0005020436802701B6803B1184770470000E3 +:1044000070B590F83430044613B1002380F834308E +:1044100004F14402204601F0CBF963689B68B3B90C +:1044200094F8443013F0600535D00021204601F0A7 +:104430006BFC0021204601F05DFC63681B6813B132 +:10444000062120469847062384F8343070BD204664 +:1044500098470028E4D0B4F84A30E26B9A4288BF0B +:10446000E36394F94430E56B002B4FF0300380F2A6 +:104470000381002D00F0F280092284F8342083F3B8 +:1044800011880021D4E90E232046FFF771FF002395 +:1044900083F31188DAE794F8452003F07F0343EAB9 +:1044A000022340F20232934200F0C58021D8B3F5D6 +:1044B000807F48D00DD8012B3FD0022B00F0938095 +:1044C000002BB2D104F14C02A2630222E263236406 +:1044D000C1E7B3F5817F00F09B80B3F5407FA4D1A5 +:1044E00094F84630012BA0D1B4F84C3043F00203CD +:1044F00032E0B3F5006F4DD017D8B3F5A06F31D0CF +:10450000A3F5C063012B90D8636894F846205E68D9 +:1045100094F84710B4F848302046B047002884D0BB +:104520004368A3630368E3631AE0B3F5106F36D002 +:1045300040F6024293427FF478AF5C4BA3630223C0 +:10454000E3630023C3E794F84630012B7FF46DAF9B +:10455000B4F84C3023F00203C4E90E55A4F84C30F3 +:10456000256478E7B4F84430B3F5A06F0ED194F821 +:10457000463084F84E30204601F060F863681B68CE +:1045800013B1012120469847032323700023C4E977 +:104590000E339CE704F14F03A3630123C3E72378A1 +:1045A000042B10D1302383F311882046FFF7C4FE7B +:1045B00085F311880321636884F84F5021701B68CC +:1045C0000BB12046984794F84630002BDED084F893 +:1045D0004F300423237063681B68002BD6D0022160 +:1045E00020469847D2E794F848301D0603F00F01A3 +:1045F00020460AD501F0CEF8012804D002287FF425 +:1046000014AF2B4B9AE72B4B98E701F0B5F8F3E783 +:1046100094F84630002B7FF408AF94F8483013F03C +:104620000F01B3D01A06204602D501F081FBADE799 +:1046300001F074FBAAE794F84630002B7FF4F5AE46 +:1046400094F8483013F00F01A0D01B06204602D585 +:1046500001F05AFB9AE701F04DFB97E7142284F82A +:10466000342083F311882B462A4629462046FFF73B +:104670006DFE85F31188E9E65DB1152284F83420DA +:1046800083F311880021D4E90E232046FFF75EFE54 +:10469000FDE60B2284F8342083F311882B462A464A +:1046A00029462046FFF764FEE3E700BF686900087B +:1046B000606900086469000838B590F83430044631 +:1046C000002B3ED0063BDAB20F2A34D80F2B32D85B +:1046D000DFE803F037313108223231313131313105 +:1046E00031313737C56BB0F84A309D4214D2C368B8 +:1046F0001B8AB5FBF3F203FB12556DB9302383F32C +:1047000011882B462A462946FFF732FE85F3118889 +:104710000A2384F834300EE0142384F83430302334 +:1047200083F3118800231A4619462046FFF70EFE30 +:10473000002383F3118838BD036C03B1984700232D +:10474000E7E70021204601F0DFFA0021204601F0D2 +:10475000D1FA63681B6813B10621204698470623E7 +:10476000D7E7000010B590F83430142B044629D058 +:1047700017D8062B05D001D81BB110BD093B022B61 +:10478000FBD80021204601F0BFFA0021204601F0AD +:10479000B1FA63681B6813B10621204698470623C7 +:1047A00019E0152BE9D10B2380F83430302383F343 +:1047B000118800231A461946FFF7DAFD002383F318 +:1047C0001188DAE7C3689B695B68002BD5D1036C5D +:1047D00003B19847002384F83430CEE700230375F3 +:1047E000826803691B6899689142FBD25A6803602A +:1047F0004260106058607047002303758268036947 +:104800001B6899689142FBD85A6803604260106047 +:104810005860704708B50846302383F311880B7D34 +:10482000032B05D0042B0DD02BB983F3118808BDC1 +:104830008B6900221A604FF0FF338361FFF7CEFFD0 +:104840000023F2E7D1E9003213605A60F3E7000079 +:10485000FFF7C4BF054BD9680875186802681A606D +:10486000536001220275D860FBF7D6BE684B00206A +:1048700030B50C4BDD684B1C87B004460FD02B467F +:10488000094A684600F084F92046FFF7E3FF009BE1 +:1048900013B1684600F086F9A86907B030BDFFF78C +:1048A000D9FFF9E7684B002015480008044B1A6847 +:1048B000DB6890689B68984294BF00200120704795 +:1048C000684B0020084B10B51C68D86822681A6035 +:1048D000536001222275DC60FFF78EFF01462046FF +:1048E000BDE81040FBF798BE684B0020044B1A68E7 +:1048F000DB6892689B689A4201D9FFF7E3BF704773 +:10490000684B002038B5074C0749084801230025AB +:104910002370656001F0FAFB0223237085F3118890 +:1049200038BD00BFD04D002070690008684B0020E2 +:1049300008B572B6044B186500F050FC00F00EFD8F +:10494000024B03221A70FEE7684B0020D04D002076 +:1049500000F05EB9EFF3118020B9EFF30583302248 +:1049600082F311887047000010B530B9EFF3058469 +:10497000C4F3080414B180F3118810BDFFF7B6FF2B +:1049800084F31188F9E70000034A516853685B1A01 +:104990009842FBD8704700BF001000E08B600223F4 +:1049A00008618B82084670478368A3F1840243F84C +:1049B000142C026943F8442C426943F8402C094AFC +:1049C00043F8242CC26843F8182C022203F80C2C5C +:1049D000002203F80B2C044A43F8102CA3F120000A +:1049E000704700BF31060008684B002008B5FFF78C +:1049F000DBFFBDE80840FFF72BBF0000024BDB6880 +:104A000098610F20FFF726BF684B0020302383F307 +:104A10001188FFF7F3BF000008B50146302383F388 +:104A200011880820FFF724FF002383F3118808BDB5 +:104A3000064BDB6839B1426818605A601360436006 +:104A40000420FFF715BF4FF0FF307047684B002080 +:104A50000368984206D01A6802605060996118464F +:104A6000FFF7F6BE7047000038B504460D462068D3 +:104A7000844200D138BD036823605C608561FFF724 +:104A8000E7FEF4E710B503689C68A2420CD85C68A6 +:104A90008A600B604C602160596099688A1A9A603C +:104AA0004FF0FF33836010BD1B68121BECE7000062 +:104AB0000A2938BF0A2170B504460D460A26601936 +:104AC00001F01EFB01F00AFB041BA54203D8751C74 +:104AD0002E460446F3E70A2E04D9BDE870400120B3 +:104AE00001F054BB70BD0000F8B5144B0D46D96100 +:104AF00003F1100141600A2A1969826038BF0A2255 +:104B0000016048601861A818144601F0EBFA0A2702 +:104B100001F0E4FA431BA342064606D37C1C281985 +:104B200001F0EEFA27463546F2E70A2F04D9BDE830 +:104B3000F840012001F02ABBF8BD00BF684B0020FF +:104B4000F8B506460D4601F0C9FA0F4A134653F868 +:104B5000107F9F4206D12A4601463046BDE8F84004 +:104B6000FFF7C2BFD169BB68441A2C1928BF2C4675 +:104B7000A34202D92946FFF79BFF2246314603484C +:104B8000BDE8F840FFF77EBF684B0020784B00205F +:104B900010B4C0E9032300235DF8044B4361FFF721 +:104BA000CFBF000010B5194C236998420DD0D0E951 +:104BB0000032816813605A609A680A449A60002340 +:104BC00003604FF0FF33A36110BD2346026843F832 +:104BD000102F53600022026022699A4203D1BDE87F +:104BE000104001F087BA936881680B44936001F02C +:104BF00075FA2269E1699268441AA242E4D9114423 +:104C0000BDE81040091AFFF753BF00BF684B0020F2 +:104C10002DE9F047DFF8BC8008F110072C4ED8F8DA +:104C2000105001F05BFAD8F81C40AA68031B9A42A6 +:104C30003ED81444D5E900324FF00009C8F81C40B2 +:104C400013605A60C5F80090D8F81030B34201D113 +:104C500001F050FA89F31188D5E9033128469847C5 +:104C6000302383F311886B69002BD8D001F036FA1A +:104C70006A69A0EB04094A4582460DD2022001F080 +:104C800085FA0022D8F81030B34208D151462846A0 +:104C9000BDE8F047FFF728BF121A2244F2E712EBF3 +:104CA000090938BF4A4629463846FFF7EBFEB5E703 +:104CB000D8F81030B34208D01444211AC8F81C00A8 +:104CC000A960BDE8F047FFF7F3BEBDE8F08700BF7D +:104CD000784B0020684B002000207047FEE7000062 +:104CE000704700004FF0FF307047000002290CD0E1 +:104CF000032904D00129074818BF00207047032A60 +:104D000005D8054800EBC2007047044870470020F2 +:104D1000704700BF486A00082C230020FC69000887 +:104D200070B59AB00546084601A9144600F0C2F8CD +:104D300001A8FCF7F9FE431C5B00C5E90034002222 +:104D4000237003236370C6B201AB02341046D1B2A4 +:104D50008E4204F1020401D81AB070BD13F8011B91 +:104D600004F8021C04F8010C0132F0E708B5302306 +:104D700083F311880348FFF723FA002383F3118894 +:104D800008BD00BFD84D002090F8443003F01F024A +:104D9000012A07D190F845200B2A03D10023C0E94E +:104DA0000E3315E003F06003202B08D1B0F8483033 +:104DB0002BB990F84520212A03D81F2A04D8FFF7E1 +:104DC000E1B9222AEBD0FAE7034A82630722C263E1 +:104DD00003640120704700BF2423002007B5052984 +:104DE00017D8DFE801F0191603191920302383F3CF +:104DF0001188104A01900121FFF784FA01980E4AA8 +:104E00000221FFF77FFA0D48FFF7A6F9002383F38D +:104E1000118803B05DF804FB302383F31188074841 +:104E2000FFF770F9F2E7302383F311880348FFF7A7 +:104E300087F9EBE79C690008C0690008D84D00209D +:104E400038B50C4D0C4C0D492A4604F10800FFF70B +:104E500067FF05F1CA0204F110000949FFF760FF7E +:104E600005F5CA7204F118000649BDE83840FFF79D +:104E700057BF00BFA05200202C2300207C690008EF +:104E8000866900089169000870B5044608460D4619 +:104E9000FCF74AFEC6B22046013403780BB9184627 +:104EA00070BD32462946FCF72BFE0028F3D10120C5 +:104EB000F6E700002DE9F04705460C46FCF734FE06 +:104EC0002B49C6B22846FFF7DFFF08B10B36F6B212 +:104ED00028492846FFF7D8FF08B11036F6B2632EEE +:104EE0000BD8DFF88C80DFF88C90234FDFF894A08C +:104EF0002E7846B92670BDE8F08729462046BDE8E1 +:104F0000F04701F091BC252E2ED1072241462846BC +:104F1000FCF7F6FD70B9194B224603F1100153F866 +:104F2000040B42F8040B8B42F9D11B881380073520 +:104F30001234DDE7082249462846FCF7E1FD98B91E +:104F40000F4BA21C197809090232C95D02F8041C32 +:104F500013F8011B01F00F015345C95D02F8031C52 +:104F6000F0D118340835C3E704F8016B0135BFE709 +:104F7000686A000891690008706A000846680008BD +:104F8000107AFF1F1C7AFF1FBFF34F8F024AD368AE +:104F9000DB03FCD4704700BF003C024008B5094B5E +:104FA0001B7873B9FFF7F0FF074B1A69002ABFBFE0 +:104FB000064A5A6002F188325A601A6822F4806206 +:104FC0001A6008BDFE540020003C024023016745E2 +:104FD00008B50B4B1B7893B9FFF7D6FF094B1A693D +:104FE00042F000421A611A6842F480521A601A684C +:104FF00022F480521A601A6842F480621A6008BD76 +:10500000FE540020003C02400B28F0B516D80C4C92 +:105010000C4923787BB90C4D0E460C234FF00062EF +:1050200055F8047B46F8042B013B13F0FF033A4488 +:10503000F6D10123237051F82000F0BD0020FCE7D9 +:105040003055002000550020846A0008014B53F8B9 +:1050500020007047846A00080C2070470B2810B5A8 +:10506000044601D9002010BDFFF7CEFF064B53F8D0 +:1050700024301844C21A0BB90120F4E71268013237 +:10508000F0D1043BF6E700BF846A00080B2810B596 +:10509000044621D8FFF778FFFFF780FF0F4AF3237C +:1050A000D360C300DBB243F4007343F00203136127 +:1050B000136943F480331361FFF766FFFFF7A4FF22 +:1050C000074B53F8241000F045F9FFF781FF204605 +:1050D000BDE81040FFF7C2BF002010BD003C0240F9 +:1050E000846A0008F8B512F00103144642D1821810 +:1050F000B2F1016F57D82D4B1B6813F0010352D04A +:105100002B4DFFF74BFFF323EB60FFF73DFF40F222 +:105110000127032C15D824F001046618244C401AEA +:1051200040F20117B142236900EB010524D123F0BD +:1051300001032361FFF74CFF0120F8BD043C04305C +:10514000E7E78307E7D12B6923F440732B612B69D1 +:105150003B432B6151F8046B0660BFF34F8FFFF7A1 +:1051600013FF03689E42E9D02B6923F001032B61F2 +:10517000FFF72EFF0020E0E723F44073236123694B +:105180003B4323610B882B80BFF34F8FFFF7FCFE5F +:105190002D8831F8023BADB2AB42C3D0236923F076 +:1051A00001032361E4E71846C7E700BF0038024067 +:1051B000003C0240084908B50B7828B11BB9FFF73D +:1051C000EDFE01230B7008BD002BFCD0BDE80840AC +:1051D0000870FFF7FDBE00BFFE54002008B54FF475 +:1051E00000314FF0005000F0B7F8BDE808404FF430 +:1051F00080314FF0805000F0AFB8000008461146F3 +:1052000001F076BA012001F073BA0000084601F0FF +:105210008DBA000070B582B0FFF79CFB0E4E0546BC +:1052200000F05CFF3268904237BF0C4A0B4951686E +:1052300014682EBFD1E900410131516004190346C1 +:1052400041F10001284601913360FFF78DFB019980 +:10525000204602B070BD00BF3455002038550020F4 +:1052600070B582B0FFF776FB104E054600F036FFB2 +:105270003268904237BF0E4A0D49516814682EBFFC +:10528000D1E9004101315160041941F100010346A7 +:10529000284601913360FFF767FB01994FF47A725A +:1052A00000232046FAF7A4FF02B070BD3455002059 +:1052B0003855002010B50244064BD2B2904200D1BE +:1052C00010BD441C00B253F8200041F8040BE0B2BA +:1052D000F4E700BF502800400F4B30B51C6F24048A +:1052E00007D41C6F44F400741C671C6F44F4004422 +:1052F0001C670A4C236843F4807323600244084B04 +:10530000D2B2904200D130BD441C00B251F8045BCF +:1053100043F82050E0B2F4E700380240007000404B +:105320005028004007B5012201A90020FFF7C2FF65 +:10533000019803B05DF804FB13B50446FFF7F2FFD4 +:10534000A04205D0012201A900200194FFF7C4FF6B +:1053500002B010BD704700007047000070470000A9 +:10536000074B45F255521A6002225A6040F6FF720E +:105370009A604CF6CC421A60024B01221A707047B8 +:105380000030004044550020034B1B781BB1034BF9 +:105390004AF6AA221A6070474455002000300040A7 +:1053A000034B1A681AB9034AD2F874281A60704776 +:1053B0004055002000300240024B4FF08072C3F88D +:1053C000742870470030024008B5FFF7E9FF024B30 +:1053D0001868C0F3407008BD4055002008B5FFF7BD +:1053E000DFFF024B1868C0F3007008BD4055002075 +:1053F00070470000FEE700000A4B0B480B4A904242 +:105400000BD30B4BDA1C121AC11E22F003028B4283 +:1054100038BF00220021FCF78FBB53F8041B40F873 +:10542000041BECE7A86C00084856002048560020F2 +:105430004856002070B5D0E915439E6800224FF011 +:10544000FF3504EB42135101D3F800090028BEBF19 +:10545000D3F8000940F08040C3F80009D3F8000BEE +:105460000028BEBFD3F8000B40F08040C3F8000B0B +:10547000013263189642C3F80859C3F8085BE0D2BA +:105480004FF00113C4F81C3870BD0000890141F0D1 +:105490002001016103699B06FCD41220FFF774BA56 +:1054A00010B5054C2046FEF70DFF4FF0A043636595 +:1054B000024BA36510BD00BF48550020D86A000804 +:1054C00070B50378012B054650D12A4B446D9842A4 +:1054D0001BD1294B5A6B42F080025A635A6D42F03D +:1054E00080025A655A6D5A6942F080025A615A69BF +:1054F00022F080025A610E2143205B69FEF72CFDE9 +:105500001E4BE3601E4BC4F800380023C4F8003E75 +:10551000C02323606E6D4FF40413A3633369002B23 +:10552000FCDA012333610C20FFF72EFA3369DB0725 +:10553000FCD41220FFF728FA3369002BFCDA00268E +:10554000A6602846FFF776FF6B68C4F81068DB6832 +:10555000C4F81468C4F81C684BB90A4BA3614FF037 +:10556000FF336361A36843F00103A36070BD064B82 +:10557000F4E700BF485500200038024040140040C6 +:1055800003002002003C30C0083C30C0F8B5446D38 +:10559000054600212046FFF779FFA96D00234FF053 +:1055A00001128F68C4F834384FF00066C4F81C2824 +:1055B0004FF0FF3004EB431201339F42C2F8006901 +:1055C000C2F8006BC2F80809C2F8080BF2D20B68E7 +:1055D0006A6DEB65636210231361166916F010069D +:1055E000FBD11220FFF7D0F9D4F8003823F4FE6382 +:1055F000C4F80038A36943F4402343F01003A361C7 +:105600000923C4F81038C4F814380A4BEB604FF083 +:10561000C043C4F8103B084BC4F8003BC4F8106901 +:10562000C4F80039EB6D03F1100243F48013EA650E +:10563000A362F8BDB46A000840800010426D90F883 +:105640004E10D2F8003823F4FE6343EA0113C2F887 +:10565000003870472DE9F84300EB8103456DDA68A7 +:10566000166806F00306731E022B05EB41130C4669 +:1056700080460FFA81F94FEA41104FF00001C3F85C +:10568000101B4FF0010104F1100398BFB60401FA9A +:1056900003F391698EBF334E06F1805606F500463E +:1056A00000293AD0578A04F15801490137436F5015 +:1056B000D5F81C180B43C5F81C382B180021C3F86B +:1056C000101953690127611EA7409BB3138A928B5F +:1056D0009B08012A88BF5343D8F85C20981842EAF7 +:1056E000034301F1400205EB8202C8F85C00214649 +:1056F00053602846FFF7CAFE08EB8900C3681B8A7F +:1057000043EA8453483464011E432E51D5F81C38B3 +:105710001F43C5F81C78BDE8F88305EB4917D7F897 +:10572000001B21F40041C7F8001BD5F81C1821EA22 +:105730000303C0E704F13F0305EB83030A4A5A6001 +:1057400028462146FFF7A2FE05EB4910D0F80039A4 +:1057500023F40043C0F80039D5F81C3823EA0707C2 +:10576000D7E700BF0080001000040002826D1268BD +:10577000C265FFF75FBE00005831436D49015B58B9 +:1057800013F4004004D013F4001F0CBF02200120CA +:10579000704700004831436D49015B5813F40040E5 +:1057A00004D013F4001F0CBF02200120704700003A +:1057B00000EB8101CB68196A0B6813604B6853607A +:1057C0007047000000EB810330B5DD68AA691368FB +:1057D000D36019B9402B84BF402313606B8A1468CF +:1057E000426D1C44013CB4FBF3F46343033323F0E8 +:1057F000030302EB411043EAC44343F0C043C0F843 +:10580000103B2B6803F00303012B09B20ED1D2F831 +:10581000083802EB411013F4807FD0F8003B14BF2E +:1058200043F0805343F00053C0F8003B02EB4112B9 +:10583000D2F8003B43F00443C2F8003B30BD000007 +:105840002DE9F041244D6E6D06EB40130446D3F86C +:10585000087BC3F8087B38070AD5D6F8143819072F +:1058600006D505EB84032146DB6828465B6898472C +:10587000FA071FD5D6F81438DB071BD505EB8403D0 +:10588000D968CCB98B69488A5A68B2FBF0F600FB3C +:1058900016228AB91868DA6890420DD2121AC3E942 +:1058A0000024302383F311880B482146FFF78AFF39 +:1058B00084F31188BDE8F081012303FA04F26B89B7 +:1058C00023EA02036B81CB68002BF3D02146024808 +:1058D000BDE8F041184700BF4855002000EB8103A8 +:1058E00070B5DD68436D6C692668E6604A0156BB99 +:1058F0001A444FF40020C2F810092A6802F003028B +:10590000012A0AB20ED1D3F8080803EB421410F4AE +:10591000807FD4F8000914BF40F0805040F0005060 +:10592000C4F8000903EB4212D2F8000940F0044029 +:10593000C2F80009D3F83408012202FA01F1014348 +:10594000C3F8341870BD19B9402E84BF40202060C0 +:1059500020682E8A8419013CB4FBF6F440EAC44066 +:1059600040F000501A44C6E72DE9F8433B4D6E6DF8 +:1059700006EB40130446D3F80889C3F8088918F0E9 +:10598000010F4FEA40171AD0D6F81038DB0716D5AA +:1059900005EB8003D9684B691868DA68904230D209 +:1059A000121A4FF000091A60C3F80490302383F3F1 +:1059B000118821462846FFF791FF89F3118818F0D6 +:1059C000800F1CD0D6F834380126A640334216D0BA +:1059D00005EB84036D6DD3F80CC0DCF814200134A2 +:1059E000E4B2D2F800E005EB04342F44516871456D +:1059F00015D3D5F8343823EA0606C5F83468BDE86F +:105A0000F883012303FA04F22B8923EA02032B8192 +:105A10008B68002BD3D0214628469847CFE7BCF8A7 +:105A20001000AEEB0103834228BF0346D7F81809E4 +:105A300080B2B3EB800FE2D89068A0F1040959F866 +:105A4000048FC4F80080A0EB09089844B8F1040F53 +:105A5000F5D818440B4490605360C7E748550020C0 +:105A60002DE9F74FA24C656D6E69AB691E4016F4C7 +:105A700080586E6107D02046FEF78CFC03B0BDE86D +:105A8000F04FFEF73FBA002E12DAD5F8003E9848E4 +:105A90009B071EBFD5F8003E23F00303C5F8003E68 +:105AA000D5F8043823F00103C5F80438FEF79CFC50 +:105AB000370505D58E48FFF7BDFC8D48FEF782FC03 +:105AC000B0040CD5D5F8083813F0060FEB6823F4B2 +:105AD00070530CBF43F4105343F4A053EB603107F1 +:105AE0001BD56368DB681BB9AB6923F00803AB61A6 +:105AF0002378052B0CD1D5F8003E7D489A071EBFB0 +:105B0000D5F8003E23F00303C5F8003EFEF76CFC19 +:105B10006368DB680BB176489847F30274D4B70228 +:105B200027D5D4F85490DFF8C8B100274FF0010A08 +:105B300009EB4712D2F8003B03F44023B3F5802F62 +:105B400011D1D2F8003B002B0DDA62890AFA07F373 +:105B500022EA0303638104EB8703DB68DB6813B18C +:105B6000394658469847A36D01379B68FFB29F425C +:105B7000DED9F00617D5676D3A6AC2F30A1002F053 +:105B80000F0302F4F012B2F5802F00F08580B2F519 +:105B9000402F08D104EB83030022DB681B6A07F562 +:105BA000805790426AD13003D5F8184813D5E103E5 +:105BB00002D50020FFF744FEA20302D50120FFF723 +:105BC0003FFE630302D50220FFF73AFE270302D50A +:105BD0000320FFF735FE75037FF550AFE00702D5D0 +:105BE0000020FFF7C1FEA10702D50120FFF7BCFE90 +:105BF000620702D50220FFF7B7FE23077FF53EAF0D +:105C00000320FFF7B1FE39E7636DDFF8E4A00193ED +:105C100000274FF00109A36D9B685FFA87FB9B4546 +:105C20003FF67DAF019B03EB4B13D3F8001901F452 +:105C30004021B1F5802F1FD1D3F8001900291BDABC +:105C4000D3F8001941F09041C3F80019D3F80019B6 +:105C50000029FBDB5946606DFFF718FC218909FA22 +:105C60000BF321EA0303238104EB8B03DB689B68BE +:105C700013B15946504698470137CCE7910708BF02 +:105C8000D7F80080072A98BF03F8018B02F10102C0 +:105C900098BF4FEA182884E7023304EB830207F524 +:105CA00080575268D2F818C0DCF80820DCE9001CE4 +:105CB000A1EB0C0C002188420AD104EB8304636839 +:105CC0009B699A6802449A605A6802445A606AE77B +:105CD00011F0030F08BFD7F800808C4588BF02F889 +:105CE000018B01F1010188BF4FEA1828E3E700BFEB +:105CF00048550020436D03EB4111D1F8003B43F4BC +:105D00000013C1F8003B7047436D03EB4111D1F81C +:105D1000003943F40013C1F800397047436D03EBB9 +:105D20004111D1F8003B23F40013C1F8003B704748 +:105D3000436D03EB4111D1F8003923F40013C1F88E +:105D40000039704730B5039C0172043304FB03250E +:105D5000C0E90653049B03630021059BC160C0E9B1 +:105D60000000C0E90422C0E90842C0E90A11436307 +:105D700030BD0000416A0022C0E90411C0E90A22D6 +:105D8000C2606FF00101FEF76FBE0000D0E904327F +:105D9000934201D1C2680AB9181D704700207047AC +:105DA00003691960C2680132C260C2691344826922 +:105DB0000361934224BF436A03610021FEF748BE9A +:105DC00038B504460D46E3683BB16269131D12689D +:105DD000A3621344E362002007E0237A33B9294623 +:105DE0002046FEF725FE0028EDDA38BD6FF00100F1 +:105DF000FBE70000C368C269013BC3604369134409 +:105E000082694361934224BF436A436100238362F2 +:105E1000036B03B11847704770B53023044683F312 +:105E20001188866A3EB9FFF7CBFF054618B186F3A5 +:105E30001188284670BDA36AE26A13F8015BA36269 +:105E4000934202D32046FFF7D5FF002383F3118846 +:105E5000EFE700002DE9F84F04460E461746984636 +:105E60004FF0300989F311880025AA46D4F828B0EC +:105E7000BBF1000F09D141462046FFF7A1FF20B139 +:105E80008BF311882846BDE8F88FD4E90A12A7EBF6 +:105E9000050B521A934528BF9346BBF1400F1BD9FF +:105EA000334601F1400251F8040B43F8040B9142D0 +:105EB000F9D1A36A40334036A3624035D4E90A23BE +:105EC0009A4202D32046FFF795FF8AF31188BD421C +:105ED000D8D289F31188C9E730465A46FBF706FE47 +:105EE000A36A5B445E44A3625D44E7E710B5029C8D +:105EF0000172043303FB0421C0E906130023C0E947 +:105F00000A33039B0363049BC460C0E90000C0E93B +:105F10000422C0E90842436310BD0000026AC26067 +:105F2000426AC0E904220022C0E90A226FF001019E +:105F3000FEF79ABDD0E904239A4201D1C26822B982 +:105F4000184650F8043B0B60704700231846FAE7E8 +:105F5000C368C2690133C360436913448269436102 +:105F6000934224BF436A43610021FEF771BD0000E4 +:105F700038B504460D46E3683BB123691A1DA26299 +:105F8000E2691344E362002007E0237A33B929462B +:105F90002046FEF74DFD0028EDDA38BD6FF0010018 +:105FA000FBE7000003691960C268013AC260C26978 +:105FB000134482690361934224BF436A036100234F +:105FC0008362036B03B118477047000070B530233C +:105FD0000D460446114683F31188866A2EB9FFF7F1 +:105FE000C7FF10B186F3118870BDA36A1D70A36A44 +:105FF000E26A01339342A36204D3E1692046043983 +:10600000FFF7D0FF002080F31188EDE72DE9F84F6E +:1060100004460D46904699464FF0300A8AF311889F +:106020000026B346A76A4FB949462046FFF7A0FFAE +:1060300020B187F311883046BDE8F88FD4E90A070C +:106040003A1AA8EB0607974228BF1746402F1BD9DC +:1060500005F1400355F8042B40F8042B9D42F9D17B +:10606000A36A4033A3624036D4E90A239A4204D398 +:10607000E16920460439FFF795FF8BF31188464507 +:10608000D9D28AF31188CDE729463A46FBF72EFD8F +:10609000A36A3B443D44A3623E44E5E7D0E90423C0 +:1060A0009A4217D1C3689BB1836A8BB1043B9B1A98 +:1060B0000ED01360C368013BC360C3691A4483698F +:1060C00002619A4224BF436A036100238362012371 +:1060D000184670470023FBE700F0D2B84FF080432A +:1060E000586A70474FF08043002258631A610222B9 +:1060F000DA6070474FF080430022DA60704700009A +:106100004FF0804358637047FEE7000070B51B4BAB +:1061100001630025044686B0586085620E46FDF78F +:10612000CDFE04F11003C4E904334FF0FF33C4E99A +:106130000635C4E90044A560E562FFF7CFFF2B46B2 +:106140000246C4E9082304F134010D4A2565802381 +:106150002046FEF723FC0123E0600A4A0375009203 +:1061600072680192B268CDE90223074B6846CDE917 +:106170000435FEF73BFC06B070BD00BFD04D0020DB +:10618000E46A0008E96A000809610008024AD36A63 +:106190001843D062704700BF684B00204B684360D3 +:1061A0008B688360CB68C3600B6943614B69036292 +:1061B0008B6943620B6803607047000008B5264B8B +:1061C00026481A6940F2FF110A431A611A6922F43B +:1061D000FF7222F001021A611A691A6B0A431A63EC +:1061E0001A6D0A431A651E4A1B6D1146FFF7D6FF4A +:1061F00002F11C0100F58060FFF7D0FF02F13801C9 +:1062000000F58060FFF7CAFF02F1540100F58060DD +:10621000FFF7C4FF02F1700100F58060FFF7BEFFD9 +:1062200002F18C0100F58060FFF7B8FF02F1A801D0 +:1062300000F58060FFF7B2FF02F1C40100F5806055 +:10624000FFF7ACFF02F1E00100F58060FFF7A6FF69 +:10625000BDE8084000F090B800380240000002405D +:10626000F06A000808B500F0FBF9FEF74BFBFFF7FA +:1062700097F8BDE80840FEF7E3BD00007047000056 +:106280000F4B1A6C42F001021A641A6E42F00102BE +:106290001A660C4A1B6E936843F0010393604FF03B +:1062A000804353229A624FF0FF32DA6200229A61F1 +:1062B0005A63DA605A6001225A611A60704700BF5F +:1062C00000380240002004E04FF0804208B5116918 +:1062D000D3680B40D9B2C9439B07116107D530235E +:1062E00083F31188FEF734FB002383F3118808BD84 +:1062F0001F4B1A696FEAC2526FEAD2521A611A69C9 +:10630000C2F308021A614FF0FF301A695A695861E6 +:1063100000215A6959615A691A6A62F080521A62F8 +:106320001A6A02F080521A621A6A5A6A58625A6AE3 +:1063300059625A6A1A6C42F080521A641A6E42F01C +:1063400080521A661A6E0B4A106840F48070106012 +:10635000186F00F44070B0F5007F1EBF4FF480301E +:1063600018671967536823F40073536000F054B939 +:106370000038024000700040334B4FF080521A64E6 +:10638000324A4FF4404111601A6842F001021A602B +:106390001A689107FCD59A6822F003029A602A4B8A +:1063A0009A6812F00C02FBD1196801F0F90119602A +:1063B0009A601A6842F480321A601A689203FCD517 +:1063C0005A6F42F001025A671F4B5A6F9007FCD573 +:1063D0001F4A5A601A6842F080721A601B4A53685A +:1063E0005904FCD5184B1A689201FCD5194A9A60D9 +:1063F000194B1A68194B9A42194B21D1194A116845 +:10640000194A91421CD140F205121A60144A1368CD +:1064100003F00F03052BFAD10B4B9A6842F00202EE +:106420009A609A6802F00C02082AFAD15A6C42F477 +:1064300080425A645A6E42F480425A665B6E7047DC +:1064400040F20572E1E700BF0038024000700040F2 +:106450000854400700948838002004E011640020AC +:10646000003C024000ED00E041C20F41074A08B580 +:10647000536903F00103536123B1054A13680BB15B +:1064800050689847BDE80840FDF73CBD003C01401E +:10649000C0550020074A08B5536903F00203536151 +:1064A00023B1054A93680BB1D0689847BDE808400E +:1064B000FDF728BD003C0140C0550020074A08B543 +:1064C000536903F00403536123B1054A13690BB107 +:1064D00050699847BDE80840FDF714BD003C0140F5 +:1064E000C0550020074A08B5536903F008035361FB +:1064F00023B1054A93690BB1D0699847BDE80840BC +:10650000FDF700BD003C0140C0550020074A08B51A +:10651000536903F01003536123B1054A136A0BB1A9 +:10652000506A9847BDE80840FDF7ECBC003C0140CC +:10653000C0550020164B10B55C6904F478725A619E +:10654000A30604D5134A936A0BB1D06A9847600634 +:1065500004D5104A136B0BB1506B9847210604D534 +:106560000C4A936B0BB1D06B9847E20504D5094AEE +:10657000136C0BB1506C9847A30504D5054A936C76 +:106580000BB1D06C9847BDE81040FDF7BBBC00BF15 +:10659000003C0140C0550020194B10B55C6904F463 +:1065A0007C425A61620504D5164A136D0BB1506DD9 +:1065B0009847230504D5134A936D0BB1D06D9847C6 +:1065C000E00404D50F4A136E0BB1506E9847A10436 +:1065D00004D50C4A936E0BB1D06E9847620404D573 +:1065E000084A136F0BB1506F9847230404D5054A2E +:1065F000936F0BB1D06F9847BDE81040FDF782BC98 +:10660000003C0140C055002008B5FFF75DFEBDE825 +:106610000840FDF777BC0000062108B50846FDF7E5 +:106620009BFC06210720FDF797FC06210820FDF7BB +:1066300093FC06210920FDF78FFC06210A20FDF7B7 +:106640008BFC06211720FDF787FC06212820FDF78B +:1066500083FCBDE8084007211C20FDF77DBC00003D +:1066600008B5FFF745FE00F00BF8FDF729FEFDF732 +:1066700001FDFFF703FEBDE80840FFF72DBD000058 +:106680000023054A19460133102BC2E9001102F11B +:106690000802F8D1704700BFC05500200B460146E4 +:1066A000184600F02DB8000000F040B8012838BFAF +:1066B000012010B50446204600F030F830B900F053 +:1066C00007F808B900F00CF88047F4E710BD0000A7 +:1066D000024B1868BFF35B8F704700BF4056002025 +:1066E00008B5062000F084F80120FEF7F7FA000054 +:1066F000024B0A4601461868FEF780BD4C23002075 +:1067000010B5054C13462CB10A4601460220AFF3E2 +:10671000008010BD2046FCE700000000024B01464F +:106720001868FEF76FBD00BF4C230020024B0146E6 +:106730001868FEF76BBD00BF4C23002010B501396F +:106740000244904201D1002005E0037811F8014F86 +:10675000A34201D0181B10BD0130F2E72DE9F04132 +:10676000A3B1C91A17780144044603F1FF3C8C42D7 +:10677000204601D9002009E00578BD4204F101045A +:10678000F5D10CEB0405D618A54201D1BDE8F08186 +:1067900015F8018D16F801EDF045F5D0E7E700009A +:1067A0001F2938B504460D4604D9162303604FF05F +:1067B000FF3038BD426C12B152F821304BB920463F +:1067C00000F030F82A4601462046BDE8384000F087 +:1067D00017B8012B0AD0591C03D1162303600120DE +:1067E000E7E7002442F82540284698470020E0E7E4 +:1067F000024B01461868FFF7D3BF00BF4C230020AF +:1068000038B5074D00230446084611462B60FEF7B5 +:1068100069FA431C02D12B6803B1236038BD00BF65 +:1068200044560020FEF758BA034611F8012B03F82E +:10683000012B002AF9D170476F72672E617264755F +:1068400070696C6F742E663430352D4D6174656BD4 +:1068500041697273706565640000000053544D33E4 +:1068600032463F3F3F0053544D3332463430780078 +:1068700053544D3332463432780053544D333246FC +:106880003434365858000000012033000010410015 +:1068900001105A00031059000710310000000000D9 +:1068A0005C68000813040000666800081904000012 +:1068B00070680008210400007A68000840A2E4F132 +:1068C000646891060041A3E5F26569920700000043 +:1068D0004261642043414E496661636520696E648C +:1068E00065782E008000000000800000000080001D +:1068F00000000000000000000D240008F52B000837 +:10690000552B00081D240008512400084D260008BE +:106910002124000831240008252400082D24000823 +:10692000292400087525000835240008C12E000818 +:10693000452400084925000800000000F13F000838 +:10694000DD3F00081940000805400008114000081C +:10695000FD3F0008E93F0008D53F0008254000083A +:106960000000000001000000000000006330000093 +:106970006C690008C04B0020D04D00204172647546 +:1069800050696C6F740025424F415244252D424C92 +:10699000002553455249414C2500000002000000EB +:1069A000000000000D42000879420008400040004D +:1069B0007052002080520020020000000000000001 +:1069C0000300000000000000BD42000800000000BD +:1069D00010000000905200200000000001000000A4 +:1069E000000000004855002001010200DD4D0008B4 +:1069F000ED4C0008894D00086D4D00084300000073 +:106A0000046A000809024300020100C032090400C0 +:106A1000000102020100052400100105240100010B +:106A2000042402020524060001070582030800FF72 +:106A300009040100020A00000007050102400000ED +:106A4000070581024000000012000000506A0008A3 +:106A50001201100102000040091241570002010218 +:106A6000030100000403090425424F41524425005C +:106A70003031323334353637383941424344454674 +:106A80000000000000400000004000000040000046 +:106A900000400000000001000000020000000200B1 +:106AA00000000200000002000000020000000200DE +:106AB000000002000000000001440008B946000880 +:106AC0006547000840004000A8550020A855002058 +:106AD00001000000B85500208000000040010000C7 +:106AE000030000006D61696E0069646C6500000060 +:106AF000AA01A81200000000AAAAAAAA550114001F +:106B0000FFBF00008877000070A70A0000000A019C +:106B100000000000AAAAAAAA00000001FFFF0000CE +:106B200000000000990000000000A0160000000016 +:106B3000AAAAAAA600005011FFDF00000000000072 +:106B4000007708002000000000000000AAAAAAAAFE +:106B500010000000FFFF000000080000000000001F +:106B60000000000000000000AAAAAAAA000000007D +:106B7000FFFF000000000000000000000000000017 +:106B800000000000AAAAAAAA00000000FFFF00005F +:106B900000000000000000000000000000000000F5 +:106BA000AAAAAAAA00000000FFFF0000000000003F +:106BB0000000000000000000000000000A000000CB +:106BC00000000000030000000000000000000000C2 +:106BD00000000000000000000000000000000000B5 +:106BE0000000000000000000000000003496FF7F5D +:106BF0000100000000000000F6030000000000009B +:106C000000000F000000000040420F00FE2A0100BB +:106C1000D2040000FF00960000000008009600006B +:106C20000000080004000000646A00080000000082 +:106C30000000000000000000000000000000000054 +:106C400000000000502300200000000000000000B1 +:106C50000000000000000000000000000000000034 +:106C60000000000000000000000000000000000024 +:106C70000000000000000000000000000000000014 +:106C80000000000000000000000000000000000004 +:106C900000000000000000000000000000000000F4 +:086CA0000000000000000000EC :00000001FF diff --git a/Tools/bootloaders/f405-MatekGPS_bl.bin b/Tools/bootloaders/f405-MatekGPS_bl.bin index ee2509b0f5ad77..723de4f8963b14 100755 Binary files a/Tools/bootloaders/f405-MatekGPS_bl.bin and b/Tools/bootloaders/f405-MatekGPS_bl.bin differ diff --git a/Tools/bootloaders/f405-MatekGPS_bl.hex b/Tools/bootloaders/f405-MatekGPS_bl.hex index 297d7985105381..68e31533fbae0b 100644 --- a/Tools/bootloaders/f405-MatekGPS_bl.hex +++ b/Tools/bootloaders/f405-MatekGPS_bl.hex @@ -1,1494 +1,1741 @@ :020000040800F2 -:1000000000070020E5040008B91D0008391D00089C -:10001000911D0008391D0008651D0008E70400084F -:10002000E7040008E7040008E7040008B1450008F9 -:10003000E7040008E7040008E7040008E7040008F4 -:10004000E7040008E7040008E7040008E7040008E4 -:10005000E7040008E70400084D5600087956000838 -:10006000A5560008D1560008FD560008E704000810 -:10007000E7040008E7040008E7040008E7040008B4 -:10008000E7040008E7040008E7040008712D0008F1 -:10009000DD2D0008312E0008852E000829570008A4 -:1000A000E7040008E7040008E7040008E704000884 -:1000B000C1540008E7040008E7040008E70400084A -:1000C000E7040008E7040008E7040008E704000864 -:1000D000E7040008E7040008E7040008E704000854 -:1000E00091570008E7040008E7040008E704000847 -:1000F000E7040008E7040008E7040008E704000834 -:10010000E7040008E7040008E7040008E704000823 -:10011000E7040008E7040008E7040008E704000813 -:10012000E7040008E7040008E7040008E704000803 -:10013000E7040008E7040008E7040008E7040008F3 -:10014000E7040008E7040008E7040008E94C000899 -:10015000E7040008E7040008E7040008E7040008D3 -:10016000E7040008E7040008E7040008E7040008C3 -:10017000E7040008E7040008E7040008E7040008B3 -:10018000E7040008E7040008E7040008E7040008A3 -:10019000E7040008E7040008E7040008E704000893 -:1001A000E7040008E7040008E7040008E704000883 -:1001B000E7040008E7040008E7040008E704000873 -:1001C000E7040008E7040008E7040008E704000863 -:1001D000E7040008E7040008E7040008E704000853 -:1001E00053B94AB9002908BF00281CBF4FF0FF319E -:1001F0004FF0FF3000F074B9ADF1080C6DE904CE9A -:1002000000F006F8DDF804E0DDE9022304B07047F1 -:100210002DE9F047089D04468E46002B4DD18A42B9 -:10022000944669D9B2FA82F252B101FA02F3C2F1EC -:10023000200120FA01F10CFA02FC41EA030E94407D -:100240004FEA1C48210CBEFBF8F61FFA8CF708FB9E -:1002500016E341EA034306FB07F199420AD91CEB76 -:10026000030306F1FF3080F01F81994240F21C81A8 -:10027000023E63445B1AA4B2B3FBF8F008FB1033F0 -:1002800044EA034400FB07F7A7420AD91CEB040425 -:1002900000F1FF3380F00A81A74240F207816444F5 -:1002A000023840EA0640E41B00261DB1D44000237A -:1002B000C5E900433146BDE8F0878B4209D9002DDE -:1002C00000F0EF800026C5E9000130463146BDE868 -:1002D000F087B3FA83F6002E4AD18B4202D38242D2 -:1002E00000F2F980841A61EB030301209E46002D81 -:1002F000E0D0C5E9004EDDE702B9FFDEB2FA82F2D6 -:10030000002A40F09280A1EB0C014FEA1C471FFA33 -:100310008CFE0126200CB1FBF7F307FB131140EA1A -:1003200001410EFB03F0884208D91CEB010103F1E7 -:10033000FF3802D2884200F2CB804346091AA4B2A9 -:10034000B1FBF7F007FB101144EA01440EFB00FE7D -:10035000A64508D91CEB040400F1FF3102D2A645E2 -:1003600000F2BB800846A4EB0E0440EA03409CE781 -:10037000C6F12007B34022FA07FC4CEA030C20FA2E -:1003800007F401FA06F31C43F9404FEA1C4900FA4E -:1003900006F3B1FBF9F8200C1FFA8CFE09FB1811CB -:1003A00040EA014108FB0EF0884202FA06F20BD93E -:1003B0001CEB010108F1FF3A80F08880884240F28E -:1003C0008580A8F102086144091AA4B2B1FBF9F0D2 -:1003D00009FB101144EA014100FB0EFE8E4508D9CD -:1003E0001CEB010100F1FF346CD28E456AD9023852 -:1003F000614440EA0840A0FB0294A1EB0E01A14237 -:10040000C846A64656D353D05DB1B3EB080261EBA4 -:100410000E0101FA07F722FA06F3F1401F43C5E97E -:10042000007100263146BDE8F087C2F12003D840B4 -:100430000CFA02FC21FA03F3914001434FEA1C47F6 -:100440001FFA8CFEB3FBF7F007FB10360B0C43EAE8 -:10045000064300FB0EF69E4204FA02F408D91CEB98 -:10046000030300F1FF382FD29E422DD90238634496 -:100470009B1B89B2B3FBF7F607FB163341EA034136 -:1004800006FB0EF38B4208D91CEB010106F1FF3885 -:1004900016D28B4214D9023E6144C91A46EA00467C -:1004A00038E72E46284605E70646E3E61846F8E60E -:1004B0004B45A9D2B9EB020864EB0C0E0138A3E757 -:1004C0004646EAE7204694E74046D1E7D0467BE738 -:1004D000023B614432E7304609E76444023842E7B0 -:1004E000704700BF02E000F000F8FEE772B63A483D -:1004F00080F30888394880F3098839484EF6085156 -:10050000CEF20001086040F20000CCF200004EF68E -:100510003471CEF200010860BFF34F8FBFF36F8FCD -:1005200040F20000C0F2F0004EF68851CEF2000119 -:100530000860BFF34F8FBFF36F8F4FF00000E1EE05 -:10054000100A4EF63C71CEF200010860062080F3DE -:100550001488BFF36F8F04F0ABF804F087F804F051 -:1005600013FF4FF055301F491B4A91423CBF41F8E1 -:10057000040BFAE71C49194A91423CBF41F8040BAD -:10058000FAE71A491A4A1B4B9A423EBF51F8040B2C -:1005900042F8040BF8E700201749184A91423CBF83 -:1005A00041F8040BFAE704F065F804F041FF144C3D -:1005B000144DAC4203DA54F8041B8847F9E700F005 -:1005C00041F8114C114DAC4203DA54F8041B884732 -:1005D000F9E704F04DB800000007002000230020D8 -:1005E000000000080001002000070020E05C000877 -:1005F00000230020542300205823002028400020FE -:10060000E0010008E0010008E0010008E001000846 -:100610002DE9F04F2DED108AC1F80CD0C3689D462E -:10062000BDEC108ABDE8F08F002383F311882846C3 -:10063000A047002003F046FBFEE703F0C1FA00DF0D -:10064000FEE70000F8B503F051FF074603F09CFFFA -:100650000546A0BB1F4B9F4231D001339F4231D092 -:100660001D4B27F0FF029A422FD1F8B200F022FD75 -:100670002E4642F2107400F027FF08B100242646EF -:1006800000F01EFD08B90646044635B1134B9F42E3 -:1006900003D003F071FF00242646002003F030FF52 -:1006A0000EB100F063F801F019FB00F06BFF01F0F0 -:1006B000A5F9204600F0B6F800F058F8F9E72E4604 -:1006C0000024D8E704460126D5E7064641F28834DF -:1006D000D1E700BF010007B0000008B0263A09B01A -:1006E00008B501F05DF9A0F120035842584108BD5A -:1006F00007B541F21203022101A8ADF8043001F060 -:100700006DF903B05DF804FB10B5202383F3118865 -:100710001248C3680BB103F05BFB114A0F4800237A -:100720004FF47A7103F018FB002383F311880D4C0A -:10073000236813B12368013B2360636813B16368C6 -:10074000013B6360084B1B7833B9636823B902200F -:1007500001F03EFA3223636010BD00BF5823002031 -:1007600009070008742400206C230020274B284A26 -:1007700010B51C461968013146D004339342F9D1B3 -:100780006268244B9A423FD9234B9B6803F1006374 -:1007900003F580339A4237D203F0C2FE03F0D4FE51 -:1007A000002001F045F91D4B0220187001F006FAF7 -:1007B0001B4B1A6C00221A64196E1A66196E596C5A -:1007C0005A64596E5A665A6E5A6942F080025A61EA -:1007D0005A6922F080025A615A691A6942F000523D -:1007E0001A611A6922F000521A611B6972B64FF041 -:1007F000E0232021C3F8084DD4E9003281F31188A9 -:100800009D4683F30888104710BD00BF0000010813 -:1008100020000108FFFF0008002300206C230020B7 -:10082000003802402DE9F04F93B0AC4B00902022ED -:10083000FF210AA89D6801F0FBF9A94A1378A3B922 -:10084000A8480121C3601170202383F31188C36875 -:100850000BB103F0BDFAA44AA24800234FF47A7109 -:1008600003F07AFA002383F31188009B9F4A03B1B7 -:1008700013609F49009C00230B70536098469B4671 -:100880001E469A46012001F099F924B1974B1B6846 -:10089000002B00F01C82002001F082F80390039BE3 -:1008A000002B01DA00F020FF039B002BEDDB012081 -:1008B00001F07AF9039B213B162BE3D801A252F8F1 -:1008C00023F000BF2109000849090008DD090008DC -:1008D000850800088508000885080008710A0008D6 -:1008E000430C00085D0B0008BF0B0008E70B000875 -:1008F0000D0C0008850800081F0C0008850800087A -:10090000910C0008C109000885080008D50C0008F2 -:100910002D090008C109000885080008BF0B000860 -:100920000220FFF7DDFE002840F0FB81009B022142 -:10093000B8F1000F08BF1C4605A841F21233ADF80C -:10094000143001F04BF89DE74FF47A7001F028F86D -:10095000071EEBDB0220FFF7C3FE0028E6D0013FB5 -:10096000052F00F2E081DFE807F0030A0D101336CF -:1009700005230593042105A801F030F817E0574836 -:100980000421F9E75B480421F6E75B480421F3E71B -:100990004FF01C09484601F04DF809F10409059093 -:1009A000042105A801F01AF8B9F12C0FF2D10120A9 -:1009B00000FA07F747EA0B0B5FFA8BFB4FF0000AD0 -:1009C00001F082F926B10BF00B030B2B08BF0024BA -:1009D000FFF78EFE56E749480421CDE7002EA5D04B -:1009E0000BF00B030B2BA1D10220FFF779FE07467A -:1009F00000289BD001203E4E01F01AF802203070F2 -:100A000001F0DCF84FF000085FFA88F9484601F081 -:100A10001FF8044690B1484601F02AF808F1010891 -:100A20000028F1D1B846044641F21213022105A86C -:100A3000ADF814303E4600F0D1FF23E70123022039 -:100A4000337001F0B1F82546244B9B68AB4207D9BF -:100A5000284600F0EFFF013040F068810435F3E7ED -:100A6000234B00251D70214BB8465D603E46A7E72D -:100A7000002E3FF45BAF0BF00B030B2B7FF456AF54 -:100A80001B4B0220187001F099F8322000F088FF0B -:100A9000B0F10009FFF64AAF19F003077FF446AF43 -:100AA0000E4A926809EB050393423FF63FAFB9F552 -:100AB000807F3FF73BAF124B0193B94522DD4FF4E6 -:100AC0007A7000F06DFF0390039A002AFFF62EAFB4 -:100AD000019B039A03F8012B0137EDE70023002067 -:100AE00070240020582300200907000874240020E7 -:100AF0006C23002004230020082300200C23002066 -:100B000070230020C820FFF7EBFD074600283FF4C4 -:100B10000DAF1F2D11D8C5F120024A450AAB25F0B3 -:100B2000030028BF4A4683490192184401F05AF84D -:100B3000019A8048FF2101F07BF84FEAA9037D4923 -:100B40000193C9F38702284601F07AF80646002887 -:100B50003FF46AAF019B05EB830531E70220FFF705 -:100B6000BFFD00283FF4E2AE00F0ACFF00283FF4E8 -:100B7000DDAE0027B946704B9B68BB4218D91F2FCA -:100B800011D80A9B01330ED027F0030312AA134495 -:100B900053F8203C05934846042205A901F012F9B8 -:100BA00004378146E7E7384600F044FF0590F2E756 -:100BB000CDF81490042105A800F010FF00E70023F1 -:100BC000642104A8049300F0FFFE00287FF4AEAE79 -:100BD0000220FFF785FD00283FF4A8AE049800F03E -:100BE00059FF0590E6E70023642104A8049300F070 -:100BF000EBFE00287FF49AAE0220FFF771FD00287B -:100C00003FF494AE049800F055FFEAE70220FFF7A6 -:100C100067FD00283FF48AAE00F064FFE1E70220A0 -:100C2000FFF75EFD00283FF481AE05A9142000F017 -:100C30005FFF04210746049004A800F0CFFE394668 -:100C4000B9E7322000F0ACFE071EFFF66FAEBB071F -:100C50007FF46CAE384A926807EB0A0393423FF682 -:100C600065AE0220FFF73CFD00283FF45FAE27F0A1 -:100C700003075744BA453FF4A3AE504600F0DAFEEE -:100C80000421059005A800F0A9FE0AF1040AF1E785 -:100C90004FF47A70FFF724FD00283FF447AE00F0D0 -:100CA00011FF002844D00A9B01330BD008220AA967 -:100CB000002000F0C5FF00283AD02022FF210AA81A -:100CC00000F0B6FFFFF714FD1C4803F001F813B065 -:100CD000BDE8F08F002E3FF429AE0BF00B030B2B79 -:100CE0007FF424AE0023642105A8059300F06CFE78 -:100CF000074600287FF41AAE0220FFF7F1FC814678 -:100D000000283FF413AEFFF7F3FC41F2883002F005 -:100D1000DFFF059801F00AF84E4600F0D5FF3C468B -:100D2000B0E506464CE64FF0000AFFE5B8467BE624 -:100D3000374679E67023002000230020A0860100BA -:100D4000094A136849F2690099B21B0C00FB013390 -:100D50001360064B186844F2506182B2000C01FB2C -:100D60000200186080B27047202300201C2300205E -:100D700010B500211022044600F05AFF034B03CBAC -:100D8000206061601868A06010BD00BF107AFF1F6E -:100D90002DE9F043224DBBB001F010F8AB6840F2F2 -:100DA000ED22C31A934232D906AFA8602B462822FF -:100DB0000021384601F010FD05F10E0000F030FF73 -:100DC000002604465FFA80F905F10E08F3B2F1003F -:100DD000994501F1280107D908EB06030822384696 -:100DE00001F0FAFC0136F1E708230122CDE90232D5 -:100DF00005340C4B0193A4B230230093CDE9047465 -:100E000005A3D3E90023297B074801F0FDFA3BB095 -:100E1000BDE8F083AFF3008078F6339F93CACD8DA1 -:100E2000C0340020CD3400209434002070B50D462D -:100E300014461E4601F07EFA50B9022E10D1012C44 -:100E40000ED112A3D3E90023C5E90023012007E056 -:100E5000282C10D005D8012C09D0052C0FD000204B -:100E600070BD302CFBD10BA3D3E90023ECE70BA31F -:100E7000D3E90023E8E70BA3D3E90023E4E70BA3BE -:100E8000D3E90023E0E700BFAFF30080401DA120BD -:100E900026812A0B78F6339F93CACD8D9E6AC42192 -:100EA000818A46EE26417272DF25D7B7F017304AA5 -:100EB00039059E5613B504462346084620220021D4 -:100EC000019001F089FC22790198032A234628BF6A -:100ED000032203F8042F2021022201F07DFC627915 -:100EE0000198072A234628BF072203F8052F22214D -:100EF000032201F071FCA2790198072A234628BF3A -:100F0000072203F8062F2521032201F065FC019832 -:100F100004F108031022282101F05EFC382002B001 -:100F200010BD00002DE9F04FADF5017D21AD0EAEF5 -:100F300040F2751280460F4622A80021296000F079 -:100F400077FE48220021304600F072FE00F036FFA6 -:100F5000564B4FF47A72B0FBF2F0186093E807003A -:100F6000012386E807000DF15A003382FFF700FFE6 -:100F70004FF20363338407AB18464D4904F0B4FCC9 -:100F80001B2230642946304686F83C20FFF792FF4A -:100F900012AB044601460822284601F01DFC082237 -:100FA000A1180DF14903284601F016FC0DF14A0382 -:100FB000082204F11001284601F00EFC13AB202298 -:100FC00004F11801284601F007FC14AB402204F19B -:100FD0003801284601F000FC16AB082204F1780124 -:100FE000284601F0F9FB0DF15903082204F18001B4 -:100FF000284601F0F1FB04F1880A0DF15A0904F5C5 -:10100000847B4B465146082228460AF1080A01F023 -:10101000E3FBD34509F10109F3D11BAB0822594683 -:10102000284601F0D9FB04F588744FF0000996F8C2 -:1010300034304B450AD9B36B21464B44082228462D -:1010400001F0CAFB083409F10109F0E74FF000098B -:1010500096F83C304B4504EBC90108D9336C0822A3 -:101060004B44284601F0B8FB09F10109F0E70023E1 -:101070000393BB7E0293073107F119030193C1F378 -:10108000CF010123CDE904510093F97E05A3D3E9F3 -:101090000023404601F0B8F90DF5017DBDE8F08F61 -:1010A000AFF300809E6AC421818A46EE7C24002032 -:1010B000F8580008014B1870704700BF88240020C2 -:1010C000F0B5334B1C7B85B034B1324B0E221A8104 -:1010D0000024204605B0F0BD2F4A1068516802ABCD -:1010E00003C308232D492E480DEB030204F0DAFB5D -:1010F000054630B9274B2B480A221A8100F018FE0A -:10110000E6E70169B1F5702F06D9224B26480B227C -:101110001A8100F00DFEDCE7438B40F2F632934279 -:1011200007D01C490C2008811946204800F000FE19 -:10113000CFE71F4A024402F11003994204D2154B33 -:101140001C4810221A81E4E710398E1A20461449EF -:1011500000F038FE3246074605F11801204600F03F -:1011600031FEAB689F4202D1EB6898420AD0094B2E -:101170000D221A810090D5E902123B460E4800F07C -:10118000D7FDA5E70D4800F0D3FD0124A1E700BF7E -:10119000C03400207C240020A5590008DCFF0E008C -:1011A00000000108145900082059000832590008AD -:1011B0000800FFF7505900086D59000896590008BB -:1011C0002DE9F04FADB006AF80460C4601F0B2F805 -:1011D000054600285AD1237E022B1BD1E38A012B1E -:1011E00018D100F0EBFD0646FFF7AAFD03464FF4C9 -:1011F000C870DFF8D092B3FBF0F206F5167602FB6A -:10120000103316FA83F3C9F80030E37E33B9A84BE4 -:1012100000221A709C37BD46BDE8F08FA38AEEB25B -:10122000013BB34205F101050BD93B1D1E44E9000A -:1012300000960023082201F0F801204601F090F901 -:10124000ECE707F11400FFF793FD324607F11401B4 -:10125000381D04F017FB0028D9D10F2E08D8944B65 -:101260001E70D9F80030A3F51673C9F80030D1E725 -:10127000FB1CF8700146009307220346204601F04C -:101280006FF9F978404601F04DF8C3E7E38A282B5F -:1012900026D010D8012B1ED0052BBBD1BFF34F8F0A -:1012A0008449854BCA6802F4E0621343CB60BFF304 -:1012B0004F8F00BFFDE7302BACD1637E7F4D0133F4 -:1012C0006A7BDBB29342E94603D1E27E2B7B9A42F2 -:1012D00065D0CD469EE721464046FFF723FE99E7BD -:1012E000A38A013B9BB2C92B94D8744D2E7B26BB9D -:1012F00005F10C030093082233463146204601F0E5 -:101300002FF9731CF2B2D9001E46A38A013B9A4200 -:1013100005DA0E322A44009200230822EEE7002369 -:101320000022C5E900230023AB6085F8D730C5F85B -:10133000D8302B7B0BB9E37E2B73002507F1140902 -:101340003B1D082229464846C7E90155FD6001F0CA -:1013500043FA3B7A05F1010AAB424FEACA0608D9C3 -:10136000FB6808222B443146484601F035FA5546C1 -:10137000EFE7C6F3CF06E17ECDE9049600230393A1 -:10138000A37E0293193428230093019446A3D3E942 -:101390000023404601F038F8FFF7FAFC3AE74FF037 -:1013A000000807F11403A7F81480102200934146A7 -:1013B0000123204601F0D4F8A68A023EB6B2F31CFF -:1013C0009B109B000733DB08A9EBC3039D460DF17F -:1013D000180A1FFA88F34FEAC801B34201F110015D -:1013E0000AD20AEB0803009308220023204601F0EA -:1013F000B7F808F10108ECE795F8D70000F028FBF2 -:10140000D5F8D83004461BB995F8D70000F030FB6A -:10141000D5F8D83033449C4204D295F8D700013037 -:1014200000F026FB4FEA960B4FF000081FFA88F1F8 -:101430008B45D5E9003209D90AEB880103EB880016 -:10144000012200F0FDFB08F10108EFE7F31842F17B -:101450000002C5E90032D5F8D83095F8D70006EB80 -:101460000308C5F8D88000F0F3FA804509D395F851 -:10147000D730D5F8D8000133001B85F8D730C5F830 -:10148000D800FF2E08D800232B7300F01BFBFFF7BA -:1014900017FE08B1FFF76AF92B68094A9B0A013366 -:1014A00013810023AB6014E726417272DF25D7B7A2 -:1014B0008D34002000ED00E00400FA05C034002067 -:1014C0007C2400209034002030B54FF00054244B91 -:1014D00022689A4285B007D003F060F80446A8B9A4 -:1014E0000024204605B030BD1E4B627D1A701E4898 -:1014F000237D03731D49C9220E3000F073FB204683 -:10150000E022002100F094FB0124EAE7184A194D7B -:10151000136C43F000731364AA6D174B9A42DFD12A -:101520002B6E013B7E2BDBD8144A07CA01AB83E844 -:1015300007001846032100F05BFC6B6D83424FF0FF -:101540000003CDD12A6D8A4201BFAB65054B2A6EDF -:101550001A7003BF0A4BEA6D1A601C46C1E700BF50 -:101560009AAD44C588240020C03400201600002015 +:1000000000070020F5040008B12E0008692E000842 +:10001000912E0008692E0008892E0008F7040008B8 +:10002000F7040008F7040008F7040008A53E0008DC +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F7040008756400089D640008B0 +:10006000C5640008ED64000815650008F704000881 +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F70400081D2E000814 +:10009000492E0008592E0008F70400083D650008A5 +:1000A000F7040008F7040008F7040008F704000844 +:1000B00011660008F7040008F7040008F7040008B8 +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008F7040008F7040008F704000814 +:1000E000A1650008F7040008F7040008F7040008F9 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008695A0008DB +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E000651800080000000000000000000000008A +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600004F04AFF05F02EFE4FF055301F491B4A9C +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE704F028FFD7 +:1005B00005F05CFE144C154DAC4203DA54F8041BF4 +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E704F010BF0007002017 +:1005E000002300200000000808ED00E000010020CA +:1005F00000070020F86B000800230020B023002033 +:10060000B023002048560020E0010008E401000863 +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002004F0EAF93C +:10064000FEE704F043F900DFFEE70000F8B501F033 +:100650001BF904F06BFE074604F0BAFE0546B8BB72 +:10066000204B9F4234D001339F4234D01E4B27F0A1 +:10067000FF029A4232D1F8B200F012FF2E4642F247 +:10068000107400F013FF08B10024264601F0FEFCB0 +:1006900020B1032000F07CF80024264635B1134B2E +:1006A0009F4203D004F08CFE00242646002004F074 +:1006B00047FE0EB100F082F801F098FA00F062FFF8 +:1006C00001F048F9204600F0D5F800F077F8F9E796 +:1006D0002E460024D5E704460126D2E7064641F21D +:1006E0008834CEE7010007B0000008B0263A09B010 +:1006F00008B501F001F9A0F120035842584108BDA6 +:1007000007B541F21203022101A8ADF8043001F04F +:1007100011F903B05DF804FB38B5302383F3118879 +:10072000174803680BB104F041FA164A1448002335 +:100730004FF47A7104F030FA002383F31188124CDD +:10074000236813B12368013B2360636813B16368B6 +:10075000013B63600D4D2B7833B963687BB9022090 +:1007600001F0BEF9322363602B78032B07D1636855 +:100770002BB9022001F0B4F94FF47A73636038BDED +:10078000B023002019070008D0240020C82300202F +:10079000084B187003280CD8DFE800F008050208A1 +:1007A000022001F093B9022001F086B9024B002229 +:1007B0005A607047C8230020D024002010B501F0F3 +:1007C00065FC30B1244B03221A70244B00225A607E +:1007D00010BD234B234A1C4619680131F8D004335D +:1007E0009342F9D16268204B9A42F1D91F4B9B6822 +:1007F00003F1006303F580339A42E9D204F0B4FDBB +:1008000004F0C6FD002001F0BFF80220FFF7C0FF92 +:10081000174B1A6C00221A64196E1A66196E596CFD +:100820005A64596E5A665A6E1A6942F000521A6139 +:100830001A6922F000521A611B6972B64FF0E02368 +:100840003021C3F8084DD4E9003281F311889D4668 +:1008500083F308881047BBE7C8230020D02400207A +:100860000000010820000108FFFF0008002300200D +:10087000003802402DE9F04F93B0AC4B009020229D +:10088000FF210AA89D6801F05BF9A94A1378A3B972 +:10089000A848012103601170302383F31188036895 +:1008A0000BB104F083F9A44AA24800234FF47A71F3 +:1008B00004F072F9002383F31188009B13B19F4B5E +:1008C000009A1A609E4A009C1378032B1EBF0023D7 +:1008D00013709A4A4FF0000A18BF5360D346564629 +:1008E000D146012001F0F2F824B1944B1B68002B93 +:1008F00000F01582002000F0FFFF0390039B002B07 +:1009000001DA00F087FE039B002BEDDB012001F0F4 +:10091000D3F8039B213B162BE3D801A252F823F016 +:100920007D090008A5090008390A0008E308000845 +:10093000E3080008E3080008C30A0008930C000855 +:10094000AD0B00080F0C0008370C00085D0C000808 +:10095000E30800086F0C0008E3080008E10C000839 +:100960001D0A0008E3080008250D00088909000891 +:100970001D0A0008E30800080F0C00080220FFF71A +:10098000B7FE002840F0F581009B0221BAF1000F6C +:1009900008BF1C4605A841F21233ADF8143000F030 +:1009A000C9FF9EE74FF47A7000F0A6FF071EEBDB4D +:1009B0000220FFF79DFE0028E6D0013F052F00F240 +:1009C000DA81DFE807F0030A0D10133605230593DB +:1009D000042105A800F0AEFF17E054480421F9E710 +:1009E00058480421F6E758480421F3E74FF01C0863 +:1009F000404600F0CBFF08F104080590042105A84B +:100A000000F098FFB8F12C0FF2D1012000FA07F79F +:100A100047EA0B0B5FFA8BFB4FF0000901F0DCF8A3 +:100A200026B10BF00B030B2B08BF0024FFF768FE69 +:100A300057E746480421CDE7002EA5D00BF00B0365 +:100A40000B2BA1D10220FFF753FE074600289BD0B5 +:100A5000012000F099FF0220FFF79AFE00261FFAFE +:100A600086F8404600F0A0FF044690B100214046C1 +:100A700000F0B2FF01360028F1D1BA46044641F237 +:100A80001213022105A8ADF814303E4600F052FFC3 +:100A900027E70120FFF77CFE2546244B9B68AB42ED +:100AA00007D9284600F072FF013040F06781043515 +:100AB000F3E7234B00251D70204BBA465D603E4690 +:100AC000ACE7002E3FF460AF0BF00B030B2B7FF471 +:100AD0005BAF0220FFF75CFE322000F00DFFB0F1AB +:100AE0000008FFF651AF18F003077FF44DAF0F4A2F +:100AF000926808EB050393423FF646AFB8F5807F56 +:100B00003FF742AF124B0193B84523DD4FF47A70A3 +:100B100000F0F2FE0390039A002AFFF635AF019B26 +:100B2000039A03F8012B0137EDE700BF00230020F3 +:100B3000CC240020B023002019070008D024002076 +:100B4000C823002004230020082300200C230020B9 +:100B5000CC230020C820FFF7CBFD074600283FF438 +:100B600013AF1F2D11D8C5F1200242450AAB25F065 +:100B7000030028BF424683490192184400F0BAFF9F +:100B8000019A8048FF2100F0DBFF4FEAA8037D496E +:100B90000193C8F38702284600F0DAFF06460028D2 +:100BA0003FF46DAF019B05EB830537E70220FFF7AC +:100BB0009FFD00283FF4E8AE00F02EFF00283FF430 +:100BC000E3AE0027B846704B9B68BB4218D91F2F75 +:100BD00011D80A9B01330ED027F0030312AA134445 +:100BE00053F8203C05934046042205A901F006FA7B +:100BF00004378046E7E7384600F0C8FE0590F2E784 +:100C0000CDF81480042105A800F094FE06E7002327 +:100C1000642104A8049300F083FE00287FF4B4AE9E +:100C20000220FFF765FD00283FF4AEAE049800F007 +:100C3000DBFE0590E6E70023642104A8049300F09E +:100C40006FFE00287FF4A0AE0220FFF751FD0028C0 +:100C50003FF49AAE049800F0D7FEEAE70220FFF7CF +:100C600047FD00283FF490AE00F0E6FEE1E70220E9 +:100C7000FFF73EFD00283FF487AE05A9142000F0E1 +:100C8000E1FE04210746049004A800F053FE394613 +:100C9000B9E7322000F030FE071EFFF675AEBB0745 +:100CA0007FF472AE384A926807EB090393423FF62D +:100CB0006BAE0220FFF71CFD00283FF465AE27F065 +:100CC00003074F44B9453FF4A9AE484600F05EFE25 +:100CD0000421059005A800F02DFE09F10409F1E7B3 +:100CE0004FF47A70FFF704FD00283FF44DAE00F09A +:100CF00093FE002844D00A9B01330BD008220AA996 +:100D0000002000F025FF00283AD02022FF210AA869 +:100D100000F016FFFFF7F4FC1C4803F081FE13B04F +:100D2000BDE8F08F002E3FF42FAE0BF00B030B2B22 +:100D30007FF42AAE0023642105A8059300F0F0FD9E +:100D4000074600287FF420AE0220FFF7D1FC804642 +:100D500000283FF419AEFFF7D3FC41F2883003F0CE +:100D60005FFE059800F06AFF464600F035FF3C46FE +:100D7000B7E5064652E64FF0000905E6BA467EE6BC +:100D800037467CE6CC23002000230020A08601000B +:100D9000094A136849F2690099B21B0C00FB013340 +:100DA0001360064B186844F2506182B2000C01FBDC +:100DB0000200186080B2704718230020142300201E +:100DC00010B500211022044600F0BAFE034B03CBFD +:100DD000206061601868A06010BD00BF107AFF1F1E +:100DE0002DE9F041ADF54E7D0DF134086CAC40F2CB +:100DF000751207460D460EA80021C8F8001000F035 +:100E00009FFE4FF4C4720021204600F099FE02F0CC +:100E100057F8274B4FF47A72B0FBF2F0186093E862 +:100E20000700022384E807000DF5E9702382FFF72D +:100E3000C7FF4FF203631F49238406A805F0F8FC9F +:100E40001B2384F832310DF2E32206AB0DF1300C96 +:100E50001E4603CE664510605160334602F108021B +:100E6000F6D13188B3789370118020464146012233 +:100E700000F0E6FE00230393AB7E029305F1190315 +:100E8000019380B20123CDE904800093E97E06A39B +:100E9000D3E90023384602F0DBFB0DF54E7DBDE8BB +:100EA000F08100BFAFF300809E6AC421818A46EEC4 +:100EB000D8240020406800082DE9F0412C4C237A0A +:100EC000DAB080460D465BBB27A9284600F0C8FF74 +:100ED0000746002842D19DF89D60C82E3ED80146A5 +:100EE0004FF4A662204600F02BFE4FF48073C4F846 +:100EF000F8314FF40073C4F80C334FF44073C4F866 +:100F0000203432460DF19E0104F1090000F0F2FD9B +:100F100026449DF89C30777223720BB9EB7E2372C6 +:100F20008122002106AC27A800F00AFE01222146FA +:100F300027A800F0D1FF00230393AB7E029305F1B5 +:100F4000190380B201932823CDE904400093E97E80 +:100F500005A3D3E90023404602F07AFB5AB0BDE86E +:100F6000F08100BFAFF3008026417272DF25D7B752 +:100F7000F0450020F0B5254E4FF48A7505FB00655D +:100F8000F1B096F8D83085F8DC300024D82221461C +:100F900085F8E8403AA800F0D3FD06F1090000F01A +:100FA000C7FDD5F8E4308DF8F000C2B206AF06F107 +:100FB00009010DF1F100CDE93A3400F09BFD39460D +:100FC00001223AA800F0B4FF80B2CDE904700823F2 +:100FD0000127CDE9023706F1D803019330230093AE +:100FE000317A0B4807A3D3E9002302F031FBA0427A +:100FF00006DD01F065FFC5F8E000384671B0F0BDD0 +:101000002046FBE778F6339F93CACD8DF04500204C +:10101000F03400202DE9F0411D4D1E4E1E4F86B0CC +:10102000284602F041FB034658B30024CDE90344AF +:10103000ADF81440027B8DF8142099684068029442 +:1010400003AA03C21B68DFF8548043F000430293F5 +:1010500001F038FF821941F10003009402A93846DB +:1010600001F0FAF9A04205DD284602F021FB88F8DC +:101070000040D5E798F80030072B05D8013388F8F1 +:10108000003006B0BDE8F081014802F011FBF8E73E +:10109000F034002040420F0020350020254B002076 +:1010A00070B50D4614461E4602F02EFA50B9022EB7 +:1010B00010D1012C0ED112A3D3E90023C5E90023DE +:1010C000012007E0282C10D005D8012C09D0052CD0 +:1010D0000FD0002070BD302CFBD10BA3D3E900232F +:1010E000ECE70BA3D3E90023E8E70BA3D3E9002344 +:1010F000E4E70BA3D3E90023E0E700BFAFF30080F0 +:10110000401DA12026812A0B78F6339F93CACD8DEE +:101110009E6AC421818A46EE26417272DF25D7B7C6 +:10112000F017304A39059E5638B505460E4C002159 +:10113000013500F051FCA4F82C55B4F82C0500F052 +:1011400033FC78B1B4F82C0500F03EFC014648B9F8 +:10115000B4F82C0500F040FCB4F82C350133A4F8A9 +:101160002C35EAE738BD00BFF045002010B50A4B2A +:101170000A4A1A6003F5805393F860203AB9DC6D8F +:101180002CB1204601F000F8204605F091FABDE8A8 +:101190001040034800F0F8BF20350020F868000830 +:1011A000684500202DE9F04F8FB000AF05460C4692 +:1011B00002F0AAF9002849D1237E022B1BD1E38A31 +:1011C000012B18D101F07CFE0646FFF7E1FD034636 +:1011D0004FF4C870DFF8C482B3FBF0F206F5167660 +:1011E00002FB103316FA83F3C8F80030E37E33B9FC +:1011F000A34B00221A703C37BD46BDE8F08F07F1C3 +:101200002401204600F0EAFD0028F4D107F1140083 +:10121000FFF7D6FD97F8264007F11401224607F1A3 +:10122000270005F08FFA0028E2D10F2C08D8944B44 +:101230001C70D8F80030A3F51673C8F80030DAE750 +:1012400097F82410284602F057F9D4E7E38A282BB0 +:101250002BD010D8012B23D0052BCCD1BFF34F8F2F +:101260008849894BCA6802F4E0621343CB60BFF33C +:101270004F8F00BFFDE7302BBDD1844EE17E327A27 +:101280009142B8D1607E3146002291F8DC5085420F +:1012900000F0A5800132042A01F58A71F5D1AAE790 +:1012A00021462846FFF79CFDA5E721462846FFF783 +:1012B00003FEA0E7B2F8EC507B6005F103094FEAAA +:1012C00099094FEA8902D11DC908A8EBC1039D46BF +:1012D000EB460021584600F033FC04F1EE012A46AB +:1012E0003144584600F006FC7B6813B9012000F039 +:1012F0004BFB96F8D20000F057FB044630B9307231 +:1013000000F08AFB204600F03FFBB1E0D6F8D42085 +:101310003AB996F8D200B6F82C25824201D8FFF7E8 +:1013200003FFD6F8D4202A44944208D296F8D2007B +:10133000B6F82C250130824201D8FFF7F5FE70681F +:101340005FFA89F2594600F003FC08B9C54679E016 +:10135000726896F8D2002A447260D6F8D42005EB61 +:101360000209C6F8D49000F01FFB814509D396F816 +:10137000D220D6F8D4000132001B86F8D220C6F85D +:10138000D400FF2D0FD80024347200F045FB204616 +:1013900000F0FAFA00F07AFE3D4B188108B9FFF729 +:1013A0000DFAC54627E7BB6896F8D9000AFB036229 +:1013B000FB68D2F8E41082F8E83001F58061C2F8E9 +:1013C000E030C2F8E410FFF7D5FDFFF723FE96F8F2 +:1013D000D920013202F0030286F8D920B6E74FF493 +:1013E0008A7A0AFB02F505F1EA013144204600F051 +:1013F000CBFDF86000287FF4FEAE3544012285F86D +:10140000E82001F05DFDD5F8E020D6ED007ADFEDB3 +:10141000216A801A192838BF192040F6B832904244 +:1014200028BF1046B8EE677A07EE900AF8EEE77A22 +:1014300067EEA67ADFED186AE7EE267AFCEEE77A29 +:10144000C6ED007A96F8D930BB60BA6873680AFBBB +:1014500002F4321992F8E81059B1D2F8E4108B4234 +:10146000E8463FF427AF002182F8E810C2F8E01008 +:10147000C5467368064A9B0A01331381BBE600BF69 +:10148000E934002000ED00E00400FA05F0450020FA +:10149000D8240020CDCCCC3D6666663FEC340020DD +:1014A000014B1870704700BFE424002030B54FF0A6 +:1014B00000542B4B22689A4285B007D003F092FF6C +:1014C000044620BB0024204605B030BD254B627D7C +:1014D00025481A70237D03724FF48073C0F8F831E9 +:1014E0004FF40073C0F80C3300254FF44073C0F87C +:1014F00020341E49C0F8E450C922093000F0FAFA3D +:101500002046E022294600F01BFB0124DBE7184AB5 +:10151000184D136C43F000731364AA6D164B9A4276 +:10152000D0D12B6E013B7E2BCCD8144A07CA01AB1D +:1015300083E807001846032100F076FD6B6D8342B7 +:101540004FF00003BED12A6D8A4201BFAB65054B47 +:101550002A6E1A7003BF0A4BEA6D1A601C46B2E786 +:101560009AAD44C5E4240020F04500201600002078 :1015700000380240006600405041A0B0586600406C -:10158000182300202DE9FF474B4C022363710023F1 -:1015900002934A4BD3F800C0BCF57A7F12D3484B74 -:1015A000484FB7FBFCF69C458CBF0A231123581EFD -:1015B000B6FBF3F503FB1562C1B2002A3ED0022848 -:1015C0000346F4D89DF80B303F4940485A1E9DF819 -:1015D0000A30013B1B0443EA0253BDF80820013ADC -:1015E00013434B6001F0B0FD00230193384B3949A0 -:1015F00000933948394B4FF4805200F06DFE384B60 -:10160000197811B1344800F08DFE00F0D7FB054683 -:10161000FFF796FB4FF4C873B0FBF3F202FB130322 -:1016200005F5167010FA83F02E4B186002F0ACFF2F -:1016300008B10F23238104B0BDE8F0876B1EB3F51A -:10164000806FBFD2C1EBC10E0EF103034FEAE30975 -:10165000C3F3C703A1EB030809F1010A4FF47A7041 -:101660005FFA88F609FB00005AFA88F8B0FBF8F038 -:10167000B0F5617F08D90EF1FF33C3F3C703C91A70 -:10168000CEB2591E0F2914D8721E072A8CBF002211 -:101690000122991901FB0551B7FBF1F7BC4591D126 -:1016A000002A8FD0ADF808508DF80A308DF80B6005 -:1016B00088E71346EDE700BF7C24002018230020B4 -:1016C0003F420F0080DE800210230020D83500202A -:1016D0002D0E00088C24002094340020C111000835 -:1016E00088240020903400202DE9F04F91A7D7E9FD -:1016F00000670FF24829D9E90089874D93B0DFF8D8 -:1017000044B2864C284600F0E3FE0DF1300A079003 -:1017100070B310220021504600F08AFA079B197B13 -:101720004FF0000261F303028DF830205868996889 -:101730000EAA03C21B680D9A63F31C029DF8303099 -:101740000D9243F020038DF83030002352461946A5 -:10175000584601F009FD079028B9284600F0BCFE64 -:10176000079B2370CEE72378072B3CD801332370E7 -:1017700018220021504600F05BFADFF8C8B1684C2F -:10178000002319465246584601F016FD014670BB2B -:10179000102208A800F04CFA636983F48043636167 -:1017A00000F00EFB0B4612A9024611E903000DF1F1 -:1017B000240C8CE803009DF83410C1F30300890663 -:1017C0004CBF0E99BDF838C08DF82C0046BFC1F350 -:1017D0001C0C4CF00041CCF30A010891284608A9E2 -:1017E00001F042F8CCE7284600F076FEC0E7284634 -:1017F00000F0A0FD0446002848D1DFF84CB100F00D -:10180000DDFADBF80030984240D300F0D7FA0790B9 -:10181000FFF796FA079A8DF8204003464FF4C870F8 -:1018200002F51672B3FBF0F101FB103312FA83F3E9 -:10183000CBF80030DFF814B19BF8001011B9012388 -:101840008DF8203050460791FFF792FA0799C1F1C1 -:101850001004E4B2062C28BF0624224651440DF1A0 -:10186000210000F0BFF908AB039318230293013461 -:101870002C4B0193E4B20123009304943B4632467F -:10188000284600F059FD00238BF8003000F096FA4E -:10189000254A264C1368C31AB3F57A7F31D31060FA -:1018A00000F08EFA02460B46284600F01FFE28463E -:1018B00000F040FD28B3237BDFF894B0002B14BF69 -:1018C000032302238BF8053000F078FA4FF47A7383 -:1018D0005146B0FBF3F0CBF800005846FFF7EAFAA8 -:1018E000182307300293124B0193C0F3CF0040F24C -:1018F0005513CDE903A0009342464B46284600F01D -:101900001BFD237B2BB1FFF743FA237B002B7FF4D6 -:10191000F6AE13B0BDE8F08F94340020A53500205A -:10192000000002408C340020A0350020C03400208C -:10193000A4350020401DA12026812A0BF1C6A7C195 -:10194000D068080FD8350020903400208D34002056 -:101950007C24002070B50F4B1B780133DBB2012BC8 -:101960000C4611D80C4D29684FF47A730E6AA2FB0D -:101970000332014622462846B047844204D1074B31 -:1019800000221A70012070BD4FF4FA7002F0A0F925 -:101990000020F8E724230020C0370020D4350020A1 -:1019A00007B50023024601210DF107008DF807302D -:1019B000FFF7D0FF20B19DF8070003B05DF804FBEE -:1019C0004FF0FF30F9E700000A4608B50421FFF7A1 -:1019D000C1FF80F00100C0B2404208BD30B4054CE8 -:1019E0002368DD69044B0A46AC460146204630BCFC -:1019F000604700BFC0370020A086010070B502F02C -:101A000017FC094E094D3080002428683388834232 -:101A100008D902F007FC2B6804440133B4F5803F79 -:101A20002B60F2D370BD00BFD6350020A835002052 -:101A300002F0C0BC00F1006000F580300068704723 -:101A400000F10060920000F5803002F03FBC000021 -:101A5000054B1A68054B1B889B1A834202D9104418 -:101A600002F0E0BB00207047A8350020D6350020EA -:101A700038B5074D04462868204402F0DBFB28B93E -:101A800028682044BDE8384002F0ECBB38BD00BFF8 -:101A9000A835002010F003030AD1B0F5047F05D269 -:101AA00000F10050A0F51040D0F8003818467047FB -:101AB0000023FBE700F10050A0F51040D0F8100A19 -:101AC00070470000064991F8243033B10023086ABA -:101AD00081F824300822FFF7B3BF0120704700BF10 -:101AE000AC350020014B1868704700BF002004E0AF -:101AF00070B52A4B1B68C3F30B0204461B0C62B182 -:101B000040F21340824230D040F2194082422ED03F -:101B100040F2214082422CD10322214D0C2000FBB7 -:101B20000252556842F20102934224D0B3F5805F1D -:101B300023D041F20102934221D041F203029342A9 -:101B40001FD041F20702934214BF3F233123013CCF -:101B50000C44013D0A46A24215D215F9016F501CF2 -:101B60009EB100F8016C0246F5E70122D5E702229A -:101B7000D3E70C4DD6E73323E9E74123E7E75A23C0 -:101B8000E5E75923E3E7104605E02C25844215706C -:101B900001D9901C5370401A70BD00BF002004E0B2 -:101BA000DC590008B0590008022802BF024B4FF070 -:101BB00080429A61704700BF00000240022802BFC5 -:101BC000024B4FF480429A61704700BF0000024010 -:101BD000022801BF024A536983F48043536170476E -:101BE0000000024010B50023934203D0CC5CC454E3 -:101BF0000133F9E710BD000010B5013810F9013FBD -:101C00003BB191F900409C4203D11AB10131013A34 -:101C1000F4E71AB191F90020981A10BD1046FCE7BC -:101C200003460246D01A12F9011B0029FAD1704767 -:101C300002440346934202D003F8011BFAE77047BF -:101C40002DE9F8431F4D144695F824200746884691 -:101C500052BBDFF870909CB395F824302BB920224A -:101C6000FF2148462F62FFF7E3FF95F82400C0F1FB -:101C70000802A24228BF2246D6B24146920005EB96 -:101C80008000FFF7AFFF95F82430A41B1E44F6B286 -:101C9000082E17449044E4B285F82460DBD1FFF7A6 -:101CA00011FF0028D7D108E02B6A03EB820383429F -:101CB000CFD0FFF707FF0028CBD10020BDE8F88385 -:101CC0000120FBE7AC350020024B1A78024B1A705A -:101CD000704700BFD43500202423002010B50F4CDE -:101CE0000F4801F00BFB21460D4801F033FB24683F -:101CF0000C48626DD2F8043843F00203C2F804388D -:101D000001F0E6FF0849204601F02AFC626DD2F896 -:101D1000043823F00203C2F8043810BDD05A00087A -:101D2000C037002040420F00D85A0008704700001A -:101D30000FB4002004B0704700B59BB0EFF30981E9 -:101D400068226846FFF74EFFEFF30583044B9A6B5A -:101D5000DA6A9A6A9A6A9A6A9A6A9A6A9B6AFEE741 -:101D600000ED00E000B59BB0EFF309816822684602 -:101D7000FFF738FFEFF30583044B9A6B9A6A9A6A70 -:101D80009A6A9A6A9A6A9B6AFEE700BF00ED00E0D1 -:101D900000B59BB0EFF3098168226846FFF722FF88 -:101DA000EFF30583034B5A6B9A6A9A6A9A6A9A6AA6 -:101DB0009B6AFEE700ED00E0FEE7000002F034BBA6 -:101DC00002F00CBB30B5094D0A4491420DD011F818 -:101DD000013B5840082340F30004013B2C4013F022 -:101DE000FF0384EA5000F6D1EFE730BD2083B8ED61 -:101DF000F7B54FF0FF33DFF854C0DFF854E000EBE5 -:101E000081011A4688421CD050F8044B019401AF5E -:101E1000042417F8015B82EA05620825DB181646E0 -:101E200005F1FF355241002EBCBF83EA0C0382EA64 -:101E30000E0215F0FF05F1D1013C14F0FF04E8D1CA -:101E4000E0E7D843D14303B0F0BD00BF9336EAA921 -:101E5000EBE1F0422DE9F041C56915B9C161BDE87A -:101E6000F0814B6823F06047C3F38A464FEAD37E84 -:101E7000C3F3807816EA230638BF3E46AC462B46AD -:101E80005A68BEEBD27F22F060440AD0002A18DAEA -:101E9000A40CB44217D19D420FD10D60DEE713466A -:101EA000EEE7A74207D102F08044C2F380724245B8 -:101EB0000BD054B1EFE708D2EDE7CCF800100B607F -:101EC000CDE7B44201D0B442E5D81A689C46002A56 -:101ED000E5D11960C3E700002DE9F047089D01F046 -:101EE00007044FEAD508224405F0070500EBD100AE -:101EF0004FF47F49944201D1BDE8F08704F0070711 -:101F000005F0070A57453E4638BF5646C6F1080653 -:101F1000111B8E4228BF0E46E10808EBD50E415C2E -:101F200013F80EC0B94029FA06F721FA0AF1FFB2F8 -:101F30008CEA010147FA0AF739408CEA010C03F8F0 -:101F40000EC034443544D5E780EA0120082341F22D -:101F5000210201B24000002980B203F1FF33B8BF73 -:101F6000504013F0FF03F4D17047000038B50C4621 -:101F70008D18A54200D138BD14F8011BFFF7E4FF0E -:101F8000F7E7000002684AB113680360C38801895B -:101F900001339BB29942C38038BF0381104670471A -:101FA00070B588B0202204460D4668460021FFF730 -:101FB0003FFE20460495FFF7E5FF024658B16B4609 -:101FC000054608AE1C4603CCB4422860696023462F -:101FD00005F10805F6D1104608B070BD082817D9DC -:101FE00009280CD00A280CD00B280CD00C280CD0B7 -:101FF0000D280CD00E2814BF4020302070470C2034 -:102000007047102070471420704718207047202018 -:1020100070470000082817D90C280CD910280CD9B3 -:1020200014280CD918280CD920280CD930288CBF9A -:102030000F200E207047092070470A2070470B20A0 -:1020400070470C2070470D207047000010B54B689A -:1020500023B9CA8A63F30902CA8210BDC4681A6828 -:102060001C60C360438A013B43824A60EFE7000083 -:102070002DE9F84F1D46CB8A0F46C3F30901062907 -:10208000814692460B4630D00020AAB207F11904CF -:102090009EB2052E1FFA80F80FD8904503F1010378 -:1020A00006D3FB8A0A4462F30903FB8201201AE08B -:1020B0001AF80060E6540130EAE79045F1D2A1F148 -:1020C000060B1C237C68BBFBF3F203FB12BB1FFA5D -:1020D0008BF6002C45D14846FFF754FF044638B92B -:1020E00078606FF00200BDE8F88F4FF00008E6E777 -:1020F000002606607860ADB24FF0000B454510D960 -:102100000AEB0803221D13F8011B9155B1B208F127 -:1021100001081B291FFA88F82BD0454506F1010656 -:10212000F1D8FB8AC3F30902154465F30903BCE740 -:10213000013292B21C462368002BF9D1AB1F0B442D -:102140001C21B3FBF1F301339BB29A42D3D2BBF112 -:10215000000FD0D14846FFF715FF20B9C4F800B0F2 -:10216000BFE70122E7E7C0F800B05E462060044602 -:10217000C1E74545D5D94846FFF704FF08B92060B7 -:10218000AFE7C0F800B0002620600446B6E70000C4 -:102190002DE9F04F2DED028B83B0CDE90013BDF892 -:1021A0003C5007469146002A00F092802DB10E9BCC -:1021B000002B00F08D80072D32D807F10C00FFF7BF -:1021C000E1FE044638B96FF00204204603B0BDECCE -:1021D000028BBDE8F08F14220021FFF729FD0E9934 -:1021E0002A4604F10800FFF7FDFC681CC0B2FFF7A7 -:1021F00011FFFFF7F3FE207499F80030013814FA4C -:1022000080F003F01F0363F03F030372009B43F071 -:102210000041616038462146FFF71CFE0124D4E7E7 -:1022200000F10C034FF0000808EE103A4FF0800A5E -:102230004646444618EE100AFFF7A4FE83460028DF -:10224000C1D014220021FFF7F3FCC6BB019BABF801 -:10225000083002200E9B00F1080299195BFA82F205 -:102260000130C0B2082801D0AE422AD3FFF7D2FE17 -:10227000FFF7B4FE99F80020009B411E02F01F02F8 -:1022800042EA4812AE4208BF4FF0400A5BFA81F1C1 -:102290004AEA020A43F0004281F808A08BF81000D5 -:1022A000CBF8042059463846FFF7D4FD0134AE423E -:1022B00024B288F001084FF0000ABBD185E7002066 -:1022C000C8E711F801CB02F801CB0136B6B2C7E777 -:1022D0006FF0010479E70000F8B515460E46282294 -:1022E000002104461F46FFF7A3FC069B6360B5F57B -:1022F000001F079BA76034BF6A094FF6FF72236275 -:1023000004F10C0097B200239A4205D80023036021 -:1023100027826382A382F8BD0660013330462036EF -:10232000F2E7000003781BB94BB2002BC8BF017065 -:1023300070470000007870472DE9F74FDDF83C90BA -:10234000BDF830500D9E9DF83840BDF84070804675 -:1023500092469B46B9F1000F01D1002F51D11F2C9D -:102360004FD898F80000B0B9072F47D835F00303CD -:1023700047D13A4649464FF6FF70FFF7F7FD20F088 -:1023800001002D02400445EA0464400C44EA402464 -:102390004FF6FF7321E040EA0520072F40EA04646E -:1023A000F6D900254FF6FF73C5F12000A5F12002F4 -:1023B0002AFA05F10BFA00F001432BFA02F211435D -:1023C0001846C9B2FFF7C0FD0835402D0346EBD1D2 -:1023D0003A464946FFF7CAFD0346CDE90097324623 -:1023E00021464046FFF7D4FE33780133DBB21F2B82 -:1023F00088BF0023337003B0BDE8F08F6FF0030097 -:10240000F9E76FF00100F6E72DE9F04F85B092464D -:10241000DDF848800F9D9DF840209DF84490BDF860 -:102420004C7006469B46B8F1000F01D1002F48D1F1 -:102430001F2A46D83378002B46D00C0244EA0264A7 -:102440009DF8381044EAC93444EA01441C43072F7C -:1024500044F0800432D900234FF6FF72C3F1200C00 -:10246000A3F120002AFA03F10BFA0CFC41EA0C015B -:102470002BFA00F00143C9B210460393FFF764FD45 -:10248000039B0833402B0246E8D13A464146FFF70A -:102490006DFD0346CDE900872A4621463046FFF709 -:1024A00077FEB9F1010F06D12B780133DBB21F2B78 -:1024B00088BF00232B7005B0BDE8F08F4FF6FF7387 -:1024C000E8E76FF00100F6E76FF00300F3E70000C4 -:1024D000C06900B104307047C3691A68C261C2683C -:1024E0001A60C360438A013B438270472DE9F04183 -:1024F000D0F81880194E14461D464146002709B9E8 -:10250000BDE8F081D1E90223A21A65EB03039642EC -:1025100077EB03031ED283698B420DD1FFF796FD43 -:1025200083691B688361C3680B60438AC1608169EA -:10253000013B43828846E2E7FFF788FD0B68C8F855 -:102540000030C3680B60438AC160013B4382D8F806 -:102550000010D4E788460968D1E700BF80841E00D8 -:102560002DE9F04F8BB00D46DDF8509014469B4698 -:102570008046002800F01981B9F1000F00F01581A4 -:10258000531E3F2B00F21181012A03D1BBF1000F32 -:1025900040F00B810023CDE90833B8F81430B5EBD7 -:1025A000C30F4FEAC30703D300200BB0BDE8F08F81 -:1025B0002B199F42D8F80C303ABF7F1BFFB2274639 -:1025C0001BB9D8F81030002B7AD02F2D4ED8C5F17A -:1025D0003006B7424FF000032CBFF6B23E460093E0 -:1025E0002946D8F8080008AB3246FFF775FCA7EB80 -:1025F000060A35445FFA8AFAB8F8143003F100533A -:10260000063BDB000493D8F80C3003933021039B86 -:1026100013B1BAF1000F2CD1D8F8100040B1BAF1C3 -:10262000000F05D0009608AB5246691AFFF754FC1C -:1026300038B2002FB8D066070AD00AAB03EBD4013A -:10264000624211F8083C02F00702134101F8083C0D -:10265000082C3CD9102C40F2B580202C40F2B780D9 -:10266000BBF1000F00F09C80082334E0BA4600263E -:10267000C2E7049BE02B28BFE02306930B44AB4248 -:10268000059314D95A1B03980096924534BF5246BD -:10269000D2B2691A08AB04300792FFF71DFC079A03 -:1026A0001644AAEB020A1544F6B25FFA8AFA049BB2 -:1026B000069A05999B1A0493039B1B680393A6E74C -:1026C0000093D8F8080008AB3A462946AEE7BBF1BC -:1026D000000F13D00123B4EBC30F6CD0082C12D819 -:1026E0009DF82030621E23FA02F2D50706D54FF07E -:1026F000FF3202FA04F423438DF820309DF8203095 -:1027000089F8003051E7102C12D8BDF82030621E35 -:1027100023FA02F2D10706D54FF0FF3202FA04F491 -:102720002343ADF82030BDF82030A9F800303CE755 -:10273000202C0FD80899631E21FA03F3DA0705D578 -:102740004FF0FF3202FA04F40C430894089BC9F8D6 -:1027500000302AE7402C2BD0DDE90865611EC4F16A -:102760002102A4F1210326FA01F105FA02F225FA69 -:1027700003F311431943CB0712D50122A4F120031F -:10278000C4F1200102FA03F322FA01F1A2405242FD -:1027900043EA010363EB430332432B43CDE90823B0 -:1027A000DDE90823C9E90023FFE66FF00100FCE63C -:1027B0006FF00800F9E6082CA0D9102CB3D9202C12 -:1027C000EED8C3E7BBF1000FADD0022383E7BBF126 -:1027D000000FBBD004237EE730B5012A144638BF72 -:1027E0000124402C85B028BF40240025012ACDE9D2 -:1027F000025518D81B788DF8083063070AD004AB4F -:1028000003EBD405624215F8083C02F0070293403E -:1028100005F8083C009103462246002102A8FFF774 -:102820005BFB05B030BD082AE4D9102A03D81B8809 -:10283000ADF80830E1E7202A8DBFD3E900231B68FB -:102840000293CDE90223D8E710B5CB681BB98B60A2 -:102850000B618B8210BDC4681A681C60C360438A18 -:10286000013B4382CA60F0E72DE9F04FD1F80080C8 -:1028700093B018F0800FCDE90323C8F3C01219BF3D -:10288000C8F3C03BC8F306264FF0020B1646B8F15A -:10289000000F04460D4680F2D18118F0C043059325 -:1028A00040F0CC810B7B002B00F0C881BBF1020F04 -:1028B00003D00178B14240F0C48108F07F01069155 -:1028C0006AB3C8F3074A2B44069A93F80390760636 -:1028D00046EA0B4646EA82465FEAD91346EA0A060A -:1028E000079300F0908000220023CDE90A23069B85 -:1028F000009367685B4652460AA92046B8470028FD -:102900007ED0A7699FB9314604F10C00FFF748FB60 -:102910000746E0B96FF0020013B0BDE8F08FC8F3CE -:102920000F2A18F07F0F08BF0AF0030ACBE73B69B4 -:102930009E420DD03F68002FF9D1314604F10C00C2 -:10294000FFF72EFB07460028E4D0A3693B60A76190 -:10295000DDE90A2300264FF6FF70C6F1200E22FAA9 -:1029600006F103FA0EFEA6F1200C23FA0CFC41EA54 -:102970000E0141EA0C01C9B2083609920893FFF72B -:10298000E3FA402EDDE90832E7D1B882FB7D09F099 -:102990001F06C3F384039B1BD7E9022198B2002BC7 -:1029A000BCBF00F120031BB252EA0100C8F3046867 -:1029B0000FD00398821A049860EB0101A748904257 -:1029C0004FF000028A4104D3079A002A5BD0012B02 -:1029D00023DDFA7D4FEA890302F0030203F07C0352 -:1029E0001343FB7539462046FFF730FB079BA3B91D -:1029F000FB7DC3F38402013262F38603FB7504E0BE -:102A00006FF00B0088E7A76917B96FF00C0083E738 -:102A10003B699E42BAD03F68F6E719F0400F32D0CA -:102A2000039BBB60049BFB60142200210DA8FFF7F1 -:102A3000FFF8039B0A93049B0B932B1D0C932B7B9A -:102A4000ADF83EA0013BDBB2ADF83C30069B8DF803 -:102A5000433094F824308DF840B083F001038DF8B2 -:102A600044308DF84160A3688DF842800AA9204661 -:102A70009847FB7DC3F38403013303F01F039B02DC -:102A8000FB82002048E7FB7DC9F34012B2EBD31F65 -:102A900040F0DA80C3F38403B34240F0D880079952 -:102AA0002B7B4FEA9912002934D0D20741D4032B53 -:102AB00040F2D080039BBB60049BFB602B7BAE1D70 -:102AC000033BDBB23246394604F10C00FFF7D0FA83 -:102AD00000280DDA20463946FFF7B8FAFB7DC3F32C -:102AE0008403013303F01F039B02FB82032013E7DF -:102AF000AB883B832A7B033AB88AD2B23146FFF7D0 -:102B000035FAFB7DB882DA43C2F3C01262F3C71311 -:102B1000FB75B6E76AB92E1D013BDBB2324639467A -:102B200004F10C00FFF7A4FA0028D3DB2A7B013A5A -:102B3000E2E7F98AC1F30901013B0529DAB259D864 -:102B4000281D002307F11A0C9A4208D910F801EB4E -:102B50000CF801E0013101330629DBB2F4D103990D -:102B60000A9104990B91934207F11A010C9138BF15 -:102B7000043379680D9134BF55FA83F300230E9323 -:102B8000FB8AADF83EA0C3F309031A44069B8DF8F7 -:102B9000433094F82430ADF83C2083F001038DF8E5 -:102BA000443000238DF840B08DF841608DF84280AC -:102BB0007B602A7BB88A013A291DFFF7D7F93B8B46 -:102BC000B882834203D1A3680AA9204698472046C9 -:102BD0000AA9FFF739FEFB7DB88AC3F384030133EA -:102BE00003F01F039B02FB823B8B984214BF112012 -:102BF000002091E67B68002BB1D0062001E01C305C -:102C00006346D3F800C0BCF1000FF8D1091A081DC3 -:102C100005F1040C00EB030905989DF8143001EB55 -:102C2000000EBEF11B0F9AD89A4298D91CF8013BAE -:102C300009F8013B059B01330593EDE76FF00900AF -:102C40006AE66FF00A0067E66FF00D0064E66FF069 -:102C50000E0061E66FF00F005EE600BF80841E008C -:102C6000404BF0B51C6C404E44F000741C641D6E6B -:102C700045F000751D661B6E3C4B9B6AD3F80052F5 -:102C8000354045F00105C3F80052D3F80042344006 -:102C900044EA002040F00100C3F80002002952D0AD -:102CA0000020C3F81C020546C3F80402C3F80C0256 -:102CB000C3F8140203EBC00401301C28C4F84052CE -:102CC000C4F84452F6D100254FF0010C96781488D0 -:102CD000F70748BFD3F804720CFA04F044BF074367 -:102CE000C3F80472B70742BFD3F80C720743C3F8A6 -:102CF0000C72760742BFD3F814620643C3F814621D -:102D000003EBC4045668C4F840629668C4F8446291 -:102D1000D3F81C4201352043A942C3F81C0202F13A -:102D20000C02D3D1D3F8002222F00102C3F8002212 -:102D30000C4B1A6C22F000721A641A6E22F00072A8 -:102D40001A661B6EF0BD0122C3F84012C3F844128C -:102D5000C3F80412C3F81412C3F80C22C3F81C22DF -:102D6000E0E700BF003802400000FFFFD835002038 -:102D7000184A916A08B58B688B6013F0010104D082 -:102D800013F00C0F18BF4FF48031D80506D513F49B -:102D9000406F14BF41F4003141F00201D80306D561 -:102DA00013F4402F14BF41F4802141F00401D36992 -:102DB0000BB108489847202383F311880648002167 -:102DC00000F0AEFF002383F31188BDE8084001F056 -:102DD00023BC00BFD8350020E035002038B5124CA8 -:102DE000A36ADD68AA0712D05A6922F002025A616A -:102DF000A36913B1012120469847202383F311884A -:102E00000A48002100F08CFF002383F31188EB06B1 -:102E100006D5A36A1021D960236A0BB102489847EE -:102E2000BDE8384001F0F8BBD8350020E835002077 -:102E300038B5124CA36A1D69AA0712D05A6922F04C -:102E400010025A61A36913B102212046984720233A -:102E500083F311880A48002100F062FF002383F306 -:102E60001188EB0606D5A36A10211961236A0BB1FC -:102E700002489847BDE8384001F0CEBBD835002065 -:102E8000E835002038B50F4CA36A5D685D602A07FD -:102E90000AD5042222701A6822F002021A60636ABC -:102EA00013B10021204698476B0706D5A36A99699C -:102EB000236A13B1034809049847BDE8384001F07C -:102EC000ABBB00BFD835002010B50E4C204600F03B -:102ED00029F90D4BA3620B21132000F00BF90B21F4 -:102EE000142000F007F90B21152000F003F90B2145 -:102EF000162000F0FFF80022BDE8104011460E2019 -:102F0000FFF7AEBED835002000640040114B984258 -:102F100010B5044609D1104B1A6C42F000721A64C5 -:102F20001A6E42F000721A661B6EA36A01221A60C2 -:102F3000A36A5A68D20707D5626851681268D961D6 -:102F40001A60064A5A6110BD0121082000F0D4FD24 -:102F5000EEE700BFD8350020003802405B87010053 -:102F600003291AD8DFE801F0020A0F14836A9B686C -:102F700013F0E05F14BF012000207047836A986857 -:102F8000C0F380607047836A9868C0F3C060704780 -:102F9000836A9868C0F30070704700207047000093 -:102FA00010B5032925D8DFE801F00225292D836A11 -:102FB0009968C1F30161183103EB0113107884069D -:102FC0004CBF54689488C0F300114FEA410148BFD8 -:102FD00041EAC40100F00F004CBF41F0040141EA96 -:102FE0004451586041F001019068D2689860DA60FD -:102FF000196010BD836A03F5C073DFE7836A03F5C8 -:10300000C873DBE7836A03F5D073D7E701290AD0D9 -:1030100002290FD081B9836ADA68920701D1186951 -:1030200003E001207047836AD86810F0030018BFDE -:1030300001207047836AF2E70020704710B539B964 -:10304000836AD96889071BD11B699C0704D110BD0D -:10305000012915D00229FAD1816AD1F8C031D1F8FD -:10306000C441D1F8C8011061D1F8CC0150612020D1 -:1030700008610869800717D1486940F0100012E024 -:10308000816AD1F8B031D1F8B441D1F8B8011061FA -:10309000D1F8BC0150612020C860C868800703D106 -:1030A000486940F002004861C3F34000C3F3800167 -:1030B000000140EA4111107920F030000143117104 -:1030C00089064BBF91681189DB085B0D4CBF63F328 -:1030D0001C0163F30A01137948BF916064F3030391 -:1030E00013714FEA14234FEA144458BF118113702F -:1030F0005480ACE700F1604303F561430901C9B2B4 -:1031000083F80013012200F01F039A4043099B003B -:1031100003F1604303F56143C3F880211A607047EF -:10312000FFF7D2BE012300F10802C0E902220370BA -:1031300000F110020023C0E90422C0E90633C0E90F -:10314000083343607047000010B52023044683F322 -:103150001188022303704160FFF7D8FE0423237017 -:10316000002383F3118810BD2DE9F0411F4604466A -:103170000D461646202383F3118800F108082378B2 -:10318000052B0DD029462046FFF7EAFE40B1204628 -:1031900032462946FFF704FF002080F3118808E03B -:1031A0003946404600F0A0FD0028E8D0002383F314 -:1031B0001188BDE8F08100002DE9F0411F4604466A -:1031C0000D461646202383F3118800F1100823785A -:1031D000052B0DD029462046FFF718FF40B12046A9 -:1031E00032462946FFF72AFF002080F3118808E0C5 -:1031F0003946404600F078FD0028E8D0002383F3EC -:103200001188BDE8F0810000026843681143016045 -:1032100003B118477047000013B5446BD4F89434D9 -:103220001A681178042915D1217C022912D1197943 -:10323000128901238B4013420CD101A904F14C00E7 -:1032400001F0A8FFD4F89444019B2179024620683C -:1032500000F0CEF902B010BD143001F02BBF000019 -:103260004FF0FF33143001F025BF00004C3001F067 -:10327000FDBF00004FF0FF334C3001F0F7BF0000FE -:10328000143001F0F9BE00004FF0FF31143001F0AE -:10329000F3BE00004C3001F0C9BF00004FF0FF3218 -:1032A0004C3001F0C3BF00000020704710B5D0F8CB -:1032B00094341A6811780429044617D1017C022934 -:1032C00014D15979528901238B4013420ED1143005 -:1032D00001F08CFE024648B1D4F894444FF4807358 -:1032E00061792068BDE8104000F070B910BD0000A1 -:1032F000406BFFF7DBBF0000704700007FB5124B4B -:10330000036000234360C0E90233012502260F4B0E -:10331000057404460290019300F184022946009648 -:103320004FF48073143001F03DFE094B0294CDE957 -:10333000006304F523724FF48073294604F14C00B6 -:1033400001F004FF04B070BD0C5A0008F13200080F -:10335000193200080B68202282F311880A7903EBE6 -:10336000820290614A79093243F822008A7912B1C7 -:1033700003EB8203986102230374C0F894140023C2 -:1033800083F311887047000038B5037F044613B1FA -:1033900090F85430ABB9201D01250221FFF734FF0E -:1033A00004F1140025776FF0010100F0B9FC84F8F6 -:1033B000545004F14C006FF00101BDE8384000F0BA -:1033C000AFBC38BD10B5012104460430FFF71CFF27 -:1033D0000023237784F8543010BD000038B504462C -:1033E0000025143001F0F6FD04F14C00257701F0C2 -:1033F000C5FE201D84F854500121FFF705FF20462B -:10340000BDE83840FFF752BF90F8443003F0600346 -:10341000202B07D190F84520212A4FF0000303D834 -:103420001F2A06D800207047222AFBD1C0E90E339C -:1034300003E0034A82630722C263036401207047EA -:103440002523002037B5D0F894341A681178042960 -:1034500004461AD1017C022917D119791289012356 -:103460008B40134211D100F14C05284601F046FF74 -:1034700058B101A9284601F08DFED4F89444019B6F -:1034800021790246206800F0B3F803B030BD000097 -:10349000F0B500EB810385B09E6904460D46FEB190 -:1034A000202383F3118804EB8507301D0821FFF7E3 -:1034B000ABFEFB685B691B6806F14C001BB1019019 -:1034C00001F076FE019803A901F064FE024648B1BE -:1034D000039B2946204600F08BF8002383F31188D4 -:1034E00005B0F0BDFB685A691268002AF5D01B8A46 -:1034F000013B1340F1D104F14402EAE7093138B548 -:1035000050F82140DCB1202383F31188D4F89424AF -:103510001368527903EB8203DB689B695D6845B1F0 -:1035200004216018FFF770FE294604F1140001F031 -:1035300067FD2046FFF7BAFE002383F3118838BDEC -:103540007047000001F02AB9012303700023C0E98D -:103550000133C36183620362C362436203637047E2 -:1035600038B50446202383F311880025C0E90355AC -:10357000C0E90555416001F021F90223237085F36C -:10358000118838BD70B500EB810305465069DA60DB -:103590000E46144618B110220021FEF749FBA0691F -:1035A00018B110220021FEF743FB31462846BDE842 -:1035B000704001F0CDB90000826802F00112826013 -:1035C0000022C0E90422826101F04EBAF0B400EB9F -:1035D00081044789E4680125A4698D403D43458104 -:1035E00023600023A2606360F0BC01F069BA0000B0 -:1035F000F0B400EB81040789E468012564698D401B -:103600003D43058123600023A2606360F0BC01F0AC -:10361000E3BA000070B50223002504460370C0E938 -:103620000255C0E90455C564856180F8345001F045 -:103630002BF963681B6823B129462046BDE870401A -:10364000184770BD037880F8503005230370436835 -:103650001B6810B504460BB1042198470023A360F2 -:1036600010BD000090F85020436802701B680BB139 -:10367000052118477047000070B590F834300446B3 -:1036800013B1002380F8343004F14402204601F0E5 -:103690000DFA63689B68B3B994F8443013F0600581 -:1036A00035D00021204601F05FFC0021204601F0CA -:1036B00051FC63681B6813B1062120469847062316 -:1036C00084F8343070BD204698470028E4D0B4F820 -:1036D0004A30E26B9A4288BFE36394F94430E56B69 -:1036E000002B4FF0200380F20381002D00F0F280C8 -:1036F000092284F8342083F311880021D4E90E23B1 -:103700002046FFF775FF002383F31188DAE794F86A -:10371000452003F07F0343EA022340F20232934242 -:1037200000F0C58021D8B3F5807F48D00DD8012B9B -:103730003FD0022B00F09380002BB2D104F14C0259 -:10374000A2630222E2632364C1E7B3F5817F00F044 -:103750009B80B3F5407FA4D194F84630012BA0D1D3 -:10376000B4F84C3043F0020332E0B3F5006F4DD0B3 -:1037700017D8B3F5A06F31D0A3F5C063012B90D853 -:10378000636894F846205E6894F84710B4F84830AF -:103790002046B047002884D04368A3630368E363EE -:1037A0001AE0B3F5106F36D040F6024293427FF430 -:1037B00078AF5C4BA3630223E3630023C3E794F871 -:1037C0004630012B7FF46DAFB4F84C3023F0020388 -:1037D000C4E90E55A4F84C30256478E7B4F84430B9 -:1037E000B3F5A06F0ED194F8463084F84E302046E1 -:1037F00001F0A2F863681B6813B1012120469847C5 -:10380000032323700023C4E90E339CE704F14F0324 -:10381000A3630123C3E72378042B10D1202383F370 -:1038200011882046FFF7C8FE85F3118803216368DD -:1038300084F84F5021701B680BB12046984794F8CC -:103840004630002BDED084F84F30042323706368A9 -:103850001B68002BD6D0022120469847D2E794F867 -:1038600048301D0603F00F0120460AD501F010F97B -:10387000012804D002287FF414AF2B4B9AE72B4B7E -:1038800098E701F0F7F8F3E794F84630002B7FF45F -:1038900008AF94F8483013F00F01B3D01A06204651 -:1038A00002D501F075FBADE701F068FBAAE794F8DB -:1038B0004630002B7FF4F5AE94F8483013F00F013A -:1038C000A0D01B06204602D501F04EFB9AE701F07E -:1038D00041FB97E7142284F8342083F311882B46A8 -:1038E0002A4629462046FFF771FE85F31188E9E64E -:1038F0005DB1152284F8342083F311880021D4E9C6 -:103900000E232046FFF762FEFDE60B2284F83420EA -:1039100083F311882B462A4629462046FFF768FE86 -:10392000E3E700BF3C5A0008345A0008385A000840 -:1039300038B590F834300446002B3ED0063BDAB25E -:103940000F2A34D80F2B32D8DFE803F03731310893 -:10395000223231313131313131313737C56BB0F845 -:103960004A309D4214D2C3681B8AB5FBF3F203FBB5 -:1039700012556DB9202383F311882B462A46294618 -:10398000FFF736FE85F311880A2384F834300EE001 -:10399000142384F83430202383F3118800231A463B -:1039A00019462046FFF712FE002383F3118838BD25 -:1039B000036C03B198470023E7E70021204601F09C -:1039C000D3FA0021204601F0C5FA63681B6813B1E1 -:1039D0000621204698470623D7E7000010B590F847 -:1039E0003430142B044629D017D8062B05D001D823 -:1039F0001BB110BD093B022BFBD80021204601F072 -:103A0000B3FA0021204601F0A5FA63681B6813B1E0 -:103A1000062120469847062319E0152BE9D10B23F0 -:103A200080F83430202383F3118800231A46194686 -:103A3000FFF7DEFD002383F31188DAE7C3689B6993 -:103A40005B68002BD5D1036C03B19847002384F841 -:103A50003430CEE7024B0022C3E900339A6070474E -:103A600004360020002303748268054B1B689968A4 -:103A70009142FBD25A680360426010605860704700 -:103A80000436002008B5202383F31188037C032B20 -:103A900005D0042B0DD02BB983F3118808BD4369E1 -:103AA00000221A604FF0FF334361FFF7DBFF002372 -:103AB000F2E7D0E9003213605A60F3E700230374A1 -:103AC0008268054B1B6899689142FBD85A6803606D -:103AD000426010605860704704360020054B196939 -:103AE0000874186802681A6053601861012303742F -:103AF000FCF78EBD0436002030B54B1C0B4D87B053 -:103B0000044610D02B690A4A01A800F025F9204686 -:103B1000FFF7E4FF049B13B101A800F059F92B69EA -:103B2000586907B030BDFFF7D9FFF8E70436002029 -:103B3000853A000838B50C4D41612B6981689A6857 -:103B40009142044603D8BDE83840FFF78BBF1846C2 -:103B5000FFF7B4FF01232C61014623742046BDE822 -:103B60003840FCF755BD00BF04360020044B1A68EE -:103B70001B6990689B68984294BF002001207047A1 -:103B80000436002010B5084C236820691A682260AA -:103B90005460012223611A74FFF790FF01462069E7 -:103BA000BDE81040FCF734BD0436002008B5FFF72F -:103BB000DDFF18B1BDE80840FFF7E4BF08BD000015 -:103BC000FFF7E0BFFEE7000010B50C4CFFF742FF27 -:103BD00000F0B4F80A498022204600F03BF80123A7 -:103BE00044F8180C037400F0F3FC002383F31188ED -:103BF00062B60448BDE8104000F04CB82C360020F6 -:103C0000405A0008505A000800F01CB9EFF3118028 -:103C100020B9EFF30583202282F31188704700005A -:103C200010B530B9EFF30584C4F3080414B180F380 -:103C3000118810BDFFF7BAFF84F31188F9E700007F -:103C4000034A516853685B1A9842FBD8704700BF1B -:103C5000001000E082600222028270478368A3F1B4 -:103C60007C0243F80C2C026943F83C2C426943F86F -:103C7000382C074A43F81C2CC26843F8102C022247 -:103C800003F8082C002203F8072CA3F11800704752 -:103C90002906000810B5202383F31188FFF7DEFF03 -:103CA00000210446FFF746FF002383F311882046D6 -:103CB00010BD0000024B1B6958610F20FFF70EBFBB -:103CC00004360020202383F31188FFF7F3BF0000A0 -:103CD00008B50146202383F311880820FFF70CFF65 -:103CE000002383F3118808BD49B1064B42681B6964 -:103CF00018605A60136043600420FFF7FDBE4FF068 -:103D0000FF307047043600200368984206D01A68D6 -:103D10000260506059611846FFF7A4BE704700006A -:103D200038B504460D462068844200D138BD03688A -:103D300023605C604561FFF795FEF4E7054B03F1F6 -:103D40001402C3E905224FF0FF310022C3E9071234 -:103D5000704700BF0436002070B51C4EC0E9032335 -:103D600005460C4601F0FCFA334653F8142F9A42EC -:103D70000DD13062C5E901242A600A2C2CBF00193C -:103D80000A30C6E90555BDE8704001F0D7BA316A7E -:103D9000431AE31838BF1C469368A34202D9081996 -:103DA00001F0DAFA73699A6894420CD85A68AC60E8 -:103DB0002B606A6015609A685D60121B9A604FF014 -:103DC000FF33F36170BD1B68A41AECE704360020D2 -:103DD00038B51B4C636998420DD0D0E900321360AE -:103DE0005A6000228168C2609A680A449A604FF063 -:103DF000FF33E36138BD2246036842F8143F0021D7 -:103E000093425A60C16003D1BDE8384001F09EBAC8 -:103E10009A688168256A0A449A6001F0A1FA636988 -:103E20009A68411B8A42E5D9AB181D1A092D206AF0 -:103E300098BF01F10A02BDE83840104401F08CBA85 -:103E4000043600202DE9F041184C002704F1140637 -:103E5000656901F085FA236AAA68C11A8A4215D8F1 -:103E600013442362D5E9003213605A606369D5F8C0 -:103E70000C80EF60B34201D101F068FA87F311883A -:103E80002869C047202383F31188E1E76169B142C3 -:103E900009D013441B1ABDE8F0410A2B2CBFC018EF -:103EA0000A3001F059BABDE8F08100BF04360020A5 -:103EB00000207047FEE70000704700004FF0FF3021 -:103EC0007047000002290CD0032904D001290748BB -:103ED00018BF00207047032A05D8054800EBC20030 -:103EE0007047044870470020704700BF345B0008EB -:103EF00034230020E85A000870B59AB005460846F9 -:103F000001A9144600F0C2F801A8FDF789FE431C80 -:103F10005B00C5E900340022237003236370C6B23E -:103F200001AB02341046D1B28E4204F1020401D832 -:103F30001AB070BD13F8011B04F8021C04F8010C40 -:103F40000132F0E708B5202383F311880348FFF717 -:103F500079FA002383F3118808BD00BFC037002021 -:103F600090F8443003F01F02012A07D190F8452051 -:103F70000B2A03D10023C0E90E3315E003F06003E0 -:103F8000202B08D1B0F848302BB990F84520212AD1 -:103F900003D81F2A04D8FFF737BA222AEBD0FAE752 -:103FA000034A82630722C26303640120704700BF93 -:103FB0002C23002007B5052917D8DFE801F01916D2 -:103FC00003191920202383F31188104A019001213D -:103FD000FFF7D8FA01980E4A0221FFF7D3FA0D48ED -:103FE000FFF7FCF9002383F3118803B05DF804FBAD -:103FF000202383F311880748FFF7C6F9F2E720234F -:1040000083F311880348FFF7DDF9EBE7885A0008CE -:10401000AC5A0008C037002038B50C4D0C4C0D4987 -:104020002A4604F10800FFF767FF05F1CA0204F110 -:1040300010000949FFF760FF05F5CA7204F1180086 -:104040000649BDE83840FFF757BF00BF883C002055 -:1040500034230020685A0008725A00087D5A00086C -:1040600070B5044608460D46FDF7DAFDC6B2204697 -:10407000013403780BB9184670BD32462946FDF766 -:10408000BBFD0028F3D10120F6E700002DE9F04741 -:1040900005460C46FDF7C4FD2B49C6B22846FFF77E -:1040A000DFFF08B10636F6B228492846FFF7D8FFE9 -:1040B00008B11036F6B2632E0BD8DFF88C80DFF82B -:1040C0008C90234FDFF894A02E7846B92670BDE877 -:1040D000F08729462046BDE8F04701F005BC252EB3 -:1040E0002ED1072241462846FDF786FD70B9194BAF -:1040F000224603F10C0153F8040B42F8040B8B42E7 -:10410000F9D11B78137007350D34DDE708224946D5 -:104110002846FDF771FD98B90F4BA21C19780909C3 -:104120000232C95D02F8041C13F8011B01F00F01F3 -:104130005345C95D02F8031CF0D118340835C3E7B4 -:1041400004F8016B0135BFE7545B00087D5A000895 -:104150006A5B00085C5B0008107AFF1F1C7AFF1F77 -:10416000BFF34F8F024AD368DB03FCD4704700BF14 -:10417000003C024008B5094B1B7873B9FFF7F0FF0C -:10418000074B1A69002ABFBF064A5A6002F18832FB -:104190005A601A6822F480621A6008BDE63E002068 -:1041A000003C02402301674508B50B4B1B7893B9CF -:1041B000FFF7D6FF094B1A6942F000421A611A68EC -:1041C00042F480521A601A6822F480521A601A6807 -:1041D00042F480621A6008BDE63E0020003C0240C6 -:1041E0000B28F0B516D80C4C0C4923787BB90C4D34 -:1041F0000E460C234FF0006255F8047B46F8042B62 -:10420000013B13F0FF033A44F6D10123237051F828 -:104210002000F0BD0020FCE7183F0020E83E002011 -:104220007C5B0008014B53F8200070477C5B000862 -:104230000C2070470B2810B5044601D9002010BD92 -:10424000FFF7CEFF064B53F824301844C21A0BB9BF -:104250000120F4E712680132F0D1043BF6E700BF19 -:104260007C5B00080B2838B5044628D8FFF7CEFC45 -:10427000FFF776FFFFF77EFF124AF323D360E300D8 -:10428000DBB243F4007343F002031361136943F498 -:104290008033136105462046FFF762FFFFF7A0FF5A -:1042A000094B53F8241000F039F92846FFF77CFF3A -:1042B000FFF7B6FC2046BDE83840FFF7BBBF002043 -:1042C00038BD00BF003C02407C5B000812F00103D7 -:1042D0002DE9F04105460E4614464BD18218B2F145 -:1042E000016F61D8314B1B6813F001035CD0304F74 -:1042F000FFF78CFCFFF73EFFF323FB60FFF730FF77 -:10430000314640F20128032C18D824F00104284E2D -:104310000C446D1A40F20118A142336905EB010704 -:104320002AD123F001033361FFF73EFFFFF778FC4A -:104330000120BDE8F081043C0435E4E7AB07E4D19B -:104340003B6923F440733B613B6943EA08033B61EB -:1043500051F8046B2E60BFF34F8FFFF701FF2B68FE -:104360009E42E8D03B6923F001033B61FFF71CFF4D -:10437000FFF756FC0020DCE723F440733361336918 -:1043800043EA080333610B883B80BFF34F8FFFF78D -:10439000E7FE3F8831F8023BBFB2BB42BCD0336975 -:1043A00023F001033361E1E71846C2E70038024019 -:1043B000003C0240084908B50B7828B11BB9FFF74B -:1043C000D9FE01230B7008BD002BFCD0BDE80840CE -:1043D0000870FFF7E9BE00BFE63E002070B582B06E -:1043E000FFF714FC0E4E054600F0BAFF326890420B -:1043F00037BF0C4A0B49516814682EBFD1E9004100 -:10440000013151600419034641F100012846019130 -:104410003360FFF705FC0199204602B070BD00BF74 -:104420001C3F0020203F002070B582B0FFF7EEFB5C -:10443000104E054600F094FF3268904237BF0E4A96 -:104440000D49516814682EBFD1E900410131516016 -:10445000041941F100010346284601913360FFF73A -:10446000DFFB01994FF47A7200232046FBF7B8FE78 -:1044700002B070BD1C3F0020203F002010B5024458 -:10448000064BD2B2904200D110BD441C00B253F88A -:10449000200041F8040BE0B2F4E700BF50280040D0 -:1044A0000F4B30B51C6F240407D41C6F44F4007408 -:1044B0001C671C6F44F400441C670A4C236843F4D7 -:1044C000807323600244084BD2B2904200D130BDC9 -:1044D000441C00B251F8045B43F82050E0B2F4E70A -:1044E00000380240007000405028004007B501220B -:1044F00001A90020FFF7C2FF019803B05DF804FB9B -:1045000013B50446FFF7F2FFA04205D0012201A92E -:1045100000200194FFF7C4FF02B010BD70470000F7 -:10452000074B45F255521A6002225A6040F6FF725C -:104530009A604CF6CC421A60024B01221A70704706 -:10454000003000402C3F0020034B1B781BB1034B75 -:104550004AF6AA221A6070472C3F00200030004023 -:10456000034B1A681AB9034AD2F874281A607047C4 -:10457000283F002000300240024B4FF08072C3F809 -:10458000742870470030024008B5FFF7E9FF024B7E -:104590001868C0F3407008BD283F002008B5FFF739 -:1045A000DFFF024B1868C0F3007008BD283F0020F1 -:1045B000EFF3098305494A6B22F001024A6368332D -:1045C00083F30988002383F31188704700EF00E02C -:1045D000202080F3118862B60C4B0D4AD96821F473 -:1045E000E0610904090C0A43DA60D3F8FC200949A8 -:1045F00042F08072C3F8FC200A6842F001020A60AF -:104600001022DA7783F82200704700BF00ED00E047 -:104610000003FA05001000E010B5202383F3118891 -:104620000E4B5B6813F4006314D0F1EE103AEFF315 -:104630000984683C4FF08073E361094BDB6B2366B0 -:1046400084F30988FFF792FA10B1064BA36110BDFD -:10465000054BFBE783F31188F9E700BF00ED00E0AD -:1046600000EF00E03B0600083E060008704700002F -:10467000FEE700000A4B0B480B4A90420BD30B4B52 -:10468000DA1C121AC11E22F003028B4238BF00222C -:104690000021FDF7CDBA53F8041B40F8041BECE7EA -:1046A000345D0008284000202840002028400020D9 -:1046B0007047000070B5D0E915439E6800224FF0A6 -:1046C000FF3504EB42135101D3F800090028BEBFA7 -:1046D000D3F8000940F08040C3F80009D3F8000B7C -:1046E0000028BEBFD3F8000B40F08040C3F8000B99 -:1046F000013263189642C3F80859C3F8085BE0D248 -:104700004FF00113C4F81C3870BD00001D4B03EBC3 -:1047100080022DE9F043D2F80CC05D6DDCF8142066 -:10472000461CD2F800E005EB063605EB4018516850 -:1047300071450AD3D5F83438012202FA00F023EA91 -:104740000000C5F83408BDE8F083BCF81040AEEBBB -:104750000103A34228BF2346D8F81849A4B2B3EBFB -:10476000840FF0D89468A4F1040959F8047F3760E5 -:10477000A4EB09071F44042FF7D81C440B44946092 -:104780005360D4E7303F0020890141F020010161EE -:1047900003699B06FCD41220FFF752BA10B5054CF2 -:1047A0002046FEF7D1FE4FF0A0436365024BA365A0 -:1047B00010BD00BF303F0020D05B000870B503780B -:1047C000012B054650D12A4B446D98421BD1294BF1 -:1047D0005A6B42F080025A635A6D42F080025A6569 -:1047E0005A6D5A6942F080025A615A6922F0800279 -:1047F0005A610E2143205B69FEF77CFC1E4BE3608F -:104800001E4BC4F800380023C4F8003EC0232360C8 -:104810006E6D4FF40413A3633369002BFCDA01239C -:1048200033610C20FFF70CFA3369DB07FCD412204C -:10483000FFF706FA3369002BFCDA0026A66028464B -:10484000FFF738FF6B68C4F81068DB68C4F81468B9 -:10485000C4F81C684BB90A4BA3614FF0FF33636186 -:10486000A36843F00103A36070BD064BF4E700BFEB -:10487000303F002000380240401400400300200276 -:10488000003C30C0083C30C0F8B5446D05460021FE -:104890002046FFF779FFA96D00234FF001128F68C2 -:1048A000C4F834384FF00066C4F81C284FF0FF30CD -:1048B00004EB431201339F42C2F80069C2F8006B57 -:1048C000C2F80809C2F8080BF2D20B686A6DEB65F2 -:1048D000636210231361166916F01006FBD11220D3 -:1048E000FFF7AEF9D4F8003823F4FE63C4F80038BB -:1048F000A36943F4402343F01003A3610923C4F8E0 -:104900001038C4F814380A4BEB604FF0C043C4F8B9 -:10491000103B084BC4F8003BC4F81069C4F80039D8 -:10492000EB6D03F1100243F48013EA65A362F8BD56 -:10493000AC5B000840800010426D90F84E10D2F839 -:10494000003823F4FE6343EA0113C2F800387047CD -:104950002DE9F84300EB8103456DDA68166806F02F -:104960000306731E022B05EB41130C4680460FFA1B -:1049700081F94FEA41104FF00001C3F8101B4FF0CE -:10498000010104F1100398BFB60401FA03F3916921 -:104990008EBF334E06F1805606F5004600293AD008 -:1049A000578A04F15801490137436F50D5F81C1854 -:1049B0000B43C5F81C382B180021C3F81019536994 -:1049C0000127611EA7409BB3138A928B9B08012A83 -:1049D00088BF5343D8F85C20981842EA034301F19A -:1049E000400205EB8202C8F85C002146536028466D -:1049F000FFF7CAFE08EB8900C3681B8A43EA8453A9 -:104A0000483464011E432E51D5F81C381F43C5F8A5 -:104A10001C78BDE8F88305EB4917D7F8001B21F493 -:104A20000041C7F8001BD5F81C1821EA0303C0E7B2 -:104A300004F13F0305EB83030A4A5A6028462146E6 -:104A4000FFF7A2FE05EB4910D0F8003923F400432C -:104A5000C0F80039D5F81C3823EA0707D7E700BFAC -:104A60000080001000040002826D1268C265FFF72A -:104A700021BE00005831436D49015B5813F40040DA -:104A800004D013F4001F0CBF022001207047000067 -:104A90004831436D49015B5813F4004004D013F4CE -:104AA000001F0CBF022001207047000000EB8101B5 -:104AB000CB68196A0B6813604B685360704700003D -:104AC00000EB810330B5DD68AA691368D36019B9BA -:104AD000402B84BF402313606B8A1468426D1C44D2 -:104AE000013CB4FBF3F46343033323F0030302EB11 -:104AF000411043EAC44343F0C043C0F8103B2B6865 -:104B000003F00303012B09B20ED1D2F8083802EBEF -:104B1000411013F4807FD0F8003B14BF43F0805362 -:104B200043F00053C0F8003B02EB4112D2F8003BC7 -:104B300043F00443C2F8003B30BD00002DE9F041D2 -:104B4000244D6E6D06EB40130446D3F8087BC3F882 -:104B5000087B38070AD5D6F81438190706D505EBAF -:104B600084032146DB6828465B689847FA071FD50F -:104B7000D6F81438DB071BD505EB8403D968CCB90C -:104B80008B69488A5A68B2FBF0F600FB16228AB994 -:104B90001868DA6890420DD2121AC3E90024202363 -:104BA00083F311880B482146FFF78AFF84F31188AD -:104BB000BDE8F081012303FA04F26B8923EA0203C2 -:104BC0006B81CB68002BF3D021460248BDE8F04151 -:104BD000184700BF303F002000EB810370B5DD684F -:104BE000436D6C692668E6604A0156BB1A444FF46F -:104BF0000020C2F810092A6802F00302012A0AB252 -:104C00000ED1D3F8080803EB421410F4807FD4F8D7 -:104C1000000914BF40F0805040F00050C4F8000973 -:104C200003EB4212D2F8000940F00440C2F8000938 -:104C3000D3F83408012202FA01F10143C3F8341811 -:104C400070BD19B9402E84BF4020206020682E8A94 -:104C50008419013CB4FBF6F440EAC44040F0005033 -:104C60001A44C6E7F8B504461E48456D05EB4413E3 -:104C7000D3F80869C3F80869F10717D5D5F81038D3 -:104C8000DA0713D500EB8403D9684B691F68DA682B -:104C9000974218D2D21B00271A605F60202383F34B -:104CA00011882146FFF798FF87F31188330617D53F -:104CB000D5F834280123A340134211D02046BDE883 -:104CC000F840FFF723BD012303FA04F2038923EA26 -:104CD000020303818B68002BE8D021469847E5E763 -:104CE000F8BD00BF303F00202DE9F74F984C666DAE -:104CF0007569B3691D4015F48058756107D0204669 -:104D0000FEF788FC03B0BDE8F04FFFF785BC002D2F -:104D100012DAD6F8003E8E489F071EBFD6F8003E36 -:104D200023F00303C6F8003ED6F8043823F001034D -:104D3000C6F80438FEF796FC280505D58448FFF729 -:104D4000B9FC8348FEF77EFCA9040CD5D6F80838D8 -:104D500013F0060FF36823F470530CBF43F41053A1 -:104D600043F4A053F3602A0704D56368DB680BB1F2 -:104D700077489847EB0274D4AF0227D5D4F8549003 -:104D8000DFF8CCB100274FF0010A09EB4712D2F847 -:104D9000003B03F44023B3F5802F11D1D2F8003B40 -:104DA000002B0DDA62890AFA07F322EA0303638112 -:104DB00004EB8703DB68DB6813B139465846984734 -:104DC000A36D01379B68FFB29F42DED9E80617D575 -:104DD000676D3A6AC2F30A1002F00F0302F4F01290 -:104DE000B2F5802F00F08880B2F5402F08D104EB97 -:104DF00083030022DB681B6A07F5805790426DD160 -:104E00002903D6F8184813D5E20302D50020FFF78E -:104E100095FEA30302D50120FFF790FE670302D59C -:104E20000220FFF78BFE260302D50320FFF786FE44 -:104E30006D037FF567AFE00702D50020FFF712FF93 -:104E4000A10702D50120FFF70DFF620702D502205E -:104E5000FFF708FF23077FF555AF0320FFF702FF99 -:104E600050E7636DDFF8E8B0019300274FF0010AC7 -:104E7000A36D9B685FFA87F999453FF67DAF019B6B -:104E800003EB4913D3F8002902F44022B2F5802F36 -:104E900022D1D3F80029002A1EDAD3F8002942F0E3 -:104EA0009042C3F80029D3F80029002AFBDB606D8B -:104EB0004946FFF769FC22890AFA09F322EA03034B -:104EC000238104EB8903DB689B6813B1494658468C -:104ED00098474846FFF71AFC0137C9E7910708BF12 -:104EE000D7F80080072A98BF03F8018B02F101026E -:104EF00098BF4FEA182881E7023304EB830207F5D5 -:104F000080575268D2F818C0DCF80820DCE9001C91 -:104F1000A1EB0C0C002188420AD104EB83046368E6 -:104F20009B699A6802449A605A6802445A6067E72B -:104F300011F0030F08BFD7F800808C4588BF02F836 -:104F4000018B01F1010188BF4FEA1828E3E700BF98 -:104F5000303F0020436D03EB4111D1F8003B43F497 -:104F60000013C1F8003B7047436D03EB4111D1F8CA -:104F7000003943F40013C1F800397047436D03EB67 -:104F80004111D1F8003B23F40013C1F8003B7047F6 -:104F9000436D03EB4111D1F8003923F40013C1F83C -:104FA0000039704730B5039C0172043304FB0325BC -:104FB000C0E90653049B03630021059BC160C0E95F -:104FC0000000C0E90422C0E90842C0E90A114363B5 -:104FD00030BD0000416A0022C0E90411C0E90A2284 -:104FE000C2606FF00101FEF79BBE0000D0E9043201 -:104FF000934201D1C2680AB9181D7047002070475A -:1050000003691960C2680132C260C26913448269CF -:105010000361934224BF436A03610021FEF774BE1B -:1050200038B504460D46E3683BB16269131D12684A -:10503000A3621344E362002007E0237A33B92946D0 -:105040002046FEF751FE0028EDDA38BD6FF0010072 -:10505000FBE70000C368C269013BC36043691344B6 -:1050600082694361934224BF436A436100238362A0 -:10507000036B03B11847704770B52023044683F3D0 -:105080001188866A3EB9FFF7CBFF054618B186F353 -:105090001188284670BDA36AE26A13F8015BA36217 -:1050A000934202D32046FFF7D5FF002383F31188F4 -:1050B000EFE700002DE9F84F04460E4617469846E4 -:1050C0004FF0200989F311880025AA46D4F828B0AA -:1050D000BBF1000F09D141462046FFF7A1FF20B1E7 -:1050E0008BF311882846BDE8F88FD4E90A12A7EBA4 -:1050F000050B521A934528BF9346BBF1400F1BD9AD -:10510000334601F1400251F8040B43F8040B91427D -:10511000F9D1A36A40334036A3624035D4E90A236B -:105120009A4202D32046FFF795FF8AF31188BD42C9 -:10513000D8D289F31188C9E730465A46FCF752FDA8 -:10514000A36A5B445E44A3625D44E7E710B5029C3A -:105150000172043304FB0321C0E906130023C0E9F4 -:105160000A33039B0363049BC460C0E90000C0E9E9 -:105170000422C0E90842436310BD0000026AC26015 -:10518000426AC0E904220022C0E90A226FF001014C -:10519000FEF7C6BDD0E904239A4201D1C26822B904 -:1051A000184650F8043B0B60704700207047000021 -:1051B000C368C2690133C3604369134482694361B0 -:1051C000934224BF436A43610021FEF79DBD000066 -:1051D00038B504460D46E3683BB123691A1DA26247 -:1051E000E2691344E362002007E0237A33B92946D9 -:1051F0002046FEF779FD0028EDDA38BD6FF001009A -:10520000FBE7000003691960C268013AC260C26925 -:10521000134482690361934224BF436A03610023FC -:105220008362036B03B118477047000070B52023F9 -:105230000D460446114683F31188866A2EB9FFF79E -:10524000C7FF10B186F3118870BDA36A1D70A36AF1 -:10525000E26A01339342A36204D3E1692046043930 -:10526000FFF7D0FF002080F31188EDE72DE9F84F1C -:1052700004460D46904699464FF0200A8AF311885D -:105280000026B346A76A4FB949462046FFF7A0FF5C -:1052900020B187F311883046BDE8F88FD4E90A07BA -:1052A0003A1AA8EB0607974228BF1746402F1BD98A -:1052B00005F1400355F8042B40F8042B9D42F9D129 -:1052C000A36A4033A3624036D4E90A239A4204D346 -:1052D000E16920460439FFF795FF8BF311884645B5 -:1052E000D9D28AF31188CDE729463A46FCF77AFCF1 -:1052F000A36A3B443D44A3623E44E5E7D0E904236E -:105300009A4217D1C3689BB1836A8BB1043B9B1A45 -:105310000ED01360C368013BC360C3691A4483693C -:1053200002619A4224BF436A03610023836201231E -:10533000184670470023FBE700F088B84FF0804321 -:10534000002258631A610222DA6070474FF08043EE -:105350000022DA60704700004FF0804358637047C6 -:105360004FF08043586A70474B6843608B68836096 -:10537000CB68C3600B6943614B6903628B6943620D -:105380000B6803607047000008B5264B26481A6971 -:1053900040F2FF110A431A611A6922F4FF7222F0E7 -:1053A00001021A611A691A6B0A431A631A6D0A43D9 -:1053B0001A651E4A1B6D1146FFF7D6FF02F11C014C -:1053C00000F58060FFF7D0FF02F1380100F5806042 -:1053D000FFF7CAFF02F1540100F58060FFF7C4FF38 -:1053E00002F1700100F58060FFF7BEFF02F18C0151 -:1053F00000F58060FFF7B8FF02F1A80100F58060BA -:10540000FFF7B2FF02F1C40100F58060FFF7ACFFC7 -:1054100002F1E00100F58060FFF7A6FFBDE808405B -:1054200000F09AB80038024000000240DC5B00083F -:1054300008B500F007FAFEF7C7FBFFF791F8BDE8E3 -:105440000840FEF7E9BD000070470000104B1A6CE1 -:1054500042F001021A641A6E42F001021A660D4A05 -:105460001B6E936843F0010393604FF08043532217 -:105470009A624FF0FF32DA6200229A615A63DA6070 -:105480005A6001225A6108211A601C20FDF732BEC1 -:1054900000380240002004E04FF0804208B5116956 -:1054A000D3680B40D9B2C9439B07116107D52023AC -:1054B00083F31188FEF7A8FB002383F3118808BD4E -:1054C00008B5FFF7E9FFBDE80840FFF7A5B8000001 -:1054D0001F4B1A696FEAC2526FEAD2521A611A69F7 -:1054E000C2F308021A614FF0FF301A695A69586115 -:1054F00000215A6959615A691A6A62F080521A6227 -:105500001A6A02F080521A621A6A5A6A58625A6A11 -:1055100059625A6A1A6C42F080521A641A6E42F04A -:1055200080521A661A6E0B4A106840F48070106040 -:10553000186F00F44070B0F5007F1EBF4FF480304C -:1055400018671967536823F40073536000F05AB961 -:105550000038024000700040334B4FF080521A6414 -:10556000324A4FF4404111601A6842F001021A6059 -:105570001A689107FCD59A6822F003029A602A4BB8 -:105580009A6812F00C02FBD1196801F0F901196058 -:105590009A601A6842F480321A601A689203FCD545 -:1055A0005A6F42F001025A671F4B5A6F9007FCD5A1 -:1055B0001F4A5A601A6842F080721A601B4A536888 -:1055C0005904FCD5184B1A689201FCD5194A9A6007 -:1055D000194B1A68194B9A42194B21D1194A116873 -:1055E000194A91421CD140F205121A60144A1368FC -:1055F00003F00F03052BFAD10B4B9A6842F002021D -:105600009A609A6802F00C02082AFAD15A6C42F4A5 -:1056100080425A645A6E42F480425A665B6E70470A -:1056200040F20572E1E700BF003802400070004020 -:105630000854400700948838002004E011640020DA -:10564000003C024000ED00E041C20F41084A08B5AD -:10565000516913680B4003F00103536123B1054AFC -:1056600013680BB150689847BDE80840FEF7D4BFF7 -:10567000003C0140A83F0020084A08B55169136862 -:105680000B4003F00203536123B1054A93680BB149 -:10569000D0689847BDE80840FEF7BEBF003C014017 -:1056A000A83F0020084A08B5516913680B4003F071 -:1056B0000403536123B1054A13690BB1506998473C -:1056C000BDE80840FEF7A8BF003C0140A83F00200D -:1056D000084A08B5516913680B4003F00803536189 -:1056E00023B1054A93690BB1D0699847BDE80840DA -:1056F000FEF792BF003C0140A83F0020084A08B5D1 -:10570000516913680B4003F01003536123B1054A3C -:10571000136A0BB1506A9847BDE80840FEF77CBF9A -:10572000003C0140A83F0020174B10B55A691C6887 -:10573000144004F478725A61A30604D5134A936A9C -:105740000BB1D06A9847600604D5104A136B0BB1B1 -:10575000506B9847210604D50C4A936B0BB1D06B64 -:105760009847E20504D5094A136C0BB1506C984771 -:10577000A30504D5054A936C0BB1D06C9847BDE8DE -:105780001040FEF749BF00BF003C0140A83F002089 -:105790001A4B10B55A691C68144004F47C425A61D3 -:1057A000620504D5164A136D0BB1506D9847230559 -:1057B00004D5134A936D0BB1D06D9847E00404D51E -:1057C0000F4A136E0BB1506E9847A10404D50C4AD2 -:1057D000936E0BB1D06E9847620404D5084A136FDC -:1057E0000BB1506F9847230404D5054A936F0BB152 -:1057F000D06F9847BDE81040FEF70EBF003C014057 -:10580000A83F0020062108B50846FDF773FC0621D5 -:105810000720FDF76FFC06210820FDF76BFC062131 -:105820000920FDF767FC06210A20FDF763FC06212D -:105830001720FDF75FFCBDE8084006212820FDF792 -:1058400059BC000008B5FFF743FE00F00DF8FDF766 -:1058500067FCFDF777FEFDF74FFDFFF7F5FDBDE8AF -:105860000840FFF769BD00000023054A19460133CF -:10587000102BC2E9001102F10802F8D1704700BFF5 -:10588000A83F002010B501390244904201D1002008 -:1058900005E0037811F8014FA34201D0181B10BD99 -:1058A0000130F2E72DE9F041A3B1C91A177801449C -:1058B000044603F1FF3C8C42204601D9002009E058 -:1058C0000578BD4204F10104F5D10CEB0405D618AE -:1058D000A54201D1BDE8F08115F8018D16F801ED62 -:1058E000F045F5D0E7E70000034611F8012B03F877 -:1058F000012B002AF9D170476F72672E61726475AF -:1059000070696C6F742E663430355F4D6174656BF1 -:10591000475053004E6F20617070207369670A0012 -:10592000426164206677206C656E67746820257517 -:105930000A0042616420626F6172645F69642025BD -:10594000752073686F756C642062652025750A0088 -:105950004261642066772064657363726970746F56 -:1059600072206C656E6774682025750A0042616458 -:105970002061707020435243203078253038783AC7 -:10598000307825303878203078253038783A3078BB -:10599000253038780A00476F6F64206669726D772A -:1059A0006172650A0040A2E4F1646891060000009B -:1059B00053544D3332463F3F3F00000053544D3364 -:1059C00032463430780053544D3332463432780006 -:1059D00053544D33324634343658580000000000DA -:1059E000B05900083F00000013040000BC59000833 -:1059F0003F00000019040000C65900083F000000E5 -:105A000021040000D05900083F0000000000000001 -:105A100075320008613200089D32000889320008A2 -:105A200095320008813200086D32000859320008B2 -:105A3000A932000800000000010000000000000082 -:105A40006D61696E0000000069646C650000000013 -:105A5000485A000848360020C037002001000000E6 -:105A6000C53B0008000000004172647550696C6F0E -:105A7000740025424F415244252D424C0025534588 -:105A80005249414C250000000200000000000000C7 -:105A900091340008FD34000840004000583C0020CC -:105AA000683C00200200000000000000030000002D -:105AB0000000000041350008000000001000000058 -:105AC000783C002000000000010000000000000001 -:105AD000303F002001010200B53F0008C53E00082C -:105AE000613F0008453F000843000000F05A0008ED -:105AF00009024300020100C0320904000001020251 -:105B00000100052400100105240100010424020203 -:105B10000524060001070582030800FF09040100AF -:105B2000020A00000007050102400000070581028B -:105B300040000000120000003C5B00081201100150 -:105B40000200004009124157000201020301000057 -:105B50000403090425424F41524425006634303580 -:105B60002D4D6174656B47505300303132333435FD -:105B70003637383941424344454600000040000072 -:105B80000040000000400000004000000000010054 -:105B900000000200000002000000020000000200FD -:105BA00000000200000002000000020000000000EF -:105BB0007936000831390008DD390008400040001E -:105BC000903F0020903F002001000000A03F0020F7 -:105BD000800000004001000003000000AA01A8129C -:105BE00000000000AAAAAAAA55011400FFBF0000E5 -:105BF0008877000070A70A0000000A01000000007A -:105C0000AAAAAAAA00000001FFFF000000000000ED -:105C1000990000000000A01600000000AAAAAAA691 -:105C200000005011FFDF00000000000000770800B6 -:105C30002000000000000000AAAAAAAA100000008C -:105C4000FFFF00000008000000000000000000004E -:105C500000000000AAAAAAAA00000000FFFF00009E -:105C60000000000000000000000000000000000034 -:105C7000AAAAAAAA00000000FFFF0000000000007E -:105C8000000000000000000000000000AAAAAAAA6C -:105C900000000000FFFF0000000000000000000006 -:105CA00000000000000000000A00000000000000EA -:105CB00003000000000000000000000000000000E1 -:105CC00000000000000000000000000000000000D4 -:105CD000000000000000000038A5FF7F0100000068 -:105CE000F60300000000000000000F0000000000AC -:105CF000640000000000000040420F00FE2A010086 -:105D0000D2040000FF00960000000008009600008A -:105D10000000080004000000505B000800000000C4 -:105D20000000000000000000000000000000000073 -:045D3000000000006F +:101580001023002037B51A4D00F080FD02236B7147 +:10159000184B288119681848012201F02FFB0023FD +:1015A0000193164B164900931648174B4FF480527F +:1015B00001F07AFF154B197811B1124801F09CFF28 +:1015C00001F07EFC0446FFF7E3FB4FF4C873B0FB69 +:1015D000F3F202FB130304F5167010FA83F00C4BC0 +:1015E000186003F0F5FE08B10F232B8103B030BD66 +:1015F000D82400201023002020350020A11000084E +:10160000E8240020F0340020A5110008E424002084 +:10161000EC3400202DE9F04F2DED028B0FF238292C +:10162000D9E90089834C93B00BAE9FED7E8BFFF719 +:10163000F1FC814FDFF828A200230A93ADF8343083 +:101640000B9373604FF0000B5B468DED008B012513 +:101650000DF11D0207A938468DF81C508DF81DB0FC +:1016600001F07CFA9DF81C30002B40F0A58020464C +:1016700001F04AFF0646002845D1704F01F020FCDA +:101680003B6898423FD301F01BFC8246FFF780FB8A +:101690004FF4C873B0FBF3F202FB13030AF51670A4 +:1016A00010FA83F03860664F97F800B0CBF1100A5B +:1016B000BBF1000F14BF33462B465FFA8AFA0EA81F +:1016C0008DF82830FFF77CFBBAF1060F28BF4FF0EA +:1016D000060A0EAB03EB0B0152460DF1290000F098 +:1016E00009FA0AAB0393182302930AF10102554B3E +:1016F000D2B2CDE90053049220464CA3D3E9002393 +:1017000001F048FF3E7001F0DBFB4F4A4F4D13687C +:10171000C31AB3F57A7F2ED3106001F0D3FB0246D3 +:101720000B46204601F0CEFF204601F0EDFE10B33F +:101730002B7A474E002B14BF03230223737101F051 +:10174000BFFB0EAF4FF47A730122B0FBF3F03946C2 +:101750003060304600F01AFB182302933D4B019392 +:1017600080B240F25513CDE90370009342464B46D8 +:10177000204601F00FFF2B7A93B101F0A1FB002668 +:1017800007464FF48A7A95F8D900304400F00300F8 +:101790000AFB005393F8E82092B30136042EF2D1ED +:1017A000C82003F03DF92B7A002B7FF43DAF13B036 +:1017B000BDEC028BBDE8F08FDAF8143083F480437F +:1017C000CAF81430594610220EA800F0B9F90DF1EC +:1017D0001E0308AA0AA9384600F03CFF96E8030059 +:1017E0000FAB83E803009DF834308DF844300A9B3A +:1017F0000E930EA9DDE90823204602F037F921E710 +:10180000D3F8E02042B12B68FA2B38BFFA23BA1A7A +:101810000533B2EB430FC0D3FFF7ACFB0028BCD1BC +:10182000BEE700BF0000000000000000401DA12036 +:1018300026812A0BF034002020350020EC340020D3 +:10184000E9340020E8340020204B0020F04500203F +:10185000D8240020244B0020F1C6A7C1D068080F6F +:101860000000024008B5054800F08EFFBDE80840C2 +:10187000034A0449002004F015BF00BF20350020B2 +:10188000604B00206D1100087047000070B50F4BD1 +:101890001B780133DBB2012B0C4611D80C4D2968A3 +:1018A0004FF47A730E6AA2FB0332014622462846A1 +:1018B000B047844204D1074B00221A70012070BD4A +:1018C0004FF4FA7003F0ACF80020F8E71C23002076 +:1018D000D84D0020544B002070B504464FF47A7662 +:1018E000412C254628BF412506FB05F003F098F85A +:1018F000641BF5D170BD000007B50023024601212D +:101900000DF107008DF80730FFF7C0FF20B19DF8FB +:10191000070003B05DF804FB4FF0FF30F9E700006B +:101920000A4608B50421FFF7B1FF80F00100C0B2FC +:10193000404208BD30B4054C2368DD69044B0A46BB +:10194000AC460146204630BC604700BFD84D002061 +:10195000A086010070B503F083FB094E094D30806D +:10196000002428683388834208D903F073FB2B686E +:1019700004440133B4F5803F2B60F2D370BD00BF47 +:10198000564B0020284B002003F018BC00F10060EB +:1019900000F580300068704700F10060920000F5AB +:1019A000803003F0A3BB0000054B1A68054B1B8871 +:1019B0009B1A834202D9104403F04CBB00207047AD +:1019C000284B0020564B0020024B1B68184403F0A4 +:1019D00049BB00BF284B0020024B1B68184403F092 +:1019E00059BB00BF284B002010F003030AD1B0F50B +:1019F000047F05D200F10050A0F51040D0F8003867 +:101A0000184670470023FBE700F10050A0F5104096 +:101A1000D0F8100A70470000064991F8243033B11D +:101A20000023086A81F824300822FFF7B5BF01209F +:101A3000704700BF2C4B0020014B1868704700BF57 +:101A4000002004E070B5194B1D68194B0138C5F32F +:101A50000B0408442D0C04221E88A6420BD15C689E +:101A60000A46013C824213460FD214F9016F4EB16F +:101A700002F8016BF6E7013A03F10803ECD1814269 +:101A80000B4602D22C2203F8012B0A4A05241688A1 +:101A9000AE4204D1984284BF967803F8016B013CB2 +:101AA00002F10402F3D1581A70BD00BF002004E017 +:101AB0009C68000888680008022802BF024B4FF0AB +:101AC00080429A61704700BF00000240022802BFB6 +:101AD000024B4FF480429A61704700BF0000024001 +:101AE000022801BF024A536983F48043536170475F +:101AF0000000024010B50023934203D0CC5CC454D4 +:101B00000133F9E710BD000010B5013810F9013FAD +:101B10003BB191F900409C4203D11AB10131013A25 +:101B2000F4E71AB191F90020981A10BD1046FCE7AD +:101B300003460246D01A12F9011B0029FAD1704758 +:101B400002440346934202D003F8011BFAE77047B0 +:101B50002DE9F8431F4D144695F824200746884682 +:101B600052BBDFF870909CB395F824302BB920223B +:101B7000FF2148462F62FFF7E3FF95F82400C0F1EC +:101B80000802A24228BF2246D6B24146920005EB87 +:101B90008000FFF7AFFF95F82430A41B1E44F6B277 +:101BA000082E17449044E4B285F82460DBD1FFF797 +:101BB00033FF0028D7D108E02B6A03EB820383426E +:101BC000CFD0FFF729FF0028CBD10020BDE8F88354 +:101BD0000120FBE72C4B0020024B1A78024B1A70B5 +:101BE000704700BF544B00201C23002010B5104C40 +:101BF000104802F045FA21460E4802F06DFA2468BA +:101C0000626DD2F8043843F00203C2F804384FF48E +:101C10007A70FFF761FE0849204602F063FB626DAF +:101C2000D2F8043823F00203C2F8043810BD00BF14 +:101C3000E4690008D84D0020EC69000870470000F6 +:101C40002DE9F0470D46044600219046284640F213 +:101C50007912FFF775FF234620220021284601F064 +:101C6000A7FE231D02222021284601F0A1FE631DAC +:101C700003222221284601F09BFEA31D03222521D9 +:101C8000284601F095FE04F1080310222821284679 +:101C900001F08EFE04F1100308223821284601F0DD +:101CA00087FE04F1110308224021284601F080FE3E +:101CB00004F1120308224821284601F079FE04F1BC +:101CC000140320225021284601F072FE04F118036B +:101CD00040227021284601F06BFE04F12003082207 +:101CE000B021284601F064FE04F121030822B82146 +:101CF000284601F05DFE04F12207C0263B4631462E +:101D000008222846083601F053FEB6F5A07F07F1F9 +:101D10000107F3D104F1320308223146284601F0CD +:101D200047FE002704F1330A94F832304FEAC7091E +:101D30009F4209F5A47615D3B8F1000F08D13146BA +:101D400004F599730722284601F032FE09F24F1676 +:101D5000274694F832213B1B93420CD3F01DC00858 +:101D6000BDE8F0870AEB070308223146284601F058 +:101D70001FFE0137D8E707F2331331460822284601 +:101D800001F016FE08360137E3E7000013B50446FC +:101D90000846002101602346C0F80310202201906C +:101DA00001F006FE0198231D0222202101F000FE11 +:101DB0000198631D0322222101F0FAFD0198A31D61 +:101DC0000322252101F0F4FD019804F108031022FB +:101DD000282101F0EDFD072002B010BDF7B500236A +:101DE000047F00910E4607221946054601F0A4FC27 +:101DF000731C0093012200230721284601F09CFC5C +:101E0000C4B9B31C0093052223460821284601F0DB +:101E100093FC0D243746B278BB1B934211D32B7F22 +:101E2000A88A0734E408BBB9844294BF002001208B +:101E300003B0F0BDAB8ADB00083BDB08B3700824BD +:101E4000E8E7FB1C0093214600230822284601F006 +:101E500073FC08340137DEE7201A18BF0120E7E7DA +:101E6000F7B50023047F00910E4608221946054667 +:101E700001F062FC731CC4B908220093114623468A +:101E8000284601F059FC1024012372785F1C013BA5 +:101E9000934211D32B7FA88A0734E408BBB984424C +:101EA00094BF0020012003B0F0BDAB8ADB00083BEB +:101EB000DB0873700824E7E7F31900932146002339 +:101EC0000822284601F038FC08343B46DDE7201A9A +:101ED00018BF0120E7E70000F8B50E460546144696 +:101EE000002181223046FFF72BFE2B4608220021DD +:101EF000304601F05DFD7CB96B1C0722082130469D +:101F000001F056FD0F2401236A785F1C013B9342C8 +:101F100004D3E01DC008F8BD0824F4E7EB192146FE +:101F20000822304601F044FD08343B46ECE700004F +:101F3000F8B50E46054614460021CE223046FFF77E +:101F4000FFFD2B4628220021304601F031FD7CB9EF +:101F500005F1080308222821304601F029FD30242C +:101F60002F462A7A7B1B934204D3E01DC008F8BD9C +:101F70002824F5E707F1090321460822304601F03D +:101F800017FD08340137ECE7F7B5047F00910E46E2 +:101F9000012310220021054601F0CEFBC4B9B31C79 +:101FA0000093092223461021284601F0C5FB19247D +:101FB00037467288BB1B9A4211D82B7FA88A0734F8 +:101FC000E408BBB9844294BF0020012003B0F0BDF7 +:101FD000AB8ADB00103BDB0873801024E8E73B1D75 +:101FE0000093214600230822284601F0A5FB08346F +:101FF0000137DEE7201A18BF0120E7E730B5094DA9 +:102000000A4491420DD011F8013B5840082340F397 +:102010000004013B2C4013F0FF0384EA5000F6D18A +:10202000EFE730BD2083B8EDF7B54FF0FF33DFF8B1 +:1020300054C0DFF854E000EB81011A4688421CD0FE +:1020400050F8044B019401AF042417F8015B82EAB5 +:1020500005620825DB18164605F1FF355241002EB2 +:10206000BCBF83EA0C0382EA0E0215F0FF05F1D132 +:10207000013C14F0FF04E8D1E0E7D843D14303B0BA +:10208000F0BD00BF9336EAA9EBE1F042F7B5384A5C +:10209000106851686B4603C36A46364936480823C0 +:1020A00004F060FB0446002833D10A25334A106847 +:1020B00051686B4603C36A4631492F48082304F030 +:1020C00051FB0446002849D00369B3F5702F45D869 +:1020D000B0F8661040F2F63291423FD1294A0244EC +:1020E00002F15C018B4239D35C3B234900209E1AEC +:1020F000FFF784FF3246074604F164010020FFF732 +:102100007DFFA3689F4229D1E368984208BF00255C +:1021100024E00369B3F5702F27D8418B40F2F632E3 +:10212000914220D1174A024402F110018B4218D388 +:10213000103B114900209D1AFFF760FF2A46064612 +:1021400004F118010020FFF759FFA3689E4202D155 +:10215000E368984201D00D25A8E70025284603B082 +:10216000F0BD1025A2E70C25A0E70B259EE700BFD8 +:10217000BC680008DCFF0E0000000108C56800080C +:1021800090FF0E000800FFF710B5037C044613B95A +:10219000006804F0CFFA204610BD00000023BFF312 +:1021A0005B8FC360BFF35B8FBFF35B8F8360BFF355 +:1021B0005B8F7047BFF35B8F0068BFF35B8F704727 +:1021C00070B505460C30FFF7F5FF05F1080604462B +:1021D0003046FFF7EFFFA04206D930466D68FFF7A3 +:1021E000E9FF2544281A70BD3046FFF7E3FF201AA7 +:1021F000F9E7000070B50546406898B105F10800A0 +:10220000FFF7D8FF05F10C0604463046FFF7D2FF72 +:102210008442304694BF6D680025FFF7CBFF013C38 +:102220002C44201A70BD000038B50C460546FFF757 +:10223000C7FFA04210D305F10800FFF7BBFF04441D +:102240006868B4FBF0F100FB1144BFF35B8F012021 +:10225000AC60BFF35B8F38BD0020FCE72DE9F04197 +:10226000144607460D46FFF7C5FF844228BF0446C3 +:10227000D4B1B84658F80C6B4046FFF79BFF30448A +:10228000286040467E68FFF795FF331A9C4203D8CA +:102290006C600120BDE8F0816B60A41B3B68AB6003 +:1022A0002044E8600220F5E72046F3E738B50C4605 +:1022B0000546FFF79FFFA04210D305F10C00FFF782 +:1022C00079FF04446868B4FBF0F100FB1144BFF3EC +:1022D0005B8F0120EC60BFF35B8F38BD0020FCE713 +:1022E0002DE9FF41884669460746FFF7B7FF6C4670 +:1022F00006B204EBC6060025B44209D06268206825 +:1023000008EB0501FFF7F6FB636808341D44F3E7AB +:1023100029463846FFF7CAFF284604B0BDE8F081D9 +:10232000F8B505460C300F46FFF744FF05F10806E7 +:1023300004463046FFF73EFFA042304688BF6C6837 +:10234000FFF738FF201A386020B130462C68FFF7BD +:1023500031FF2044F8BD000073B5144606460D4613 +:10236000FFF72EFF844228BF04460190DCB101A98B +:102370003046FFF7D5FF019B33B93268C5E9023318 +:10238000C5E9002401200CE09C4238BF019428607C +:10239000019868608442F5D93368AB60241AEC6018 +:1023A000022002B070BD2046FBE700002DE9FF418E +:1023B0000F466946FFF7D0FF6C4600B204EBC0053C +:1023C0000026AC4209D0D4F8048054F8081BB81990 +:1023D0004246FFF78FFB4644F3E7304604B0BDE8C2 +:1023E000F081000038B50546FFF7E0FF04460146DE +:1023F0002846FFF719FF204638BD0000302383F33D +:10240000118862B670470000002383F3118862B61A +:102410007047000010B4026854681A4623465DF8FD +:10242000044B184701207047002070470020704778 +:1024300070470000002070470E20704700F5805064 +:1024400090F8C800C0F340007047000000F58050CD +:1024500090F9C90070470000F7B50C68BDF820700E +:1024600014F000541E466FD10B7B082B6CD8FFF77D +:10247000C5FF4569AB685B010CD4AB681B0108D490 +:10248000AC6814F080545DD1FFF7BEFF204603B066 +:10249000F0BD01240B6804F1180C002BB8BFDB0061 +:1024A0004FEA0C1CB4BF43F004035B0545F80C3045 +:1024B0000B680FFA84FC13F0804F18BF05EB0C1E5D +:1024C00005EB0C1C1EBFDEF8803143F00203CEF892 +:1024D00080310B7BCCF8843105EB04158B68C5F893 +:1024E0008C314B68C5F88831DCF8803143F001034A +:1024F000CCF8803100EB441541F268031D4403EB36 +:1025000044130344C5E9002608330D4601F10C0CC1 +:1025100055F804EB43F804EB6545F9D184342D8874 +:102520001D8000EB441407F00303257925F00B050B +:102530002B432371FFF768FF0097334600F0E2FC5E +:102540000120A4E70224A5E74FF0FF309FE7000039 +:1025500013B500F580540191E06DFFF74BFE1F2885 +:102560000AD90199E06D2022FFF7BAFEA0F12003FD +:102570005842584102B010BD0020FBE708B500F5F5 +:102580008050FFF73BFFC06DFFF708FEBDE8084035 +:10259000FFF73ABF0022026082814260826070478A +:1025A00010B500220023C0E9002300230446038164 +:1025B0000C30FFF7EFFF204610BD0000F0B50546D8 +:1025C00000F580500C4690F8C83013F0040FC3F3A8 +:1025D000800108BF114661F3820304F1840680F88C +:1025E000C83005EB461389B01B79D8072ED57AB3CE +:1025F00019072DD46846FFF7D3FF05EB441303F505 +:10260000835303F1180703AA103318685968144656 +:1026100003C40833BB422246F7D1186820609B8868 +:10262000A380DDE90E23CDE900230123ADF80830B6 +:102630002B686946DB6B2846984705EB46152B79D6 +:102640001A075CBF43F008032B7101E0002AF4D1A4 +:1026500009B0F0BD2DE9F047074688B007F5805472 +:1026600068469A468846FFF7C9FE9146FFF798FFED +:10267000E06DFFF7A5FD1F2829D9E06D20226946EE +:10268000FFF7B0FE202822D103AD444605AB2E460D +:1026900003CE9E4220606160354604F10804F6D105 +:1026A00030682060B388A380DDE90023C9E90023F6 +:1026B000BDF80830AAF80030FFF7A6FE4A46534698 +:1026C0004146384608B0BDE8F04700F009BCFFF7C6 +:1026D0009BFE002008B0BDE8F08700002DE9F84F10 +:1026E0000023C0E90133254B044640F8183B0F4650 +:1026F000FFF750FF04F12800FFF752FF04F14808EC +:1027000004F582554646083530462036FFF748FF27 +:10271000AE42F9D104F580554FF480534FF00009D3 +:10272000C5E91339C5F848800123EE6504F58758DB +:1027300004F58456C5F8549085F8583085F8603013 +:10274000083608F108084FF0000A4FF0000B46E980 +:1027500008ABA6F11800FFF71DFF203646F8289CAD +:102760004645F4D185F8C97017B1054800F0A2FBC1 +:10277000044B63612046BDE8F88F00BFF86800088D +:10278000D06800080064004010B5044B1978044676 +:102790004A1C1A70FFF7A2FF204610BD5C4B0020B8 +:1027A0002DE9F047002950D0294B2A4FB7FBF1F50E +:1027B00099428CBF0A231123581EB5FBF3FC03FB7F +:1027C0001C53C4B22BB102280346F5D80020BDE843 +:1027D000F0870CF1FF36B6F5806FF7D2C4EBC40E6C +:1027E0000EF103034FEAE309C3F3C703A4EB0308A5 +:1027F00009F1010A4FF47A755FFA88F009FB055573 +:102800005AFA88F8B5FBF8F5B5F5617FC1BF0EF14E +:10281000FF33C3F3C703E01AC0B25C1C50FA84F460 +:102820000CFB04F4B7FBF4F4A142CFD1013BDBB2C3 +:102830000F2BCBD80138C0B20728C7D800211071A0 +:1028400016809170D3700120C1E70846BFE700BF32 +:102850003F420F0080DE800270B505460E464FF401 +:102860007A746B695B6803F00103B34207D04FF4DD +:102870007A7002F0D5F8013CF3D1204670BD0120FA +:10288000FCE7000030B54269936913F0700F16D071 +:1028900000230B4C936103F1840200EB4212117987 +:1028A0004D0709D5890707D5416954F823508D6034 +:1028B000117941F0040111710133032BEBD130BDCB +:1028C000E468000873B51D46436916469A68D20746 +:1028D000044609D59A6801219960C2F34002CDE906 +:1028E00000650021FFF76AFE63699A68D1050BD580 +:1028F0009A684FF480719960C2F34022CDE9006577 +:1029000001212046FFF75AFE63699A68D2030BD56E +:102910009A684FF480319960C2F34042CDE9006576 +:1029200002212046FFF74AFE204602B0BDE8704073 +:10293000FFF7A8BFF8B50446466900296CD106F137 +:102940000C07386880076AD006EB01153868D5F89F +:10295000B00110F0040FD5F8B0011ABFC00840F064 +:102960000040400DA061D5F8B0C11CF0020F1CBFA3 +:1029700040F08040A061D5F8B40106EB011100F0F1 +:102980000F0084F82400D1F8B8012077D1F8B801FD +:10299000000A6077D1F8B801000CA077D1F8B8012F +:1029A000000EE077D1F8BC0184F82000D1F8BC011A +:1029B000000A84F82100D1F8BC01000C84F8220040 +:1029C000D1F8BC11090E84F823103821396004F1C4 +:1029D000340004F1180104F1240551F8046B40F8A7 +:1029E000046BA942F9D109880180C4E90A23214670 +:1029F0000023238651F8283B2046DB6B984704F5DB +:102A00008052204692F8C83043F0040382F8C83060 +:102A1000BDE8F840FFF736BF06F1100791E7F8BDB3 +:102A200010B5044600F04EFA02460B4652EA030186 +:102A300002D0013A63F100030449086820B121463D +:102A4000BDE81040FFF776BF10BD00BF584B002017 +:102A5000F8B500F583511E46FFF7D0FCDFF844C0FF +:102A60000831002404F1840500EB45152B795F073C +:102A70000ED4DB060CD5D1E900739742B34107D2DF +:102A800043695CF824709F602B7943F004032B7139 +:102A90000134032C01F12001E4D1BDE8F840FFF737 +:102AA000B3BC00BFE468000808B5FFF7A7FCFFF758 +:102AB000E9FEBDE80840FFF7A7BC0000F8B5436990 +:102AC0000546986800F0E050B0F1E05F0F461FD077 +:102AD000E8B1FFF793FC05F583541034002606F1A6 +:102AE000840305EB43131B791A0706D50136032E21 +:102AF00004F12004F3D1012007E05B07F6D421465E +:102B0000384600F039FA0028F0D1FFF77DFCF8BD17 +:102B10000120FCE700F5805008B5FFF76FFCC06DA1 +:102B2000FFF74EFBFFF770FC43090CBF01200020AC +:102B300008BD0000F8B51D46002313700F46064679 +:102B40001446FFF7E7FF80F00100387025B12946F1 +:102B50003046FFF7B3FF2070F8BD00002DE9B84103 +:102B60000C4615461F46804600F0ACF90B4621780E +:102B7000024609B9287850B14046FFF769FFFFF7D0 +:102B800093FF3B462A462146FFF7D4FF0120BDE8CC +:102B9000B881000010B5FFF731FC174B1A6C42F0FA +:102BA00000721A641A6A42F000721A621A6A00F518 +:102BB000805422F000721A62FFF726FC94F8C830A5 +:102BC000DB0718D4B9B103211320FFF717FC01F07C +:102BD000C7F90321142001F0C3F90321152001F0E6 +:102BE000BFF994F8C83043F0010384F8C830BDE859 +:102BF0001040FFF709BC10BD003802402DE9F04736 +:102C000000F5805588B095F8C930012B04468846F8 +:102C100016467FD8804F57F823200AB947F823007B +:102C2000D7F800A0C4F80C802674BAF1000F63D066 +:102C300095F8C930012B6FD001212046FFF7AAFF7C +:102C4000FFF7DCFB6269136823F00203136062691B +:102C5000136843F001031360636900275F6101217A +:102C60002046FFF7D1FBFFF7F7FD002800F0958025 +:102C7000E86DFFF793FA04F58359BA4609F108099C +:102C8000202200216846FEF75BFF02A8FFF782FCC6 +:102C9000CDF818A06A4609EB07030DF1180E94460B +:102CA000BCE80300F44518605960624603F108036C +:102CB000F5D1DCF80000186020379CF804201A7168 +:102CC000602FDDD195F8C8306FF38203002785F8B7 +:102CD000C8306A4641462046ADF80070ADF8027033 +:102CE0008DF80470FFF75CFD636948BB4FF4004248 +:102CF0001A6008B0BDE8F08741F2D00003F0DAFCBA +:102D0000814610B15146FFF7E9FCC7F80090B9F1D0 +:102D1000000F8DD10020ECE7386803681B6B9847E3 +:102D20000146002888D13868FFF734FF3868036807 +:102D300032465B684146984700287FF47DAFE9E75B +:102D400061221A609DF802309DF803201B061204D0 +:102D500002F4702203F040731343BDF80020C2F365 +:102D6000090213439DF804201205022E02F4E0022A +:102D70000CBF4FF000410021134362690B43D36144 +:102D8000636913225A616269136823F001031360B7 +:102D900039462046FFF760FD08B96369A6E795F854 +:102DA000C93093BB6169D1F8002242F00102C1F839 +:102DB00000226169D1F8002222F47C5222F00E0236 +:102DC000C1F800226169D1F8002242F46062C1F8C2 +:102DD00000226269C2F814326269C2F80432626980 +:102DE00041F6FF71C2F80C126269C2F840326269A2 +:102DF000C2F8443263690122C3F81C226269D2F826 +:102E0000003223F00103C2F8003295F8C83043F0D5 +:102E1000020385F8C8306CE7584B002008B500F075 +:102E200051F850EA0103024602D0421E61F100014E +:102E3000044B186810B10B46FFF744FDBDE808408D +:102E400001F064B8584B002008B50020FFF7E8FDFA +:102E5000BDE8084001F05AB808B50120FFF7E0FDD1 +:102E6000BDE8084001F052B800B59BB0EFF309810E +:102E700068226846FEF73EFEEFF30583014B9B6B2D +:102E8000FEE700BF00ED00E008B5FFF7EDFF000032 +:102E900000B59BB0EFF3098168226846FEF72AFE71 +:102EA000EFF30583014B5B6BFEE700BF00ED00E035 +:102EB000FEE700000FB408B5029801F03DFDFEE703 +:102EC00002F0D2B902F0AAB913B56C4684E8060044 +:102ED000031D94E8030083E80500012002B010BD43 +:102EE00073B58568019155B11B885B0707D4D0E99C +:102EF00000369B6B9847019AC1B23046A847012023 +:102F000002B070BDF0B5866889B005460C465EB16A +:102F1000BDF838305B070AD4D0E900379B6B98477F +:102F20002246C1B23846B047012009B0F0BD0022A8 +:102F30000023CDE900230023ADF808300A4603AB97 +:102F400001F10806106851681C4603C40832B242F9 +:102F50002346F7D1106820609288A280FFF7B2FF65 +:102F60000423ADF808302B68CDE90001DB6B69461E +:102F700028469847D8E7000030B503680968DD0F98 +:102F8000B5EBD17F23F0604421F060424FEAD1706D +:102F90000BD0002BB8BFA40C0029B8BF920C9442F0 +:102FA00002D034BF0120002030BD944205D1C1F3CE +:102FB0008070C3F380738342F6D194422CBF00200B +:102FC0000120F1E72DE9F041456A15B94162BDE8FC +:102FD000F0814B6823F06047C3F38A464FEAD37E03 +:102FE000C3F3807816EA230638BF3E46AC462B462C +:102FF0005A68BEEBD27F22F060440AD0002A18DA69 +:10300000A40CB44217D19D420FD10D60DEE71346E8 +:10301000EEE7A74207D102F08044C2F38072424536 +:103020000BD054B1EFE708D2EDE7CCF800100B60FD +:10303000CDE7B44201D0B442E5D81A689C46002AD4 +:10304000E5D11960C3E700002DE9F047089D01F0C4 +:1030500007044FEAD508224405F0070500EBD1002C +:103060004FF47F49944201D1BDE8F08704F007078F +:1030700005F0070A57453E4638BF5646C6F10806D2 +:10308000111B8E4228BF0E46E10808EBD50E415CAD +:1030900013F80EC0B94029FA06F721FA0AF1FFB277 +:1030A0008CEA010147FA0AF739408CEA010C03F86F +:1030B0000EC034443544D5E780EA0120082341F2AC +:1030C000210201B24000002980B203F1FF33B8BFF2 +:1030D000504013F0FF03F4D17047000038B50C46A0 +:1030E0008D18A54200D138BD14F8011BFFF7E4FF8D +:1030F000F7E7000042684AB1136843604389818959 +:1031000001339BB29942438138BF83811046704797 +:1031100070B588B0202204460D4668460021FEF7AF +:103120000FFD20460495FFF7E5FF024658B16B46B8 +:10313000054608AE1C4603CCB442286069602346AD +:1031400005F10805F6D1104608B070BD082817D95A +:1031500009280CD00A280CD00B280CD00C280CD035 +:103160000D280CD00E2814BF4020302070470C20B2 +:103170007047102070471420704718207047202097 +:1031800070470000082817D90C280CD910280CD932 +:1031900014280CD918280CD920280CD930288CBF19 +:1031A0000F200E207047092070470A2070470B201F +:1031B00070470C2070470D20704700002DE9F84340 +:1031C000078C072F04461ED9D0E9029800254FF638 +:1031D000FF73C5F12006A5F1200029FA05F108FAD0 +:1031E00006F628FA00F031430143C9B21846FFF74A +:1031F00063FF0835402D0346EBD1E1693A46BDE84F +:10320000F843FFF76BBF4FF6FF70BDE8F88300008F +:1032100010B54B6823B9CA8A63F30902CA8210BD8C +:1032200004691A681C600361C38A013BC3824A6057 +:10323000EFE700002DE9F84F1D46CB8A0F46C3F398 +:1032400009010529814692460B4630D00020AAB2DA +:1032500007F11A049EB2042E1FFA80F80FD8904589 +:1032600003F1010306D3FB8A0A4462F30903FB82DC +:1032700001201AE01AF80060E6540130EAE79045B0 +:10328000F1D2A1F1050B1C237C68BBFBF3F203FB1D +:1032900012BB1FFA8BF6002C45D14846FFF72AFFD8 +:1032A000044638B978606FF00200BDE8F88F4FF03F +:1032B0000008E6E7002606607860ADB24FF0000B2C +:1032C000454510D90AEB0803221D13F8011B91553F +:1032D000B1B208F101081B291FFA88F82BD0454527 +:1032E00006F10106F1D8FB8AC3F30902154465F320 +:1032F0000903BCE7013292B21C462368002BF9D1C6 +:103300006B1F0B441C21B3FBF1F301339BB29A42B8 +:10331000D3D2BBF1000FD0D14846FFF7EBFE20B966 +:10332000C4F800B0BFE70122E7E7C0F800B05E468E +:1033300020600446C1E74545D5D94846FFF7DAFE87 +:1033400008B92060AFE7C0F800B00026206004464E +:10335000B6E700002DE9F04F2DED028B1C4683B03F +:103360005B69019207468846002B00F09A80238C07 +:103370002BB1E269002A00F09480072B35D807F1C1 +:103380000C00FFF7B7FE054638B96FF00205284676 +:1033900003B0BDEC028BBDE8F08F14220021FEF7D4 +:1033A000CFFB228CE16905F10800FEF7A3FB208C1E +:1033B000013080B2FFF7E6FEFFF7C8FE013880B2A9 +:1033C0002084013028746369228C1B782A4403F01E +:1033D0001F0363F03F0348F00041137238466960F1 +:1033E0002946FFF7EFFD0125D1E700F10C034FF06F +:1033F000000908EE103A4FF0800A4E464D4618EE8E +:10340000100AFFF777FE83460028BED01422002161 +:10341000FEF796FB002E3AD1019BABF80830022252 +:103420000BF1080E1FFA82FC0CF10100BCF1060F33 +:10343000218C80B201D88E422BD3FFF7A3FEFFF779 +:1034400085FE62691278013802F01F028E4208BFC1 +:103450004FF0400A42EA49121BFA80F14AEA020A96 +:10346000013048F0004281F808A08BF81000CBF83A +:10347000042059463846FFF7A5FD238C0135B34299 +:103480002DB289F001094FF0000AB8D17FE7002280 +:10349000C6E7E169895D0EF802100136B6B2013265 +:1034A000C0E76FF0010572E7F8B515460E46302209 +:1034B000002104461F46FEF743FB069B6360B5F5FB +:1034C000001F079BA76034BF6A094FF6FF72A36213 +:1034D00097B2E66104F1100000239A4206D8002357 +:1034E0000360A782E3822383E360F8BD06600133B3 +:1034F00030462036F1E7000003781BB94BB2002BB1 +:10350000C8BF01707047000000787047F8B50C46DE +:10351000C969074611B9238C002B37D1257E1F2D91 +:1035200034D8387828BB228C072A2CD8268A36F043 +:1035300003032BD14FF6FF70FFF7D0FD20F0010001 +:103540003102400441EA0561400C41EA40254FF652 +:10355000FF72234629463846FFF7FCFE002807DDA8 +:10356000626913780133DBB21F2B88BF002313700D +:10357000F8BD218A2D0645EA012505432046FFF7BF +:103580001DFE0246E5E76FF00300F1E76FF0010072 +:10359000EEE7000070B58AB00446164600212822E6 +:1035A00068461D46FEF7CCFABDF83830ADF810304D +:1035B0000F9B05939DF840308DF81830119B0793B1 +:1035C0006946BDF84830ADF820302046CDE90265A7 +:1035D000FFF79CFF0AB070BD2DE9F041D3690546A5 +:1035E0000C4616460BB9138C5BBB377E1F2F28D8B1 +:1035F00095F80080B8F1000F26D03046FFF7DEFDC9 +:103600003378210241EAC33141EA0801338A41EAB1 +:10361000076141EA03410246334641F080012846F2 +:10362000FFF798FE00280ADD3378012B07D1726975 +:1036300013780133DBB21F2B88BF00231370BDE862 +:10364000F0816FF00100FAE76FF00300F7E7000088 +:10365000F0B58BB004460D46174600212822684677 +:103660001E46FEF76DFA9DF84C305A1E53425341E8 +:103670008DF800309DF84030ADF81030119B059367 +:103680009DF848308DF81830149B07936A46BDF8B2 +:103690005430ADF8203029462046CDE90276FFF7B8 +:1036A0009BFF0BB0F0BD0000406A00B104307047D2 +:1036B000436A1A68426202691A600361C38A013B65 +:1036C000C38270472DE9F041D0F82080194E14468E +:1036D0001D464146002709B9BDE8F081D1E9022322 +:1036E000A21A65EB0303964277EB03031ED2036A2B +:1036F0008B420DD1FFF78CFD036A1B6803620369DF +:103700000B60C38A0161016A013BC3828846E2E71C +:10371000FFF77EFD0B68C8F8003003690B60C38AB1 +:103720000161013BC382D8F80010D4E788460968DC +:10373000D1E700BF80841E002DE9F04F8BB00D460D +:10374000DDF8509014469B468046002800F0198111 +:10375000B9F1000F00F01581531E3F2B00F21181CB +:10376000012A03D1BBF1000F40F00B810023CDE90A +:103770000833B8F81430B5EBC30F4FEAC30703D3CF +:1037800000200BB0BDE8F08F2B199F42D8F80C3009 +:103790003ABF7F1BFFB227461BB9D8F81030002B69 +:1037A0007AD0272D4ED8C5F12806B7424FF0000336 +:1037B0002CBFF6B23E4600932946D8F8080008AB65 +:1037C0003246FFF741FCA7EB060A35445FFA8AFA56 +:1037D000B8F8143003F10053053BDB000493D8F82C +:1037E0000C3003932821039B13B1BAF1000F2CD1A5 +:1037F000D8F8100040B1BAF1000F05D0009608AB20 +:103800005246691AFFF720FC38B2002FB8D066077D +:103810000AD00AAB03EBD401624211F8083C02F073 +:103820000702134101F8083C082C3CD9102C40F247 +:10383000B580202C40F2B780BBF1000F00F09C80D7 +:10384000082334E0BA460026C2E7049BE02B28BFD9 +:10385000E02306930B44AB42059314D95A1B0398FB +:103860000096924534BF5246D2B2691A08AB043072 +:103870000792FFF7E9FB079A1644AAEB020A1544E0 +:10388000F6B25FFA8AFA049B069A05999B1A04938A +:10389000039B1B680393A6E70093D8F8080008ABC6 +:1038A0003A462946AEE7BBF1000F13D00123B4EB33 +:1038B000C30F6CD0082C12D89DF82030621E23FA5A +:1038C00002F2D50706D54FF0FF3202FA04F4234383 +:1038D0008DF820309DF8203089F8003051E7102C09 +:1038E00012D8BDF82030621E23FA02F2D10706D5A5 +:1038F0004FF0FF3202FA04F42343ADF82030BDF854 +:103900002030A9F800303CE7202C0FD80899631E1E +:1039100021FA03F3DA0705D54FF0FF3202FA04F477 +:103920000C430894089BC9F800302AE7402C2BD0A0 +:10393000DDE90865611EC4F12102A4F1210326FA24 +:1039400001F105FA02F225FA03F311431943CB07FB +:1039500012D50122A4F12003C4F1200102FA03F3DD +:1039600022FA01F1A240524243EA010363EB43030E +:1039700032432B43CDE90823DDE90823C9E90023BD +:10398000FFE66FF00100FCE66FF00800F9E6082C96 +:10399000A0D9102CB3D9202CEED8C3E7BBF1000F6F +:1039A000ADD0022383E7BBF1000FBBD004237EE739 +:1039B00030B5012A144638BF0124402C85B028BFF9 +:1039C00040240025012ACDE9025518D81B788DF82E +:1039D000083063070AD004AB03EBD405624215F844 +:1039E000083C02F00702934005F8083C00910346AA +:1039F0002246002102A8FFF727FB05B030BD082AA8 +:103A0000E4D9102A03D81B88ADF80830E1E7202A52 +:103A10008DBFD3E900231B680293CDE90223D8E7C9 +:103A200010B5CB681BB98B600B618B8210BD04692C +:103A30001A681C600361C38A013BC382CA60F0E755 +:103A400003064CBFC0F3C0300220704708B50246E1 +:103A5000FFF7F6FF022806D15306C2F30F2001D16B +:103A600000F0030008BDC2F30740FBE72DE9F04F6B +:103A700093B0CDE903230A6804461046FFF7E0FF40 +:103A8000022814BFC2F306260026002A0D468246ED +:103A900080F2F28112F0C04940F0EE81097B0029EA +:103AA00000F0EA81022803D02378B34240F0E78196 +:103AB000C2F304630693104602F07F030593FFF7F9 +:103AC000C5FF059B29444FEA834848EA0A4848EA6B +:103AD0004668CE7800230022CDE90823F309834607 +:103AE00048EA0008029367D0059B00930246676886 +:103AF000534608A92046B847002800F0C381276A2A +:103B00004FB9414604F10C00FFF702FB074690B99C +:103B10006FF0020054E03B6998450DD03F68002FDC +:103B2000F9D1414604F10C00FFF7F2FA07460028EC +:103B3000EED0236A3B60276297F817C006F01F0893 +:103B4000CCF3840CACEB08001FFA80FE0028B8BF51 +:103B50000EF12000A8EB0C031FFA83FED7E9022127 +:103B6000B8BF00B2002B0793BEBF0EF120031BB2FB +:103B7000079352EA010338D0039BDFF824E39A1A33 +:103B8000049B4FF0000C63EB010196457CEB0103B5 +:103B90002BD36B7B97F81AE0734519D1029B002B4E +:103BA00078D0012821DC7868F8B9DFF8F0C29445B4 +:103BB00070EB010316D337E0276A27B96FF00C00CA +:103BC00013B0BDE8F08F3B699845B5D03F68F4E786 +:103BD000B24890427CEB010301D30020F0E7029B46 +:103BE000002BFAD0079B0F2B17DCFA7DB30002F0F5 +:103BF000030203F07C031343FB7539462046FFF7AD +:103C000007FB6B7BBB76029B3BB9FB7DC3F3840256 +:103C1000013262F38603FB75D0E76A7BBB7E9A4272 +:103C2000DBD1029B002B35D0B309022B32D0039B92 +:103C3000BB60049BFB60142200210DA8FDF780FFF0 +:103C4000039B0A93049B0B932B1D0C932B7BADF8CA +:103C50003EB0013BDBB2ADF83C30069B8DF8423004 +:103C6000059B8DF8433094F82C308DF840A083F0FC +:103C700001038DF844308DF84180A3680AA92046DD +:103C80009847FB7DC3F38403013303F01F039B02BA +:103C9000FB82A2E7FB7DC6F34012B2EBD31F40F0DC +:103CA000F480C3F38403434540F0F280029A2B7BF7 +:103CB000B609002A4DD0F2075DD4032B40F2EB8009 +:103CC000039BBB60049BFB602B7BAE1D033BDBB205 +:103CD0003246394604F10C00FFF7ACFA00280CDA42 +:103CE00039462046FFF794FAFB7DC3F38403013382 +:103CF00003F01F039B02FB820AE7DDE90884AB881F +:103D00003B834FF6FF73C9F12000A9F1200228FA86 +:103D100009F104FA00F0014324FA02F211431846B3 +:103D2000C9B2FFF7C9F909F10809B9F1400F034613 +:103D3000E9D1B8822A7B033AD2B23146FFF7CEF9F5 +:103D4000FB7DB882DA43C2F3C01262F3C713FB757E +:103D500043E786B92E1D013BDBB23246394604F1FA +:103D60000C00FFF767FA0028BADB2A7BB88A013A11 +:103D7000D2B23146E2E7F98AC1F30901013B0429D5 +:103D8000DAB25BD8281D002307F11B069A4208D936 +:103D900010F801CB06F801C0013101330529DBB26F +:103DA000F4D103990A9104990B91934207F11B01F5 +:103DB0000C9138BF043379680D9134BF55FA83F301 +:103DC00000230E93FB8AADF83EB0C3F309031A44F7 +:103DD000069B8DF84230059B8DF8433094F82C30CB +:103DE000ADF83C2083F001038DF8443000238DF8BA +:103DF00040A08DF841807B602A7BB88A013A291D5A +:103E0000FFF76CF93B8BB882834203D1A3680AA900 +:103E10002046984720460AA9FFF702FEFB7DBA8A92 +:103E2000C3F38403013303F01F039B02FB823B8B2C +:103E30009A420CBF00206FF01000C1E67B68002B97 +:103E4000AFD0052001E01C3033461E68002EFAD1A9 +:103E5000091A081D2E1D184401EB090CBCF11B0F9B +:103E60005FFA89F39DD89A429BD916F8013B00F876 +:103E7000013B09F10109EFE76FF00900A0E66FF0DF +:103E80000A009DE66FF00B009AE66FF00D0097E6D2 +:103E90006FF00E0094E66FF00F0091E640420F00C5 +:103EA00080841E00EFF3098305494A6B22F001026A +:103EB0004A63683383F30988002383F311887047CA +:103EC00000EF00E0302080F3118862B60C4B0D4A01 +:103ED000D96821F4E0610904090C0A43DA60D3F8D7 +:103EE000FC20094942F08072C3F8FC200A6842F0C5 +:103EF00001020A602022DA7783F82200704700BFAF +:103F000000ED00E00003FA05001000E010B53023DA +:103F100083F311880E4B5B6813F4006314D0F1EE49 +:103F2000103AEFF30984683C4FF08073E361094B6A +:103F3000DB6B236684F3098800F0BCFC10B1064BF0 +:103F4000A36110BD054BFBE783F31188F9E700BFC0 +:103F500000ED00E000EF00E0430600084606000820 +:103F600000F1604303F561430901C9B283F800130E +:103F7000012200F01F039A4043099B0003F16043B4 +:103F800003F56143C3F880211A60704702684368F3 +:103F90001143016003B118477047000013B5446B2B +:103FA000D4F894341A681178042915D1217C022997 +:103FB00012D11979128901238B4013420CD101A926 +:103FC00004F14C0001F0BAFFD4F89444019B21792C +:103FD0000246206800F0D0F902B010BD143001F0A4 +:103FE0003DBF00004FF0FF33143001F037BF000039 +:103FF0004C3002F00FB800004FF0FF334C3002F0AD +:1040000009B80000143001F00BBF00004FF0FF3181 +:10401000143001F005BF00004C3001F0DBBF0000A0 +:104020004FF0FF324C3001F0D5BF00000020704748 +:1040300010B5D0F894341A6811780429044617D1C1 +:10404000017C022914D15979528901238B401342F2 +:104050000ED1143001F09EFE024648B1D4F89444CB +:104060004FF4807361792068BDE8104000F072B9A8 +:1040700010BD0000406BFFF7DBBF00007047000081 +:104080007FB5124B036000234360C0E90233012572 +:1040900002260F4B057404460290019300F184023E +:1040A000294600964FF48073143001F04FFE094BFF +:1040B0000294CDE9006304F523724FF4807329461E +:1040C00004F14C0001F016FF04B070BD386900081F +:1040D000754000089D3F00080B68302282F311886C +:1040E0000A7903EB820290614A79093243F822008F +:1040F0008A7912B103EB820398610223C0F8941409 +:104100000374002080F311887047000038B5037FE6 +:10411000044613B190F85430ABB9201D012502219B +:10412000FFF734FF04F1140025776FF0010100F070 +:104130009FFC84F8545004F14C006FF00101BDE87D +:10414000384000F095BC38BD10B50121044604305C +:10415000FFF71CFF0023237784F8543010BD0000C4 +:1041600038B504460025143001F008FE04F14C0077 +:10417000257701F0D7FE201D84F854500121FFF768 +:1041800005FF2046BDE83840FFF752BF90F84430A5 +:1041900003F06003202B07D190F84520212A4FF02F +:1041A000000303D81F2A06D800207047222AFBD11B +:1041B000C0E90E3303E0034A82630722C26303644B +:1041C000012070471D23002037B5D0F894341A68B9 +:1041D0001178042904461AD1017C022917D11979D2 +:1041E000128901238B40134211D100F14C0528465E +:1041F00001F058FF58B101A9284601F09FFED4F8FC +:104200009444019B21790246206800F0B5F803B080 +:1042100030BD0000F0B500EB810385B09E69044617 +:104220000D46FEB1302383F3118804EB8507301D62 +:104230000821FFF7ABFEFB685B691B6806F14C00C9 +:104240001BB1019001F088FE019803A901F076FEF0 +:10425000024648B1039B2946204600F08DF8002312 +:1042600083F3118805B0F0BDFB685A691268002A13 +:10427000F5D01B8A013B1340F1D104F14402EAE777 +:10428000093138B550F82140DCB1302383F311886F +:10429000D4F894241368527903EB8203DB689B699A +:1042A0005D6845B104216018FFF770FE294604F1EE +:1042B000140001F079FD2046FFF7BAFE002383F3D6 +:1042C000118838BD7047000001F0EEB8012303707B +:1042D0000023C0E90133C36183620362C3624362A6 +:1042E0000363704738B50446302383F311880025F3 +:1042F000C0E90355C0E90555416001F0E5F8022326 +:10430000237085F31188284638BD000070B500EB96 +:10431000810305465069DA600E46144618B1102232 +:104320000021FDF70DFCA06918B110220021FDF756 +:1043300007FC31462846BDE8704001F08FB9000007 +:10434000826802F0011282600022C0E904228261C8 +:1043500001F010BAF0B400EB81044789E46801254C +:10436000A4698D403D43458123600023A2606360C2 +:10437000F0BC01F02BBA0000F0B400EB8104078917 +:10438000E468012564698D403D4305812360002375 +:10439000A2606360F0BC01F0A5BA000070B5022312 +:1043A000002504460370C0E90255C0E90455C56400 +:1043B000856180F8345001F0EDF863681B6823B123 +:1043C00029462046BDE87040184770BD0378052B8C +:1043D00010B504460AD080F85030052303704368B6 +:1043E0001B680BB1042198470023A36010BD000097 +:1043F0000178052906D190F85020436802701B68A7 +:1044000003B118477047000070B590F83430044687 +:1044100013B1002380F8343004F14402204601F047 +:10442000CBF963689B68B3B994F8443013F0600526 +:1044300035D00021204601F06BFC0021204601F020 +:104440005DFC63681B6813B106212046984706236C +:1044500084F8343070BD204698470028E4D0B4F882 +:104460004A30E26B9A4288BFE36394F94430E56BCB +:10447000002B4FF0300380F20381002D00F0F2801A +:10448000092284F8342083F311880021D4E90E2313 +:104490002046FFF771FF002383F31188DAE794F8D1 +:1044A000452003F07F0343EA022340F202329342A5 +:1044B00000F0C58021D8B3F5807F48D00DD8012BFE +:1044C0003FD0022B00F09380002BB2D104F14C02BC +:1044D000A2630222E2632364C1E7B3F5817F00F0A7 +:1044E0009B80B3F5407FA4D194F84630012BA0D136 +:1044F000B4F84C3043F0020332E0B3F5006F4DD016 +:1045000017D8B3F5A06F31D0A3F5C063012B90D8B5 +:10451000636894F846205E6894F84710B4F8483011 +:104520002046B047002884D04368A3630368E36350 +:104530001AE0B3F5106F36D040F6024293427FF492 +:1045400078AF5C4BA3630223E3630023C3E794F8D3 +:104550004630012B7FF46DAFB4F84C3023F00203EA +:10456000C4E90E55A4F84C30256478E7B4F844301B +:10457000B3F5A06F0ED194F8463084F84E30204643 +:1045800001F060F863681B6813B101212046984769 +:10459000032323700023C4E90E339CE704F14F0387 +:1045A000A3630123C3E72378042B10D1302383F3C3 +:1045B00011882046FFF7C4FE85F311880321636844 +:1045C00084F84F5021701B680BB12046984794F82F +:1045D0004630002BDED084F84F300423237063680C +:1045E0001B68002BD6D0022120469847D2E794F8CA +:1045F00048301D0603F00F0120460AD501F0CEF821 +:10460000012804D002287FF414AF2B4B9AE72B4BE0 +:1046100098E701F0B5F8F3E794F84630002B7FF403 +:1046200008AF94F8483013F00F01B3D01A062046B3 +:1046300002D501F081FBADE701F074FBAAE794F825 +:104640004630002B7FF4F5AE94F8483013F00F019C +:10465000A0D01B06204602D501F05AFB9AE701F0D4 +:104660004DFB97E7142284F8342083F311882B46FE +:104670002A4629462046FFF76DFE85F31188E9E6B4 +:104680005DB1152284F8342083F311880021D4E928 +:104690000E232046FFF75EFEFDE60B2284F8342051 +:1046A00083F311882B462A4629462046FFF764FEED +:1046B000E3E700BF686900086069000864690008F2 +:1046C00038B590F834300446002B3ED0063BDAB2C1 +:1046D0000F2A34D80F2B32D8DFE803F037313108F6 +:1046E000223231313131313131313737C56BB0F8A8 +:1046F0004A309D4214D2C3681B8AB5FBF3F203FB18 +:1047000012556DB9302383F311882B462A4629466A +:10471000FFF732FE85F311880A2384F834300EE067 +:10472000142384F83430302383F3118800231A468D +:1047300019462046FFF70EFE002383F3118838BD8B +:10474000036C03B198470023E7E70021204601F0FE +:10475000DFFA0021204601F0D1FA63681B6813B12B +:104760000621204698470623D7E7000010B590F8A9 +:104770003430142B044629D017D8062B05D001D885 +:104780001BB110BD093B022BFBD80021204601F0D4 +:10479000BFFA0021204601F0B1FA63681B6813B12B +:1047A000062120469847062319E0152BE9D10B2353 +:1047B00080F83430302383F3118800231A461946D9 +:1047C000FFF7DAFD002383F31188DAE7C3689B69FA +:1047D0005B68002BD5D1036C03B19847002384F8A4 +:1047E0003430CEE700230375826803691B6899683B +:1047F0009142FBD25A680360426010605860704773 +:1048000000230375826803691B6899689142FBD88D +:104810005A680360426010605860704708B50846E7 +:10482000302383F311880B7D032B05D0042B0DD08F +:104830002BB983F3118808BD8B6900221A604FF0F1 +:10484000FF338361FFF7CEFF0023F2E7D1E90032A7 +:1048500013605A60F3E70000FFF7C4BF054BD96847 +:104860000875186802681A60536001220275D860E2 +:10487000FBF7D2BE684B002030B50C4BDD684B1CFB +:1048800087B004460FD02B46094A684600F084F9E9 +:104890002046FFF7E3FF009B13B1684600F086F95E +:1048A000A86907B030BDFFF7D9FFF9E7684B0020D2 +:1048B0001D480008044B1A68DB6890689B689842A2 +:1048C00094BF002001207047684B0020084B10B5B2 +:1048D0001C68D86822681A60536001222275DC6067 +:1048E000FFF78EFF01462046BDE81040FBF794BE5F +:1048F000684B0020044B1A68DB6892689B689A42F8 +:1049000001D9FFF7E3BF7047684B002038B5074C6B +:1049100007490848012300252370656001F0FAFB70 +:104920000223237085F3118838BD00BFD04D0020CD +:1049300070690008684B002008B572B6044B186512 +:1049400000F050FC00F00EFD024B03221A70FEE74F +:10495000684B0020D04D002000F05EB9EFF31180CD +:1049600020B9EFF30583302282F3118870470000ED +:1049700010B530B9EFF30584C4F3080414B180F323 +:10498000118810BDFFF7B6FF84F31188F9E7000026 +:10499000034A516853685B1A9842FBD8704700BFBE +:1049A000001000E08B60022308618B82084670478C +:1049B0008368A3F1840243F8142C026943F8442C61 +:1049C000426943F8402C094A43F8242CC26843F852 +:1049D000182C022203F80C2C002203F80B2C044A9A +:1049E00043F8102CA3F12000704700BF31060008E7 +:1049F000684B002008B5FFF7DBFFBDE80840FFF774 +:104A00002BBF0000024BDB6898610F20FFF726BF29 +:104A1000684B0020302383F31188FFF7F3BF0000B9 +:104A200008B50146302383F311880820FFF724FFDF +:104A3000002383F3118808BD064BDB6839B1426857 +:104A400018605A60136043600420FFF715BF4FF0F1 +:104A5000FF307047684B00200368984206D01A6800 +:104A60000260506099611846FFF7F6BE704700007B +:104A700038B504460D462068844200D138BD03682D +:104A800023605C608561FFF7E7FEF4E710B503681B +:104A90009C68A2420CD85C688A600B604C60216004 +:104AA000596099688A1A9A604FF0FF33836010BD8D +:104AB0001B68121BECE700000A2938BF0A2170B5F9 +:104AC00004460D460A26601901F01EFB01F00AFBA0 +:104AD000041BA54203D8751C2E460446F3E70A2E94 +:104AE00004D9BDE87040012001F054BB70BD000046 +:104AF000F8B5144B0D46D96103F1100141600A2A43 +:104B00001969826038BF0A22016048601861A818DC +:104B1000144601F0EBFA0A2701F0E4FA431BA34222 +:104B2000064606D37C1C281901F0EEFA27463546C6 +:104B3000F2E70A2F04D9BDE8F840012001F02ABBB2 +:104B4000F8BD00BF684B0020F8B506460D4601F0E1 +:104B5000C9FA0F4A134653F8107F9F4206D12A46DE +:104B600001463046BDE8F840FFF7C2BFD169BB68D7 +:104B7000441A2C1928BF2C46A34202D92946FFF714 +:104B80009BFF224631460348BDE8F840FFF77EBF51 +:104B9000684B0020784B002010B4C0E903230023A9 +:104BA0005DF8044B4361FFF7CFBF000010B5194C0F +:104BB000236998420DD0D0E90032816813605A60B1 +:104BC0009A680A449A60002303604FF0FF33A361A0 +:104BD00010BD2346026843F8102F53600022026084 +:104BE00022699A4203D1BDE8104001F087BA936868 +:104BF00081680B44936001F075FA2269E16992685B +:104C0000441AA242E4D91144BDE81040091AFFF742 +:104C100053BF00BF684B00202DE9F047DFF8BC8090 +:104C200008F110072C4ED8F8105001F05BFAD8F8B4 +:104C30001C40AA68031B9A423ED81444D5E90032AE +:104C40004FF00009C8F81C4013605A60C5F8009086 +:104C5000D8F81030B34201D101F050FA89F311882D +:104C6000D5E9033128469847302383F311886B69CF +:104C7000002BD8D001F036FA6A69A0EB04094A4546 +:104C800082460DD2022001F085FA0022D8F81030B9 +:104C9000B34208D151462846BDE8F047FFF728BF88 +:104CA000121A2244F2E712EB090938BF4A46294694 +:104CB0003846FFF7EBFEB5E7D8F81030B34208D01E +:104CC0001444211AC8F81C00A960BDE8F047FFF79A +:104CD000F3BEBDE8F08700BF784B0020684B002092 +:104CE00000207047FEE70000704700004FF0FF30E3 +:104CF0007047000002290CD0032904D0012907487D +:104D000018BF00207047032A05D8054800EBC200F1 +:104D10007047044870470020704700BF486A000889 +:104D20002C230020FC69000870B59AB0054608469F +:104D300001A9144600F0C2F801A8FCF7F9FE431CD3 +:104D40005B00C5E900340022237003236370C6B200 +:104D500001AB02341046D1B28E4204F1020401D8F4 +:104D60001AB070BD13F8011B04F8021C04F8010C02 +:104D70000132F0E708B5302383F311880348FFF7C9 +:104D800023FA002383F3118808BD00BFD84D00200B +:104D900090F8443003F01F02012A07D190F8452013 +:104DA0000B2A03D10023C0E90E3315E003F06003A2 +:104DB000202B08D1B0F848302BB990F84520212A93 +:104DC00003D81F2A04D8FFF7E1B9222AEBD0FAE76B +:104DD000034A82630722C26303640120704700BF55 +:104DE0002423002007B5052917D8DFE801F019169C +:104DF00003191920302383F31188104A01900121EF +:104E0000FFF784FA01980E4A0221FFF77FFA0D4856 +:104E1000FFF7A6F9002383F3118803B05DF804FBC4 +:104E2000302383F311880748FFF770F9F2E7302346 +:104E300083F311880348FFF787F9EBE79C690008C3 +:104E4000C0690008D84D002038B50C4D0C4C0D49F8 +:104E50002A4604F10800FFF767FF05F1CA0204F1D2 +:104E600010000949FFF760FF05F5CA7204F1180048 +:104E70000649BDE83840FFF757BF00BFA0520020E9 +:104E80002C2300207C6900088669000891690008CD +:104E900070B5044608460D46FCF74AFEC6B22046E9 +:104EA000013403780BB9184670BD32462946FCF729 +:104EB0002BFE0028F3D10120F6E700002DE9F04792 +:104EC00005460C46FCF734FE2B49C6B22846FFF7D0 +:104ED000DFFF08B10636F6B228492846FFF7D8FFAB +:104EE00008B11036F6B2632E0BD8DFF88C80DFF8ED +:104EF0008C90234FDFF894A02E7846B92670BDE839 +:104F0000F08729462046BDE8F04701F091BC252EE8 +:104F10002ED1072241462846FCF7F6FD70B9194B01 +:104F2000224603F10C0153F8040B42F8040B8B42A8 +:104F3000F9D11B78137007350D34DDE70822494697 +:104F40002846FCF7E1FD98B90F4BA21C1978090916 +:104F50000232C95D02F8041C13F8011B01F00F01B5 +:104F60005345C95D02F8031CF0D118340835C3E776 +:104F700004F8016B0135BFE7686A00089169000811 +:104F8000706A00084E680008107AFF1F1C7AFF1F25 +:104F9000BFF34F8F024AD368DB03FCD4704700BFD6 +:104FA000003C024008B5094B1B7873B9FFF7F0FFCE +:104FB000074B1A69002ABFBF064A5A6002F18832BD +:104FC0005A601A6822F480621A6008BDFE540020FC +:104FD000003C02402301674508B50B4B1B7893B991 +:104FE000FFF7D6FF094B1A6942F000421A611A68AE +:104FF00042F480521A601A6822F480521A601A68C9 +:1050000042F480621A6008BDFE540020003C024059 +:105010000B28F0B516D80C4C0C4923787BB90C4DF5 +:105020000E460C234FF0006255F8047B46F8042B23 +:10503000013B13F0FF033A44F6D10123237051F8EA +:105040002000F0BD0020FCE7305500200055002076 +:10505000846A0008014B53F820007047846A0008F6 +:105060000C2070470B2810B5044601D9002010BD54 +:10507000FFF7CEFF064B53F824301844C21A0BB981 +:105080000120F4E712680132F0D1043BF6E700BFDB +:10509000846A00080B2810B5044621D8FFF778FF72 +:1050A000FFF780FF0F4AF323D360C300DBB243F462 +:1050B000007343F002031361136943F480331361F7 +:1050C000FFF766FFFFF7A4FF074B53F8241000F02B +:1050D00045F9FFF781FF2046BDE81040FFF7C2BF4A +:1050E000002010BD003C0240846A0008F8B512F0B0 +:1050F0000103144642D18218B2F1016F57D82D4BEB +:105100001B6813F0010352D02B4DFFF74BFFF32325 +:10511000EB60FFF73DFF40F20127032C15D824F088 +:1051200001046618244C401A40F20117B142236969 +:1051300000EB010524D123F001032361FFF74CFFAD +:105140000120F8BD043C0430E7E78307E7D12B6971 +:1051500023F440732B612B693B432B6151F8046BA3 +:105160000660BFF34F8FFFF713FF03689E42E9D03D +:105170002B6923F001032B61FFF72EFF0020E0E7EE +:1051800023F44073236123693B4323610B882B8005 +:10519000BFF34F8FFFF7FCFE2D8831F8023BADB215 +:1051A000AB42C3D0236923F001032361E4E718462F +:1051B000C7E700BF00380240003C0240084908B57C +:1051C0000B7828B11BB9FFF7EDFE01230B7008BD6A +:1051D000002BFCD0BDE808400870FFF7FDBE00BF03 +:1051E000FE54002008B54FF400314FF0005000F09D +:1051F000B7F8BDE808404FF480314FF0805000F020 +:10520000AFB800000846114601F076BA012001F05F +:1052100073BA0000084601F08DBA000070B582B084 +:10522000FFF79CFB0E4E054600F05CFF3268904293 +:1052300037BF0C4A0B49516814682EBFD1E90041B1 +:10524000013151600419034641F1000128460191E2 +:105250003360FFF78DFB0199204602B070BD00BF9F +:10526000345500203855002070B582B0FFF776FB2A +:10527000104E054600F036FF3268904237BF0E4AA6 +:105280000D49516814682EBFD1E9004101315160C8 +:10529000041941F100010346284601913360FFF7EC +:1052A00067FB01994FF47A7200232046FAF7A0FFBA +:1052B00002B070BD345500203855002010B50244AE +:1052C000064BD2B2904200D110BD441C00B253F83C +:1052D000200041F8040BE0B2F4E700BF5028004082 +:1052E0000F4B30B51C6F240407D41C6F44F40074BA +:1052F0001C671C6F44F400441C670A4C236843F489 +:10530000807323600244084BD2B2904200D130BD7A +:10531000441C00B251F8045B43F82050E0B2F4E7BB +:1053200000380240007000405028004007B50122BC +:1053300001A90020FFF7C2FF019803B05DF804FB4C +:1053400013B50446FFF7F2FFA04205D0012201A9E0 +:1053500000200194FFF7C4FF02B010BD70470000A9 +:105360007047000070470000074B45F255521A6025 +:1053700002225A6040F6FF729A604CF6CC421A60E4 +:10538000024B01221A707047003000404455002043 +:10539000034B1B781BB1034B4AF6AA221A607047D5 +:1053A0004455002000300040034B1A681AB9034AE4 +:1053B000D2F874281A60704740550020003002402F +:1053C000024B4FF08072C3F87428704700300240DF +:1053D00008B5FFF7E9FF024B1868C0F3407008BD3D +:1053E0004055002008B5FFF7DFFF024B1868C0F3F7 +:1053F000007008BD4055002070470000FEE7000027 +:105400000A4B0B480B4A90420BD30B4BDA1C121A77 +:10541000C11E22F003028B4238BF00220021FCF79C +:105420008FBB53F8041B40F8041BECE7A86C000882 +:1054300048560020485600204856002070B5D0E954 +:1054400015439E6800224FF0FF3504EB42135101D3 +:10545000D3F800090028BEBFD3F8000940F080400F +:10546000C3F80009D3F8000B0028BEBFD3F8000B27 +:1054700040F08040C3F8000B013263189642C3F835 +:105480000859C3F8085BE0D24FF00113C4F81C3888 +:1054900070BD0000890141F02001016103699B0694 +:1054A000FCD41220FFF774BA10B5054C2046FEF765 +:1054B0000DFF4FF0A0436365024BA36510BD00BF15 +:1054C00048550020D86A000870B50378012B0546BE +:1054D00050D12A4B446D98421BD1294B5A6B42F054 +:1054E00080025A635A6D42F080025A655A6D5A69B9 +:1054F00042F080025A615A6922F080025A610E21FC +:1055000043205B69FEF72CFD1E4BE3601E4BC4F885 +:1055100000380023C4F8003EC02323606E6D4FF4B2 +:105520000413A3633369002BFCDA012333610C20DD +:10553000FFF72EFA3369DB07FCD41220FFF728FAB5 +:105540003369002BFCDA0026A6602846FFF776FFB9 +:105550006B68C4F81068DB68C4F81468C4F81C6889 +:105560004BB90A4BA3614FF0FF336361A36843F06B +:105570000103A36070BD064BF4E700BF485500204F +:10558000003802404014004003002002003C30C0BC +:10559000083C30C0F8B5446D054600212046FFF7B1 +:1055A00079FFA96D00234FF001128F68C4F83438D9 +:1055B0004FF00066C4F81C284FF0FF3004EB431294 +:1055C00001339F42C2F80069C2F8006BC2F80809B3 +:1055D000C2F8080BF2D20B686A6DEB6563621023A8 +:1055E0001361166916F01006FBD11220FFF7D0F9EF +:1055F000D4F8003823F4FE63C4F80038A36943F4F8 +:10560000402343F01003A3610923C4F81038C4F801 +:1056100014380A4BEB604FF0C043C4F8103B084B02 +:10562000C4F8003BC4F81069C4F80039EB6D03F10D +:10563000100243F48013EA65A362F8BDB46A00085F +:1056400040800010426D90F84E10D2F8003823F4DC +:10565000FE6343EA0113C2F8003870472DE9F843AE +:1056600000EB8103456DDA68166806F00306731EC9 +:10567000022B05EB41130C4680460FFA81F94FEAE5 +:1056800041104FF00001C3F8101B4FF0010104F16D +:10569000100398BFB60401FA03F391698EBF334E2D +:1056A00006F1805606F5004600293AD0578A04F1E3 +:1056B0005801490137436F50D5F81C180B43C5F802 +:1056C0001C382B180021C3F8101953690127611EDB +:1056D000A7409BB3138A928B9B08012A88BF534330 +:1056E000D8F85C20981842EA034301F1400205EB28 +:1056F0008202C8F85C00214653602846FFF7CAFEC4 +:1057000008EB8900C3681B8A43EA84534834640168 +:105710001E432E51D5F81C381F43C5F81C78BDE830 +:10572000F88305EB4917D7F8001B21F40041C7F8AF +:10573000001BD5F81C1821EA0303C0E704F13F035E +:1057400005EB83030A4A5A6028462146FFF7A2FE6A +:1057500005EB4910D0F8003923F40043C0F80039B4 +:10576000D5F81C3823EA0707D7E700BF00800010F0 +:1057700000040002826D1268C265FFF75FBE000080 +:105780005831436D49015B5813F4004004D013F4C1 +:10579000001F0CBF02200120704700004831436DFC +:1057A00049015B5813F4004004D013F4001F0CBFF0 +:1057B000022001207047000000EB8101CB68196ACC +:1057C0000B6813604B6853607047000000EB810367 +:1057D00030B5DD68AA691368D36019B9402B84BF5E +:1057E000402313606B8A1468426D1C44013CB4FB77 +:1057F000F3F46343033323F0030302EB411043EA62 +:10580000C44343F0C043C0F8103B2B6803F00303CC +:10581000012B09B20ED1D2F8083802EB411013F473 +:10582000807FD0F8003B14BF43F0805343F0005317 +:10583000C0F8003B02EB4112D2F8003B43F00443B6 +:10584000C2F8003B30BD00002DE9F041244D6E6DE3 +:1058500006EB40130446D3F8087BC3F8087B3807EF +:105860000AD5D6F81438190706D505EB8403214666 +:10587000DB6828465B689847FA071FD5D6F81438C6 +:10588000DB071BD505EB8403D968CCB98B69488A43 +:105890005A68B2FBF0F600FB16228AB91868DA687B +:1058A00090420DD2121AC3E90024302383F31188E9 +:1058B0000B482146FFF78AFF84F31188BDE8F08189 +:1058C000012303FA04F26B8923EA02036B81CB689C +:1058D000002BF3D021460248BDE8F041184700BF35 +:1058E0004855002000EB810370B5DD68436D6C699D +:1058F0002668E6604A0156BB1A444FF40020C2F8FD +:1059000010092A6802F00302012A0AB20ED1D3F864 +:10591000080803EB421410F4807FD4F8000914BF88 +:1059200040F0805040F00050C4F8000903EB4212F0 +:10593000D2F8000940F00440C2F80009D3F8340856 +:10594000012202FA01F10143C3F8341870BD19B9FC +:10595000402E84BF4020206020682E8A8419013C9C +:10596000B4FBF6F440EAC44040F000501A44C6E7E5 +:105970002DE9F8433B4D6E6D06EB40130446D3F81A +:105980000889C3F8088918F0010F4FEA40171AD0A8 +:10599000D6F81038DB0716D505EB8003D9684B69BC +:1059A0001868DA68904230D2121A4FF000091A6073 +:1059B000C3F80490302383F3118821462846FFF76B +:1059C00091FF89F3118818F0800F1CD0D6F8343875 +:1059D0000126A640334216D005EB84036D6DD3F843 +:1059E0000CC0DCF814200134E4B2D2F800E005EB7E +:1059F00004342F445168714515D3D5F8343823EA5F +:105A00000606C5F83468BDE8F883012303FA04F2FA +:105A10002B8923EA02032B818B68002BD3D02146EC +:105A200028469847CFE7BCF81000AEEB010383424D +:105A300028BF0346D7F8180980B2B3EB800FE2D82D +:105A40009068A0F1040959F8048FC4F80080A0EB15 +:105A500009089844B8F1040FF5D818440B44906035 +:105A60005360C7E7485500202DE9F74FA24C656DFC +:105A70006E69AB691E4016F480586E6107D02046EF +:105A8000FEF78CFC03B0BDE8F04FFEF73FBA002EE6 +:105A900012DAD5F8003E98489B071EBFD5F8003EA5 +:105AA00023F00303C5F8003ED5F8043823F00103C2 +:105AB000C5F80438FEF79CFC370505D58E48FFF77E +:105AC000BDFC8D48FEF782FCB0040CD5D5F8083833 +:105AD00013F0060FEB6823F470530CBF43F410531C +:105AE00043F4A053EB6031071BD56368DB681BB937 +:105AF000AB6923F00803AB612378052B0CD1D5F8F3 +:105B0000003E7D489A071EBFD5F8003E23F00303F0 +:105B1000C5F8003EFEF76CFC6368DB680BB17648A5 +:105B20009847F30274D4B70227D5D4F85490DFF81D +:105B3000C8B100274FF0010A09EB4712D2F8003B29 +:105B400003F44023B3F5802F11D1D2F8003B002B92 +:105B50000DDA62890AFA07F322EA0303638104EB90 +:105B60008703DB68DB6813B1394658469847A36D55 +:105B700001379B68FFB29F42DED9F00617D5676DEB +:105B80003A6AC2F30A1002F00F0302F4F012B2F5FF +:105B9000802F00F08580B2F5402F08D104EB8303FD +:105BA0000022DB681B6A07F5805790426AD13003F8 +:105BB000D5F8184813D5E10302D50020FFF744FEBD +:105BC000A20302D50120FFF73FFE630302D50220A6 +:105BD000FFF73AFE270302D50320FFF735FE7503D2 +:105BE0007FF550AFE00702D50020FFF7C1FEA10707 +:105BF00002D50120FFF7BCFE620702D50220FFF7A5 +:105C0000B7FE23077FF53EAF0320FFF7B1FE39E76C +:105C1000636DDFF8E4A0019300274FF00109A36D45 +:105C20009B685FFA87FB9B453FF67DAF019B03EBCB +:105C30004B13D3F8001901F44021B1F5802F1FD187 +:105C4000D3F8001900291BDAD3F8001941F090416C +:105C5000C3F80019D3F800190029FBDB5946606D21 +:105C6000FFF718FC218909FA0BF321EA03032381CA +:105C700004EB8B03DB689B6813B159465046984789 +:105C80000137CCE7910708BFD7F80080072A98BFF3 +:105C900003F8018B02F1010298BF4FEA182884E74C +:105CA000023304EB830207F580575268D2F818C01C +:105CB000DCF80820DCE9001CA1EB0C0C0021884278 +:105CC0000AD104EB830463689B699A6802449A6072 +:105CD0005A6802445A606AE711F0030F08BFD7F808 +:105CE00000808C4588BF02F8018B01F1010188BF5B +:105CF0004FEA1828E3E700BF48550020436D03EB47 +:105D00004111D1F8003B43F40013C1F8003B704748 +:105D1000436D03EB4111D1F8003943F40013C1F88E +:105D200000397047436D03EB4111D1F8003B23F478 +:105D30000013C1F8003B7047436D03EB4111D1F8EC +:105D4000003923F40013C1F80039704730B5039CC3 +:105D50000172043304FB0325C0E90653049B03636B +:105D60000021059BC160C0E90000C0E90422C0E930 +:105D70000842C0E90A11436330BD0000416A0022B5 +:105D8000C0E90411C0E90A22C2606FF00101FEF708 +:105D90006FBE0000D0E90432934201D1C2680AB953 +:105DA000181D70470020704703691960C2680132EE +:105DB000C260C269134482690361934224BF436A8B +:105DC00003610021FEF748BE38B504460D46E3687E +:105DD0003BB16269131D1268A3621344E3620020A1 +:105DE00007E0237A33B929462046FEF725FE00282E +:105DF000EDDA38BD6FF00100FBE70000C368C2694F +:105E0000013BC3604369134482694361934224BFE9 +:105E1000436A436100238362036B03B118477047F1 +:105E200070B53023044683F31188866A3EB9FFF7C4 +:105E3000CBFF054618B186F31188284670BDA36ACA +:105E4000E26A13F8015BA362934202D32046FFF794 +:105E5000D5FF002383F31188EFE700002DE9F84F09 +:105E600004460E46174698464FF0300989F31188CC +:105E70000025AA46D4F828B0BBF1000F09D141464D +:105E80002046FFF7A1FF20B18BF311882846BDE81B +:105E9000F88FD4E90A12A7EB050B521A934528BFD5 +:105EA0009346BBF1400F1BD9334601F1400251F834 +:105EB000040B43F8040B9142F9D1A36A40334036F6 +:105EC000A3624035D4E90A239A4202D32046FFF761 +:105ED00095FF8AF31188BD42D8D289F31188C9E7AA +:105EE00030465A46FBF706FEA36A5B445E44A36253 +:105EF0005D44E7E710B5029C0172043303FB042103 +:105F0000C0E906130023C0E90A33039B0363049B23 +:105F1000C460C0E90000C0E90422C0E9084243634C +:105F200010BD0000026AC260426AC0E90422002279 +:105F3000C0E90A226FF00101FEF79ABDD0E90423FF +:105F40009A4201D1C26822B9184650F8043B0B604E +:105F5000704700231846FAE7C368C2690133C3607B +:105F60004369134482694361934224BF436A436196 +:105F70000021FEF771BD000038B504460D46E36808 +:105F80003BB123691A1DA262E2691344E362002057 +:105F900007E0237A33B929462046FEF74DFD002855 +:105FA000EDDA38BD6FF00100FBE70000036919600E +:105FB000C268013AC260C2691344826903619342B4 +:105FC00024BF436A036100238362036B03B1184754 +:105FD0007047000070B530230D460446114683F328 +:105FE0001188866A2EB9FFF7C7FF10B186F31188B2 +:105FF00070BDA36A1D70A36AE26A01339342A36273 +:1060000004D3E16920460439FFF7D0FF002080F374 +:106010001188EDE72DE9F84F04460D469046994664 +:106020004FF0300A8AF311880026B346A76A4FB9A9 +:1060300049462046FFF7A0FF20B187F3118830467C +:10604000BDE8F88FD4E90A073A1AA8EB0607974289 +:1060500028BF1746402F1BD905F1400355F8042BE4 +:1060600040F8042B9D42F9D1A36A4033A362403625 +:10607000D4E90A239A4204D3E16920460439FFF7A0 +:1060800095FF8BF311884645D9D28AF31188CDE765 +:1060900029463A46FBF72EFDA36A3B443D44A362E2 +:1060A0003E44E5E7D0E904239A4217D1C3689BB187 +:1060B000836A8BB1043B9B1A0ED01360C368013B0B +:1060C000C360C3691A44836902619A4224BF436A68 +:1060D0000361002383620123184670470023FBE716 +:1060E00000F0D2B84FF08043586A70474FF08043B9 +:1060F000002258631A610222DA6070474FF0804331 +:106100000022DA60704700004FF080435863704708 +:10611000FEE7000070B51B4B01630025044686B006 +:10612000586085620E46FDF7CDFE04F11003C4E908 +:1061300004334FF0FF33C4E90635C4E90044A560D9 +:10614000E562FFF7CFFF2B460246C4E9082304F1BE +:1061500034010D4A256580232046FEF723FC0123E8 +:10616000E0600A4A0375009272680192B268CDE954 +:106170000223074B6846CDE90435FEF73BFC06B029 +:1061800070BD00BFD04D0020E46A0008E96A000835 +:1061900011610008024AD36A1843D062704700BFF9 +:1061A000684B00204B6843608B688360CB68C3609A +:1061B0000B6943614B6903628B6943620B6803603F +:1061C0007047000008B5264B26481A6940F2FF11B7 +:1061D0000A431A611A6922F4FF7222F001021A615D +:1061E0001A691A6B0A431A631A6D0A431A651E4A22 +:1061F0001B6D1146FFF7D6FF02F11C0100F5806010 +:10620000FFF7D0FF02F1380100F58060FFF7CAFF09 +:1062100002F1540100F58060FFF7C4FF02F1700144 +:1062200000F58060FFF7BEFF02F18C0100F5806091 +:10623000FFF7B8FF02F1A80100F58060FFF7B2FF99 +:1062400002F1C40100F58060FFF7ACFF02F1E0014C +:1062500000F58060FFF7A6FFBDE8084000F090B8A9 +:106260000038024000000240F06A000808B500F063 +:10627000FBF9FEF74BFBFFF797F8BDE80840FEF788 +:10628000E3BD0000704700000F4B1A6C42F00102A2 +:106290001A641A6E42F001021A660C4A1B6E936869 +:1062A00043F0010393604FF0804353229A624FF012 +:1062B000FF32DA6200229A615A63DA605A60012280 +:1062C0005A611A60704700BF00380240002004E0A5 +:1062D0004FF0804208B51169D3680B40D9B2C94369 +:1062E0009B07116107D5302383F31188FEF734FB38 +:1062F000002383F3118808BD1F4B1A696FEAC2524D +:106300006FEAD2521A611A69C2F308021A614FF099 +:10631000FF301A695A69586100215A6959615A69EE +:106320001A6A62F080521A621A6A02F080521A6285 +:106330001A6A5A6A58625A6A59625A6A1A6C42F060 +:1063400080521A641A6E42F080521A661A6E0B4A14 +:10635000106840F480701060186F00F44070B0F561 +:10636000007F1EBF4FF4803018671967536823F40D +:106370000073536000F054B90038024000700040D0 +:10638000334B4FF080521A64324A4FF4404111604F +:106390001A6842F001021A601A689107FCD59A68DF +:1063A00022F003029A602A4B9A6812F00C02FBD189 +:1063B000196801F0F90119609A601A6842F4803294 +:1063C0001A601A689203FCD55A6F42F001025A67AC +:1063D0001F4B5A6F9007FCD51F4A5A601A6842F04B +:1063E00080721A601B4A53685904FCD5184B1A680E +:1063F0009201FCD5194A9A60194B1A68194B9A42B6 +:10640000194B21D1194A1168194A91421CD140F205 +:1064100005121A60144A136803F00F03052BFAD112 +:106420000B4B9A6842F002029A609A6802F00C02E2 +:10643000082AFAD15A6C42F480425A645A6E42F4E5 +:1064400080425A665B6E704740F20572E1E700BF1A +:10645000003802400070004008544007009488381B +:10646000002004E011640020003C024000ED00E048 +:1064700041C20F41074A08B5536903F00103536154 +:1064800023B1054A13680BB150689847BDE808402E +:10649000FDF73CBD003C0140C0550020074A08B54F +:1064A000536903F00203536123B1054A93680BB1AA +:1064B000D0689847BDE80840FDF728BD003C014082 +:1064C000C0550020074A08B5536903F0040353611F +:1064D00023B1054A13690BB150699847BDE80840DC +:1064E000FDF714BD003C0140C0550020074A08B527 +:1064F000536903F00803536123B1054A93690BB153 +:10650000D0699847BDE80840FDF700BD003C014058 +:10651000C0550020074A08B5536903F010035361C2 +:1065200023B1054A136A0BB1506A9847BDE8084089 +:10653000FDF7ECBC003C0140C0550020164B10B5E7 +:106540005C6904F478725A61A30604D5134A936A0D +:106550000BB1D06A9847600604D5104A136B0BB193 +:10656000506B9847210604D50C4A936B0BB1D06B46 +:106570009847E20504D5094A136C0BB1506C984753 +:10658000A30504D5054A936C0BB1D06C9847BDE8C0 +:106590001040FDF7BBBC00BF003C0140C0550020CF +:1065A000194B10B55C6904F47C425A61620504D54C +:1065B000164A136D0BB1506D9847230504D5134A45 +:1065C000936D0BB1D06D9847E00404D50F4A136E5C +:1065D0000BB1506E9847A10404D50C4A936E0BB1D1 +:1065E000D06E9847620404D5084A136F0BB1506F00 +:1065F0009847230404D5054A936F0BB1D06F984791 +:10660000BDE81040FDF782BC003C0140C0550020B1 +:1066100008B5FFF75DFEBDE80840FDF777BC000058 +:10662000062108B50846FDF79BFC06210720FDF76B +:1066300097FC06210820FDF793FC06210920FDF7B1 +:106640008FFC06210A20FDF78BFC06211720FDF7A1 +:1066500087FC06212820FDF783FCBDE808400721C0 +:106660001C20FDF77DBC000008B5FFF745FE00F0DB +:106670000BF8FDF729FEFDF701FDFFF703FEBDE86E +:106680000840FFF72DBD00000023054A19460133DD +:10669000102BC2E9001102F10802F8D1704700BFC7 +:1066A000C05500200B460146184600F02DB80000EA +:1066B00000F040B8012838BF012010B5044620463C +:1066C00000F030F830B900F007F808B900F00CF825 +:1066D0008047F4E710BD0000024B1868BFF35B8FE2 +:1066E000704700BF4056002008B5062000F084F82F +:1066F0000120FEF7F7FA0000024B0A46014618682F +:10670000FEF780BD4C23002010B5054C13462CB17C +:106710000A4601460220AFF3008010BD2046FCE788 +:1067200000000000024B01461868FEF76FBD00BF75 +:106730004C230020024B01461868FEF76BBD00BFDA +:106740004C23002010B501390244904201D10020B1 +:1067500005E0037811F8014FA34201D0181B10BDCA +:106760000130F2E72DE9F041A3B1C91A17780144CD +:10677000044603F1FF3C8C42204601D9002009E089 +:106780000578BD4204F10104F5D10CEB0405D618DF +:10679000A54201D1BDE8F08115F8018D16F801ED93 +:1067A000F045F5D0E7E700001F2938B504460D464F +:1067B00004D9162303604FF0FF3038BD426C12B18C +:1067C00052F821304BB9204600F030F82A460146F5 +:1067D0002046BDE8384000F017B8012B0AD0591CFC +:1067E00003D1162303600120E7E7002442F8254087 +:1067F000284698470020E0E7024B01461868FFF75B +:10680000D3BF00BF4C23002038B5074D00230446FA +:10681000084611462B60FEF769FA431C02D12B682B +:1068200003B1236038BD00BF44560020FEF758BABC +:10683000034611F8012B03F8012B002AF9D1704708 +:106840006F72672E6172647570696C6F742E663436 +:1068500030352D4D6174656B4750530053544D33A3 +:1068600032463F3F3F0053544D3332463430780078 +:1068700053544D3332463432780053544D333246FC +:106880003434365858000000012033000010410015 +:1068900001105A00031059000710310000000000D9 +:1068A0005C68000813040000666800081904000012 +:1068B00070680008210400007A68000840A2E4F132 +:1068C000646891060041A3E5F26569920700000043 +:1068D0004261642043414E496661636520696E648C +:1068E00065782E008000000000800000000080001D +:1068F000000000000000000015240008FD2B000827 +:106900005D2B00082524000859240008552600089E +:1069100029240008392400082D2400083524000803 +:10692000312400087D2500083D240008C92E0008F8 +:106930004D2400085125000800000000F93F000820 +:10694000E53F0008214000080D40000819400008FC +:1069500005400008F13F0008DD3F00082D40000819 +:106960000000000001000000000000006330000093 +:106970006C690008C04B0020D04D00204172647546 +:1069800050696C6F740025424F415244252D424C92 +:10699000002553455249414C2500000002000000EB +:1069A000000000001542000881420008400040003D +:1069B0007052002080520020020000000000000001 +:1069C0000300000000000000C542000800000000B5 +:1069D00010000000905200200000000001000000A4 +:1069E000000000004855002001010200E54D0008AC +:1069F000F54C0008914D0008754D0008430000005B +:106A0000046A000809024300020100C032090400C0 +:106A1000000102020100052400100105240100010B +:106A2000042402020524060001070582030800FF72 +:106A300009040100020A00000007050102400000ED +:106A4000070581024000000012000000506A0008A3 +:106A50001201100102000040091241570002010218 +:106A6000030100000403090425424F41524425005C +:106A70003031323334353637383941424344454674 +:106A80000000000000400000004000000040000046 +:106A900000400000000001000000020000000200B1 +:106AA00000000200000002000000020000000200DE +:106AB000000002000000000009440008C146000870 +:106AC0006D47000840004000A8550020A855002050 +:106AD00001000000B85500208000000040010000C7 +:106AE000030000006D61696E0069646C6500000060 +:106AF000AA01A81200000000AAAAAAAA550114001F +:106B0000FFBF00008877000070A70A0000000A019C +:106B100000000000AAAAAAAA00000001FFFF0000CE +:106B200000000000990000000000A0160000000016 +:106B3000AAAAAAA600005011FFDF00000000000072 +:106B4000007708002000000000000000AAAAAAAAFE +:106B500010000000FFFF000000080000000000001F +:106B60000000000000000000AAAAAAAA000000007D +:106B7000FFFF000000000000000000000000000017 +:106B800000000000AAAAAAAA00000000FFFF00005F +:106B900000000000000000000000000000000000F5 +:106BA000AAAAAAAA00000000FFFF0000000000003F +:106BB0000000000000000000000000000A000000CB +:106BC00000000000030000000000000000000000C2 +:106BD00000000000000000000000000000000000B5 +:106BE0000000000000000000000000003496FF7F5D +:106BF0000100000000000000F6030000000000009B +:106C000000000F000000000040420F00FE2A0100BB +:106C1000D2040000FF00960000000008009600006B +:106C20000000080004000000646A00080000000082 +:106C30000000000000000000000000000000000054 +:106C400000000000502300200000000000000000B1 +:106C50000000000000000000000000000000000034 +:106C60000000000000000000000000000000000024 +:106C70000000000000000000000000000000000014 +:106C80000000000000000000000000000000000004 +:106C900000000000000000000000000000000000F4 +:086CA0000000000000000000EC :00000001FF diff --git a/Tools/bootloaders/fmuv3-bdshot_bl.bin b/Tools/bootloaders/fmuv3-bdshot_bl.bin new file mode 100755 index 00000000000000..87f62577ec0bad Binary files /dev/null and b/Tools/bootloaders/fmuv3-bdshot_bl.bin differ diff --git a/Tools/bootloaders/mRo-M10095_bl.bin b/Tools/bootloaders/mRo-M10095_bl.bin index 377091dfc2df16..d6e9552de9d889 100755 Binary files a/Tools/bootloaders/mRo-M10095_bl.bin and b/Tools/bootloaders/mRo-M10095_bl.bin differ diff --git a/Tools/bootloaders/mRo-M10095_bl.elf b/Tools/bootloaders/mRo-M10095_bl.elf index 67ac806284a39b..f516a144bc382b 100755 Binary files a/Tools/bootloaders/mRo-M10095_bl.elf and b/Tools/bootloaders/mRo-M10095_bl.elf differ diff --git a/Tools/bootloaders/mRo-M10095_bl.hex b/Tools/bootloaders/mRo-M10095_bl.hex index 30030e9f4f2bba..097fbdc19b25cd 100644 --- a/Tools/bootloaders/mRo-M10095_bl.hex +++ b/Tools/bootloaders/mRo-M10095_bl.hex @@ -1,19 +1,19 @@ :020000040800F2 -:1000000000070020F5040008492C0008012C000816 -:10001000292C0008012C0008212C0008F7040008F6 -:10002000F7040008F7040008F7040008193C00086A +:1000000000070020F5040008A52F00085D2F000858 +:10001000852F00085D2F00087D2F0008F7040008D9 +:10002000F7040008F7040008F7040008853F0008FB :10003000F7040008F7040008F7040008F7040008B4 :10004000F7040008F7040008F7040008F7040008A4 -:10005000F7040008F7040008914F0008B94F0008A2 -:10006000E14F00080950000831500008F70400086B +:10005000F7040008F7040008D9520008015300080B +:10006000295300085153000879530008F704000889 :10007000F7040008F7040008F7040008F704000874 :10008000F7040008F7040008F7040008F704000864 -:10009000F7040008E12B0008F12B00085950000874 +:10009000F70400083D2F00084D2F0008A153000869 :1000A000F7040008F7040008F7040008F704000844 -:1000B00041510008F7040008F7040008F70400089D +:1000B00089540008F7040008F7040008F704000852 :1000C000F7040008F7040008F7040008F704000824 -:1000D000F70400082D510008F7040008F704000891 -:1000E000BD500008F7040008F7040008F7040008F2 +:1000D000F704000875540008F7040008F704000846 +:1000E00005540008F7040008F7040008F7040008A6 :1000F000F7040008F7040008F7040008F7040008F4 :10010000F7040008F7040008F7040008F7040008E3 :10011000F7040008F7040008F7040008F7040008D3 @@ -29,7 +29,7 @@ :1001B000F7040008F7040008F7040008F704000833 :1001C000F7040008F7040008F7040008F704000823 :1001D000F7040008F7040008F7040008F704000813 -:1001E0007D16000800000000000000000000000074 +:1001E00009180008000000000000000000000000E6 :1001F00053B94AB9002908BF00281CBF4FF0FF318E :100200004FF0FF3000F074B9ADF1080C6DE904CE89 :1002100000F006F8DDF804E0DDE9022304B07047E1 @@ -85,1276 +85,1328 @@ :10053000F0004EF68851CEF200010860BFF34F8FF5 :10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 :10055000CEF200010860062080F31488BFF36F8F8D -:1005600004F046FB04F0D8FB4FF055301F491B4AFE +:1005600004F0EAFC04F07CFD4FF055301F491B4AB3 :1005700091423CBF41F8040BFAE71D49184A9142E9 :100580003CBF41F8040BFAE71A491B4A1B4B9A423D :100590003EBF51F8040B42F8040BF8E7002018495D -:1005A000184A91423CBF41F8040BFAE704F024FBDF -:1005B00004F0F8FB144C154DAC4203DA54F8041B5C +:1005A000184A91423CBF41F8040BFAE704F0C8FC3A +:1005B00004F09CFD144C154DAC4203DA54F8041BB6 :1005C0008847F9E700F042F8114C124DAC4203DACB -:1005D00054F8041B8847F9E704F00CBB000700201F +:1005D00054F8041B8847F9E704F0B0BC000700207A :1005E000002300200000000808ED00E000010020CA -:1005F0000007002048540008002300208C2300201E -:100600009023002070500020E0010008E401000861 +:1005F0000007002090570008002300208C230020D3 +:1006000090230020C0540020E0010008E40100080D :10061000E4010008E40100082DE9F04F2DED108AF7 :10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 -:10063000002383F311882846A047002003F056FFCB -:10064000FEE703F0B9FE00DFFEE70000F8B504F0B6 -:1006500071FA074604F0C2FA0546B8BB204B9F4228 -:1006600034D001339F4234D01E4B27F0FF029A4210 -:1006700032D1F8B200F04EFE2E4642F2107400F075 -:100680004FFE08B10024264601F0A6FA20B103204F -:1006900000F07CF80024264635B1134B9F4203D06E -:1006A00004F094FA00242646002004F04DFA0EB11E -:1006B00000F082F801F05AF900F056FE01F04CF813 -:1006C000204600F0D7F800F077F8F9E72E4600242E -:1006D000D5E704460126D2E706464FF47A74CEE702 -:1006E000010007B0000008B0263A09B008B500F0D4 -:1006F000FFFFA0F120035842584108BD07B541F261 -:100700001203022101A8ADF8043001F00FF803B084 -:100710005DF804FB38B5302383F31188174803686C -:100720000BB103F0A1FF164A144800234FF47A716D -:1007300003F090FF002383F31188124C236813B158 -:100740002368013B2360636813B16368013B636006 -:100750000D4D2B7833B963687BB9022001F094F812 -:10076000322363602B78032B07D163682BB90220F7 -:1007700001F08AF84FF47A73636038BD902300204B -:1007800015070008B0240020A8230020084B18708B -:1007900003280CD8DFE800F008050208022001F069 -:1007A0006BB8022001F060B8024B00225A6070471B -:1007B000A8230020B024002038B501F00DFA30B194 -:1007C000254B03221A70254B00225A6038BD244B5A -:1007D000244A19680131F9D004339342F9D1224CEB -:1007E0001F4DD4F80428AA42F0D3204B9B6803F194 -:1007F000006303F5F0439A42E8D204F0B9F904F03B -:10080000CBF9002000F0C2FF0220FFF7BFFF184B1A -:100810009A6D00229A65996F9A67996FD96DDA651A -:10082000D96FDA67D96F196E1A66D3F88010C3F8DA -:100830008020D3F8803072B64FF0E0233021C3F827 -:10084000085DD4F80038D4F8042881F311889D4657 -:1008500083F308881047B9E7A8230020B0240020BC -:1008600000780008207800080070000800230020AD -:10087000001002402DE9F04F93B0AC4B00902022C5 -:10088000FF210AA89D6801F01BF8A94A1378A3B9B3 -:10089000A848012103601170302383F31188036895 -:1008A0000BB103F0E1FEA44AA24800234FF47A7191 -:1008B00003F0D0FE002383F31188009B13B19F4BFC -:1008C000009A1A609E4A009C1378032B1EBF0023D7 -:1008D00013709A4A4FF0000A18BF5360D346564629 -:1008E000D146012000F0C8FF24B1944B1B68002BB7 -:1008F00000F01582002000F0FBFE0390039B002B0C -:1009000001DA00F079FD039B002BEDDB012000F004 -:10091000ABFF039B213B162BE3D801A252F823F037 -:100920007D090008A5090008390A0008E308000845 -:10093000E3080008E3080008C30A0008930C000855 -:10094000AD0B00080F0C0008370C00085D0C000808 -:10095000E30800086F0C0008E3080008E10C000839 -:100960001D0A0008E3080008250D00088909000891 -:100970001D0A0008E30800080F0C00080220FFF71A -:10098000B5FE002840F0F581009B0221BAF1000F6E -:1009900008BF1C4605A841F21233ADF8143000F030 -:1009A000C5FE9EE74FF47A7000F0A2FE071EEBDB57 -:1009B0000220FFF79BFE0028E6D0013F052F00F242 -:1009C000DA81DFE807F0030A0D10133605230593DB -:1009D000042105A800F0AAFE17E054480421F9E715 -:1009E00058480421F6E758480421F3E74FF01C0863 -:1009F000404600F0CDFE08F104080590042105A84A -:100A000000F094FEB8F12C0FF2D1012000FA07F7A4 -:100A100047EA0B0B5FFA8BFB4FF0000900F09CFFDD -:100A200026B10BF00B030B2B08BF0024FFF766FE6B -:100A300057E746480421CDE7002EA5D00BF00B0365 -:100A40000B2BA1D10220FFF751FE074600289BD0B7 -:100A5000012000F09BFE0220FFF798FE00265FFABF -:100A600086F8404600F0A4FE044690B100214046BE -:100A700000F0AEFE01360028F1D1BA46044641F23C -:100A80001213022105A8ADF814303E4600F04EFEC8 -:100A900027E70120FFF77AFE2546244B9B68AB42EF -:100AA00007D9284600F074FE013040F06781043514 -:100AB000F3E7234B00251D70204BBA465D603E4690 -:100AC000ACE7002E3FF460AF0BF00B030B2B7FF471 -:100AD0005BAF0220FFF75AFE322000F009FEB0F1B2 -:100AE0000008FFF651AF18F003077FF44DAF0F4A2F -:100AF000926808EB050393423FF646AFB8F5807F56 -:100B00003FF742AF124B0193B84523DD4FF47A70A3 -:100B100000F0EEFD0390039A002AFFF635AF019B2B -:100B2000039A03F8012B0137EDE700BF00230020F3 -:100B3000AC2400209023002015070008B0240020DA -:100B4000A823002004230020082300200C230020D9 -:100B5000AC230020C820FFF7C9FD074600283FF45A -:100B600013AF1F2D11D8C5F1200242450AAB25F065 -:100B7000030028BF424683490192184400F08EFECC -:100B8000019A8048FF2100F09BFE4FEAA8037D49AF -:100B90000193C8F38702284600F09AFE0646002813 -:100BA0003FF46DAF019B05EB830537E70220FFF7AC -:100BB0009DFD00283FF4E8AE00F01CFE00283FF445 -:100BC000E3AE0027B846704B9B68BB4218D91F2F75 -:100BD00011D80A9B01330ED027F0030312AA134445 -:100BE00053F8203C05934046042205A900F0DEFF9F -:100BF00004378046E7E7384600F0CAFD0590F2E783 -:100C0000CDF81480042105A800F090FD06E700232C -:100C1000642104A8049300F07FFD00287FF4B4AEA3 -:100C20000220FFF763FD00283FF4AEAE049800F009 -:100C3000D7FD0590E6E70023642104A8049300F0A3 -:100C40006BFD00287FF4A0AE0220FFF74FFD0028C7 -:100C50003FF49AAE049800F0C5FDEAE70220FFF7E2 -:100C600045FD00283FF490AE00F0D4FDE1E70220FE -:100C7000FFF73CFD00283FF487AE05A9142000F0E3 -:100C8000CFFD04210746049004A800F04FFD39462B -:100C9000B9E7322000F02CFD071EFFF675AEBB074A -:100CA0007FF472AE384A926807EB090393423FF62D -:100CB0006BAE0220FFF71AFD00283FF465AE27F067 -:100CC00003074F44B9453FF4A9AE484600F060FD24 -:100CD0000421059005A800F029FD09F10409F1E7B8 -:100CE0004FF47A70FFF702FD00283FF44DAE00F09C -:100CF00081FD002844D00A9B01330BD008220AA9A9 -:100D0000002000F0E5FD00283AD02022FF210AA8AB -:100D100000F0D6FDFFF7F2FC1C4803F0EDFB13B02A -:100D2000BDE8F08F002E3FF42FAE0BF00B030B2B22 -:100D30007FF42AAE0023642105A8059300F0ECFCA3 -:100D4000074600287FF420AE0220FFF7CFFC804644 -:100D500000283FF419AEFFF7D1FC41F2883003F0D0 -:100D6000CBFB059800F00EFE464600F0F5FD3C4634 -:100D7000B7E5064652E64FF0000905E6BA467EE6BC -:100D800037467CE6AC23002000230020A08601002B -:100D9000094A136849F2690099B21B0C00FB013340 -:100DA0001360064B186844F2506182B2000C01FBDC -:100DB0000200186080B27047142300201023002026 -:100DC00010B500211022044600F07AFD034B03CB3E -:100DD000206061601868A06010BD00BF9075FF1FA3 -:100DE0002DE9F041ADF54E7D0DF134086CAC40F2CB -:100DF000751207460D460EA80021C8F8001000F035 -:100E00005FFD4FF4C4720021204600F059FD01F04F -:100E100023FF254B4FF47A72B0FBF2F0186093E891 -:100E20000700012384E807000DF5E9702382FFF72E -:100E3000C7FF41F204131D49238406A804F01CFADD -:100E4000182384F832310DF2E3266B440DF1300C97 -:100E50001A4603CA624530607160134606F10806FF -:100E6000F6D141460122204600F0A6FD002303935F -:100E7000AB7E029305F11903019380B20123CDE902 -:100E800004800093E97E06A3D3E90023384602F0EC -:100E9000A3FA0DF54E7DBDE8F08100BFAFF30080F1 -:100EA0009E6AC421818A46EEB82400208852000838 -:100EB0002DE9F043224DBBB001F0CEFEAB6840F20D -:100EC000ED22C31A934232D906AFA8602B462822DE -:100ED0000021384602F030FC05F10E0000F0E8FC7D -:100EE000002604465FFA80F905F10E08F3B2F1001E -:100EF000994501F1280107D908EB06030822384675 -:100F000002F01AFC0136F1E708230122CDE9023292 -:100F100005340C4B0193A4B230230093CDE9047443 -:100F200005A3D3E90023297B074802F055FA3BB01B -:100F3000BDE8F083AFF3008078F6339F93CACD8D80 -:100F4000B0490020BD490020D0340020F0B58B8A84 -:100F5000013B9BB2C92BC9B006460C4647D8274D6A -:100F60002F7B27BB05F10C03009308223B46394633 -:100F7000204602F0A5FA7B1CFAB2D9001F46A38ACC -:100F8000013B9A4205DA0E322A44009200230822DD -:100F9000EEE700230022C5E900230023AB6085F8BB -:100FA000D730C5F8D8302B7B0BB9E37E2B73812269 -:100FB000002106AD27A800F083FC0122294627A8BE -:100FC00000F0C8FD00230393A37E029304F11903EC -:100FD00080B201932823CDE90450E17E009330468E -:100FE00004A3D3E9002302F0F7F9FFF761FF49B04A -:100FF000F0BD00BF26417272DF25D7B7B04900208F -:1010000070B50D4614461E4602F042F950B9022E44 -:1010100010D1012C0ED112A3D3E90023C5E900237E -:10102000012007E0282C10D005D8012C09D0052C70 -:101030000FD0002070BD302CFBD10BA3D3E90023CF -:10104000ECE70BA3D3E90023E8E70BA3D3E90023E4 -:10105000E4E70BA3D3E90023E0E700BFAFF3008090 -:10106000401DA12026812A0B78F6339F93CACD8D8F -:101070009E6AC421818A46EE26417272DF25D7B767 -:10108000F017304A39059E562DE9F04F8DB002AF6A -:1010900080460D4602F0FCF8044600285CD12B7E09 -:1010A000022B1BD1EB8A012B18D101F0D5FD06468E -:1010B000FFF76EFE03464FF4C870DFF81C92B3FBD7 -:1010C000F0F206F5167602FB103316FA83F3C9F830 -:1010D0000030EB7E33B97B4B00221A702C37BD46B3 -:1010E000BDE8F08FAB8AE6B2013BB34204F10104E4 -:1010F0000CD907F108031E44E100009600230822E2 -:1011000001F0F801284602F0DBF9EBE707F11800DF -:10111000FFF756FE324607F1180107F1080004F008 -:1011200079F80028D7D10F2E08D8664B1E70D9F851 -:101130000030A3F51673C9F80030CFE7FB1DF87136 -:101140000146009307220346284602F0B9F9F979CF -:10115000404602F095F8C1E7EB8A282B26D010D83C -:10116000012B1ED0052BB9D1BFF34F8F5649574BDA -:10117000CA6802F4E0621343CB60BFF34F8F00BF35 -:10118000FDE7302BAAD16B7E514C0133627BDBB281 -:101190009342E94603D1EA7E237B9A420BD0CD46A7 -:1011A0009CE729464046FFF71BFE97E72946404645 -:1011B000FFF7CCFE92E74FF0000807F11803A7F8FD -:1011C00018801022009341460123284602F078F946 -:1011D000AE8A023EB6B2F31C9B109B000733DB08BD -:1011E000A9EBC3039D460DF1080A1FFA88F34FEAE5 -:1011F000C8019E4201F110010AD90AEB08030093CD -:1012000008220023284602F05BF908F10108ECE708 -:1012100094F8D70000F0CCFAD4F8D810054619B9E4 -:1012200094F8D70000F0D4FAD4F8D83033449D4273 -:1012300005D294F8D7000021013000F0C9FA4FEA36 -:10124000960B4FF000081FFA88F18B45D4E9003265 -:1012500009D90AEB880103EB8800012200F038FB72 -:1012600008F10108EFE7F31842F10002C4E9003287 -:10127000D4F8D83094F8D70006EB0308C4F8D88027 -:1012800000F096FA804509D394F8D730D4F8D80006 -:101290000133401B84F8D730C4F8D800FF2E0D4D21 -:1012A00009D80023237300F0A5FA00F095FC2881EB -:1012B00008B9FFF781FA23689B0A01332B810023C9 -:1012C000A3606CE7C934002000ED00E00400FA05DB -:1012D000B0490020B8240020CC34002010B50A4BBF -:1012E0000A4A1A6003F5805393F848203AB95C6CB7 -:1012F0002CB1204600F0EEFC204603F073FFBDE861 -:101300001040034800F0E6BC00350020E052000821 -:1013100030450020014B1870704700BFC4240020E6 -:1013200010B54FF000540C4B22689A4211D10B4B70 -:10133000627D1A700A48237D03730A49C9220E3060 -:1013400000F0ACFAE0220021204600F0B9FA0120BA -:1013500010BD0020FCE700BF9AAD44C5C4240020A6 -:10136000B04900201600002037B500F035FC194DBB -:101370001949288102236B7100220123174801F0CB -:101380006FF800230193164B164900931648174B2C -:101390004FF4805201F04CFF154B197811B11248EF -:1013A00001F06EFF01F058FC0446FFF7F1FC4FF42A -:1013B000C873B0FBF3F202FB130304F5167010FAC6 -:1013C00083F00C4B186003F009FC08B10F232B814C -:1013D00003B030BDB824002040420F00003500208B -:1013E00001100008C8240020D03400208910000813 -:1013F000C4240020CC3400202DE9F04F2DED028BC9 -:1014000095A7D7E900670FF25829D9E900898C4CD4 -:1014100095B0DFF854A2DFF854B2204602F008F885 -:10142000034650B30025CDE911551095ADF84C5049 -:10143000027B8DF84C209968406811AA03C21B6892 -:1014400043F00043109301F009FC10EB0A0241F154 -:101450000003009510A9584600F0DAFDA842794A29 -:1014600005DD204601F0E8FF764A1570D5E71378D0 -:10147000072B00F2B980013313700DAD9FED6E8B19 -:101480000023DFF8E8B10C93ADF83C300D936B60AE -:1014900000230DF125028DED008B4FF0010A09A903 -:1014A00058468DF825308DF824A001F03DFB9DF8BD -:1014B00024200023002A40F09B80204601F0E8FE13 -:1014C0000546002847D1DFF8A8B101F0C5FBDBF8DD -:1014D000003098423FD301F0BFFB0790FFF758FC64 -:1014E000079A4FF4C87302F51672B0FBF3F101FBD3 -:1014F000130312FA83F3CBF80030DFF878B19BF8CE -:1015000000100791002914BF2B46534610A88DF8F0 -:101510003030FFF755FC0799C1F11002D2B2062A0C -:1015200010AB28BF062219440DF13100079200F0DC -:10153000B5F9079A0CAB0393182302930132424B7F -:10154000D2B2CDE900A304923B463246204601F0D8 -:10155000E5FE8BF8005001F07FFB3C4A3C4D1368E0 -:10156000C31AB3F57A7F32D3106001F077FB0246DD -:101570000B46204601F06AFF204601F089FE30B399 -:101580002B7BDFF8F4A0002B14BF032302238AF87F -:10159000053001F061FB0DF1400B4FF47A7301222D -:1015A000B0FBF3F05946CAF80000504600F0AAFA22 -:1015B00018230293274B019380B240F25513CDE9D3 -:1015C00003B0009342464B46204601F0A7FE2B7B1A -:1015D0002BB1FFF76DFC2B7B002B7FF41AAF15B0FE -:1015E000BDEC028BBDE8F08F204601F025FF44E7FB -:1015F0004FF0904110A84A6982F010024A611946E2 -:10160000102200F05DF90DF126030AAA0CA9584634 -:1016100000F0F0FD95E8030011AB83E803009DF8AE -:101620003C308DF84C300C9B109310A9DDE90A2357 -:10163000204602F0C9F82BE700000000000000007F -:10164000D0340020954A0020C8340020904A002061 -:10165000B0490020944A0020401DA12026812A0B79 -:10166000F1C6A7C1D068080F40420F000035002026 -:10167000CC340020C9340020B824002008B5054827 -:1016800000F05CFEBDE80840034A0449002003F076 -:10169000A3BD00BF00350020E84A0020DD1200088D -:1016A00070B5104B1B780133DBB2012B0C4612D8FE -:1016B0000D4B1D6829684FF47A730E6AA2FB033242 -:1016C000014622462846B047844204D1074B0022F7 -:1016D0001A70012070BD4FF4FA7002F00DFF002067 -:1016E000F8E700BF182300201C230020DC4A00205C -:1016F00007B50023024601210DF107008DF80730E0 -:10170000FFF7CEFF20B19DF8070003B05DF804FBA2 -:101710004FF0FF30F9E700000A4608B50421FFF753 -:10172000BFFF80F00100C0B2404208BD30B4074B9B -:101730000A461978064B53F821402368DD69054BAA -:101740000146AC46204630BC604700BFDC4A002062 -:101750001C230020A086010070B503F075F8094E27 -:10176000094D3080002428683388834208D903F06B -:1017700067F82B6804440133B4F5F04F2B60F2D3C3 -:1017800070BD00BFDE4A0020984A002003F020B957 -:1017900000F1006000F5E040D0F80008704700005C -:1017A00000F10060920000F5F04003F091B80000F5 -:1017B000054B1A68054B1B889B1A834202D91044BB -:1017C00003F03EB800207047984A0020DE4A00200F -:1017D000024B1B68184403F04BB800BF984A002026 -:1017E0000020704700F10050A0F51040D0F890059F -:1017F00070470000064991F8243033B10023086A8D -:1018000081F824300822FFF7CBBF0120704700BFCA -:101810009C4A0020014B1868704700BF002004E07C -:1018200030B50F4B0F4C1B682288C3F30B030138F4 -:10183000934208440BD164680A46013C8242134635 -:101840000BD214F9015F2DB102F8015BF6E781427A -:101850000B4602D22C2203F8012B581A30BD00BFD0 -:10186000002004E020230020022802BF4FF0904314 -:1018700010229A6170470000022802BF4FF0904387 -:101880004FF480129A617047022801BF4FF09042D6 -:10189000536983F0100353617047000010B50023B3 -:1018A000934203D0CC5CC4540133F9E710BD00006F -:1018B00003460246D01A12F9011B0029FAD17047DB -:1018C00002440346934202D003F8011BFAE7704733 -:1018D0002DE9F8431F4D144695F824200746884605 -:1018E00052BBDFF870909CB395F824302BB92022BE -:1018F000FF2148462F62FFF7E3FF95F82400C0F16F -:101900000802A24228BF2246D6B24146920005EB09 -:101910008000FFF7C3FF95F82430A41B1E44F6B2E5 -:10192000082E17449044E4B285F82460DBD1FFF719 -:1019300061FF0028D7D108E02B6A03EB82038342C2 -:10194000CFD0FFF757FF0028CBD10020BDE8F883A8 -:101950000120FBE79C4A0020024B1A78024B1A70C8 -:10196000704700BFDC4A00201823002003494FF4D1 -:10197000E1330B60024B186802F084BCC44A0020BB -:101980001C230020094B10B51822044600211846DC -:10199000FFF796FF064A074B127804600146BDE840 -:1019A000104053F8220002F06DBC00BFC44A002072 -:1019B000DC4A00201C2300202DE9F0470D46044698 -:1019C00000219046284640F27912FFF779FF23461E -:1019D00020220021284601F0AFFE231D02222021F3 -:1019E000284601F0A9FE631D03222221284601F0AA -:1019F000A3FEA31D03222521284601F09DFE04F12C -:101A0000080310222821284601F096FE04F1100355 -:101A100008223821284601F08FFE04F11103082224 -:101A20004021284601F088FE04F1120308224821D3 -:101A3000284601F081FE04F114032022502128469B -:101A400001F07AFE04F1180340227021284601F0CB -:101A500073FE04F120030822B021284601F06CFE39 -:101A600004F121030822B821284601F065FE04F1A3 -:101A70002207C0263B46314608222846083601F098 -:101A80005BFEB6F5A07F07F10107F3D104F1320345 -:101A900008223146284601F04FFE002704F1330AA0 -:101AA00094F832304FEAC7099F4209F5A47615D35E -:101AB000B8F1000F08D1314604F599730722284682 -:101AC00001F03AFE09F24F16274694F832213B1BEB -:101AD00093420CD3F01DC008BDE8F0870AEB070362 -:101AE00008223146284601F027FE0137D8E707F2E1 -:101AF000331331460822284601F01EFE083601370E -:101B0000E3E7000013B504460846002101602346C0 -:101B1000C0F803102022019001F00EFE0198231D51 -:101B20000222202101F008FE0198631D03222221D8 -:101B300001F002FE0198A31D0322252101F0FCFD06 -:101B4000019804F108031022282101F0F5FD072077 -:101B500002B010BDF8B50E4605461446002181229C -:101B60003046FFF7ADFE2B4608220021304601F03B -:101B7000E3FD7CB96B1C07220821304601F0DCFD37 -:101B80000F2401236A785F1C013B934204D3E01DBC -:101B9000C008F8BD0824F4E7EB19214608223046B6 -:101BA00001F0CAFD08343B46ECE7000030B5094DB2 -:101BB0000A4491420DD011F8013B5840082340F3EC -:101BC0000004013B2C4013F0FF0384EA5000F6D1DF -:101BD000EFE730BD2083B8ED73B5384A106851681F -:101BE0006B4603C36A4636493648082303F022FB96 -:101BF000044670B9344A106851686B4603C36A469C -:101C000032493048082303F015FB044630BB0A2054 -:101C100022E00369B3F5623FECD8418B40F21142F8 -:101C20009142E7D12A4A024402F110018B42E1D3EA -:101C3000103B244900209D1AFFF7B8FF2A460646AC -:101C400004F118010020FFF7B1FFA3689E42D1D133 -:101C5000E3689842CED1002002B070BD0369B3F5AD -:101C6000623F22D8B0F8661040F2114291421ED174 -:101C7000174A024402F15C018B421AD35C3B1149C2 -:101C800000209D1AFFF792FF2A46064604F16401E0 -:101C90000020FFF78BFFA268964203460BD1E06855 -:101CA000834214BF0D200020D6E70B20D4E70C2080 -:101CB000D2E71020D0E70D20CEE700BFB0520008D9 -:101CC000DC87030000780008B95200089087030001 -:101CD0000888FFF710B5037C044613B9006803F0C9 -:101CE00091FA204610BD00000023BFF35B8FC36054 -:101CF000BFF35B8FBFF35B8F8360BFF35B8F704776 -:101D0000BFF35B8F0068BFF35B8F704770B505460C -:101D10000C30FFF7F5FF05F1080604463046FFF7E3 -:101D2000EFFFA04206D930466D68FFF7E9FF254472 -:101D3000281A70BD3046FFF7E3FF201AF9E70000CC -:101D400070B50546406898B105F10800FFF7D8FF67 -:101D500005F10C0604463046FFF7D2FF84423046B8 -:101D600094BF6D680025FFF7CBFF013C2C44201A7F -:101D700070BD000038B50C460546FFF7C7FFA0420E -:101D800010D305F10800FFF7BBFF04446868B4FBFB -:101D9000F0F100FB1144BFF35B8F0120AC60BFF397 -:101DA0005B8F38BD0020FCE72DE9F0411446074663 -:101DB0000D46FFF7C5FF844228BF0446D4B1B8469C -:101DC00058F80C6B4046FFF79BFF304428604046B4 -:101DD0007E68FFF795FF331A9C4203D86C600120A0 -:101DE000BDE8F0816B60A41B3B68AB602044E860F9 -:101DF0000220F5E72046F3E738B50C460546FFF725 -:101E00009FFFA04210D305F10C00FFF779FF0444B7 -:101E10006868B4FBF0F100FB1144BFF35B8F012055 -:101E2000EC60BFF35B8F38BD0020FCE72DE9FF417C -:101E3000884669460746FFF7B7FF6C4606B204EBD3 -:101E4000C6060025B44209D06268206808EB050187 -:101E5000FFF724FD636808341D44F3E7294638463C -:101E6000FFF7CAFF284604B0BDE8F081F8B5054683 -:101E70000C300F46FFF744FF05F1080604463046D4 -:101E8000FFF73EFFA042304688BF6C68FFF738FF7F -:101E9000201A386020B130462C68FFF731FF20440B -:101EA000F8BD000073B5144606460D46FFF72EFF39 -:101EB000844228BF04460190DCB101A93046FFF7F7 -:101EC000D5FF019B33B93268C5E90233C5E9002467 -:101ED00001200CE09C4238BF0194286001986860A2 -:101EE0008442F5D93368AB60241AEC60022002B05A -:101EF00070BD2046FBE700002DE9FF410F46694613 -:101F0000FFF7D0FF6C4600B204EBC0050026AC42E0 -:101F100009D0D4F8048054F8081BB8194246FFF7DA -:101F2000BDFC4644F3E7304604B0BDE8F081000054 -:101F300038B50546FFF7E0FF044601462846FFF79F -:101F400019FF204638BD0000302383F3118862B6A4 -:101F500070470000002383F3118862B670470000C9 -:101F6000012070477047000010B4134602681468DF -:101F70000022A4465DF8044B6047000000F5805045 -:101F800090F859047047000000F5805090F8520412 -:101F90007047000000F5805090F958047047000029 -:101FA0005020704700F5805208B5FFF7CDFFD2F8FA -:101FB0009834D2F894041844D2F890341844D2F8E3 -:101FC00078341844D2F888341844D2F88434184449 -:101FD000FFF7C0FF08BD000038B5C26A936923F05F -:101FE00001039361044600F037FE0546E36A9B69EE -:101FF000DB0706D500F030FE431BFA2BF6D9002094 -:1020000004E004F58054012084F8520438BD000037 -:102010002DE9F04F0C4600F5805185B01F4691F830 -:102020005234BDF83890054690469BB1D1F87434CF -:102030000133C1F8743423689A0006D4237B082B3B -:102040000BD9627B0AB10F2B07D9D1F87834013351 -:10205000C1F878344FF0FF300FE0FFF775FFEB6AFF -:10206000D3F8C42012F4001A0AD0D1F87C3401331A -:10207000C1F87C34FFF76EFF002005B0BDE8F08F9B -:10208000D3F8C46022686B6AC6F301464FF0480B70 -:10209000002A1BFB063BB4BF42F080429204CBF8FF -:1020A000002023685B0044BF42F00052CBF80020C0 -:1020B000227B330643EA0243CBF80430607B720193 -:1020C00018B343F44013CBF80430D1F8A4340133EF -:1020D000C1F8A434AB1803F58353197B41F02001F8 -:1020E0001973207B039200F015FE039A03308010D1 -:1020F0005FFA8AF383420AF1010A0DDA04EB8301E5 -:102100000BEB830349689960F2E7AB1803F583533F -:10211000197B60F34511E3E7EB6A0121B140C3F895 -:10212000CC10AB1803F58253C3E9048705EB4613C3 -:1021300003F582532146183304F10C0051F804CB07 -:1021400043F804CB8142F9D1098819802A4441F22D -:1021500068032846D65002F5805209F0030392F82E -:102160006C1043F0100321F01F010B4382F86C3018 -:10217000FFF7F0FE4246CDF800903B46214600F0C6 -:102180008FFD012079E7000013B500F5805401911F -:10219000606CFFF7D5FD1F280AD90199606C2022D9 -:1021A000FFF744FEA0F120035842584102B010BD91 -:1021B0000020FBE708B500F58050FFF7C5FE406C36 -:1021C000FFF792FDBDE80840FFF7C4BE00220260A1 -:1021D000828142608260704710B500220023C0E90E -:1021E00000230023044603810C30FFF7EFFF204655 -:1021F00010BD00002DE9F047074688B007F5805470 -:1022000068469A468846FFF79FFE9146FFF7E4FF2F -:10221000606CFFF77BFD1F282CD9606C202269467B -:10222000FFF786FE202825D194F8523413B303AD6E -:10223000444605AB2E4603CE9E4220606160354683 -:1022400004F10804F6D130682060B388A380DDE98A -:102250000023C9E90023BDF80830AAF80030FFF7D1 -:1022600079FE4A4653464146384608B0BDE8F04735 -:1022700000F004BDFFF76EFE002008B0BDE8F08757 -:102280002DE9F84F00230646C0E90133284B46F8F4 -:10229000303B00F5815405468846374610343846B1 -:1022A0002037FFF799FFA742F9D105F580544FF485 -:1022B000805326630026C4E90D366764012305F5C3 -:1022C000835705F5A359E66384F8403084F8483015 -:1022D000103709F110094FF0000A4FF0000B47E9E1 -:1022E00008ABA7F11800FFF771FF203747F8286CFB -:1022F0004F45F4D184F85884A4F85A64A4F85C6477 -:10230000A4F85E6484F86064A4F86264A4F8646469 -:10231000A4F8666484F86864B8F1000F02D0054838 -:1023200000F094FC044BEB622846BDE8F88F00BF38 -:10233000E0520008C45200080064004010B5044B8D -:10234000197804464A1C1A70FFF79AFF204610BD00 -:10235000E54A00202DE9F04300295FD03048314B99 -:10236000B3FBF1F381428CBF0A201120451EB3FB61 -:10237000F0F700FB1730ECB220B1022D2846F5D85B -:10238000002037E07D1EB5F5806F33D2C4EBC40862 -:1023900008F103034FEAE30EC3F3C703A4EB030CF6 -:1023A0000EF101094FF47A705FFA8CF60EFB000E05 -:1023B00059FA8CFCBEFBFCFCBCF5617F1CDC1FFAEF -:1023C0008CF4581C56FA80F047431648B0FBF7F7D8 -:1023D000B942D5D1013BDBB20F2BD1D8711EC9B2A6 -:1023E00007294FF0000005D81071148055805371F3 -:1023F00091710120BDE8F08308F1FF334FEAE30C4F -:10240000C3F3C703E41A0CF1010EE6B20CFB0000A3 -:102410005EFA84F4B0FBF4F4A4B2D2E70846E9E72C -:102420003F420F0000127A000B4B10B54FF454726C -:10243000044600211846FFF743FA084BA3614033D6 -:10244000E361D8332362F0336362E36A60610022A0 -:10245000C3F8C02010BD00BF00A4004070A400401D -:102460002DE9F04F00F58055994695F85834012B29 -:1024700089B004468A46904604D90027384609B0F8 -:10248000BDE8F08F904A52F8231009B942F82300B2 -:102490008E49C4F80CA00B7884F8109093B9FFF71C -:1024A00053FD8B4B9A6D42F000729A659A6B42F025 -:1024B00000729A639A6B22F000729A6301230B7088 -:1024C000FFF748FD95F8513473B903211520FFF744 -:1024D0003BFD01F021FD0321162001F01DFD01232C -:1024E00085F85134FFF736FDFFF72EFDE26A936958 -:1024F00023F01003936100F0AFFB0746E36A9E6987 -:1025000016F0080607D000F0A7FBC31BFA2BF5D97D -:10251000FFF720FDB1E79A6942F001029A6100F0ED -:102520009BFB0746E36A9A69D00705D400F094FB49 -:10253000C31BFA2BF6D9EBE79A6942F002029A61C3 -:10254000E36A00275F65FFF705FD686CFFF7CCFBCA -:1025500004F5825B0BF1100B202200216846FFF787 -:10256000AFF902A8FFF732FE06976A460BEB0603A7 -:102570000DF1180E9446BCE80300F445186059604C -:10258000624603F10803F5D1DCF80000186020363C -:102590009CF804201A71B6F5806FDDD1002304F594 -:1025A000A25285F8503485F853341A3251462046E9 -:1025B000FFF7D0FE074690B9E26A936923F0010362 -:1025C000936100F049FB0546E36A9B69D9077FF5F3 -:1025D00054AF00F041FB431BFA2BF5D94DE795F8BA -:1025E0005F6495F85E24C5F86CA4360246EA42663C -:1025F00095F86024E36A1643B5F85C2446EA02467F -:10260000DE61B8F1000F29D004F5A3520232414631 -:102610002046FFF79FFE90B9E26A936923F0010319 -:10262000936100F019FB0546E36A9B69DA077FF5C1 -:1026300024AF00F011FB431BFA2BF5D91DE795F8E9 -:10264000683495F86714C5F870841B0143EA0123C8 -:10265000B5F86414E26A43EA0143D3602046FFF709 -:10266000E3FE002385F85934E36A6FF040421A65AF -:10267000E36A184A5A65E36A44229A65E36A0722C4 -:10268000C3F8DC20E36A0322DA65E26A9369B9F1F0 -:10269000030F43F4407393613FF4F0AEE26A936931 -:1026A00023F00103936100F0D7FA0646E36A9B69C1 -:1026B000DB0705D500F0D0FA831BFA2BF6D9DCE650 -:1026C000012385F85234D9E6E04A0020E44A00208C -:1026D000001002409B0008002DE9F04F054689B02C -:1026E00090469946002741F2680A00F58056EB6A49 -:1026F000D3F8D430FB40D8074AD505EB47125244F3 -:102700004FEA471B1379190742D4D6F880340133B6 -:10271000C6F8803413799A0648BFD6F8A83405EB7A -:102720000B0248BF0133524448BFC6F8A83413799E -:1027300043F008031371DB0722D596F85334FBB13D -:1027400005F58254183468465C44FFF745FD03AB39 -:1027500004F1080C206861681A4603C20834644515 -:102760001346F7D120681060A2889A800123ADF843 -:1027700008302B68CDE90089DB6B6946284698470D -:10278000D6F8543423B1D6F89C340133C6F89C34BF -:102790000137202FABD109B0BDE8F08F2DE9F04F04 -:1027A0008DB004460F4600F059FA82468946002F44 -:1027B00056D1E36AD3F89020920141BF04F58051CD -:1027C000D1F894240132C1F89424D3F8902016074C -:1027D00003D100200DB0BDE8F08FD3F89050E6692A -:1027E000C5F30125482303FB0566E8464046FFF78D -:1027F000EDFC326851004ABF22F06043C2F38A43C5 -:1028000043F00043920048BF43F080430093736855 -:1028100013F400131FBF04F5805201238DF80D300F -:10282000D2F8AC340EBF8DF80D300133C2F8AC34A1 -:10283000F38803F00F038DF80C304FF0000B9DF878 -:102840000C0000F067FA5FFA8BF3984220D9F21877 -:102850000CA90B44127A03F82C2C0BF1010BEEE7B8 -:10286000012FB6D1E36AD3F89820950141BF04F552 -:102870008051D1F894240132C1F89424D3F89820DF -:102880001007A6D0D3F89850266AC5F30125A9E70A -:10289000EFB9E36AC3F8945004A8FFF79DFC98E8E9 -:1028A0000F0007AD07C52B800023ADF81830236853 -:1028B0002046CDE904A9DB6B04A9984704F58054B0 -:1028C00058B1D4F88C340133C4F88C3482E7012F2A -:1028D00004BFE36AC3F89C50DEE7D4F890340133B8 -:1028E000C4F89034012075E7F8B505460F4600F5A9 -:1028F0008054012639462846FFF750FF10B184F86E -:102900005364F7E7D4F8543423B1D4F89C3401333A -:10291000C4F89C34F8BD0000F0B5C36A1A6C12F418 -:102920007F0F2BD000F580541B6CC4F8A03441F20B -:102930006805002347194FF0010C00EB43122A44AD -:102940005E01117911F0020F15D0490713D4B9595E -:10295000C66AD6F8C8E00CFA01F111EA0E0F0AD0E7 -:10296000C6F8D010117941F004011171D4F888240F -:102970000132C4F888240133202BDED1F0BD0000E1 -:1029800010B5254C254B226802B338B31A6D1206D8 -:102990000ED580221A6500F061F950EA01020B465B -:1029A00002D0013861F1000302462068FFF794FE6F -:1029B0001A4A136D1B032AD523684FF4002103F52F -:1029C00080531165012283F8592420E001221A6501 -:1029D00008221A654FF480621A6510BD196DC80788 -:1029E00002D4196D890705D5032119651046002108 -:1029F000FFF77AFF094B1A6D100702D41A6DD10642 -:102A000005D518221A6520680121FFF76DFF20689F -:102A1000BDE81040FFF780BFE04A0020006400409E -:102A200008B5FFF791FAFFF777FFBDE80840FFF719 -:102A300091BA0000C36AD3F8C40080F40010C0F358 -:102A40004050704700F5805008B5FFF77DFA406CA4 -:102A5000FFF75CF9FFF77EFA43090CBF0120002065 -:102A600008BD000000F5805393F8592462B1C16A93 -:102A70008A6922F001028A61D3F898240132C3F8EE -:102A80009824002283F85924704700002DE9F74369 -:102A900000F5825198461031FFF756FA002541F2B1 -:102AA000680E4FF0010900F5805C00EB451474449A -:102AB00023795E071CD4DB061AD5C36A8E69D3F866 -:102AC000C87009FA06F63E4212D04F6801970F68A7 -:102AD0009742019F77EB08070AD2C3F8D0602379A9 -:102AE00043F004032371DCF884340133CCF88434DC -:102AF0000135202D01F12001D7D103B0BDE8F0430D -:102B0000FFF728BAF8B51E46002313700F46054696 -:102B10001446FFF797FF80F0010038701EB1284679 -:102B2000FFF788FF2070F8BD2DE9F04F85B099467A -:102B3000DDE90EA30D4602931378019391F800B0DE -:102B40008046164600F08AF82B7804460F4613B9E3 -:102B50003378002B42D022463B464046FFF796FF93 -:102B6000FFF75EFFFFF77EFF4B4632462946FFF731 -:102B7000C9FF2B7833B1BBF1000F03D0012005B0A2 -:102B8000BDE8F08F337813B1019B002BF6D108F527 -:102B900080530393029B544577EB03031ED2039BA0 -:102BA000D3F85404D0B10368AAEB0401DB6889B2FE -:102BB00098474B46324629464046FFF7A3FF2B78FD -:102BC00013B1BBF1000FD9D1337813B1019B002BA6 -:102BD000D4D100F043F804460F46DBE70020CEE7EF -:102BE00008B50020FFF7CCFEBDE8084001F048B86A -:102BF00008B50120FFF7C4FEBDE8084001F040B869 -:102C000000B59BB0EFF3098168226846FEF746FEE7 -:102C1000EFF30583014B9B6BFEE700BF00ED00E087 -:102C200008B5FFF7EDFF000000B59BB0EFF3098199 -:102C300068226846FEF732FEEFF30583014B5B6BBB -:102C4000FEE700BF00ED00E0FEE700000FB408B5AE -:102C5000029801F0E7FBFEE701F008BF01F0E0BEDB -:102C600001F0DEBE13B56C4684E80600031D94E84F -:102C7000030083E80500012002B010BD73B585682C -:102C8000019155B11B885B0707D4D0E900369B6BD7 -:102C90009847019AC1B23046A847012002B070BDE2 -:102CA000F0B5866889B005460C465EB1BDF838308F -:102CB0005B070AD4D0E900379B6B98472246C1B224 -:102CC0003846B047012009B0F0BD00220023CDE90D -:102CD00000230023ADF808300A4603AB01F10806D3 -:102CE000106851681C4603C40832B2422346F7D12B -:102CF000106820609288A280FFF7B2FF0423ADF82D -:102D000008302B68CDE90001DB6B694628469847FF -:102D1000D8E70000082817D909280CD00A280CD0B9 -:102D20000B280CD00C280CD00D280CD00E2814BF6A -:102D30004020302070470C2070471020704714202E -:102D40007047182070472020704700002DE9F0419F -:102D5000456A15B94162BDE8F0814B6823F06047D0 -:102D6000C3F38A464FEAD37EC3F3807816EA23067C -:102D700038BF3E46AC462B465A68BEEBD27F22F0A7 -:102D800060440AD0002A18DAA40CB44217D19D423C -:102D90000FD10D60DEE71346EEE7A74207D102F040 -:102DA0008044C2F3807242450BD054B1EFE708D2A1 -:102DB000EDE7CCF800100B60CDE7B44201D0B4428F -:102DC000E5D81A689C46002AE5D11960C3E70000DF -:102DD0002DE9F047089D01F007044FEAD508224489 -:102DE00005F0070500EBD1004FF47F49944201D173 -:102DF000BDE8F08704F0070705F0070A57453E468F -:102E000038BF5646C6F10806111B8E4228BF0E4633 -:102E1000E10808EBD50E415C13F80EC0B94029FA61 -:102E200006F721FA0AF1FFB28CEA010147FA0AF724 -:102E300039408CEA010C03F80EC034443544D5E720 -:102E400080EA0120082341F2210201B2400000295A -:102E500080B203F1FF33B8BF504013F0FF03F4D149 -:102E60007047000038B50C468D18A54200D138BD1A -:102E700014F8011BFFF7E4FFF7E7000042684AB1CE -:102E8000136843604389818901339BB2994243812E -:102E900038BF83811046704770B588B02022044641 -:102EA0000D4668460021FEF70BFD20460495FFF70E -:102EB000E5FF024658B16B46054608AE1C4603CCFA -:102EC000B44228606960234605F10805F6D1104632 -:102ED00008B070BD082817D909280CD00A280CD0D2 -:102EE0000B280CD00C280CD00D280CD00E2814BFA9 -:102EF0004020302070470C2070471020704714206D -:102F0000704718207047202070470000082817D904 -:102F10000C280CD910280CD914280CD918280CD935 -:102F200020280CD930288CBF0F200E207047092094 -:102F300070470A2070470B2070470C2070470D2007 -:102F4000704700002DE9F843078C072F04461ED96F -:102F5000D0E9029800254FF6FF73C5F12006A5F1D0 -:102F6000200029FA05F108FA06F628FA00F03143A4 -:102F70000143C9B21846FFF763FF0835402D0346E9 -:102F8000EBD1E1693A46BDE8F843FFF76BBF4FF676 -:102F9000FF70BDE8F883000010B54B6823B9CA8AFA -:102FA00063F30902CA8210BD04691A681C600361D8 -:102FB000C38A013BC3824A60EFE700002DE9F84F66 -:102FC0001D46CB8A0F46C3F3090105298146924667 -:102FD0000B4630D00020AAB207F11A049EB2042E8C -:102FE0001FFA80F80FD8904503F1010306D3FB8A3E -:102FF0000A4462F30903FB8201201AE01AF8006018 -:10300000E6540130EAE79045F1D2A1F1050B1C230B -:103010007C68BBFBF3F203FB12BB1FFA8BF6002CA0 -:1030200045D14846FFF72AFF044638B978606FF06B -:103030000200BDE8F88F4FF00008E6E700260660C2 -:103040007860ADB24FF0000B454510D90AEB08038C -:10305000221D13F8011B9155B1B208F101081B297B -:103060001FFA88F82BD0454506F10106F1D8FB8AF6 -:10307000C3F30902154465F30903BCE7013292B2B8 -:103080001C462368002BF9D16B1F0B441C21B3FB9A -:10309000F1F301339BB29A42D3D2BBF1000FD0D1EE -:1030A0004846FFF7EBFE20B9C4F800B0BFE70122A5 -:1030B000E7E7C0F800B05E4620600446C1E745453A -:1030C000D5D94846FFF7DAFE08B92060AFE7C0F867 -:1030D00000B0002620600446B6E700002DE9F04F5E -:1030E0002DED028B1C4683B05B6901920746884632 -:1030F000002B00F09A80238C2BB1E269002A00F0AB -:103100009480072B35D807F10C00FFF7B7FE054672 -:1031100038B96FF00205284603B0BDEC028BBDE85C -:10312000F08F14220021FEF7CBFB228CE16905F120 -:103130000800FEF7B3FB208C013080B2FFF7E6FEFB -:10314000FFF7C8FE013880B220840130287463691B -:10315000228C1B782A4403F01F0363F03F0348F0DE -:1031600000411372384669602946FFF7EFFD0125DB -:10317000D1E700F10C034FF0000908EE103A4FF0D0 -:10318000800A4E464D4618EE100AFFF777FE83463A -:103190000028BED014220021FEF792FB002E3AD167 -:1031A000019BABF8083002220BF1080E1FFA82FCDB -:1031B0000CF10100BCF1060F218C80B201D88E42C7 -:1031C0002BD3FFF7A3FEFFF785FE62691278013863 -:1031D00002F01F028E4208BF4FF0400A42EA491235 -:1031E0001BFA80F14AEA020A013048F0004281F8F5 -:1031F00008A08BF81000CBF8042059463846FFF79A -:10320000A5FD238C0135B3422DB289F001094FF0A1 -:10321000000AB8D17FE70022C6E7E169895D0EF8B0 -:1032200002100136B6B20132C0E76FF0010572E755 -:10323000F8B515460E463022002104461F46FEF71B -:103240003FFB069B6360B5F5001F079BA76034BF7B -:103250006A094FF6FF72A36297B2E66104F11000AB -:1032600000239A4206D800230360A782E3822383C7 -:10327000E360F8BD0660013330462036F1E7000018 -:1032800003781BB94BB2002BC8BF01707047000018 -:1032900000787047F8B50C46C969074611B9238C08 -:1032A000002B37D1257E1F2D34D8387828BB228CAF -:1032B000072A2CD8268A36F003032BD14FF6FF704D -:1032C000FFF7D0FD20F001003102400441EA056122 -:1032D000400C41EA40254FF6FF7223462946384606 -:1032E000FFF7FCFE002807DD626913780133DBB2CB -:1032F0001F2B88BF00231370F8BD218A2D0645EAD5 -:10330000012505432046FFF71DFE0246E5E76FF065 -:103310000300F1E76FF00100EEE7000070B58AB03E -:10332000044616460021282268461D46FEF7C8FAC4 -:10333000BDF83830ADF810300F9B05939DF8403044 -:103340008DF81830119B07936946BDF84830ADF8E9 -:1033500020302046CDE90265FFF79CFF0AB070BD22 -:103360002DE9F041D36905460C4616460BB9138C7E -:103370005BBB377E1F2F28D895F80080B8F1000F6F -:1033800026D03046FFF7DEFD3378210241EAC33113 -:1033900041EA0801338A41EA076141EA03410246F2 -:1033A000334641F080012846FFF798FE00280ADDE9 -:1033B0003378012B07D1726913780133DBB21F2BED -:1033C00088BF00231370BDE8F0816FF00100FAE7B9 -:1033D0006FF00300F7E70000F0B58BB004460D4630 -:1033E00017460021282268461E46FEF769FA9DF816 -:1033F0004C305A1E534253418DF800309DF84030F6 -:10340000ADF81030119B05939DF848308DF81830B9 -:10341000149B07936A46BDF85430ADF82030294616 -:103420002046CDE90276FFF79BFF0BB0F0BD000010 -:10343000406A00B104307047436A1A684262026908 -:103440001A600361C38A013BC38270472DE9F041D2 -:10345000D0F82080194E14461D464146002709B970 -:10346000BDE8F081D1E90223A21A65EB030396427D -:1034700077EB03031ED2036A8B420DD1FFF78CFD5D -:10348000036A1B68036203690B60C38A0161016AF6 -:10349000013BC3828846E2E7FFF77EFD0B68C8F870 -:1034A000003003690B60C38A0161013BC382D8F815 -:1034B0000010D4E788460968D1E700BF80841E0069 -:1034C0002DE9F04F8BB00D46DDF8509014469B4629 -:1034D0008046002800F01981B9F1000F00F0158135 -:1034E000531E3F2B00F21181012A03D1BBF1000FC3 -:1034F00040F00B810023CDE90833B8F81430B5EB68 -:10350000C30F4FEAC30703D300200BB0BDE8F08F11 -:103510002B199F42D8F80C303ABF7F1BFFB22746C9 -:103520001BB9D8F81030002B7AD0272D4ED8C5F112 -:103530002806B7424FF000032CBFF6B23E46009378 -:103540002946D8F8080008AB3246FFF741FCA7EB44 -:10355000060A35445FFA8AFAB8F8143003F10053CA -:10356000053BDB000493D8F80C3003932821039B20 -:1035700013B1BAF1000F2CD1D8F8100040B1BAF154 -:10358000000F05D0009608AB5246691AFFF720FCE1 -:1035900038B2002FB8D066070AD00AAB03EBD401CB -:1035A000624211F8083C02F00702134101F8083C9E -:1035B000082C3CD9102C40F2B580202C40F2B7806A -:1035C000BBF1000F00F09C80082334E0BA460026CF -:1035D000C2E7049BE02B28BFE02306930B44AB42D9 -:1035E000059314D95A1B03980096924534BF52464E -:1035F000D2B2691A08AB04300792FFF7E9FB079AC9 -:103600001644AAEB020A1544F6B25FFA8AFA049B42 -:10361000069A05999B1A0493039B1B680393A6E7DC -:103620000093D8F8080008AB3A462946AEE7BBF14C -:10363000000F13D00123B4EBC30F6CD0082C12D8A9 -:103640009DF82030621E23FA02F2D50706D54FF00E -:10365000FF3202FA04F423438DF820309DF8203025 -:1036600089F8003051E7102C12D8BDF82030621EC6 -:1036700023FA02F2D10706D54FF0FF3202FA04F422 -:103680002343ADF82030BDF82030A9F800303CE7E6 -:10369000202C0FD80899631E21FA03F3DA0705D509 -:1036A0004FF0FF3202FA04F40C430894089BC9F867 -:1036B00000302AE7402C2BD0DDE90865611EC4F1FB -:1036C0002102A4F1210326FA01F105FA02F225FAFA -:1036D00003F311431943CB0712D50122A4F12003B0 -:1036E000C4F1200102FA03F322FA01F1A24052428E -:1036F00043EA010363EB430332432B43CDE9082341 -:10370000DDE90823C9E90023FFE66FF00100FCE6CC -:103710006FF00800F9E6082CA0D9102CB3D9202CA2 -:10372000EED8C3E7BBF1000FADD0022383E7BBF1B6 -:10373000000FBBD004237EE730B5012A144638BF02 -:103740000124402C85B028BF40240025012ACDE962 -:10375000025518D81B788DF8083063070AD004ABDF -:1037600003EBD405624215F8083C02F007029340CF -:1037700005F8083C009103462246002102A8FFF705 -:1037800027FB05B030BD082AE4D9102A03D81B88CE -:10379000ADF80830E1E7202A8DBFD3E900231B688C -:1037A0000293CDE90223D8E710B5CB681BB98B6033 -:1037B0000B618B8210BD04691A681C600361C38AA7 -:1037C000013BC382CA60F0E72DE9F04F93B0CDE929 -:1037D00003230B6804460D461806C3F3C01147BF08 -:1037E000C3F3C03BC3F306264FF0020B0E46002B7B -:1037F00080F2FF8113F0C04940F0FB812A7B002A50 -:1038000000F0F781BBF1020F03D02078B04240F006 -:10381000F381C3F30460079003F07F00059059B370 -:10382000C3F3074A2A44059B92F80380760646EACA -:103830000B4646EA834600220023CDE908235FEACF -:10384000D81346EA0A0602936AD0059B009367687C -:103850005B46524608A92046B847002800F0CF81B1 -:10386000276A87B9314604F10C00FFF715FB0746BC -:10387000C8B96FF0020057E0C3F30F2A590608BF1A -:103880000AF0030ACEE73B699E420DD03F68002F45 -:10389000F9D1314604F10C00FFF7FEFA0746002883 -:1038A000E7D0236A3B602762FE7D08F01F03C6F362 -:1038B0008406F01A1FFA80FC0028B8BF0CF1200023 -:1038C000D7E902210693A3EB06031FFA83FCB8BFD6 -:1038D00000B2002BBCBF0CF120031BB252EA010660 -:1038E00036D0039EDFF8D4C2B21A049E66EB010103 -:1038F0000026944576EB010C2AD395F80DE097F855 -:103900001AC0E64518D1029E002E79D001281FDC8E -:103910007868E8B9A84E964270EB010216D337E0FA -:10392000276A27B96FF00C0013B0BDE8F08F3B6930 -:103930009E42B9D03F68F4E79F48904276EB01027F -:1039400001D30020F0E7029A002AFAD00F2B18DCEE -:10395000FA7D4FEA880302F0030203F07C0313436D -:10396000FB7539462046FFF717FB6B7BBB76029B46 -:103970003BB9FB7DC3F38402013262F38603FB751E -:10398000D0E76A7BBB7E9A42DBD1029B002B37D00B -:103990004FEA9813022B33D0039BBB60049BFB6060 -:1039A000142200210DA8FDF78BFF039B0A93049BB3 -:1039B0000B932B1D0C932B7BADF83EA0013BDBB290 -:1039C000ADF83C30069B8DF84130079B8DF84230B6 -:1039D000059B8DF8433094F82C308DF840B083F07F -:1039E00001038DF844300AA9A36820469847FB7D5F -:1039F000C3F38403013303F01F039B02FB82A0E7A0 -:103A0000FB7DC8F34012B2EBD31F40F0FB80069A57 -:103A1000C3F38403934240F0F88002992B7B4FEA72 -:103A2000981200294DD0D2075DD4032B40F2F080CC -:103A3000039BBB60049BFB602B7BAE1D033BDBB297 -:103A40003246394604F10C00FFF7B8FA00280CDAC8 -:103A500039462046FFF7A0FAFB7DC3F38403013308 -:103A600003F01F039B02FB8203E7DDE90884AB88B8 -:103A70003B834FF6FF73C9F12000A9F1200228FA19 -:103A800009F104FA00F0014324FA02F21143184646 -:103A9000C9B2FFF7D5F909F10809B9F1400F03469A -:103AA000E9D1B8822A7B033AD2B23146FFF7DAF97C -:103AB000FB7DB882DA43C2F3C01262F3C713FB7511 -:103AC0003FE782B92E1D013BDBB23246394604F195 -:103AD0000C00FFF773FA0028BADB2A7BB88A013A98 -:103AE000D2B23146E2E7F98AC1F30901013B042968 -:103AF000DAB25CD8281D002307F11B069A4208D9C8 -:103B000010F801CB06F801C0013101330529DBB201 -:103B1000F4D103990A9104990B91934207F11B0187 -:103B20000C9138BF043379680D9134BF55FA83F393 -:103B300000230E93FB8AADF83EA0C3F309031A4499 -:103B4000069B8DF84130079B8DF84230059B8DF820 -:103B5000433094F82C30ADF83C2083F001038DF80D -:103B6000443000238DF840B07B602A7BB88A013A4C -:103B7000291DFFF777F93B8BB882834203D1A368F5 -:103B80000AA92046984720460AA9FFF70DFEFB7DAB -:103B9000BA8AC3F38403013303F01F039B02FB8241 -:103BA0003B8B9A420CBF00206FF01000BCE67B6894 -:103BB000002BAED0052005E040420F0080841E009F -:103BC0001C3033461E68002EFAD1091A081D2E1D1E -:103BD000184401EB090CBCF11B0F5FFA89F398D86C -:103BE0009A4296D916F8013B00F8013B09F1010908 -:103BF000EFE76FF0090097E66FF00A0094E66FF0C8 -:103C00000B0091E66FF00D008EE66FF00E008BE674 -:103C10006FF00F0088E600BFEFF3098305494A6B98 -:103C200022F001024A63683383F30988002383F397 -:103C30001188704700EF00E0302080F3118862B6F1 -:103C40000C4B0D4AD96821F4E0610904090C0A43C0 -:103C5000DA60D3F8FC20094942F08072C3F8FC20F6 -:103C60000A6842F001020A602022DA7783F8220013 -:103C7000704700BF00ED00E00003FA05001000E00F -:103C800010B5302383F311880E4B5B6813F4006387 -:103C900014D0F1EE103AEFF30984683C4FF08073D2 -:103CA000E361094BDB6B236684F3098800F078FB42 -:103CB00010B1064BA36110BD054BFBE783F31188E0 -:103CC000F9E700BF00ED00E000EF00E04306000868 -:103CD00046060008026843681143016003B11847B3 -:103CE00070470000024A136843F0C0031360704736 -:103CF0000038014013B50E4C204600F0B7FA04F12D -:103D000014000C49009400234FF4807200F074F901 -:103D1000094B0A4900944FF4807204F1380000F016 -:103D2000EDF9074A074BC4E9172302B010BD00BFE5 -:103D3000EC4A0020584B0020E53C0008584C00207D -:103D400000380140007A030A30B5037C234C002977 -:103D500018BF0C46012B0FD1214B98420CD1214B9F -:103D60001A6E42F480421A66D3F8802042F48042F0 -:103D7000C3F88020D3F880302268036EC16D84665A -:103D800003EB5203B3FBF2F36268150442BF23F066 -:103D9000070503F0070343EA4503CB60A36843F03C -:103DA00040034B60E36843F001038B6042F4967379 -:103DB00043F001030B604FF0FF330B62510505D553 -:103DC00012F0102205D0B2F1805F04D080F8643088 -:103DD00030BD7F23FAE73F23F8E700BF20530008F8 -:103DE000EC4A0020001002402DE9F047C66D37680C -:103DF000F46934622107054619D014F0080118BF90 -:103E00004FF48071E20748BF41F02001A30748BF8B -:103E100041F04001600748BF41F08001302383F347 -:103E20001188281DFFF756FF002383F31188E20550 -:103E30000AD5302383F311884FF48061281DFFF7E2 -:103E400049FF002383F311884FF030094FF0000A37 -:103E500014F0200838D13B0616D54FF0300905F193 -:103E6000380A200610D589F31188504600F07AF9F7 -:103E7000002836DA0821281DFFF72CFF27F08003E1 -:103E80003360002383F31188790614D5620612D5B6 -:103E9000302383F31188D5E913239A4208D12B6C80 -:103EA00033B11021281D27F04007FFF713FF3760BB -:103EB000002383F31188E30618D5AA6E1369ABB10A -:103EC000BDE8F0475069184789F31188736A95F87F -:103ED00064102846194000F0E3F98AF31188F46968 -:103EE000B6E7B06288F31188F469BAE7BDE8F087F5 -:103EF0004FF0E023002258684FF0FF31930003F1A8 -:103F0000604303F5614301329042C3F88010C3F867 -:103F10008011F3D27047000000F1604303F5614364 -:103F20000901C9B283F80013012200F01F039A406F -:103F300043099B0003F1604303F56143C3F880210B -:103F40001A607047F8B5154682680669AA420B46A2 -:103F5000816938BF8568761AB54204460BD2184687 -:103F60002A46FDF79BFCA3692B44A361A3685B1B56 -:103F7000A3602846F8BD0CD918463246FDF78EFCE2 -:103F8000AF1BE1683A463044FDF788FCE3683B44E8 -:103F9000EBE718462A46FDF781FCE368E5E70000F9 -:103FA00083689342F7B51546044638BF8568D0E963 -:103FB0000460361AB5420BD22A46FDF76FFC6369DE -:103FC0002B446361A36828465B1BA36003B0F0BD6C -:103FD0000DD932460191FDF761FC0199E068AF1BF4 -:103FE0003A463144FDF75AFCE3683B44E9E72A4688 -:103FF000FDF754FCE368E4E710B50A440024C3610C -:10400000029B8460C0E90000C0E90511C160026143 -:10401000036210BD08B5D0E90532934201D1826830 -:1040200082B98268013282605A1C42611970D0E9FB -:1040300004329A4224BFC3684361002100F078FA39 -:10404000002008BD4FF0FF30FBE7000070B53023C3 -:1040500004460E4683F31188A568A5B1A368A2693A -:10406000013BA360531CA36115782269934224BFCE -:10407000E368A361E3690BB120469847002383F30B -:104080001188284607E03146204600F041FA002812 -:10409000E2DA85F3118870BD2DE9F74F04460E462C -:1040A00017469846D0F81C904FF0300A8AF31188D2 -:1040B0004FF0000B154665B12A4631462046FFF702 -:1040C00041FF034660B94146204600F021FA00282E -:1040D000F1D0002383F31188781B03B0BDE8F08F83 -:1040E000B9F1000F03D001902046C847019B8BF324 -:1040F0001188ED1A1E448AF31188DCE7C0E9051126 -:10410000C160C3611144009B8260C0E9000001618D -:1041100003627047F8B504460D461646302383F314 -:104120001188A768A7B1A368013BA36063695A1C03 -:1041300062611D70D4E904329A4224BFE36863616E -:10414000E3690BB120469847002080F3118807E00F -:104150003146204600F0DCF90028E2DA87F31188C6 -:10416000F8BD0000D0E905239A4210B501D182685C -:104170007AB98268013282605A1C82611C780369B4 -:104180009A4224BFC3688361002100F0D1F9204620 -:1041900010BD4FF0FF30FBE72DE9F74F04460E4608 -:1041A00017469846D0F81C904FF0300A8AF31188D1 -:1041B0004FF0000B154665B12A4631462046FFF701 -:1041C000EFFE034660B94146204600F0A1F9002801 -:1041D000F1D0002383F31188781B03B0BDE8F08F82 -:1041E000B9F1000F03D001902046C847019B8BF323 -:1041F0001188ED1A1E448AF31188DCE702684368CF -:104200001143016003B11847704700001430FFF7F5 -:1042100043BF00004FF0FF331430FFF73DBF0000F5 -:104220003830FFF7B9BF00004FF0FF333830FFF7E9 -:10423000B3BF00001430FFF709BF00004FF0FF319B -:104240001430FFF703BF00003830FFF763BF0000F2 -:104250004FF0FF323830FFF75DBF0000012914BF77 -:104260006FF0130000207047FFF744BD044B03605C -:104270000023C0E90233436001230374704700BF89 -:104280003853000810B53023044683F31188FFF734 -:104290005BFD02232374002080F3118810BD000011 -:1042A00038B5C36904460D461BB904210844FFF71D -:1042B000A5FF294604F11400FFF7ACFE002806DA3A -:1042C000201D4FF40061BDE83840FFF797BF38BDAF -:1042D00000230375826803691B6899689142FBD2C9 -:1042E0005A6803604260106058607047002303758D -:1042F000826803691B6899689142FBD85A68036019 -:10430000426010605860704708B50846302383F358 -:1043100011880B7D032B05D0042B0DD02BB983F313 -:10432000118808BD8B6900221A604FF0FF3383614A -:10433000FFF7CEFF0023F2E7D1E9003213605A60A5 -:10434000F3E70000FFF7C4BF054BD968087518688C -:1043500002681A60536001220275D860FCF75CB9EC -:10436000584D002030B50C4BDD684B1C87B004461F -:104370000FD02B46094A684600F06CF92046FFF73B -:10438000E3FF009B13B1684600F06EF9A86907B01F -:1043900030BDFFF7D9FFF9E7584D00200943000869 -:1043A000044B1A68DB6890689B68984294BF0020B1 -:1043B00001207047584D0020084B10B51C68D86884 -:1043C00022681A60536001222275DC60FFF78EFFBD -:1043D00001462046BDE81040FCF71EB9584D0020AC -:1043E000044B1A68DB6892689B689A4201D9FFF710 -:1043F000E3BF7047584D002038B5074C07490848BF -:10440000012300252370656000F02EFC0223237039 -:1044100085F3118838BD00BFC04F002064530008E9 -:10442000584D002008B572B6044B186500F0E4FA48 -:1044300000F09CFB024B03221A70FEE7584D00204F -:10444000C04F002000F046B9EFF3118020B9EFF320 -:104450000583302282F311887047000010B530B90F -:10446000EFF30584C4F3080414B180F3118810BD80 -:10447000FFF7B6FF84F31188F9E700008B60022391 -:1044800008618B82084670478368A3F1840243F871 -:10449000142C026943F8442C426943F8402C094A21 -:1044A00043F8242CC26843F8182C022203F80C2C81 -:1044B000002203F80B2C044A43F8102CA3F120002F -:1044C000704700BF31060008584D002008B5FFF7BF -:1044D000DBFFBDE80840FFF735BF0000024BDB689B -:1044E00098610F20FFF730BF584D0020302383F331 -:1044F0001188FFF7F3BF000008B50146302383F3AE -:1045000011880820FFF72EFF002383F3118808BDD0 -:10451000064BDB6839B1426818605A60136043602B -:104520000420FFF71FBF4FF0FF307047584D0020A9 -:104530000368984206D01A68026050609961184674 -:10454000FFF700BF7047000010B503689C68A242E7 -:104550000CD85C688A600B604C6021605960996877 -:104560008A1A9A604FF0FF33836010BD1B68121BDC -:10457000ECE700000A2938BF0A2170B504460D4651 -:104580000A26601900F06AFB00F056FB041BA542E6 -:1045900003D8751C2E460446F3E70A2E04D9BDE85D -:1045A0007040012000F0A0BB70BD0000F8B5144BB6 -:1045B0000D46D96103F1100141600A2A1969826030 -:1045C00038BF0A22016048601861A818144600F03C -:1045D00037FB0A2700F030FB431BA342064606D3F5 -:1045E0007C1C281900F03AFB27463546F2E70A2FD3 -:1045F00004D9BDE8F840012000F076BBF8BD00BF4B -:10460000584D0020F8B506460D4600F015FB0F4A40 -:10461000134653F8107F9F4206D12A460146304682 -:10462000BDE8F840FFF7C2BFD169BB68441A2C1936 -:1046300028BF2C46A34202D92946FFF79BFF2246FA -:1046400031460348BDE8F840FFF77EBF584D0020D3 -:10465000684D002010B4C0E9032300235DF8044B2B -:104660004361FFF7CFBF000010B5194C2369984292 -:104670000DD0D0E90032816813605A609A680A440C -:104680009A60002303604FF0FF33A36110BD2346FF -:10469000026843F8102F53600022026022699A4298 -:1046A00003D1BDE8104000F0D3BA936881680B4491 -:1046B000936000F0C1FA2269E1699268441AA2424B -:1046C000E4D91144BDE81040091AFFF753BF00BFF9 -:1046D000584D00202DE9F047DFF8BC8008F11007A5 -:1046E0002C4ED8F8105000F0A7FAD8F81C40AA6851 -:1046F000031B9A423ED81444D5E900324FF000091A -:10470000C8F81C4013605A60C5F80090D8F8103003 -:10471000B34201D100F09CFA89F31188D5E9033145 -:1047200028469847302383F311886B69002BD8D033 -:1047300000F082FA6A69A0EB04094A4582460DD26C -:10474000022000F0D1FA0022D8F81030B34208D18C -:1047500051462846BDE8F047FFF728BF121A224409 -:10476000F2E712EB090938BF4A4629463846FFF7F7 -:10477000EBFEB5E7D8F81030B34208D01444211A44 -:10478000C8F81C00A960BDE8F047FFF7F3BEBDE81C -:10479000F08700BF684D0020584D00200020704772 -:1047A000FEE70000704700004FF0FF307047000048 -:1047B000BFF34F8F024A1369DB03FCD4704700BF7D -:1047C0000020024008B5094B1B7873B9FFF7F0FFD2 -:1047D000074B5A69002ABFBF064A9A6002F1883225 -:1047E0009A601A6822F480621A6008BDD84F0020CF -:1047F000002002402301674508B50B4B1B7893B995 -:10480000FFF7D6FF094B5A6942F000425A611A6815 -:1048100042F480521A601A6822F480521A601A68B0 -:1048200042F480621A6008BDD84F00200020024088 -:104830007F289ABF00F58030C0020020704700003A -:104840004FF4006070470000802070477F2808B553 -:104850000BD8FFF7EDFF00F500630268013204D1C9 -:1048600004308342F9D1012008BD0020FCE700009C -:104870007F2838B5044626D8FFF7E6FDFFF798FFF6 -:10488000FFF7A0FF114BF3221A6102225A615A6905 -:1048900042EAC4025A615A6942F480325A610546BA -:1048A0002046FFF785FF4FF40061FFF7C1FF00F0DE -:1048B00059F92846FFF7A0FFFFF7D0FD2046BDE8D5 -:1048C0003840FFF7C3BF002038BD00BF00200240C2 -:1048D00040EA020313F007032DE9F04705460C46B2 -:1048E000164606D0344B40F231321A600020BDE843 -:1048F000F0878118314A91420CD92F4A40F2363163 -:104900001160F3E72B1D1B686268934208D1083ED3 -:1049100008350834072E19D92A6823689A42F1D03D -:10492000FFF792FDFFF74EFFFFF742FF04F108018A -:10493000234C4FF001084FF00009012EA1F10807A8 -:1049400008D8FFF759FFFFF789FD01E0002EE7D1F6 -:104950000120CCE7C4F81480AA4651F8083C4AF874 -:10496000043B51F8043C6B60FFF722FF236943F0DE -:1049700001032361C4F814902A6851F8083C9A4254 -:104980000ED00D4B40F25E321A600E4B1D600E4B86 -:104990001E600E4B1F60FFF72FFFFFF75FFDA5E7BF -:1049A000DAF800A051F8043C9A4501F10801E8D179 -:1049B000083E0835C1E700BFD44F002000000408BE -:1049C00000200240C84F0020D04F0020CC4F0020D4 -:1049D000084908B50B7828B11BB9FFF7F3FE01238E -:1049E0000B7008BD002BFCD0BDE808400870FFF735 -:1049F00003BF00BFD84F002008B54FF4C0314FF0BF -:104A0000005000F0B1F8BDE808404FF480414FF08D -:104A1000805000F0A9B80000084600F0F3BB000089 -:104A200070B582B0FFF710FD0E4E054600F004F998 -:104A30003268904237BF0C4A0B49516814682EBF48 -:104A4000D1E90041013151600419034641F10001EF -:104A5000284601913360FFF701FD0199204602B01D -:104A600070BD00BFDC4F0020E04F002070B582B069 -:104A7000FFF7EAFC104E054600F0DEF8326890427F -:104A800037BF0E4A0D49516814682EBFD1E9004165 -:104A900001315160041941F100010346284601919A -:104AA0003360FFF7DBFC01994FF47A720023204654 -:104AB000FBF79EFB02B070BDDC4F0020E04F0020F2 -:104AC0000244D2B2904200D17047431C800000F1F2 -:104AD000804000F51450006841F8040BD8B2F1E7AB -:104AE000124B10B5D3F89040240409D4D3F8904069 -:104AF000C3F89040D3F8904044F40044C3F8904089 -:104B00000B4C2368024443F480732360D2B290427A -:104B100000D110BD431C800000F1804000F514500E -:104B200051F8044B0460D8B2F1E700BF0010024016 -:104B30000070004007B5012201A90020FFF7C0FF67 -:104B4000019803B05DF804FB13B50446FFF7F2FFCC -:104B5000A04205D0012201A900200194FFF7C0FF67 -:104B600002B010BD704700007047000070470000A1 -:104B7000074B45F255521A6002225A6040F6FF7206 -:104B80009A604CF6CC421A60024B01221A707047B0 -:104B900000300040EC4F0020034B1B781BB1034B4F -:104BA0004AF6AA221A607047EC4F002000300040FD -:104BB000054B1A6832B902F1804202F50432D2F88C -:104BC00094201A60704700BFE84F0020024B4FF45A -:104BD0000002C3F8942070470010024008B5FFF7A8 -:104BE000E7FF024B1868C0F3407008BDE84F002093 -:104BF00070470000FEE700000A4B0B480B4A90424A -:104C00000BD30B4BDA1C121AC11E22F003028B428B -:104C100038BF00220021FCF753BE53F8041B40F8B4 -:104C2000041BECE7D45400087050002070500020A2 -:104C30007050002000F0C2B84FF08043586A7047AF -:104C40004FF08043002258631A610222DA607047F5 -:104C50004FF080430022DA60704700004FF080433D -:104C600058637047FEE7000070B51B4B01630025D9 -:104C7000044686B0586085620E46FEF7DDFF04F1FB -:104C80001003C4E904334FF0FF33C4E90635C4E927 -:104C90000044A560E562FFF7CFFF2B460246C4E95A -:104CA000082304F134010D4A256580232046FFF7CF -:104CB000E5FB0123E0600A4A0375009272680192E5 -:104CC000B268CDE90223074B6846CDE90435FFF70A -:104CD000FDFB06B070BD00BFC04F00207053000840 -:104CE00075530008654C0008024AD36A1843D06225 -:104CF000704700BF584D00204B6843608B6883604D -:104D0000CB68C3600B6943614B6903628B69436283 -:104D10000B6803607047000008B5204BDA6A42F068 -:104D20007F02DA62DA6A22F07F02DA62DA6ADA6C29 -:104D300042F07F02DA64DA6E42F07F02DA66184AE5 -:104D4000DB6E11464FF09040FFF7D6FF02F11C01D9 -:104D500000F58060FFF7D0FF02F1380100F58060B8 -:104D6000FFF7CAFF02F1540100F58060FFF7C4FFAE -:104D700002F1700100F58060FFF7BEFF02F18C01C7 -:104D800000F58060FFF7B8FF02F1A80100F5806030 -:104D9000FFF7B2FFBDE8084000F050B80010024035 -:104DA0007C53000808B500F0FBF9FFF725FBBDE8D0 -:104DB0000840FFF7FDBE0000704700000F4B9A6DE2 -:104DC00042F001029A659A6F42F001029A670C4A1A -:104DD0009B6F936843F0010393604FF08043A722D9 -:104DE0009A624FF0FF32DA6200229A615A63DA6007 -:104DF0005A6001225A611A60704700BF00100240D9 -:104E0000002004E04FF0804208B51169D3680B40E0 -:104E1000D9B2C9439B07116107D5302383F31188A9 -:104E2000FFF710FB002383F3118808BD08B5FFF7D7 -:104E30005FF8BDE8084000F08BB900004E4B4FF022 -:104E4000FF319A6A99629A6A00229A62986AD86ACD -:104E500060F07F00D862D86A00F07F00D862D86A1C -:104E6000186B1963186B1A63186B986B9963986BBE -:104E70009A63986BD86BD963D86BDA63D86B186C6C -:104E80001964196C1A64196C196E41F001011966E4 -:104E9000D3F8801021F00101C3F88010D3F88010FE -:104EA000996D41F080519965996F21F08051996712 -:104EB000996F32494FF400408860CA600A624A62C2 -:104EC0008A62CA620A634A638A63CA630A644A647A -:104ED0008A64CA640A654A654A604FF48072C1F800 -:104EE00080204FF440720A604A6912F48062FBD15C -:104EF000D3F8901011F4407F1EBF4FF48031C3F8F7 -:104F00009010C3F89020D3F8982042F00102C3F823 -:104F10009820D3F898209207FBD51A6842F4803283 -:104F20001A601A689003FCD5D3F8902022F003226F -:104F3000C3F89020124ADA601A6842F080721A6050 -:104F40001A689101FCD50F490F4800229A60C3F8F6 -:104F500088100E49C3F89C20016002684A4012077D -:104F6000FBD19A6842F003029A609A6802F00C0240 -:104F70000C2AFAD1704700BF0010024000700040B8 -:104F8000032A61015501005000200240040704007B -:104F9000074A08B5536903F00103536123B1054A79 -:104FA00013680BB150689847BDE80840FEF768BE2B -:104FB00000040140F04F0020074A08B5536903F090 -:104FC0000203536123B1054A93680BB1D068984737 -:104FD000BDE80840FEF754BE00040140F04F002039 -:104FE000074A08B5536903F00403536123B1054A26 -:104FF00013690BB150699847BDE80840FEF740BE01 -:1050000000040140F04F0020074A08B5536903F03F -:105010000803536123B1054A93690BB1D0699847DE -:10502000BDE80840FEF72CBE00040140F04F002010 -:10503000074A08B5536903F01003536123B1054AC9 -:10504000136A0BB1506A9847BDE80840FEF718BED6 -:1050500000040140F04F0020164B10B55C6904F4C9 -:1050600078725A61A30604D5134A936A0BB1D06AC9 -:105070009847600604D5104A136B0BB1506B9847E4 -:10508000210604D50C4A936B0BB1D06B9847E2050F -:1050900004D5094A136C0BB1506C9847A30504D58D -:1050A000054A936C0BB1D06C9847BDE81040FEF7F1 -:1050B000E7BD00BF00040140F04F0020194B10B5C0 -:1050C0005C6904F47C425A61620504D5164A136D8A -:1050D0000BB1506D9847230504D5134A936D0BB15E -:1050E000D06D9847E00404D50F4A136E0BB1506E93 -:1050F0009847A10404D50C4A936E0BB1D06E984723 -:10510000620404D5084A136F0BB1506F984723040B -:1051100004D5054A936F0BB1D06F9847BDE8104096 -:10512000FEF7AEBD00040140F04F002008B5034873 -:10513000FEF75AFEBDE80840FEF7A2BDEC4A00208B -:1051400008B5FFF75FFEBDE80840FEF799BD000017 -:10515000062108B50846FEF7DFFE06210720FEF708 -:10516000DBFE06210820FEF7D7FE06210920FEF708 -:10517000D3FE06210A20FEF7CFFE06211720FEF7F8 -:10518000CBFE06212820FEF7C7FE07211C20FEF7D4 -:10519000C3FEBDE808400C212520FEF7BDBE00007F -:1051A00008B5FFF743FE00F009F8FFF75DF8FFF7D9 -:1051B00003FEBDE80840FFF73DBD00000023054A9F -:1051C00019460133102BC2E9001102F10802F8D18F -:1051D000704700BFF04F00200B460146184600F014 -:1051E00003B8000000F00EB810B5054C13462CB102 -:1051F0000A4601460220AFF3008010BD2046FCE7BE -:1052000000000000024B01461868FFF705BC00BF14 -:105210002823002010B501390244904201D100201A -:1052200005E0037811F8014FA34201D0181B10BD0F -:105230000130F2E72DE9F041A3B1C91A1778014412 -:10524000044603F1FF3C8C42204601D9002009E0CE -:105250000578BD4204F10104F5D10CEB0405D61824 -:10526000A54201D1BDE8F08115F8018D16F801EDD8 -:10527000F045F5D0E7E70000034611F8012B03F8ED -:10528000012B002AF9D170476F72672E6172647525 -:1052900070696C6F742E6D526F2D4D313030393511 -:1052A0000000000053544D333247343F3F000000AC -:1052B00040A2E4F1646891060041A3E5F2656992B9 -:1052C000070000004261642043414E496661636506 -:1052D00020696E6465782E00000000000000000068 -:1052E00061240008691F0008292B0008611F0008BD -:1052F00011200008F5210008D91F0008A11F00088F -:10530000A51F00087D1F0008651F0008B5210008C3 -:10531000891F0008652C0008951F000889210008D6 -:1053200000960000000000000000000000000000E7 -:1053300000000000000000000000000029420008FA -:1053400015420008514200083D4200084942000849 -:1053500035420008214200080D4200085D42000865 -:105360006330000060530008B04D0020C04F0020A3 -:105370006D61696E0069646C650000000001A82A17 -:1053800000000000AAAABEAA00001424EFFF00003B -:1053900000000000709709000000000000000000FD -:1053A000AAAAAAAA00000000FFFF00000000000057 -:1053B000000000000000000000000000AAAAAAAA45 -:1053C00000000000FFFF00000000000000000000DF -:1053D0000000000000000000AAAAAAAA0000000025 -:1053E000FFFF0000000000000000000000000000BF -:1053F00000000000AAAAAAAA00000000FFFF000007 -:10540000000000000000000000000000000000009C -:10541000AAAAAAAA00000000FFFF000000000000E6 -:10542000000000000000000000000000AAAAAAAAD4 -:1054300000000000FFFF000000000000000000006E -:10544000E0ADFF7F0100000011040000000000003B -:105450000088030000000000FE2A0100D2040000C2 -:10546000FF000000EC4A002000000000A4520008E9 -:105470002C230020000000000000000000000000BD -:10548000000000000000000000000000000000001C -:10549000000000000000000000000000000000000C -:1054A00000000000000000000000000000000000FC -:1054B00000000000000000000000000000000000EC -:1054C00000000000000000000000000000000000DC -:0454D00000000000D8 +:10063000002383F311882846A047002004F00CF91A +:10064000FEE704F06FF800DFFEE70000F8B501F008 +:10065000EDF804F013FC074604F064FC0546B8BB53 +:10066000204B9F4234D001339F4234D01E4B27F0A1 +:10067000FF029A4232D1F8B200F010FF2E4642F249 +:10068000107400F011FF08B10024264601F058FC58 +:1006900020B1032000F07CF80024264635B1134B2E +:1006A0009F4203D004F036FC00242646002004F0CC +:1006B000EFFB0EB100F082F801F028FA00F026FFFF +:1006C00001F012F9204600F0D7F800F077F8F9E7CA +:1006D0002E460024D5E704460126D2E706464FF40D +:1006E0007A74CEE7010007B0000008B0263A09B0DE +:1006F00008B501F0C5F8A0F120035842584108BDE3 +:1007000007B541F21203022101A8ADF8043001F04F +:10071000D5F803B05DF804FB38B5302383F31188B6 +:10072000174803680BB104F055F9164A1448002322 +:100730004FF47A7104F044F9002383F31188124CCA +:10074000236813B12368013B2360636813B16368B6 +:10075000013B63600D4D2B7833B963687BB9022090 +:1007600001F062F9322363602B78032B07D16368B1 +:100770002BB9022001F058F94FF47A73636038BD49 +:100780009023002019070008B0240020A82300208F +:10079000084B187003280CD8DFE800F008050208A1 +:1007A000022001F039B9022001F02EB9024B0022DB +:1007B0005A607047A8230020B024002038B501F00B +:1007C000BFFB30B1254B03221A70254B00225A6023 +:1007D00038BD244B244A19680131F9D004339342BF +:1007E000F9D1224C1F4DD4F80428AA42F0D3204B53 +:1007F0009B6803F1006303F5F0439A42E8D204F0EA +:100800005BFB04F06DFB002001F088F80220FFF78D +:10081000BFFF184B9A6D00229A65996F9A67996F7E +:10082000D96DDA65D96FDA67D96F196E1A66D3F8A0 +:100830008010C3F88020D3F8803072B64FF0E023E8 +:100840003021C3F8085DD4F80038D4F8042881F3C7 +:1008500011889D4683F308881047B9E7A823002034 +:10086000B0240020007800082078000800700008FC +:1008700000230020001002402DE9F04F93B0AC4B54 +:1008800000902022FF210AA89D6801F0E9F8A94AFA +:100890001378A3B9A848012103601170302383F3B2 +:1008A000118803680BB104F095F8A44AA24800230C +:1008B0004FF47A7104F084F8002383F31188009BCD +:1008C00013B19F4B009A1A609E4A009C1378032B29 +:1008D0001EBF002313709A4A4FF0000A18BF5360DE +:1008E000D3465646D146012001F096F824B1944BE8 +:1008F0001B68002B00F01582002000F0C1FF039060 +:10090000039B002B01DA00F049FE039B002BEDDB7B +:10091000012001F079F8039B213B162BE3D801A2BB +:1009200052F823F081090008A90900083D0A0008CF +:10093000E7080008E7080008E7080008C70A0008F9 +:10094000970C0008B10B0008130C00083B0C0008C2 +:10095000610C0008E7080008730C0008E7080008AD +:10096000E50C0008210A0008E7080008290D000826 +:100970008D090008210A0008E7080008130C000888 +:100980000220FFF7B5FE002840F0F581009B022110 +:10099000BAF1000F08BF1C4605A841F21233ADF8AA +:1009A000143000F08BFF9EE74FF47A7000F068FF80 +:1009B000071EEBDB0220FFF79BFE0028E6D0013F7D +:1009C000052F00F2DA81DFE807F0030A0D10133675 +:1009D00005230593042105A800F070FF17E0544893 +:1009E0000421F9E758480421F6E758480421F3E7C1 +:1009F0004FF01C08404600F093FF08F104080590F2 +:100A0000042105A800F05AFFB8F12C0FF2D1012003 +:100A100000FA07F747EA0B0B5FFA8BFB4FF0000970 +:100A200001F06AF826B10BF00B030B2B08BF002472 +:100A3000FFF766FE57E746480421CDE7002EA5D014 +:100A40000BF00B030B2BA1D10220FFF751FE074641 +:100A500000289BD0012000F061FF0220FFF798FEE4 +:100A600000261FFA86F8404600F06AFF044690B15F +:100A70000021404600F07CFF01360028F1D1BA4643 +:100A8000044641F21213022105A8ADF814303E4687 +:100A900000F014FF27E70120FFF77AFE2546244BDC +:100AA0009B68AB4207D9284600F03AFF013040F07E +:100AB00067810435F3E7234B00251D70204BBA46B0 +:100AC0005D603E46ACE7002E3FF460AF0BF00B03D9 +:100AD0000B2B7FF45BAF0220FFF75AFE322000F0B1 +:100AE000CFFEB0F10008FFF651AF18F003077FF416 +:100AF0004DAF0F4A926808EB050393423FF646AFAD +:100B0000B8F5807F3FF742AF124B0193B84523DD24 +:100B10004FF47A7000F0B4FE0390039A002AFFF6B7 +:100B200035AF019B039A03F8012B0137EDE700BFB6 +:100B300000230020AC240020902300201907000887 +:100B4000B0240020A8230020042300200823002034 +:100B50000C230020AC230020C820FFF7C9FD074666 +:100B600000283FF413AF1F2D11D8C5F120024245D4 +:100B70000AAB25F0030028BF42468349019218447E +:100B800000F05CFF019A8048FF2100F069FF4FEA06 +:100B9000A8037D490193C8F38702284600F068FF47 +:100BA000064600283FF46DAF019B05EB830537E750 +:100BB0000220FFF79DFD00283FF4E8AE00F0EAFEBA +:100BC00000283FF4E3AE0027B846704B9B68BB4259 +:100BD00018D91F2F11D80A9B01330ED027F0030319 +:100BE00012AA134453F8203C05934046042205A959 +:100BF00001F090F904378046E7E7384600F090FEB0 +:100C00000590F2E7CDF81480042105A800F056FE07 +:100C100006E70023642104A8049300F045FE0028A1 +:100C20007FF4B4AE0220FFF763FD00283FF4AEAEC0 +:100C3000049800F0A5FE0590E6E70023642104A8CF +:100C4000049300F031FE00287FF4A0AE0220FFF7ED +:100C50004FFD00283FF49AAE049800F093FEEAE7B7 +:100C60000220FFF745FD00283FF490AE00F0A2FE01 +:100C7000E1E70220FFF73CFD00283FF487AE05A91D +:100C8000142000F09DFE04210746049004A800F003 +:100C900015FE3946B9E7322000F0F2FD071EFFF6D7 +:100CA00075AEBB077FF472AE384A926807EB090352 +:100CB00093423FF66BAE0220FFF71AFD00283FF487 +:100CC00065AE27F003074F44B9453FF4A9AE484647 +:100CD00000F026FE0421059005A800F0EFFD09F1C3 +:100CE0000409F1E74FF47A70FFF702FD00283FF4A2 +:100CF0004DAE00F04FFE002844D00A9B01330BD0CC +:100D000008220AA9002000F0B3FE00283AD02022D1 +:100D1000FF210AA800F0A4FEFFF7F2FC1C4803F034 +:100D2000A1FD13B0BDE8F08F002E3FF42FAE0BF005 +:100D30000B030B2B7FF42AAE0023642105A8059337 +:100D400000F0B2FD074600287FF420AE0220FFF736 +:100D5000CFFC804600283FF419AEFFF7D1FC41F2EA +:100D6000883003F07FFD059800F0DCFE464600F079 +:100D7000C3FE3C46B7E5064652E64FF0000905E6DD +:100D8000BA467EE637467CE6AC23002000230020EE +:100D9000A0860100094A136849F2690099B21B0C48 +:100DA00000FB01331360064B186844F2506182B2B5 +:100DB000000C01FB0200186080B270471423002071 +:100DC0001023002010B500211022044600F048FE38 +:100DD000034B03CB206061601868A06010BD00BFAA +:100DE0009075FF1F2DE9F041ADF54E7D0DF13408F2 +:100DF0006CAC40F2751207460D460EA80021C8F8EB +:100E0000001000F02DFE4FF4C4720021204600F0C7 +:100E100027FE02F0CFF8254B4FF47A72B0FBF2F0C8 +:100E2000186093E80700022384E807000DF5E970D5 +:100E30002382FFF7C7FF41F204131D49238406A84C +:100E400004F0BEFB182384F832310DF2E3266B4424 +:100E50000DF1300C1A4603CA6245306071601346CA +:100E600006F10806F6D141460122204600F074FE44 +:100E700000230393AB7E029305F11903019380B223 +:100E80000123CDE904800093E97E06A3D3E9002382 +:100E9000384602F04DFC0DF54E7DBDE8F08100BFF7 +:100EA000AFF300809E6AC421818A46EEB8240020F8 +:100EB000D05500082DE9F0412C4C237ADAB0804659 +:100EC0000D465BBB27A9284600F056FF07460028C1 +:100ED00042D19DF89D60C82E3ED801464FF4A662CF +:100EE000204600F0BDFD4FF48073C4F8F8314FF494 +:100EF0000073C4F80C334FF44073C4F82034324606 +:100F00000DF19E0104F1090000F098FD26449DF8C2 +:100F10009C30777223720BB9EB7E23728122002101 +:100F200006AC27A800F09CFD0122214627A800F06E +:100F30005FFF00230393AB7E029305F1190380B298 +:100F400001932823CDE904400093E97E05A3D3E96A +:100F50000023404602F0ECFB5AB0BDE8F08100BF30 +:100F6000AFF3008026417272DF25D7B7B049002069 +:100F7000F0B5254E4FF48A7505FB0065F1B096F883 +:100F8000D83085F8DC300024D822214685F8E840A6 +:100F90003AA800F065FD06F1090000F059FDD5F80A +:100FA000E4308DF8F000C2B206AF06F109010DF190 +:100FB000F100CDE93A3400F041FD394601223AA86A +:100FC00000F042FF80B2CDE9047008230127CDE98B +:100FD000023706F1D803019330230093317A0B488E +:100FE00007A3D3E9002302F0A3FBA04206DD01F032 +:100FF000E1FFC5F8E000384671B0F0BD2046FBE7E0 +:1010000078F6339F93CACD8DB0490020D0340020AC +:101010002DE9F0411D4D1E4E1E4F86B0284602F0B0 +:10102000B3FB034658B30024CDE90344ADF81440A4 +:10103000027B8DF8142099684068029403AA03C2C9 +:101040001B68DFF8548043F00043029301F0B4FFC3 +:10105000821941F10003009402A9384601F08CF98D +:10106000A04205DD284602F093FB88F80040D5E752 +:1010700098F80030072B05D8013388F8003006B007 +:10108000BDE8F081014802F083FBF8E7D03400208E +:1010900040420F0000350020E54E002070B50D469F +:1010A00014461E4602F0A0FA50B9022E10D1012CAF +:1010B0000ED112A3D3E90023C5E90023012007E0E4 +:1010C000282C10D005D8012C09D0052C0FD00020D9 +:1010D00070BD302CFBD10BA3D3E90023ECE70BA3AD +:1010E000D3E90023E8E70BA3D3E90023E4E70BA34C +:1010F000D3E90023E0E700BFAFF30080401DA1204B +:1011000026812A0B78F6339F93CACD8D9E6AC4211F +:10111000818A46EE26417272DF25D7B7F017304A32 +:1011200039059E5638B505460E4C0021013500F0B4 +:101130001FFCA4F82C55B4F82C0500F001FC78B184 +:10114000B4F82C0500F00CFC014648B9B4F82C05A5 +:1011500000F00EFCB4F82C350133A4F82C35EAE786 +:1011600038BD00BFB049002010B50A4B0A4A1A60CA +:1011700003F5805393F848203AB95C6C2CB12046B3 +:1011800000F05CFF204604F0D1F9BDE810400348B0 +:1011900000F054BF003500202856000830450020DC +:1011A0002DE9F04F8FB000AF05460C4602F01CFA57 +:1011B000002849D1237E022B1BD1E38A012B18D1B1 +:1011C00001F0F8FE0646FFF7E5FD03464FF4C87050 +:1011D000DFF8C482B3FBF0F206F5167602FB10339B +:1011E00016FA83F3C8F80030E37E33B9A34B00222C +:1011F0001A703C37BD46BDE8F08F07F12401204648 +:1012000000F078FD0028F4D107F11400FFF7DAFDB3 +:1012100097F8264007F11401224607F1270004F051 +:101220009DF90028E2D10F2C08D8944B1C70D8F8F7 +:101230000030A3F51673C8F80030DAE797F82410E9 +:10124000284602F0C9F9D4E7E38A282B2BD010D81E +:10125000012B23D0052BCCD1BFF34F8F8849894B6D +:10126000CA6802F4E0621343CB60BFF34F8F00BF44 +:10127000FDE7302BBDD1844EE17E327A9142B8D168 +:10128000607E3146002291F8DC50854200F0A58056 +:101290000132042A01F58A71F5D1AAE721462846D0 +:1012A000FFF7A0FDA5E721462846FFF703FEA0E7CC +:1012B000B2F8EC507B6005F103094FEA99094FEA57 +:1012C0008902D11DC908A8EBC1039D46EB46002148 +:1012D000584600F0C5FB04F1EE012A463144584659 +:1012E00000F0ACFB7B6813B9012000F017FB96F807 +:1012F000D20000F025FB044630B9307200F04AFB02 +:10130000204600F00BFBB1E0D6F8D4203AB996F8AD +:10131000D200B6F82C25824201D8FFF703FFD6F899 +:10132000D4202A44944208D296F8D200B6F82C254C +:101330000130824201D8FFF7F5FE70685FFA89F24A +:10134000594600F095FB08B9C54679E0726896F8F1 +:10135000D2002A447260D6F8D42005EB0209C6F800 +:10136000D49000F0EDFA814509D396F8D220D6F852 +:10137000D4000132001B86F8D220C6F8D400FF2D1D +:101380000FD80024347200F005FB204600F0C6FAA6 +:1013900000F0D6FD3D4B188108B9FFF70FFAC5469E +:1013A00027E7BB6896F8D9000AFB0362FB68D2F80E +:1013B000E41082F8E83001F58061C2F8E030C2F84C +:1013C000E410FFF7D5FDFFF723FE96F8D920013290 +:1013D00002F0030286F8D920B6E74FF48A7A0AFBB6 +:1013E00002F505F1EA013144204600F059FDF860AC +:1013F00000287FF4FEAE3544012285F8E82001F094 +:10140000D9FDD5F8E020D6ED007ADFED216A801A0B +:10141000192838BF192040F6B832904228BF10462C +:10142000B8EE677A07EE900AF8EEE77A67EEA67AEA +:10143000DFED186AE7EE267AFCEEE77AC6ED007A71 +:1014400096F8D930BB60BA6873680AFB02F43219A7 +:1014500092F8E81059B1D2F8E4108B42E8463FF414 +:1014600027AF002182F8E810C2F8E010C546736883 +:10147000064A9B0A01331381BBE600BFC934002032 +:1014800000ED00E00400FA05B0490020B824002077 +:10149000CDCCCC3D6666663FCC340020014B187045 +:1014A000704700BFC424002038B54FF00054134BE0 +:1014B00022689A4220D1124B627D12481A70237D15 +:1014C00003724FF48073C0F8F8314FF40073C0F822 +:1014D0000C3300254FF44073C0F820340A49C0F89B +:1014E000E450C922093000F0A9FAE022294620463A +:1014F00000F0B6FA012038BD0020FCE79AAD44C5E3 +:10150000C4240020B04900201600002037B500F0A8 +:1015100017FD194D1949288102236B7100220123FF +:10152000174801F051F900230193164B1649009317 +:101530001648174B4FF4805202F026F8154B1978D5 +:1015400011B1124802F048F801F034FD0446FFF7EB +:1015500021FC4FF4C873B0FBF3F202FB130304F554 +:10156000167010FA83F00C4B186003F0DBFC08B126 +:101570000F232B8103B030BDB824002040420F0060 +:10158000003500209D100008C8240020D034002021 +:10159000A1110008C4240020CC3400202DE9F04F14 +:1015A0002DED028B90A7D7E900670FF24429D9E906 +:1015B0000089884C95B00DAD9FED848BFFF728FD19 +:1015C000DFF834B200230C93ADF83C300D936B6020 +:1015D00000230DF125028DED008B4FF0010A09A9C2 +:1015E00058468DF825308DF824A001F04BFC9DF86D +:1015F00024200023002A40F0AF80204601F0F4FFB1 +:101600000546002847D1DFF8F4B101F0D3FCDBF840 +:10161000003098423FD301F0CDFC0790FFF7BAFBB2 +:10162000079A4FF4C873B0FBF3F101FB130302F503 +:10163000167010FA83F0CBF80000DFF8C4B19BF805 +:1016400000100791002914BF2B46534610A88DF8AF +:101650003030FFF7B7FB0799C1F11002D2B2062A6A +:1016600010AB28BF062219440DF13100079200F09B +:10167000E5F9079A0CAB0393182302930132564BFA +:10168000D2B2CDE900A304923B463246204601F097 +:10169000F1FF8BF8005001F08DFC504A504D13685B +:1016A000C31AB3F57A7F32D3106001F085FC02468D +:1016B0000B46204602F076F8204601F095FF30B345 +:1016C0002B7ADFF840A1002B14BF032302238AF8F2 +:1016D000053001F06FFC0DF1400B4FF47A730122DD +:1016E000B0FBF3F05946CAF80000504600F0DAFAB1 +:1016F000182302933B4B019380B240F25513CDE97E +:1017000003B0009342464B46204601F0B3FF2B7ACC +:10171000B3B101F04FFC4FF0000A83464FF48A72D8 +:1017200095F8D900504400F0030002FB005393F8F1 +:10173000E810002934D00AF1010ABAF1040FEFD100 +:10174000C82003F08FF82B7A002B7FF434AF15B04C +:10175000BDEC028BBDE8F08F4FF0904110A84A69B4 +:1017600082F010024A611946102200F079F90DF159 +:1017700026030AAA0CA9584600F0F0FE95E80300DB +:1017800011AB83E803009DF83C308DF84C300C9B86 +:10179000109310A9DDE90A23204602F0D7F917E7D4 +:1017A000D3F8E01049B12B68FA2B38BFFA23ABEB22 +:1017B00001010533B1EB430FBDD3FFF7D9FB4FF464 +:1017C0008A720028B7D1BBE7AFF3008000000000A9 +:1017D00000000000D0340020C8340020E04E00207B +:1017E000B0490020E44E0020401DA12026812A0B94 +:1017F000F1C6A7C1D068080F00350020CC34002006 +:10180000C9340020B824002008B5054800F04AFF7C +:10181000BDE80840034A0449002003F081BE00BF30 +:1018200000350020384F0020691100087047000083 +:1018300070B5104B1B780133DBB2012B0C4612D86C +:101840000D4B1D6829684FF47A730E6AA2FB0332B0 +:10185000014622462846B047844204D1074B002265 +:101860001A70012070BD4FF4FA7002F0FBFF0020E7 +:10187000F8E700BF182300201C2300202C4F002075 +:1018800007B50023024601210DF107008DF807304E +:10189000FFF7CEFF20B19DF8070003B05DF804FB11 +:1018A0004FF0FF30F9E700000A4608B50421FFF7C2 +:1018B000BFFF80F00100C0B2404208BD30B4074B0A +:1018C0000A461978064B53F821402368DD69054B19 +:1018D0000146AC46204630BC604700BF2C4F00207C +:1018E0001C230020A086010070B503F063F9094EA7 +:1018F000094D3080002428683388834208D903F0DA +:1019000055F92B6804440133B4F5F04F2B60F2D342 +:1019100070BD00BF2E4F0020E84E002003F0FCB940 +:1019200000F1006000F5E040D0F8000870470000CA +:1019300000F10060920000F5F04003F077B900007C +:10194000054B1A68054B1B889B1A834202D9104429 +:1019500003F02CB900207047E84E00202E4F0020E5 +:10196000024B1B68184403F027B900BFE84E002063 +:10197000024B1B68184403F031B900BFE84E002049 +:101980000020704700F10050A0F51040D0F89005FD +:1019900070470000064991F8243033B10023086AEB +:1019A00081F824300822FFF7C3BF0120704700BF31 +:1019B000EC4E0020014B1868704700BF002004E087 +:1019C00030B50F4B0F4C1B682288C3F30B03013853 +:1019D000934208440BD164680A46013C8242134694 +:1019E0000BD214F9015F2DB102F8015BF6E78142D9 +:1019F0000B4602D22C2203F8012B581A30BD00BF2F +:101A0000002004E020230020022802BF4FF0904372 +:101A100010229A6170470000022802BF4FF09043E5 +:101A20004FF480129A617047022801BF4FF0904234 +:101A3000536983F0100353617047000010B5002311 +:101A4000934203D0CC5CC4540133F9E710BD0000CD +:101A500003460246D01A12F9011B0029FAD1704739 +:101A600002440346934202D003F8011BFAE7704791 +:101A70002DE9F8431F4D144695F824200746884663 +:101A800052BBDFF870909CB395F824302BB920221C +:101A9000FF2148462F62FFF7E3FF95F82400C0F1CD +:101AA0000802A24228BF2246D6B24146920005EB68 +:101AB0008000FFF7C3FF95F82430A41B1E44F6B244 +:101AC000082E17449044E4B285F82460DBD1FFF778 +:101AD00061FF0028D7D108E02B6A03EB8203834221 +:101AE000CFD0FFF757FF0028CBD10020BDE8F88307 +:101AF0000120FBE7EC4E0020024B1A78024B1A70D3 +:101B0000704700BF2C4F00201823002003494FF4DA +:101B1000E1330B60024B186802F06ABD144F0020DD +:101B20001C230020094B10B518220446002118463A +:101B3000FFF796FF064A074B127804600146BDE89E +:101B4000104053F8220002F053BD00BF144F002094 +:101B50002C4F00201C2300202DE9F0470D460446A1 +:101B600000219046284640F27912FFF779FF23467C +:101B700020220021284601F08BFF231D0222202174 +:101B8000284601F085FF631D03222221284601F02B +:101B90007FFFA31D03222521284601F079FF04F1D0 +:101BA000080310222821284601F072FF04F11003D7 +:101BB00008223821284601F06BFF04F111030822A6 +:101BC0004021284601F064FF04F112030822482155 +:101BD000284601F05DFF04F114032022502128461D +:101BE00001F056FF04F1180340227021284601F04D +:101BF0004FFF04F120030822B021284601F048FFDE +:101C000004F121030822B821284601F041FF04F124 +:101C10002207C0263B46314608222846083601F0F6 +:101C200037FFB6F5A07F07F10107F3D104F13203C6 +:101C300008223146284601F02BFF002704F1330A21 +:101C400094F832304FEAC7099F4209F5A47615D3BC +:101C5000B8F1000F08D1314604F5997307222846E0 +:101C600001F016FF09F24F16274694F832213B1B6C +:101C700093420CD3F01DC008BDE8F0870AEB0703C0 +:101C800008223146284601F003FF0137D8E707F262 +:101C9000331331460822284601F0FAFE0836013790 +:101CA000E3E7000013B5044608460021016023461F +:101CB000C0F803102022019001F0EAFE0198231DD4 +:101CC0000222202101F0E4FE0198631D032222215B +:101CD00001F0DEFE0198A31D0322252101F0D8FEAC +:101CE000019804F108031022282101F0D1FE0720F9 +:101CF00002B010BDF7B50023047F00910E46072205 +:101D00001946054601F088FD731C0093012200234B +:101D10000721284601F080FDC4B9B31C00930522B9 +:101D200023460821284601F077FD0D243746B27876 +:101D3000BB1B934211D32B7FA88A0734E408BBB99D +:101D4000844294BF0020012003B0F0BDAB8ADB00C9 +:101D5000083BDB08B3700824E8E7FB1C009321462E +:101D600000230822284601F057FD08340137DEE73A +:101D7000201A18BF0120E7E7F7B50023047F009180 +:101D80000E4608221946054601F046FD731CC4B9EB +:101D90000822009311462346284601F03DFD1024F9 +:101DA000012372785F1C013B934211D32B7FA88AD9 +:101DB0000734E408BBB9844294BF0020012003B07B +:101DC000F0BDAB8ADB00083BDB0873700824E7E753 +:101DD000F3190093214600230822284601F01CFD38 +:101DE00008343B46DDE7201A18BF0120E7E7000072 +:101DF000F8B50E4605461446002181223046FFF70D +:101E00002FFE2B4608220021304601F041FE7CB90E +:101E10006B1C07220821304601F03AFE0F240123F3 +:101E20006A785F1C013B934204D3E01DC008F8BDF3 +:101E30000824F4E7EB1921460822304601F028FE79 +:101E400008343B46ECE70000F8B50E46054614465C +:101E50000021CE223046FFF703FE2B462822002128 +:101E6000304601F015FE7CB905F10803082228214F +:101E7000304601F00DFE30242F462A7A7B1B934218 +:101E800004D3E01DC008F8BD2824F5E707F10903D5 +:101E900021460822304601F0FBFD08340137ECE70B +:101EA000F7B5047F00910E4601231022002105465C +:101EB00001F0B2FCC4B9B31C0093092223461021DF +:101EC000284601F0A9FC192437467288BB1B9A42A8 +:101ED00011D82B7FA88A0734E408BBB9844294BF89 +:101EE0000020012003B0F0BDAB8ADB00103BDB0813 +:101EF00073801024E8E73B1D00932146002308224D +:101F0000284601F089FC08340137DEE7201A18BFA3 +:101F10000120E7E730B5094D0A4491420DD011F890 +:101F2000013B5840082340F30004013B2C4013F0D0 +:101F3000FF0384EA5000F6D1EFE730BD2083B8ED0F +:101F4000F7B5384A106851686B4603C36A4636498C +:101F50003648082303F012FB0446002833D10A2533 +:101F6000334A106851686B4603C36A4631492F48AB +:101F7000082303F003FB0446002849D00369B3F5A6 +:101F8000623F45D8B0F8661040F2114291423FD10D +:101F9000294A024402F15C018B4239D35C3B23495C +:101FA00000209E1AFFF7B6FF3246074604F164018F +:101FB0000020FFF7AFFFA3689F4229D1E368984252 +:101FC00008BF002524E00369B3F5623F27D8418BA1 +:101FD00040F21142914220D1174A024402F110010D +:101FE0008B4218D3103B114900209D1AFFF792FF36 +:101FF0002A46064604F118010020FFF78BFFA3686C +:102000009E4202D1E368984201D00D25A8E7002541 +:10201000284603B0F0BD1025A2E70C25A0E70B254C +:102020009EE700BFF8550008DC8703000078000831 +:1020300001560008908703000888FFF710B5037C5D +:10204000044613B9006803F081FA204610BD000071 +:102050000023BFF35B8FC360BFF35B8FBFF35B8F66 +:102060008360BFF35B8F7047BFF35B8F0068BFF384 +:102070005B8F704770B505460C30FFF7F5FF05F133 +:10208000080604463046FFF7EFFFA04206D9304667 +:102090006D68FFF7E9FF2544281A70BD3046FFF749 +:1020A000E3FF201AF9E7000070B50546406898B1D3 +:1020B00005F10800FFF7D8FF05F10C06044630468D +:1020C000FFF7D2FF8442304694BF6D680025FFF7CA +:1020D000CBFF013C2C44201A70BD000038B50C46E3 +:1020E0000546FFF7C7FFA04210D305F10800FFF730 +:1020F000BBFF04446868B4FBF0F100FB1144BFF37C +:102100005B8F0120AC60BFF35B8F38BD0020FCE724 +:102110002DE9F041144607460D46FFF7C5FF8442FE +:1021200028BF0446D4B1B84658F80C6B4046FFF7B8 +:102130009BFF3044286040467E68FFF795FF331AC6 +:102140009C4203D86C600120BDE8F0816B60A41B49 +:102150003B68AB602044E8600220F5E72046F3E7E7 +:1021600038B50C460546FFF79FFFA04210D305F196 +:102170000C00FFF779FF04446868B4FBF0F100FB42 +:102180001144BFF35B8F0120EC60BFF35B8F38BD60 +:102190000020FCE72DE9FF41884669460746FFF726 +:1021A000B7FF6C4606B204EBC6060025B44209D060 +:1021B0006268206808EB0501FFF740FC636808349B +:1021C0001D44F3E729463846FFF7CAFF284604B006 +:1021D000BDE8F081F8B505460C300F46FFF744FF27 +:1021E00005F1080604463046FFF73EFFA0423046A0 +:1021F00088BF6C68FFF738FF201A386020B130467E +:102200002C68FFF731FF2044F8BD000073B5144679 +:1022100006460D46FFF72EFF844228BF0446019074 +:10222000DCB101A93046FFF7D5FF019B33B9326815 +:10223000C5E90233C5E9002401200CE09C4238BF07 +:1022400001942860019868608442F5D93368AB60D6 +:10225000241AEC60022002B070BD2046FBE70000AB +:102260002DE9FF410F466946FFF7D0FF6C4600B2EB +:1022700004EBC0050026AC4209D0D4F8048054F821 +:10228000081BB8194246FFF7D9FB4644F3E730462E +:1022900004B0BDE8F081000038B50546FFF7E0FF67 +:1022A000044601462846FFF719FF204638BD0000C6 +:1022B000302383F3118862B670470000002383F354 +:1022C000118862B670470000012070477047000017 +:1022D00010B41346026814680022A4465DF8044B4B +:1022E0006047000000F5805090F8590470470000E6 +:1022F00000F5805090F852047047000000F58050BF +:1023000090F95804704700005020704700F5805243 +:1023100008B5FFF7CDFFD2F89834D2F894041844EA +:10232000D2F890341844D2F878341844D2F888346B +:102330001844D2F884341844FFF7C0FF08BD0000E9 +:1023400038B5C26A936923F001039361044600F033 +:1023500031FE0546E36A9B69DB0706D500F02AFEDD +:10236000431BFA2BF6D9002004E004F58054012029 +:1023700084F8520438BD00002DE9F04F0C4600F5FA +:10238000805185B01F4691F85234BDF8389005460B +:1023900090469BB1D1F874340133C1F8743423688A +:1023A0009A0006D4237B082B0BD9627B0AB10F2B32 +:1023B00007D9D1F878340133C1F878344FF0FF30C1 +:1023C0000FE0FFF775FFEB6AD3F8C42012F4001A90 +:1023D0000AD0D1F87C340133C1F87C34FFF76EFFAA +:1023E000002005B0BDE8F08FD3F8C46022686B6AA6 +:1023F000C6F301464FF0480B002A1BFB063BB4BF57 +:1024000042F080429204CBF8002023685B0044BF76 +:1024100042F00052CBF80020227B330643EA02430D +:10242000CBF80430607B720118B343F44013CBF84F +:102430000430D1F8A4340133C1F8A434AB1803F547 +:102440008353197B41F020011973207B039200F024 +:102450000DFE039A033080105FFA8AF383420AF17B +:10246000010A0DDA04EB83010BEB830349689960E1 +:10247000F2E7AB1803F58353197B60F34511E3E7EB +:10248000EB6A0121B140C3F8CC10AB1803F58253BD +:10249000C3E9048705EB461303F58253214618333D +:1024A00004F10C0051F804CB43F804CB8142F9D17C +:1024B000098819802A4441F268032846D65002F55B +:1024C000805209F0030392F86C1043F0100321F0DE +:1024D0001F010B4382F86C30FFF7F0FE4246CDF847 +:1024E00000903B46214600F087FD012079E700007F +:1024F00013B500F580540191606CFFF7D5FD1F28DE +:102500000AD90199606C2022FFF744FEA0F1200354 +:102510005842584102B010BD0020FBE708B500F555 +:102520008050FFF7C5FE406CFFF792FDBDE8084004 +:10253000FFF7C4BE00220260828142608260704761 +:1025400010B500220023C0E90023002304460381C4 +:102550000C30FFF7EFFF204610BD00002DE9F047DB +:10256000074688B007F5805468469A468846FFF7C4 +:102570009FFE9146FFF7E4FF606CFFF77BFD1F288D +:102580002CD9606C20226946FFF786FE202825D1D1 +:1025900094F8523413B303AD444605AB2E4603CE34 +:1025A0009E4220606160354604F10804F6D130682F +:1025B0002060B388A380DDE90023C9E90023BDF8CA +:1025C0000830AAF80030FFF779FE4A4653464146E4 +:1025D000384608B0BDE8F04700F0FCBCFFF76EFEDF +:1025E000002008B0BDE8F0872DE9F84F002306462B +:1025F000C0E90133284B46F8303B00F581540546CD +:1026000088463746103438462037FFF799FFA742EF +:10261000F9D105F580544FF4805326630026C4E9B0 +:102620000D366764012305F5835705F5A359E66365 +:1026300084F8403084F84830103709F110094FF021 +:10264000000A4FF0000B47E908ABA7F11800FFF7AD +:1026500071FF203747F8286C4F45F4D184F858842F +:10266000A4F85A64A4F85C64A4F85E6484F8606416 +:10267000A4F86264A4F86464A4F8666484F86864E6 +:10268000B8F1000F02D0054800F08EFC044BEB625D +:102690002846BDE8F88F00BF285600080C560008F1 +:1026A0000064004010B5044B197804464A1C1A70A7 +:1026B000FFF79AFF204610BD354F00202DE9F0436B +:1026C00000295FD03048314BB3FBF1F381428CBF1E +:1026D0000A201120451EB3FBF0F700FB1730ECB2C7 +:1026E00020B1022D2846F5D8002037E07D1EB5F533 +:1026F000806F33D2C4EBC40808F103034FEAE30E42 +:10270000C3F3C703A4EB030C0EF101094FF47A7075 +:102710005FFA8CF60EFB000E59FA8CFCBEFBFCFC3B +:10272000BCF5617F1CDC1FFA8CF4581C56FA80F053 +:1027300047431648B0FBF7F7B942D5D1013BDBB2AE +:102740000F2BD1D8711EC9B207294FF0000005D850 +:10275000107114805580537191710120BDE8F08390 +:1027600008F1FF334FEAE30CC3F3C703E41A0CF19B +:10277000010EE6B20CFB00005EFA84F4B0FBF4F448 +:10278000A4B2D2E70846E9E73F420F0000127A0000 +:102790000B4B10B54FF45472044600211846FFF756 +:1027A0005FF9084BA3614033E361D8332362F03310 +:1027B0006362E36A60610022C3F8C02010BD00BFFD +:1027C00000A4004070A400402DE9F04F00F58055B2 +:1027D000994695F85834012B89B004468A469046AC +:1027E00004D90027384609B0BDE8F08F8D4A52F869 +:1027F000231009B942F823008B49C4F80CA00B78C8 +:1028000084F8109093B9FFF753FD884B9A6D42F00E +:1028100000729A659A6B42F000729A639A6B22F08A +:1028200000729A6301230B70FFF748FD95F851344D +:1028300073B903211520FFF73BFD01F023FD0321B0 +:10284000162001F01FFD012385F85134FFF736FDF6 +:10285000FFF72EFDE26A936923F01003936100F005 +:10286000A9FB0746E36A9E6916F0080607D000F048 +:10287000A1FBC31BFA2BF5D9FFF720FDB1E79A693D +:1028800042F001029A6100F095FB0746E36A9A69FB +:10289000D00705D400F08EFBC31BFA2BF6D9EBE76B +:1028A0009A6942F002029A61E36A00275F65FFF7C6 +:1028B00005FD686CFFF7CCFB04F5825B0BF1100B98 +:1028C000202200216846FFF7CBF802A8FFF732FE6E +:1028D00006976A460BEB06030DF1180E9446BCE80A +:1028E0000300F44518605960624603F10803F5D10E +:1028F000DCF80000186020369CF804201A71B6F548 +:10290000806FDDD1002304F5A25285F8503485F89C +:1029100053341A3251462046FFF7D0FE074690B98D +:10292000E26A936923F00103936100F043FB0546DB +:10293000E36A9B69D9077FF554AF00F03BFB431B6B +:10294000FA2BF5D94DE795F85F6495F85E24C5F844 +:102950006CA4360246EA426695F86024E36A1643A0 +:10296000B5F85C2446EA0246DE61B8F1000F29D0D2 +:1029700004F5A352023241462046FFF79FFE90B96C +:10298000E26A936923F00103936100F013FB0546AB +:10299000E36A9B69DA077FF524AF00F00BFB431B6A +:1029A000FA2BF5D91DE795F8683495F86714C5F842 +:1029B00070841B0143EA0123B5F86414E26A43EA18 +:1029C0000143D3602046FFF7E3FE002385F8593426 +:1029D000E36A6FF040421A65E36A154A5A65E36A92 +:1029E00044229A65E36A0722C3F8DC20E36A0322E3 +:1029F0009145DA653FF4F6AEE26A936923F001038C +:102A0000936100F0D7FA0646E36A9B69DB0705D5B8 +:102A100000F0D0FA831BFA2BF6D9E2E6012385F801 +:102A20005234DFE6304F0020344F002000100240C7 +:102A30009B0008002DE9F04F054689B09046994665 +:102A4000002741F2680A00F58056EB6AD3F8D430CB +:102A5000FB40D8074AD505EB471252444FEA471BC3 +:102A60001379190742D4D6F880340133C6F880347C +:102A700013799A0648BFD6F8A83405EB0B0248BF75 +:102A80000133524448BFC6F8A834137943F0080311 +:102A90001371DB0722D596F85334FBB105F5825448 +:102AA000183468465C44FFF74BFD03AB04F1080C97 +:102AB000206861681A4603C2083464451346F7D19A +:102AC00020681060A2889A800123ADF808302B6836 +:102AD000CDE90089DB6B694628469847D6F854341F +:102AE00023B1D6F89C340133C6F89C340137202F2B +:102AF000ABD109B0BDE8F08F2DE9F04F8DB00446A1 +:102B00000F4600F059FA82468946002F56D1E36AF3 +:102B1000D3F89020920141BF04F58051D1F894245C +:102B20000132C1F89424D3F89020160703D1002075 +:102B30000DB0BDE8F08FD3F89050E669C5F30125DC +:102B4000482303FB0566E8464046FFF7F3FC32687E +:102B500051004ABF22F06043C2F38A4343F000436E +:102B6000920048BF43F080430093736813F400134E +:102B70001FBF04F5805201238DF80D30D2F8AC341C +:102B80000EBF8DF80D300133C2F8AC34F38803F07A +:102B90000F038DF80C304FF0000B9DF80C0000F087 +:102BA00065FA5FFA8BF3984220D9F2180CA90B440E +:102BB000127A03F82C2C0BF1010BEEE7012FB6D1A2 +:102BC000E36AD3F89820950141BF04F58051D1F80C +:102BD00094240132C1F89424D3F898201007A6D089 +:102BE000D3F89850266AC5F30125A9E7EFB9E36A3F +:102BF000C3F8945004A8FFF7A3FC98E80F0007ADB2 +:102C000007C52B800023ADF8183023682046CDE996 +:102C100004A9DB6B04A9984704F5805458B1D4F893 +:102C20008C340133C4F88C3482E7012F04BFE36A8B +:102C3000C3F89C50DEE7D4F890340133C4F89034E4 +:102C4000012075E7F8B505460F4600F580540126CA +:102C500039462846FFF750FF10B184F85364F7E770 +:102C6000D4F8543423B1D4F89C340133C4F89C34E0 +:102C7000F8BD0000F0B5C36A1A6C12F47F0F2BD0B8 +:102C800000F580541B6CC4F8A03441F268050023A1 +:102C900047194FF0010C00EB43122A445E011179F1 +:102CA00011F0020F15D0490713D4B959C66AD6F8E6 +:102CB000C8E00CFA01F111EA0E0F0AD0C6F8D010E4 +:102CC000117941F004011171D4F888240132C4F85B +:102CD00088240133202BDED1F0BD000010B5254C37 +:102CE000254B226802B338B31A6D12060ED5802226 +:102CF0001A6500F061F950EA01020B4602D0013872 +:102D000061F1000302462068FFF794FE1A4A136D32 +:102D10001B032AD523684FF4002103F58053116566 +:102D2000012283F8592420E001221A6508221A653D +:102D30004FF480621A6510BD196DC80702D4196D71 +:102D4000890705D50321196510460021FFF77AFF91 +:102D5000094B1A6D100702D41A6DD10605D5182239 +:102D60001A6520680121FFF76DFF2068BDE810405B +:102D7000FFF780BF304F00200064004008B5FFF728 +:102D800097FAFFF777FFBDE80840FFF797BA000012 +:102D9000C36AD3F8C40080F40010C0F340507047F9 +:102DA00000F5805008B5FFF783FA406CFFF762F931 +:102DB000FFF784FA43090CBF0120002008BD000082 +:102DC00000F5805393F8592462B1C16A8A6922F0F0 +:102DD00001028A61D3F898240132C3F898240022B2 +:102DE00083F85924704700002DE9F74300F582511C +:102DF00098461031FFF75CFA002541F2680E4FF05B +:102E0000010900F5805C00EB4514744423795E07EA +:102E10001CD4DB061AD5C36A8E69D3F8C87009FAC8 +:102E200006F63E4212D04F6801970F689742019F05 +:102E300077EB08070AD2C3F8D060237943F0040384 +:102E40002371DCF884340133CCF884340135202D2F +:102E500001F12001D7D103B0BDE8F043FFF72EBA4E +:102E6000F8B51E46002313700F4605461446FFF7BB +:102E700097FF80F0010038701EB12846FFF788FFE9 +:102E80002070F8BD2DE9F04F85B09946DDE90EA31D +:102E90000D4602931378019391F800B080461646D0 +:102EA00000F08AF82B7804460F4613B93378002BCC +:102EB00042D022463B464046FFF796FFFFF75EFFB3 +:102EC000FFF77EFF4B4632462946FFF7C9FF2B78B6 +:102ED00033B1BBF1000F03D0012005B0BDE8F08F86 +:102EE000337813B1019B002BF6D108F5805303937F +:102EF000029B544577EB03031ED2039BD3F8540483 +:102F0000D0B10368AAEB0401DB6889B298474B464D +:102F1000324629464046FFF7A3FF2B7813B1BBF199 +:102F2000000FD9D1337813B1019B002BD4D100F01D +:102F300043F804460F46DBE70020CEE708B5002043 +:102F4000FFF7CCFEBDE8084001F050B808B50120FD +:102F5000FFF7C4FEBDE8084001F048B800B59BB0DB +:102F6000EFF3098168226846FEF768FDEFF30583F9 +:102F7000014B9B6BFEE700BF00ED00E008B5FFF7DB +:102F8000EDFF000000B59BB0EFF3098168226846B1 +:102F9000FEF754FDEFF30583014B5B6BFEE700BFCB +:102FA00000ED00E0FEE700000FB408B5029801F064 +:102FB000EFFBFEE701F0FEBE01F0D6BE13B56C4696 +:102FC00084E80600031D94E8030083E8050001205F +:102FD00002B010BD73B58568019155B11B885B07C0 +:102FE00007D4D0E900369B6B9847019AC1B23046AE +:102FF000A847012002B070BDF0B5866889B00546CB +:103000000C465EB1BDF838305B070AD4D0E9003712 +:103010009B6B98472246C1B23846B047012009B0A1 +:10302000F0BD00220023CDE900230023ADF80830D5 +:103030000A4603AB01F10806106851681C4603C438 +:103040000832B2422346F7D1106820609288A280ED +:10305000FFF7B2FF0423ADF808302B68CDE900017B +:10306000DB6B694628469847D8E70000082817D93F +:1030700009280CD00A280CD00B280CD00C280CD016 +:103080000D280CD00E2814BF4020302070470C2093 +:103090007047102070471420704718207047202078 +:1030A000704700002DE9F041456A15B94162BDE85D +:1030B000F0814B6823F06047C3F38A464FEAD37E22 +:1030C000C3F3807816EA230638BF3E46AC462B464B +:1030D0005A68BEEBD27F22F060440AD0002A18DA88 +:1030E000A40CB44217D19D420FD10D60DEE7134608 +:1030F000EEE7A74207D102F08044C2F38072424556 +:103100000BD054B1EFE708D2EDE7CCF800100B601C +:10311000CDE7B44201D0B442E5D81A689C46002AF3 +:10312000E5D11960C3E700002DE9F047089D01F0E3 +:1031300007044FEAD508224405F0070500EBD1004B +:103140004FF47F49944201D1BDE8F08704F00707AE +:1031500005F0070A57453E4638BF5646C6F10806F1 +:10316000111B8E4228BF0E46E10808EBD50E415CCC +:1031700013F80EC0B94029FA06F721FA0AF1FFB296 +:103180008CEA010147FA0AF739408CEA010C03F88E +:103190000EC034443544D5E780EA0120082341F2CB +:1031A000210201B24000002980B203F1FF33B8BF11 +:1031B000504013F0FF03F4D17047000038B50C46BF +:1031C0008D18A54200D138BD14F8011BFFF7E4FFAC +:1031D000F7E7000042684AB1136843604389818978 +:1031E00001339BB29942438138BF838110467047B7 +:1031F00070B588B0202204460D4668460021FEF7CF +:103200002FFC20460495FFF7E5FF024658B16B46B8 +:10321000054608AE1C4603CCB442286069602346CC +:1032200005F10805F6D1104608B070BD082817D979 +:1032300009280CD00A280CD00B280CD00C280CD054 +:103240000D280CD00E2814BF4020302070470C20D1 +:1032500070471020704714207047182070472020B6 +:1032600070470000082817D90C280CD910280CD951 +:1032700014280CD918280CD920280CD930288CBF38 +:103280000F200E207047092070470A2070470B203E +:1032900070470C2070470D20704700002DE9F8435F +:1032A000078C072F04461ED9D0E9029800254FF657 +:1032B000FF73C5F12006A5F1200029FA05F108FAEF +:1032C00006F628FA00F031430143C9B21846FFF769 +:1032D00063FF0835402D0346EBD1E1693A46BDE86E +:1032E000F843FFF76BBF4FF6FF70BDE8F8830000AF +:1032F00010B54B6823B9CA8A63F30902CA8210BDAC +:1033000004691A681C600361C38A013BC3824A6076 +:10331000EFE700002DE9F84F1D46CB8A0F46C3F3B7 +:1033200009010529814692460B4630D00020AAB2F9 +:1033300007F11A049EB2042E1FFA80F80FD89045A8 +:1033400003F1010306D3FB8A0A4462F30903FB82FB +:1033500001201AE01AF80060E6540130EAE79045CF +:10336000F1D2A1F1050B1C237C68BBFBF3F203FB3C +:1033700012BB1FFA8BF6002C45D14846FFF72AFFF7 +:10338000044638B978606FF00200BDE8F88F4FF05E +:103390000008E6E7002606607860ADB24FF0000B4B +:1033A000454510D90AEB0803221D13F8011B91555E +:1033B000B1B208F101081B291FFA88F82BD0454546 +:1033C00006F10106F1D8FB8AC3F30902154465F33F +:1033D0000903BCE7013292B21C462368002BF9D1E5 +:1033E0006B1F0B441C21B3FBF1F301339BB29A42D8 +:1033F000D3D2BBF1000FD0D14846FFF7EBFE20B986 +:10340000C4F800B0BFE70122E7E7C0F800B05E46AD +:1034100020600446C1E74545D5D94846FFF7DAFEA6 +:1034200008B92060AFE7C0F800B00026206004466D +:10343000B6E700002DE9F04F2DED028B1C4683B05E +:103440005B69019207468846002B00F09A80238C26 +:103450002BB1E269002A00F09480072B35D807F1E0 +:103460000C00FFF7B7FE054638B96FF00205284695 +:1034700003B0BDEC028BBDE8F08F14220021FEF7F3 +:10348000EFFA228CE16905F10800FEF7D7FA208CEB +:10349000013080B2FFF7E6FEFFF7C8FE013880B2C8 +:1034A0002084013028746369228C1B782A4403F03D +:1034B0001F0363F03F0348F0004113723846696010 +:1034C0002946FFF7EFFD0125D1E700F10C034FF08E +:1034D000000908EE103A4FF0800A4E464D4618EEAD +:1034E000100AFFF777FE83460028BED01422002181 +:1034F000FEF7B6FA002E3AD1019BABF80830022253 +:103500000BF1080E1FFA82FC0CF10100BCF1060F52 +:10351000218C80B201D88E422BD3FFF7A3FEFFF798 +:1035200085FE62691278013802F01F028E4208BFE0 +:103530004FF0400A42EA49121BFA80F14AEA020AB5 +:10354000013048F0004281F808A08BF81000CBF859 +:10355000042059463846FFF7A5FD238C0135B342B8 +:103560002DB289F001094FF0000AB8D17FE700229F +:10357000C6E7E169895D0EF802100136B6B2013284 +:10358000C0E76FF0010572E7F8B515460E46302228 +:10359000002104461F46FEF763FA069B6360B5F5FB +:1035A000001F079BA76034BF6A094FF6FF72A36232 +:1035B00097B2E66104F1100000239A4206D8002376 +:1035C0000360A782E3822383E360F8BD06600133D2 +:1035D00030462036F1E7000003781BB94BB2002BD0 +:1035E000C8BF01707047000000787047F8B50C46FE +:1035F000C969074611B9238C002B37D1257E1F2DB1 +:1036000034D8387828BB228C072A2CD8268A36F062 +:1036100003032BD14FF6FF70FFF7D0FD20F0010020 +:103620003102400441EA0561400C41EA40254FF671 +:10363000FF72234629463846FFF7FCFE002807DDC7 +:10364000626913780133DBB21F2B88BF002313702C +:10365000F8BD218A2D0645EA012505432046FFF7DE +:103660001DFE0246E5E76FF00300F1E76FF0010091 +:10367000EEE7000070B58AB0044616460021282205 +:1036800068461D46FEF7ECF9BDF83830ADF810304D +:103690000F9B05939DF840308DF81830119B0793D0 +:1036A0006946BDF84830ADF820302046CDE90265C6 +:1036B000FFF79CFF0AB070BD2DE9F041D3690546C4 +:1036C0000C4616460BB9138C5BBB377E1F2F28D8D0 +:1036D00095F80080B8F1000F26D03046FFF7DEFDE8 +:1036E0003378210241EAC33141EA0801338A41EAD1 +:1036F000076141EA03410246334641F08001284612 +:10370000FFF798FE00280ADD3378012B07D1726994 +:1037100013780133DBB21F2B88BF00231370BDE881 +:10372000F0816FF00100FAE76FF00300F7E70000A7 +:10373000F0B58BB004460D46174600212822684696 +:103740001E46FEF78DF99DF84C305A1E53425341E8 +:103750008DF800309DF84030ADF81030119B059386 +:103760009DF848308DF81830149B07936A46BDF8D1 +:103770005430ADF8203029462046CDE90276FFF7D7 +:103780009BFF0BB0F0BD0000406A00B104307047F1 +:10379000436A1A68426202691A600361C38A013B84 +:1037A000C38270472DE9F041D0F82080194E1446AD +:1037B0001D464146002709B9BDE8F081D1E9022341 +:1037C000A21A65EB0303964277EB03031ED2036A4A +:1037D0008B420DD1FFF78CFD036A1B6803620369FE +:1037E0000B60C38A0161016A013BC3828846E2E73C +:1037F000FFF77EFD0B68C8F8003003690B60C38AD1 +:103800000161013BC382D8F80010D4E788460968FB +:10381000D1E700BF80841E002DE9F04F8BB00D462C +:10382000DDF8509014469B468046002800F0198130 +:10383000B9F1000F00F01581531E3F2B00F21181EA +:10384000012A03D1BBF1000F40F00B810023CDE929 +:103850000833B8F81430B5EBC30F4FEAC30703D3EE +:1038600000200BB0BDE8F08F2B199F42D8F80C3028 +:103870003ABF7F1BFFB227461BB9D8F81030002B88 +:103880007AD0272D4ED8C5F12806B7424FF0000355 +:103890002CBFF6B23E4600932946D8F8080008AB84 +:1038A0003246FFF741FCA7EB060A35445FFA8AFA75 +:1038B000B8F8143003F10053053BDB000493D8F84B +:1038C0000C3003932821039B13B1BAF1000F2CD1C4 +:1038D000D8F8100040B1BAF1000F05D0009608AB3F +:1038E0005246691AFFF720FC38B2002FB8D066079D +:1038F0000AD00AAB03EBD401624211F8083C02F093 +:103900000702134101F8083C082C3CD9102C40F266 +:10391000B580202C40F2B780BBF1000F00F09C80F6 +:10392000082334E0BA460026C2E7049BE02B28BFF8 +:10393000E02306930B44AB42059314D95A1B03981A +:103940000096924534BF5246D2B2691A08AB043091 +:103950000792FFF7E9FB079A1644AAEB020A1544FF +:10396000F6B25FFA8AFA049B069A05999B1A0493A9 +:10397000039B1B680393A6E70093D8F8080008ABE5 +:103980003A462946AEE7BBF1000F13D00123B4EB52 +:10399000C30F6CD0082C12D89DF82030621E23FA79 +:1039A00002F2D50706D54FF0FF3202FA04F42343A2 +:1039B0008DF820309DF8203089F8003051E7102C28 +:1039C00012D8BDF82030621E23FA02F2D10706D5C4 +:1039D0004FF0FF3202FA04F42343ADF82030BDF873 +:1039E0002030A9F800303CE7202C0FD80899631E3E +:1039F00021FA03F3DA0705D54FF0FF3202FA04F497 +:103A00000C430894089BC9F800302AE7402C2BD0BF +:103A1000DDE90865611EC4F12102A4F1210326FA43 +:103A200001F105FA02F225FA03F311431943CB071A +:103A300012D50122A4F12003C4F1200102FA03F3FC +:103A400022FA01F1A240524243EA010363EB43032D +:103A500032432B43CDE90823DDE90823C9E90023DC +:103A6000FFE66FF00100FCE66FF00800F9E6082CB5 +:103A7000A0D9102CB3D9202CEED8C3E7BBF1000F8E +:103A8000ADD0022383E7BBF1000FBBD004237EE758 +:103A900030B5012A144638BF0124402C85B028BF18 +:103AA00040240025012ACDE9025518D81B788DF84D +:103AB000083063070AD004AB03EBD405624215F863 +:103AC000083C02F00702934005F8083C00910346C9 +:103AD0002246002102A8FFF727FB05B030BD082AC7 +:103AE000E4D9102A03D81B88ADF80830E1E7202A72 +:103AF0008DBFD3E900231B680293CDE90223D8E7E9 +:103B000010B5CB681BB98B600B618B8210BD04694B +:103B10001A681C600361C38A013BC382CA60F0E774 +:103B200003064CBFC0F3C0300220704708B5024600 +:103B3000FFF7F6FF022806D15306C2F30F2001D18A +:103B400000F0030008BDC2F30740FBE72DE9F04F8A +:103B500093B0CDE903230A6804461046FFF7E0FF5F +:103B6000022814BFC2F306260026002A0D4682460C +:103B700080F2F28112F0C04940F0EE81097B002909 +:103B800000F0EA81022803D02378B34240F0E781B5 +:103B9000C2F304630693104602F07F030593FFF718 +:103BA000C5FF059B29444FEA834848EA0A4848EA8A +:103BB0004668CE7800230022CDE90823F309834626 +:103BC00048EA0008029367D0059B009302466768A5 +:103BD000534608A92046B847002800F0C381276A49 +:103BE0004FB9414604F10C00FFF702FB074690B9BC +:103BF0006FF0020054E03B6998450DD03F68002FFC +:103C0000F9D1414604F10C00FFF7F2FA074600280B +:103C1000EED0236A3B60276297F817C006F01F08B2 +:103C2000CCF3840CACEB08001FFA80FE0028B8BF70 +:103C30000EF12000A8EB0C031FFA83FED7E9022146 +:103C4000B8BF00B2002B0793BEBF0EF120031BB21A +:103C5000079352EA010338D0039BDFF824E39A1A52 +:103C6000049B4FF0000C63EB010196457CEB0103D4 +:103C70002BD36B7B97F81AE0734519D1029B002B6D +:103C800078D0012821DC7868F8B9DFF8F0C29445D3 +:103C900070EB010316D337E0276A27B96FF00C00E9 +:103CA00013B0BDE8F08F3B699845B5D03F68F4E7A5 +:103CB000B24890427CEB010301D30020F0E7029B65 +:103CC000002BFAD0079B0F2B17DCFA7DB30002F014 +:103CD000030203F07C031343FB7539462046FFF7CC +:103CE00007FB6B7BBB76029B3BB9FB7DC3F3840276 +:103CF000013262F38603FB75D0E76A7BBB7E9A4292 +:103D0000DBD1029B002B35D0B309022B32D0039BB1 +:103D1000BB60049BFB60142200210DA8FDF7A0FEF0 +:103D2000039B0A93049B0B932B1D0C932B7BADF8E9 +:103D30003EB0013BDBB2ADF83C30069B8DF8423023 +:103D4000059B8DF8433094F82C308DF840A083F01B +:103D500001038DF844308DF84180A3680AA92046FC +:103D60009847FB7DC3F38403013303F01F039B02D9 +:103D7000FB82A2E7FB7DC6F34012B2EBD31F40F0FB +:103D8000F480C3F38403434540F0F280029A2B7B16 +:103D9000B609002A4DD0F2075DD4032B40F2EB8028 +:103DA000039BBB60049BFB602B7BAE1D033BDBB224 +:103DB0003246394604F10C00FFF7ACFA00280CDA61 +:103DC00039462046FFF794FAFB7DC3F384030133A1 +:103DD00003F01F039B02FB820AE7DDE90884AB883E +:103DE0003B834FF6FF73C9F12000A9F1200228FAA6 +:103DF00009F104FA00F0014324FA02F211431846D3 +:103E0000C9B2FFF7C9F909F10809B9F1400F034632 +:103E1000E9D1B8822A7B033AD2B23146FFF7CEF914 +:103E2000FB7DB882DA43C2F3C01262F3C713FB759D +:103E300043E786B92E1D013BDBB23246394604F119 +:103E40000C00FFF767FA0028BADB2A7BB88A013A30 +:103E5000D2B23146E2E7F98AC1F30901013B0429F4 +:103E6000DAB25BD8281D002307F11B069A4208D955 +:103E700010F801CB06F801C0013101330529DBB28E +:103E8000F4D103990A9104990B91934207F11B0114 +:103E90000C9138BF043379680D9134BF55FA83F320 +:103EA00000230E93FB8AADF83EB0C3F309031A4416 +:103EB000069B8DF84230059B8DF8433094F82C30EA +:103EC000ADF83C2083F001038DF8443000238DF8D9 +:103ED00040A08DF841807B602A7BB88A013A291D79 +:103EE000FFF76CF93B8BB882834203D1A3680AA920 +:103EF0002046984720460AA9FFF702FEFB7DBA8AB2 +:103F0000C3F38403013303F01F039B02FB823B8B4B +:103F10009A420CBF00206FF01000C1E67B68002BB6 +:103F2000AFD0052001E01C3033461E68002EFAD1C8 +:103F3000091A081D2E1D184401EB090CBCF11B0FBA +:103F40005FFA89F39DD89A429BD916F8013B00F895 +:103F5000013B09F10109EFE76FF00900A0E66FF0FE +:103F60000A009DE66FF00B009AE66FF00D0097E6F1 +:103F70006FF00E0094E66FF00F0091E640420F00E4 +:103F800080841E00EFF3098305494A6B22F0010289 +:103F90004A63683383F30988002383F311887047E9 +:103FA00000EF00E0302080F3118862B60C4B0D4A20 +:103FB000D96821F4E0610904090C0A43DA60D3F8F6 +:103FC000FC20094942F08072C3F8FC200A6842F0E4 +:103FD00001020A602022DA7783F82200704700BFCE +:103FE00000ED00E00003FA05001000E010B53023FA +:103FF00083F311880E4B5B6813F4006314D0F1EE69 +:10400000103AEFF30984683C4FF08073E361094B89 +:10401000DB6B236684F3098800F078FB10B1064B54 +:10402000A36110BD054BFBE783F31188F9E700BFDF +:1040300000ED00E000EF00E043060008460600083F +:10404000026843681143016003B1184770470000DC +:10405000024A136843F0C003136070470038014000 +:1040600013B50E4C204600F0B7FA04F114000C49C9 +:10407000009400234FF4807200F074F9094B0A4950 +:1040800000944FF4807204F1380000F0EDF9074A13 +:10409000074BC4E9172302B010BD00BF3C4F0020FE +:1040A000A84F002051400008A850002000380140CF +:1040B000007A030A30B5037C234C002918BF0C4654 +:1040C000012B0FD1214B98420CD1214B1A6E42F497 +:1040D00080421A66D3F8802042F48042C3F88020E0 +:1040E000D3F880302268036EC16D846603EB5203FF +:1040F000B3FBF2F36268150442BF23F0070503F037 +:10410000070343EA4503CB60A36843F040034B60D9 +:10411000E36843F001038B6042F4967343F00103BC +:104120000B604FF0FF330B62510505D512F01022E2 +:1041300005D0B2F1805F04D080F8643030BD7F23B9 +:10414000FAE73F23F8E700BF685600083C4F00201D +:10415000001002402DE9F047C66D3768F4693462FB +:104160002107054619D014F0080118BF4FF48071DB +:10417000E20748BF41F02001A30748BF41F04001DA +:10418000600748BF41F08001302383F31188281D68 +:10419000FFF756FF002383F31188E2050AD5302389 +:1041A00083F311884FF48061281DFFF749FF002336 +:1041B00083F311884FF030094FF0000A14F0200803 +:1041C00038D13B0616D54FF0300905F1380A2006E4 +:1041D00010D589F31188504600F07AF9002836DAB4 +:1041E0000821281DFFF72CFF27F0800333600023F0 +:1041F00083F31188790614D5620612D5302383F330 +:104200001188D5E913239A4208D12B6C33B11021C0 +:10421000281D27F04007FFF713FF3760002383F3C3 +:104220001188E30618D5AA6E1369ABB1BDE8F04753 +:104230005069184789F31188736A95F86410284605 +:10424000194000F0E3F98AF31188F469B6E7B06227 +:1042500088F31188F469BAE7BDE8F0874FF0E023EE +:10426000002258684FF0FF31930003F1604303F5DB +:10427000614301329042C3F88010C3F88011F3D239 +:104280007047000000F1604303F561430901C9B2C2 +:1042900083F80013012200F01F039A4043099B009A +:1042A00003F1604303F56143C3F880211A6070474E +:1042B000F8B5154682680669AA420B46816938BF7F +:1042C0008568761AB54204460BD218462A46FDF791 +:1042D000B5FBA3692B44A361A3685B1BA3602846BD +:1042E000F8BD0CD918463246FDF7A8FBAF1BE168B4 +:1042F0003A463044FDF7A2FBE3683B44EBE718463F +:104300002A46FDF79BFBE368E5E7000083689342DC +:10431000F7B51546044638BF8568D0E90460361AFB +:10432000B5420BD22A46FDF789FB63692B446361D2 +:10433000A36828465B1BA36003B0F0BD0DD93246CD +:104340000191FDF77BFB0199E068AF1B3A463144D0 +:10435000FDF774FBE3683B44E9E72A46FDF76EFB93 +:10436000E368E4E710B50A440024C361029B84605B +:10437000C0E90000C0E90511C1600261036210BD1F +:1043800008B5D0E90532934201D1826882B98268CA +:10439000013282605A1C42611970D0E904329A429B +:1043A00024BFC3684361002100F078FA002008BDF3 +:1043B0004FF0FF30FBE7000070B5302304460E4697 +:1043C00083F31188A568A5B1A368A269013BA36026 +:1043D000531CA36115782269934224BFE368A3614B +:1043E000E3690BB120469847002383F311882846E0 +:1043F00007E03146204600F041FA0028E2DA85F372 +:10440000118870BD2DE9F74F04460E4617469846B1 +:10441000D0F81C904FF0300A8AF311884FF0000B4F +:10442000154665B12A4631462046FFF741FF03464F +:1044300060B94146204600F021FA0028F1D000235F +:1044400083F31188781B03B0BDE8F08FB9F1000F3A +:1044500003D001902046C847019B8BF31188ED1AC9 +:104460001E448AF31188DCE7C0E90511C160C3610D +:104470001144009B8260C0E9000001610362704743 +:10448000F8B504460D461646302383F31188A76815 +:10449000A7B1A368013BA36063695A1C62611D70E8 +:1044A000D4E904329A4224BFE3686361E3690BB143 +:1044B00020469847002080F3118807E031462046C7 +:1044C00000F0DCF90028E2DA87F31188F8BD00007B +:1044D000D0E905239A4210B501D182687AB9826881 +:1044E000013282605A1C82611C7803699A4224BF9F +:1044F000C3688361002100F0D1F9204610BD4FF060 +:10450000FF30FBE72DE9F74F04460E461746984665 +:10451000D0F81C904FF0300A8AF311884FF0000B4E +:10452000154665B12A4631462046FFF7EFFE0346A1 +:1045300060B94146204600F0A1F90028F1D00023DF +:1045400083F31188781B03B0BDE8F08FB9F1000F39 +:1045500003D001902046C847019B8BF31188ED1AC8 +:104560001E448AF31188DCE7026843681143016046 +:1045700003B11847704700001430FFF743BF000035 +:104580004FF0FF331430FFF73DBF00003830FFF726 +:10459000B9BF00004FF0FF333830FFF7B3BF000062 +:1045A0001430FFF709BF00004FF0FF311430FFF760 +:1045B00003BF00003830FFF763BF00004FF0FF3249 +:1045C0003830FFF75DBF0000012914BF6FF0130002 +:1045D00000207047FFF744BD044B03600023C0E98F +:1045E0000233436001230374704700BF8056000804 +:1045F00010B53023044683F31188FFF75BFD0223D7 +:104600002374002080F3118810BD000038B5C36901 +:1046100004460D461BB904210844FFF7A5FF2946AF +:1046200004F11400FFF7ACFE002806DA201D4FF459 +:104630000061BDE83840FFF797BF38BD0023037520 +:10464000826803691B6899689142FBD25A680360CB +:1046500042601060586070470023037582680369E8 +:104660001B6899689142FBD85A68036042601060E9 +:104670005860704708B50846302383F311880B7DD6 +:10468000032B05D0042B0DD02BB983F3118808BD63 +:104690008B6900221A604FF0FF338361FFF7CEFF72 +:1046A0000023F2E7D1E9003213605A60F3E700001B +:1046B000FFF7C4BF054BD9680875186802681A600F +:1046C000536001220275D860FBF7A6BFA8510020F5 +:1046D00030B50C4BDD684B1C87B004460FD02B4621 +:1046E000094A684600F06CF92046FFF7E3FF009B9B +:1046F00013B1684600F06EF9A86907B030BDFFF746 +:10470000D9FFF9E7A851002075460008044B1A6844 +:10471000DB6890689B68984294BF00200120704736 +:10472000A8510020084B10B51C68D86822681A6090 +:10473000536001222275DC60FFF78EFF01462046A0 +:10474000BDE81040FBF768BFA8510020044B1A6871 +:10475000DB6892689B689A4201D9FFF7E3BF704714 +:10476000A851002038B5074C074908480123002507 +:104770002370656000F01CFC0223237085F3118810 +:1047800038BD00BF10540020AC560008A8510020CE +:1047900008B572B6044B186500F0D2FA00F08AFB37 +:1047A000024B03221A70FEE7A8510020105400208B +:1047B00000F046B9EFF3118020B9EFF30583302202 +:1047C00082F311887047000010B530B9EFF305840B +:1047D000C4F3080414B180F3118810BDFFF7B6FFCD +:1047E00084F31188F9E700008B60022308618B8253 +:1047F000084670478368A3F1840243F8142C0269C9 +:1048000043F8442C426943F8402C094A43F8242CCD +:10481000C26843F8182C022203F80C2C002203F87B +:104820000B2C044A43F8102CA3F12000704700BF62 +:1048300031060008A851002008B5FFF7DBFFBDE8EE +:104840000840FFF735BF0000024BDB6898610F207E +:10485000FFF730BFA8510020302383F31188FFF702 +:10486000F3BF000008B50146302383F31188082008 +:10487000FFF72EFF002383F3118808BD064BDB688A +:1048800039B1426818605A60136043600420FFF732 +:104890001FBF4FF0FF307047A851002003689842B7 +:1048A00006D01A680260506099611846FFF700BF91 +:1048B0007047000010B503689C68A2420CD85C6881 +:1048C0008A600B604C602160596099688A1A9A600E +:1048D0004FF0FF33836010BD1B68121BECE7000034 +:1048E0000A2938BF0A2170B504460D460A26601908 +:1048F00000F058FB00F044FB041BA54203D8751CD4 +:104900002E460446F3E70A2E04D9BDE87040012084 +:1049100000F08EBB70BD0000F8B5144B0D46D96198 +:1049200003F1100141600A2A1969826038BF0A2226 +:10493000016048601861A818144600F025FB0A279A +:1049400000F01EFB431BA342064606D37C1C28191D +:1049500000F028FB27463546F2E70A2F04D9BDE8C8 +:10496000F840012000F064BBF8BD00BFA851002052 +:10497000F8B506460D4600F003FB0F4A134653F800 +:10498000107F9F4206D12A4601463046BDE8F840D6 +:10499000FFF7C2BFD169BB68441A2C1928BF2C4647 +:1049A000A34202D92946FFF79BFF2246314603481E +:1049B000BDE8F840FFF77EBFA8510020B8510020A5 +:1049C00010B4C0E9032300235DF8044B4361FFF7F3 +:1049D000CFBF000010B5194C236998420DD0D0E923 +:1049E0000032816813605A609A680A449A60002312 +:1049F00003604FF0FF33A36110BD2346026843F804 +:104A0000102F53600022026022699A4203D1BDE850 +:104A1000104000F0C1BA936881680B44936000F0C5 +:104A2000AFFA2269E1699268441AA242E4D91144BA +:104A3000BDE81040091AFFF753BF00BFA85100207E +:104A40002DE9F047DFF8BC8008F110072C4ED8F8AC +:104A5000105000F095FAD8F81C40AA68031B9A423F +:104A60003ED81444D5E900324FF00009C8F81C4084 +:104A700013605A60C5F80090D8F81030B34201D1E5 +:104A800000F08AFA89F31188D5E90331284698475E +:104A9000302383F311886B69002BD8D000F070FAB3 +:104AA0006A69A0EB04094A4582460DD2022000F053 +:104AB000BFFA0022D8F81030B34208D15146284638 +:104AC000BDE8F047FFF728BF121A2244F2E712EBC5 +:104AD000090938BF4A4629463846FFF7EBFEB5E7D5 +:104AE000D8F81030B34208D01444211AC8F81C007A +:104AF000A960BDE8F047FFF7F3BEBDE8F08700BF4F +:104B0000B8510020A851002000207047FEE70000A7 +:104B1000704700004FF0FF3070470000BFF34F8F29 +:104B2000024A1369DB03FCD4704700BF0020024037 +:104B300008B5094B1B7873B9FFF7F0FF074B5A69AB +:104B4000002ABFBF064A9A6002F188329A601A684A +:104B500022F480621A6008BD285400200020024020 +:104B60002301674508B50B4B1B7893B9FFF7D6FFB8 +:104B7000094B5A6942F000425A611A6842F4805265 +:104B80001A601A6822F480521A601A6842F480622D +:104B90001A6008BD28540020002002407F289ABFD8 +:104BA00000F58030C0020020704700004FF4006024 +:104BB00070470000802070477F2808B50BD8FFF7AA +:104BC000EDFF00F500630268013204D10430834236 +:104BD000F9D1012008BD0020FCE700007F2810B5B6 +:104BE00004461FD8FFF79AFFFFF7A2FF0E4BF322F0 +:104BF0001A6102225A615A6942EAC0025A615A692C +:104C000042F480325A61FFF789FF4FF40061FFF7E9 +:104C1000C5FF00F04BF9FFF7A5FF2046BDE81040A7 +:104C2000FFF7CABF002010BD002002402DE9F84365 +:104C300040EA020313F00703144606D0304B40F25B +:104C400031321A600020BDE8F88385182D4A95425C +:104C50000CD92B4A40F236311160F3E7031D1B6873 +:104C60004A68934208D1083C08300831072C14D90F +:104C700002680B689A42F1D0FFF75AFFFFF74EFF28 +:104C8000214E08314FF001084FF00009012CA1F12D +:104C9000080706D8FFF766FF01E0002CECD10120E1 +:104CA000D1E7C6F81480054651F8083C45F8043BA6 +:104CB00051F8043C4360FFF731FF336943F00103CF +:104CC0003361C6F81490026851F8083C9A420CD03F +:104CD0000B4B40F25E321A600C4B18600C4B1C60A0 +:104CE0000C4B1F60FFF73EFFACE72D6851F8043C0A +:104CF0009D4201F10801EBD1083C0830C6E700BF36 +:104D00002454002000000408002002401854002011 +:104D1000205400201C540020084908B50B7828B105 +:104D20001BB9FFF705FF01230B7008BD002BFCD05A +:104D3000BDE808400870FFF715BF00BF28540020E9 +:104D400008B54FF4C0314FF0005000F0B1F8BDE8A5 +:104D500008404FF480414FF0805000F0A9B80000A7 +:104D6000084600F0F3BB000070B582B0FFF722FDEB +:104D70000E4E054600F004F93268904237BF0C4AE7 +:104D80000B49516814682EBFD1E9004101315160CF +:104D90000419034641F10001284601913360FFF7F1 +:104DA00013FD0199204602B070BD00BF2C540020B5 +:104DB0003054002070B582B0FFF7FCFC104E054661 +:104DC00000F0DEF83268904237BF0E4A0D49516854 +:104DD00014682EBFD1E9004101315160041941F13D +:104DE00000010346284601913360FFF7EDFC01996D +:104DF0004FF47A7200232046FBF7FAF902B070BD37 +:104E00002C540020305400200244D2B2904200D1F1 +:104E10007047431C800000F1804000F5145000688A +:104E200041F8040BD8B2F1E7124B10B5D3F890401B +:104E3000240409D4D3F89040C3F89040D3F89040AC +:104E400044F40044C3F890400B4C2368024443F4FC +:104E500080732360D2B2904200D110BD431C800009 +:104E600000F1804000F5145051F8044B0460D8B2B2 +:104E7000F1E700BF001002400070004007B50122BA +:104E800001A90020FFF7C0FF019803B05DF804FB03 +:104E900013B50446FFF7F2FFA04205D0012201A995 +:104EA00000200194FFF7C0FF02B010BD7047000062 +:104EB0007047000070470000074B45F255521A60DA +:104EC00002225A6040F6FF729A604CF6CC421A6099 +:104ED000024B01221A707047003000403C54002001 +:104EE000034B1B781BB1034B4AF6AA221A6070478A +:104EF0003C54002000300040054B1A6832B902F1E2 +:104F0000804202F50432D2F894201A60704700BF44 +:104F100038540020024B4FF40002C3F8942070472D +:104F20000010024008B5FFF7E7FF024B1868C0F316 +:104F3000407008BD3854002070470000FEE70000B4 +:104F40000A4B0B480B4A90420BD30B4BDA1C121A3C +:104F5000C11E22F003028B4238BF00220021FCF761 +:104F60007FBD53F8041B40F8041BECE71C580008F5 +:104F7000C0540020C0540020C054002000F0C2B82B +:104F80004FF08043586A70474FF0804300225863C7 +:104F90001A610222DA6070474FF080430022DA6023 +:104FA000704700004FF0804358637047FEE70000F1 +:104FB00070B51B4B01630025044686B058608562BE +:104FC0000E46FEF7EFFF04F11003C4E904334FF07F +:104FD000FF33C4E90635C4E90044A560E562FFF784 +:104FE000CFFF2B460246C4E9082304F134010D4AE1 +:104FF000256580232046FFF7F7FB0123E0600A4A7E +:105000000375009272680192B268CDE90223074BE2 +:105010006846CDE90435FFF70FFC06B070BD00BF50 +:1050200010540020B8560008BD560008AD4F0008C7 +:10503000024AD36A1843D062704700BFA8510020CB +:105040004B6843608B688360CB68C3600B694361C6 +:105050004B6903628B6943620B6803607047000011 +:1050600008B5204BDA6A42F07F02DA62DA6A22F08F +:105070007F02DA62DA6ADA6C42F07F02DA64DA6EB0 +:1050800042F07F02DA66184ADB6E11464FF090401C +:10509000FFF7D6FF02F11C0100F58060FFF7D0FF9B +:1050A00002F1380100F58060FFF7CAFF02F15401F8 +:1050B00000F58060FFF7C4FF02F1700100F5806029 +:1050C000FFF7BEFF02F18C0100F58060FFF7B8FF2B +:1050D00002F1A80100F58060FFF7B2FFBDE80840CB +:1050E00000F050B800100240C456000808B500F0A7 +:1050F000FBF9FFF737FBBDE80840FFF7FDBE0000F6 +:10510000704700000F4B9A6D42F001029A659A6F4A +:1051100042F001029A670C4A9B6F936843F00103C7 +:1051200093604FF08043A7229A624FF0FF32DA6219 +:1051300000229A615A63DA605A6001225A611A6049 +:10514000704700BF00100240002004E04FF0804292 +:1051500008B51169D3680B40D9B2C9439B071161E7 +:1051600007D5302383F31188FFF722FB002383F355 +:10517000118808BD08B5FFF771F8BDE8084000F0D8 +:105180008BB900004E4B4FF0FF319A6A99629A6AD0 +:1051900000229A62986AD86A60F07F00D862D86A62 +:1051A00000F07F00D862D86A186B1963186B1A6315 +:1051B000186B986B9963986B9A63986BD86BD963EB +:1051C000D86BDA63D86B186C1964196C1A64196C93 +:1051D000196E41F001011966D3F8801021F0010128 +:1051E000C3F88010D3F88010996D41F08051996513 +:1051F000996F21F080519967996F32494FF40040BF +:105200008860CA600A624A628A62CA620A634A6342 +:105210008A63CA630A644A648A64CA640A654A651E +:105220004A604FF48072C1F880204FF440720A60E7 +:105230004A6912F48062FBD1D3F8901011F4407FD8 +:105240001EBF4FF48031C3F89010C3F89020D3F8FC +:10525000982042F00102C3F89820D3F898209207D2 +:10526000FBD51A6842F480321A601A689003FCD5A4 +:10527000D3F8902022F00322C3F89020124ADA607B +:105280001A6842F080721A601A689101FCD50F49C1 +:105290000F4800229A60C3F888100E49C3F89C207A +:1052A000016002684A401207FBD19A6842F003028B +:1052B0009A609A6802F00C020C2AFAD1704700BF7B +:1052C0000010024000700040032A610155010050A7 +:1052D0000020024004070400074A08B5536903F0A0 +:1052E0000103536123B1054A13680BB15068984715 +:1052F000BDE80840FEF77ABE00040140405400209B +:10530000074A08B5536903F00203536123B1054A04 +:1053100093680BB1D0689847BDE80840FEF766BEB9 +:105320000004014040540020074A08B5536903F0C7 +:105330000403536123B1054A13690BB150699847BF +:10534000BDE80840FEF752BE000401404054002072 +:10535000074A08B5536903F00803536123B1054AAE +:1053600093690BB1D0699847BDE80840FEF73EBE8F +:105370000004014040540020074A08B5536903F077 +:105380001003536123B1054A136A0BB1506A984761 +:10539000BDE80840FEF72ABE00040140405400204A +:1053A000164B10B55C6904F478725A61A30604D5F3 +:1053B000134A936A0BB1D06A9847600604D5104A25 +:1053C000136B0BB1506B9847210604D50C4A936BB5 +:1053D0000BB1D06B9847E20504D5094A136C0BB1A9 +:1053E000506C9847A30504D5054A936C0BB1D06C5B +:1053F0009847BDE81040FEF7F9BD00BF000401402A +:1054000040540020194B10B55C6904F47C425A6189 +:10541000620504D5164A136D0BB1506D98472305EC +:1054200004D5134A936D0BB1D06D9847E00404D5B1 +:105430000F4A136E0BB1506E9847A10404D50C4A65 +:10544000936E0BB1D06E9847620404D5084A136F6F +:105450000BB1506F9847230404D5054A936F0BB1E5 +:10546000D06F9847BDE81040FEF7C0BD0004014072 +:105470004054002008B50348FEF76CFEBDE8084024 +:10548000FEF7B4BD3C4F002008B5FFF75FFEBDE856 +:105490000840FEF7ABBD0000062108B50846FEF740 +:1054A000F1FE06210720FEF7EDFE06210820FEF79B +:1054B000E9FE06210920FEF7E5FE06210A20FEF797 +:1054C000E1FE06211720FEF7DDFE06212820FEF76B +:1054D000D9FE07211C20FEF7D5FEBDE808400C21AF +:1054E0002520FEF7CFBE000008B5FFF743FE00F011 +:1054F00009F8FFF76FF8FFF703FEBDE80840FFF774 +:105500003DBD00000023054A19460133102BC2E9B6 +:10551000001102F10802F8D1704700BF405400208A +:105520000B460146184600F003B8000000F00EB824 +:1055300010B5054C13462CB10A4601460220AFF3C4 +:10554000008010BD2046FCE700000000024B014631 +:105550001868FFF705BC00BF2823002010B50139EB +:105560000244904201D1002005E0037811F8014F78 +:10557000A34201D0181B10BD0130F2E72DE9F04124 +:10558000A3B1C91A17780144044603F1FF3C8C42C9 +:10559000204601D9002009E00578BD4204F101044C +:1055A000F5D10CEB0405D618A54201D1BDE8F08178 +:1055B00015F8018D16F801EDF045F5D0E7E700008C +:1055C000034611F8012B03F8012B002AF9D170478B +:1055D0006F72672E6172647570696C6F742E6D5294 +:1055E0006F2D4D31303039350000000053544D33AC +:1055F0003247343F3F00000040A2E4F16468910666 +:105600000041A3E5F2656992070000004261642051 +:1056100043414E496661636520696E6465782E007A +:105620000000000000000000C9270008D122000887 +:10563000852E0008C9220008792300085D2500088E +:1056400041230008092300080D230008E522000873 +:10565000CD2200081D250008F1220008BD2F0008FA +:10566000FD220008F1240008009600000000000060 +:10567000000000000000000000000000000000002A +:10568000000000009545000881450008BD45000860 +:10569000A9450008B5450008A14500088D4500084A +:1056A00079450008C945000863300000A856000885 +:1056B00000520020105400206D61696E0069646C16 +:1056C000650000000001A82A00000000AAAABEAAE6 +:1056D00000001424EFFF0000000000007097090094 +:1056E0000000000000000000AAAAAAAA0000000012 +:1056F000FFFF0000000000000000000000000000AC +:1057000000000000AAAAAAAA00000000FFFF0000F3 +:105710000000000000000000000000000000000089 +:10572000AAAAAAAA00000000FFFF000000000000D3 +:10573000000000000000000000000000AAAAAAAAC1 +:1057400000000000FFFF000000000000000000005B +:105750000000000000000000AAAAAAAA00000000A1 +:10576000FFFF00000000000000000000000000003B +:1057700000000000AAAAAAAA00000000FFFF000083 +:10578000000000000000000098AAFF7F0100000058 +:105790001104000000000000008803000000000069 +:1057A000FE2A0100D2040000FF0000003C4F002050 +:1057B00000000000EC5500082C2300200000000031 +:1057C00000000000000000000000000000000000D9 +:1057D00000000000000000000000000000000000C9 +:1057E00000000000000000000000000000000000B9 +:1057F00000000000000000000000000000000000A9 +:105800000000000000000000000000000000000098 +:0C5810000000000000000000000000008C :00000001FF diff --git a/Tools/bootloaders/mRoCANPWM-M10126_bl.bin b/Tools/bootloaders/mRoCANPWM-M10126_bl.bin index b72acfa80dde18..96fd236045c79e 100755 Binary files a/Tools/bootloaders/mRoCANPWM-M10126_bl.bin and b/Tools/bootloaders/mRoCANPWM-M10126_bl.bin differ diff --git a/Tools/bootloaders/mRoCZeroOEMH7-bdshot_bl.bin b/Tools/bootloaders/mRoCZeroOEMH7-bdshot_bl.bin new file mode 100755 index 00000000000000..f00424fe91adce Binary files /dev/null and b/Tools/bootloaders/mRoCZeroOEMH7-bdshot_bl.bin differ diff --git a/Tools/bootloaders/mRoCZeroOEMH7-bdshot_bl.hex b/Tools/bootloaders/mRoCZeroOEMH7-bdshot_bl.hex new file mode 100644 index 00000000000000..adc596e29c74bf --- /dev/null +++ b/Tools/bootloaders/mRoCZeroOEMH7-bdshot_bl.hex @@ -0,0 +1,1007 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008F9340008D4 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008E13800080D39000857 +:10006000393900086539000891390008E3020008B1 +:10007000E3020008E3020008E3020008E3020008CC +:10008000E3020008E3020008E3020008E3020008BC +:10009000E3020008E3020008E3020008BD3900089B +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E000213A0008E3020008E3020008E3020008E6 +:1000F000E3020008E3020008E3020008E30200084C +:10010000E3020008E3020008953A0008E302000851 +:10011000E3020008E3020008E3020008E30200082B +:10012000E3020008E3020008E3020008E30200081B +:10013000E3020008E3020008E3020008E30200080B +:10014000E3020008E3020008E3020008E3020008FB +:10015000E3020008E3020008E3020008E3020008EB +:10016000E3020008E3020008E3020008E3020008DB +:10017000E3020008792E0008E3020008E302000809 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008652E0008E3020008E3020008BD +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F000F876 +:1003500003F024F84FF055301F491B4A91423CBF2F +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F018F803F082F8CA +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F000B800060020002200206C +:1003D0000000000808ED00E00000002000060020FA +:1003E000703E0008002200205C22002060220020D5 +:1003F00034430020E0020008E0020008E0020008A8 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F00AFBFEE701F0F2 +:1004300073FA00DFFEE7000038B500F0CDFB01F0F5 +:1004400047FF054601F07AFF0446D0B90F4B9D42A5 +:1004500019D001339D4241F2883512BF0446002570 +:100460000124002001F03EFF0CB100F077F800F00D +:100470005DFD00F007FC284600F010F900F06EF872 +:10048000F9E70025EDE70546EBE700BF010007B0FF +:1004900008B500F0C9FBA0F120035842584108BD3F +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000D9FB03B05DF804FB38B5302383F3118812 +:1004C000174803680BB101F087FB0023154A4FF46E +:1004D0007A71134801F076FB002383F31188124CE4 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F086FC322363602B78032B07D16368ED +:100510002BB9022000F07CFC4FF47A73636038BD85 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F057BC022000F044BC024B002205 +:100550005A6070477822002080230020F8B5494B6C +:10056000494A1C461968013100F08A8004339342DD +:10057000F8D16268454B9A4240F28280444B9B68B6 +:1005800003F1006303F500339A4279D2002000F0B2 +:1005900093FB0220FFF7CCFF3E4B0021D3F8E8206D +:1005A000C3F8E810D3F81021C3F81011D3F81021C4 +:1005B000D3F8EC20C3F8EC10D3F81421C3F81411CD +:1005C000D3F81421D3F8F020C3F8F010D3F8182191 +:1005D000C3F81811D3F81821D3F8802042F0007224 +:1005E000C3F88020D3F8802022F00072C3F8802066 +:1005F000D3F8803072B64FF0E023C3F8084DD4E949 +:100600000004BFF34F8FBFF36F8F234AC2F88410EB +:10061000BFF34F8F536923F480335361BFF34F8F80 +:10062000D2F8803043F6E076C3F3C905C3F34E3306 +:100630005B0103EA060C29464CEA81770139C2F8CE +:100640007472F9D2203B13F1200FF2D1BFF34F8F18 +:10065000BFF36F8FBFF34F8FBFF36F8F536923F4D7 +:10066000003353610023C2F85032BFF34F8FBFF302 +:100670006F8F302383F31188854680F308882047E5 +:10068000F8BD00BF0000020820000208FFFF0108BB +:10069000002200200044025800ED00E02DE9F04F58 +:1006A00093B0B44B2022FF2100900AA89D6800F06F +:1006B000E7FBB14A1378A3B90121B0481170036078 +:1006C000302383F3118803680BB101F085FA00230E +:1006D000AB4A4FF47A71A94801F074FA002383F30E +:1006E0001188009B13B1A74B009A1A60A64A137891 +:1006F000032B03D000231370A24A53604FF0000A6B +:10070000009CD3465646D146012000F073FB24B12D +:100710009C4B1B68002B00F02682002000F084FA1E +:100720000390039B002BF2DB012000F053FB039BA3 +:10073000213B1F2BE8D801A252F823F0BD07000887 +:10074000E5070008790800080907000809070008FC +:10075000090700080B090008DB0A0008F509000872 +:10076000570A00087F0A0008A50A000809070008C0 +:10077000B70A000809070008290B00085D080008EF +:10078000090700086D0B0008C90700085D0800088C +:1007900009070008570A00080907000809070008A8 +:1007A00009070008090700080907000809070008E9 +:1007B0000907000809070008790800080220FFF768 +:1007C00067FE002840F0F981009B022105A8BAF1DC +:1007D000000F08BF1C4641F21233ADF8143000F090 +:1007E00041FA91E74FF47A7000F01EFA071EEBDB36 +:1007F0000220FFF74DFE0028E6D0013F052F00F252 +:10080000DE81DFE807F0030A0D101336052304210B +:1008100005A8059300F026FA17E004215548F9E7EA +:1008200004215A48F6E704215948F3E74FF01C0821 +:10083000404608F1040800F041FA0421059005A89B +:1008400000F010FAB8F12C0FF2D101204FF000099E +:1008500000FA07F747EA0B0B5FFA8BFB00F05CFB33 +:1008600026B10BF00B030B2B08BF0024FFF718FE7B +:100870004AE704214748CDE7002EA5D00BF00B0333 +:100880000B2BA1D10220FFF703FE074600289BD0C7 +:100890000120002600F010FA0220FFF749FE1FFA9F +:1008A00086F8404600F018FA0446B0B10399404675 +:1008B0000136A1F140025142514100F01DFA0028D9 +:1008C000EDD1BA46044641F21213022105A83E4674 +:1008D000ADF8143000F0C6F916E725460120FFF701 +:1008E00027FE244B9B68AB4207D9284600F0E6F967 +:1008F000013040F067810435F3E70025224BBA460A +:100900003E461D701F4B5D60A8E7002E3FF45CAFB4 +:100910000BF00B030B2B7FF457AF0220FFF708FE01 +:10092000322000F081F9B0F10008FFF64DAF18F069 +:1009300003077FF449AF0F4A08EB0503926893421F +:100940003FF642AFB8F5807F3FF73EAF124BB84558 +:10095000019323DD4FF47A7000F066F90390039A57 +:10096000002AFFF631AF039A0137019B03F8012BF0 +:10097000EDE700BF002200207C2300206022002041 +:10098000B9040008802300207822002004220020DF +:10099000082200200C2200207C220020C820FFF723 +:1009A00077FD074600283FF40FAF1F2D11D8C5F182 +:1009B00020020AAB25F0030084494245184428BFB1 +:1009C0004246019200F036FA019AFF217F4800F07A +:1009D00057FA4FEAA803C8F387027C4928460193D7 +:1009E00000F056FA064600283FF46DAF019B05EB78 +:1009F000830533E70220FFF74BFD00283FF4E4AE08 +:100A000000F098F900283FF4DFAE0027B846704B9D +:100A10009B68BB4218D91F2F11D80A9B01330ED0F7 +:100A200027F0030312AA134453F8203C05934046D1 +:100A3000042205A9043700F0A5FA8046E7E7384606 +:100A400000F03CF90590F2E7CDF81480042105A8E8 +:100A500000F008F902E70023642104A8049300F0E1 +:100A6000F7F800287FF4B0AE0220FFF711FD002850 +:100A70003FF4AAAE049800F053F90590E6E700238E +:100A8000642104A8049300F0E3F800287FF49CAEEE +:100A90000220FFF7FDFC00283FF496AE049800F01A +:100AA00041F9EAE70220FFF7F3FC00283FF48CAE9F +:100AB00000F050F9E1E70220FFF7EAFC00283FF4DC +:100AC00083AE05A9142000F04BF9074604210490D9 +:100AD00004A800F0C7F83946B9E7322000F0A4F8BE +:100AE000071EFFF671AEBB077FF46EAE384A07EB08 +:100AF0000903926893423FF667AE0220FFF7C8FCF5 +:100B000000283FF461AE27F003074F44B9453FF496 +:100B1000A5AE484609F1040900F0D0F8042105907B +:100B200005A800F09FF8F1E74FF47A70FFF7B0FCEA +:100B300000283FF449AE00F0FDF8002844D00A9B9D +:100B400001330BD008220AA9002000F0A1F90028E7 +:100B50003AD02022FF210AA800F092F9FFF7A0FC6A +:100B60001C4800F073FF13B0BDE8F08F002E3FF477 +:100B70002BAE0BF00B030B2B7FF426AE002364216E +:100B800005A8059300F064F8074600287FF41CAE22 +:100B90000220FFF77DFC804600283FF415AEFFF7EA +:100BA0007FFC41F2883000F051FF059800F0E8F931 +:100BB00046463C4600F0B0F9A6E506464EE64FF044 +:100BC000000901E6BA467EE637467CE67C22002034 +:100BD00000220020A0860100704700000F4B70B576 +:100BE0001B780C460133DBB2012B11D80C4D4FF4AE +:100BF0007A732968A2FB033222460E6A0146284610 +:100C0000B047844204D1074B002201201A7070BD06 +:100C10004FF4FA7000F01AFF0020F8E710220020CD +:100C200028260020B4230020002307B50246012116 +:100C30000DF107008DF80730FFF7D0FF20B19DF8C8 +:100C4000070003B05DF804FB4FF0FF30F9E7000048 +:100C50000A46042108B5FFF7C1FF80F00100C0B2C9 +:100C6000404208BD30B4054C0A4601462368204680 +:100C7000DD69034BAC4630BC604700BF282600202E +:100C8000A086010070B50A4E00240A4D01F0F8F963 +:100C9000308028683388834208D901F0EDF92B6849 +:100CA00004440133B4F5003F2B60F2D370BD00BFA4 +:100CB000B62300208823002001F0C0BA00F10060B4 +:100CC00000F500300068704700F10060920000F508 +:100CD000003001F037BA0000054B1A68054B1B883D +:100CE0009B1A834202D9104401F0C6B90020704714 +:100CF00088230020B623002038B50446074D29B1CB +:100D000028682044BDE8384001F0CEB92868204466 +:100D100001F0B8F90028F3D038BD00BF88230020C7 +:100D20000020704700F1FF5000F58F10D0F8000848 +:100D300070470000064991F8243033B1002308229F +:100D4000086A81F82430FFF7BFBF0120704700BF59 +:100D50008C230020014B1868704700BF0010005C16 +:100D6000194B01380322084470B51D68174BC5F3B1 +:100D70000B042D0C1E88A6420BD15C680A46013C70 +:100D8000824213460FD214F9016F4EB102F8016B83 +:100D9000F6E7013A03F10803ECD181420B4602D297 +:100DA0002C2203F8012B0424094A1688AE4204D1F0 +:100DB000984284BF967803F8016B013C02F104026B +:100DC000F3D1581A70BD00BF0010005C142200203F +:100DD0008C3B0008022804D1054B4FF000629A6159 +:100DE00070470128FCD1024B4FF40032F7E700BFF7 +:100DF00000040258022804D1044B4FF400629A61A7 +:100E000070470128FCD1014B0222F8E70004025888 +:100E1000022805D1064A536983F400635361704781 +:100E20000128FCD1024A536983F00203F6E700BFB0 +:100E300000040258002310B5934203D0CC5CC45484 +:100E40000133F9E710BD0000013810B510F9013F7A +:100E50003BB191F900409C4203D11AB10131013AF2 +:100E6000F4E71AB191F90020981A10BD1046FCE77A +:100E700003460246D01A12F9011B0029FAD1704725 +:100E800002440346934202D003F8011BFAE770477D +:100E90002DE9F8431F4D14460746884695F824204F +:100EA00052BBDFF870909CB395F824302BB9202208 +:100EB000FF2148462F62FFF7E3FF95F824004146E3 +:100EC000C0F1080205EB8000A24228BF2246D6B23C +:100ED0009200FFF7AFFF95F82430A41B17441E447F +:100EE0009044E4B2F6B2082E85F82460DBD1FFF717 +:100EF00021FF0028D7D108E02B6A03EB820383424D +:100F0000CFD0FFF717FF0028CBD10020BDE8F88332 +:100F10000120FBE78C230020024B1A78024B1A7049 +:100F2000704700BFB42300201022002010B5104CE1 +:100F3000104800F0B9F821460E4800F0E1F82468A6 +:100F40000D48D4F89020D2F8043843F00203C2F8D8 +:100F5000043800F07BFD0949204600F0DFF9D4F8A1 +:100F60009020D2F8043823F00203C2F8043810BDF0 +:100F7000403C00082826002040420F00483C000862 +:100F80007047000030B50A44084D91420DD011F869 +:100F9000013B5840082340F30004013B2C4013F070 +:100FA000FF0384EA5000F6D1EFE730BD2083B8EDAF +:100FB000026843681143016003B11847704700009D +:100FC00013B5406B00F58054D4F8A4381A68117832 +:100FD000042914D1017C022911D119790123128924 +:100FE0008B4013420BD101A94C3002F08DF8D4F89C +:100FF000A4480246019B2179206800F0DFF902B085 +:1010000010BD0000143002F00FB800004FF0FF33A5 +:10101000143002F009B800004C3002F0E1B80000D2 +:101020004FF0FF334C3002F0DBB80000143001F019 +:10103000DDBF00004FF0FF31143001F0D7BF0000DA +:101040004C3002F0ADB800004FF0FF324C3002F0EF +:10105000A7B800000020704710B500F58054D4F800 +:10106000A4381A681178042917D1017C022914D1F7 +:101070005979012352898B4013420ED1143001F06B +:101080006FFF024648B1D4F8A4484FF44073617929 +:101090002068BDE8104000F07FB910BD406BFFF73D +:1010A000DBBF0000704700007FB5124B012504260E +:1010B000044603600023057400F18402436029465E +:1010C000C0E902330C4B0290143001934FF440738B +:1010D000009601F021FF094B04F69442294604F1E1 +:1010E0004C000294CDE900634FF4407301F0E8FF37 +:1010F00004B070BD9C3B00089D100008C10F0008A3 +:101100000A68302383F311880B790B3342F82300EC +:101110004B79133342F823008B7913B10B3342F828 +:10112000230000F58053C3F8A418022303740020A1 +:1011300080F311887047000038B5037F044613B16F +:1011400090F85430ABB90125201D0221FFF730FF84 +:1011500004F114006FF00101257700F09FFC04F109 +:101160004C0084F854506FF00101BDE8384000F0A5 +:1011700095BC38BD10B5012104460430FFF718FFB7 +:101180000023237784F8543010BD000038B504469E +:101190000025143001F0D8FE04F14C00257701F051 +:1011A000A7FF201D84F854500121FFF701FF2046BE +:1011B000BDE83840FFF750BF90F8803003F060037F +:1011C000202B06D190F881200023212A03D81F2A42 +:1011D00006D800207047222AFBD1C0E91D3303E066 +:1011E000034A426707228267C3670120704700BF36 +:1011F0002C22002037B500F58055D5F8A4381A68A0 +:10120000117804291AD1017C022917D119790123F7 +:1012100012898B40134211D100F14C04204602F098 +:1012200027F858B101A9204601F06EFFD5F8A4486F +:101230000246019B2179206800F0C0F803B030BD60 +:1012400001F10B03F0B550F8236085B004460D465C +:10125000FEB1302383F3118804EB8507301D08218C +:10126000FFF7A6FEFB6806F14C005B691B681BB12B +:10127000019001F057FF019803A901F045FF0246D4 +:1012800048B1039B2946204600F098F8002383F3D9 +:10129000118805B0F0BDFB685A691268002AF5D0C4 +:1012A0001B8A013B1340F1D104F18002EAE7000000 +:1012B000133138B550F82140ECB1302383F3118855 +:1012C00004F58053D3F8A4281368527903EB820302 +:1012D000DB689B695D6845B104216018FFF768FE13 +:1012E000294604F1140001F045FE2046FFF7B4FE44 +:1012F000002383F3118838BD7047000001F0FCB86B +:1013000001234022002110B5044600F8303BFFF7CE +:10131000B7FD0023C4E9013310BD000010B5302330 +:10132000044683F311882422416000210C30FFF72A +:10133000A7FD204601F002F902230020237080F36C +:10134000118810BD70B500EB8103054650690E464B +:101350001446DA6018B110220021FFF791FDA06950 +:1013600018B110220021FFF78BFD31462846BDE859 +:10137000704001F0E9B9000083682022002103F0E9 +:10138000011310B5044683601030FFF779FD204645 +:10139000BDE8104001F064BAF0B4012500EB81040F +:1013A00047898D40E4683D43A4694581236000235B +:1013B000A2606360F0BC01F081BA0000F0B40125C6 +:1013C00000EB810407898D40E4683D436469058131 +:1013D00023600023A2606360F0BC01F0F7BA000054 +:1013E00070B5022300250446242203702946C0F864 +:1013F00088500C3040F8045CFFF742FD204684F82A +:10140000705001F035F963681B6823B12946204606 +:10141000BDE87040184770BD0378052B10B5044631 +:101420000AD080F88C300523037043681B680BB129 +:10143000042198470023A36010BD0000017805290E +:1014400006D190F88C20436802701B6803B11847DE +:101450007047000070B590F87030044613B1002357 +:1014600080F8703004F18002204601F01DFA6368B4 +:101470009B68B3B994F8803013F0600535D0002133 +:10148000204601F00FFD0021204601F0FFFC6368BB +:101490001B6813B1062120469847062384F8703054 +:1014A00070BD204698470028E4D0B4F88630A26F7B +:1014B0009A4288BFA36794F98030A56F002B4FF044 +:1014C000300380F20381002D00F0F280092284F8BD +:1014D000702083F3118800212046D4E91D23FFF7F3 +:1014E0006DFF002383F31188DAE794F8812003F07D +:1014F0007F0343EA022340F20232934200F0C580A8 +:1015000021D8B3F5807F48D00DD8012B3FD0022BD6 +:1015100000F09380002BB2D104F1880262670222AE +:10152000A267E367C1E7B3F5817F00F09B80B3F565 +:10153000407FA4D194F88230012BA0D1B4F8883038 +:1015400043F0020332E0B3F5006F4DD017D8B3F586 +:10155000A06F31D0A3F5C063012B90D863682046FB +:1015600094F882205E6894F88310B4F88430B04711 +:10157000002884D0436863670368A3671AE0B3F563 +:10158000106F36D040F6024293427FF478AF5C4B46 +:1015900063670223A3670023C3E794F88230012B1B +:1015A0007FF46DAFB4F8883023F00203A4F88830DC +:1015B000C4E91D55E56778E7B4F88030B3F5A06F4E +:1015C0000ED194F88230204684F88A3001F0AEF8CB +:1015D00063681B6813B101212046984703232370D9 +:1015E0000023C4E91D339CE704F18B0363670123E7 +:1015F000C3E72378042B10D1302383F311882046CE +:10160000FFF7BAFE85F311880321636884F88B50D5 +:1016100021701B680BB12046984794F88230002B4C +:10162000DED084F88B300423237063681B68002BA2 +:10163000D6D0022120469847D2E794F8843020463D +:101640001D0603F00F010AD501F020F9012804D08E +:1016500002287FF414AF2B4B9AE72B4B98E701F04D +:1016600007F9F3E794F88230002B7FF408AF94F881 +:10167000843013F00F01B3D01A06204602D501F0D2 +:1016800029FCADE701F01AFCAAE794F88230002BA0 +:101690007FF4F5AE94F8843013F00F01A0D01B0650 +:1016A000204602D501F0FEFB9AE701F0EFFB97E739 +:1016B000142284F8702083F311882B462A46294689 +:1016C0002046FFF769FE85F31188E9E65DB1152232 +:1016D00084F8702083F3118800212046D4E91D236B +:1016E000FFF75AFEFDE60B2284F8702083F3118881 +:1016F0002B462A4629462046FFF760FEE3E700BF57 +:10170000CC3B0008C43B0008C83B000838B590F843 +:1017100070300446002B3ED0063BDAB20F2A34D894 +:101720000F2B32D8DFE803F0373131082232313164 +:101730003131313131313737856FB0F886309D42E4 +:1017400014D2C3681B8AB5FBF3F203FB12556DB9C3 +:10175000302383F311882B462A462946FFF72EFEB5 +:1017600085F311880A2384F870300EE0142384F87E +:101770007030302383F31188002320461A4619461F +:10178000FFF70AFE002383F3118838BDC36F03B14E +:1017900098470023E7E70021204601F083FB002162 +:1017A000204601F073FB63681B6813B106212046D5 +:1017B00098470623D7E7000010B590F8703004462C +:1017C000142B29D017D8062B05D001D81BB110BD7A +:1017D000093B022BFBD80021204601F063FB0021CE +:1017E000204601F053FB63681B6813B106212046B5 +:1017F0009847062319E0152BE9D10B2380F87030A8 +:10180000302383F3118800231A461946FFF7D6FDCB +:10181000002383F31188DAE7C3689B695B68002BB8 +:10182000D5D1C36F03B19847002384F87030CEE759 +:1018300000238268037503691B6899689142FBD293 +:101840005A680360426010605860704700238268E5 +:10185000037503691B6899689142FBD85A68036055 +:10186000426010605860704708B50846302383F323 +:1018700011880B7D032B05D0042B0DD02BB983F3DE +:10188000118808BD8B6900221A604FF0FF33836115 +:10189000FFF7CEFF0023F2E7D1E9003213605A6070 +:1018A000F3E70000FFF7C4BF054BD9680875186857 +:1018B000026853601A600122D8600275FEF7A2BD6B +:1018C000B82300200C4B30B5DD684B1C87B00446B4 +:1018D0000FD02B46094A684600F074F92046FFF7FE +:1018E000E3FF009B13B1684600F076F9A86907B0E2 +:1018F00030BDFFF7D9FFF9E7B823002069180008C9 +:10190000044B1A68DB6890689B68984294BF00207B +:1019100001207047B8230020084B10B51C68D86818 +:10192000226853601A600122DC602275FFF78EFF87 +:1019300001462046BDE81040FEF764BDB8230020F4 +:10194000044B1A68DB6892689B689A4201D9FFF7DA +:10195000E3BF7047B823002038B5074C01230025AA +:10196000064907482370656001F0C0FC022323701C +:1019700085F3118838BD00BF20260020D43B000825 +:10198000B823002000F05EB9EFF3118020B9EFF327 +:101990000583302282F311887047000010B530B9FA +:1019A000EFF30584C4F3080414B180F3118810BD6B +:1019B000FFF7C6FF84F31188F9E70000034A516876 +:1019C00053685B1A9842FBD8704700BF001000E0D4 +:1019D0008B600223086108468B8270478368A3F1FD +:1019E000840243F8142C026943F8442C426943F8FA +:1019F000402C094A43F8242CC268A3F1200043F884 +:101A0000182C022203F80C2C002203F80B2C034A9A +:101A100043F8102C704700BF1D040008B8230020B5 +:101A200008B5FFF7DBFFBDE80840FFF73BBF00004C +:101A3000024BDB6898610F20FFF736BFB823002008 +:101A4000302383F31188FFF7F3BF000008B5014688 +:101A5000302383F311880820FFF734FF002383F33A +:101A6000118808BD064BDB6839B1426818605A60BE +:101A7000136043600420FFF725BF4FF0FF3070472D +:101A8000B82300200368984206D01A6802605060AC +:101A900018469961FFF706BF7047000038B5044645 +:101AA0000D462068844200D138BD036823605C6025 +:101AB0008561FFF7F7FEF4E7036810B59C68A24262 +:101AC0000CD85C688A600B604C6021605960996832 +:101AD0008A1A9A604FF0FF33836010BD121B1B6897 +:101AE000ECE700000A2938BF0A2170B504460D460C +:101AF0000A26601901F0F2FB01F0DAFB041BA54293 +:101B000003D8751C04462E46F3E70A2E04D901209B +:101B1000BDE8704001F02ABC70BD0000F8B5144B60 +:101B20000D460A2A4FF00A07D96103F110018260BD +:101B300038BF0A2241601969144601604860186183 +:101B4000A81801F0BBFB01F0B3FB431B0646A34200 +:101B500006D37C1C28192746354601F0BFFBF2E767 +:101B60000A2F04D90120BDE8F84001F0FFBBF8BD01 +:101B7000B8230020F8B506460D4601F099FB0F4A40 +:101B8000134653F8107F9F4206D12A46014630463D +:101B9000BDE8F840FFF7C2BFD169BB68441A2C19F1 +:101BA00028BF2C46A34202D92946FFF79BFF2246B5 +:101BB00031460348BDE8F840FFF77EBFB823002058 +:101BC000C8230020C0E90323002310B45DF8044BB0 +:101BD0004361FFF7CFBF000010B5194C236998424D +:101BE0000DD08168D0E9003213605A609A680A44C7 +:101BF0009A60002303604FF0FF33A36110BD0268B9 +:101C0000234643F8102F53600022026022699A4253 +:101C100003D1BDE8104001F05BBB936881680B44C1 +:101C2000936001F045FB2269E1699268441AA2427F +:101C3000E4D91144BDE81040091AFFF753BF00BFB3 +:101C4000B82300202DE9F047DFF8BC8008F1100729 +:101C50002C4ED8F8105001F02BFBD8F81C40AA6885 +:101C6000031B9A423ED814444FF00009D5E90032D4 +:101C7000C8F81C4013605A60C5F80090D8F81030BE +:101C8000B34201D101F024FB89F31188D5E9033176 +:101C900028469847302383F311886B69002BD8D0EE +:101CA00001F006FB6A69A0EB040982464A450DD2A1 +:101CB000022001F05BFB0022D8F81030B34208D1BB +:101CC00051462846BDE8F047FFF728BF121A2244C4 +:101CD000F2E712EB09092946384638BF4A46FFF7B2 +:101CE000EBFEB5E7D8F81030B34208D01444C8F87A +:101CF0001C00211AA960BDE8F047FFF7F3BEBDE85C +:101D0000F08700BFC8230020B823002000207047C0 +:101D1000FEE70000704700004FF0FF307047000002 +:101D200002290CD0032904D00129074818BF00203C +:101D30007047032A05D8054800EBC20070470448E5 +:101D400070470020704700BFA43C00083C220020E0 +:101D5000583C000870B59AB005460846144601A9DB +:101D600000F0C2F801A8FFF783F8431C0022C6B2B6 +:101D70005B001046C5E9003423700323023404F8E5 +:101D8000013C01ABD1B202348E4201D81AB070BD11 +:101D900013F8011B013204F8010C04F8021CF1E7EE +:101DA00008B5302383F311880348FFF723FA002393 +:101DB00083F3118808BD00BF2826002090F88030EA +:101DC00003F01F02012A07D190F881200B2A03D1CA +:101DD0000023C0E91D3315E003F06003202B08D178 +:101DE000B0F884302BB990F88120212A03D81F2A1B +:101DF00004D8FFF7E1B9222AEBD0FAE7034A426799 +:101E000007228267C3670120704700BF332200208A +:101E100007B5052917D8DFE801F0191603191920AD +:101E2000302383F31188104A01210190FFF78AFAC9 +:101E3000019802210D4AFFF785FA0D48FFF7A6F930 +:101E4000002383F3118803B05DF804FB302383F390 +:101E500011880748FFF770F9F2E7302383F3118800 +:101E60000348FFF787F9EBE7F83B00081C3C000844 +:101E70002826002038B50C4D0C4C2A460C4904F19C +:101E80000800FFF767FF05F1CA0204F110000949D5 +:101E9000FFF760FF05F5CA7204F118000649BDE8B6 +:101EA0003840FFF757BF00BF003F00203C22002012 +:101EB000E03B0008E43B0008EF3B000870B5044637 +:101EC00008460D46FEF7D4FFC6B22046013403781B +:101ED0000BB9184670BD32462946FEF7B5FF0028FB +:101EE000F3D10120F6E700002DE9F04705460C4646 +:101EF000FEF7BEFF2A49C6B22846FFF7DFFF08B14A +:101F00000D36F6B227492846FFF7D8FF08B110363C +:101F1000F6B2632E0BD8DFF88880DFF88890224F66 +:101F2000DFF890A02E7846B92670BDE8F0872946E4 +:101F30002046BDE8F04701F00BBE252E2CD107222C +:101F400041462846FEF780FF60B9184B224603F150 +:101F5000140153F8040B8B4242F8040BF9D10735F6 +:101F60001434DFE7082249462846FEF76DFF98B98A +:101F7000A21C0F4B197802320909C95D02F8041C32 +:101F800013F8011B01F00F015345C95D02F8031C52 +:101F9000F0D118340835C5E7013504F8016BC1E705 +:101FA000C43C0008EF3B0008E13C0008CC3C0008C2 +:101FB00000E8F11F0CE8F11FBFF34F8F044B1A69C3 +:101FC0005107FCD1D3F810215207F8D1704700BF58 +:101FD0000020005208B50D4B1B78ABB9FFF7ECFFA2 +:101FE0000B4BDA68D10704D50A4A5A6002F18832ED +:101FF0005A60D3F80C21D20706D5064AC3F804214B +:1020000002F18832C3F8042108BD00BF5E41002000 +:10201000002000522301674508B5114B1B78F3B926 +:10202000104B1A69510703D5DA6842F04002DA60B2 +:10203000D3F81021520705D5D3F80C2142F0400205 +:10204000C3F80C21FFF7B8FF064BDA6842F0010233 +:10205000DA60D3F80C2142F00102C3F80C2108BD6C +:102060005E410020002000520F289ABF00F58060DA +:1020700040040020704700004FF40030704700001B +:10208000102070470F2808B50BD8FFF7EDFF00F5BB +:1020900000330268013204D104308342F9D10120B7 +:1020A00008BD0020FCE700000F2870B5054645D8A4 +:1020B000FFF76AFC224CFFF77FFF0646FFF78AFF17 +:1020C0004FF0FF33072D6361C4F8143120D823612A +:1020D000FFF772FF2B0243F02403E360E36843F051 +:1020E0008003E36023695A07FCD42846FFF764FFA6 +:1020F0004FF40031FFF7B8FF00F002F93046FFF768 +:102100008BFFFFF74BFC2846BDE87040FFF7BABFD6 +:10211000C4F81031FFF750FFA5F108031B0243F08C +:102120002403C4F80C31D4F80C3143F08003C4F814 +:102130000C31D4F810315B07FBD4D6E7002070BD1A +:10214000002000522DE9F84F40EA020305460C46F4 +:102150001746D80602D00020BDE8F88F27F01F07E9 +:10216000DFF8D4B0FFF736FF2744BC4203D101208B +:10217000FFF752FFF0E720222946204601F0D8FC65 +:1021800010B920352034F0E72B4605F120021E68F7 +:10219000711CE0D104339A42F9D1FFF7F5FB05F148 +:1021A0007843234AB3F5801F224B28BF9A4603F198 +:1021B000040338BF9046A2F1080228BF9846A3F155 +:1021C00008033ABF9146DA469946FFF7F5FEC8F88C +:1021D0000060A5EB040CD9F8002004F11C0142F0CA +:1021E0000202C9F80020221FDAF8006016F0050686 +:1021F000FAD152F8043F8A424CF80230F4D1BFF3CE +:102200004F8FFFF7D9FE4FF0FF32C8F80020D9F802 +:10221000002022F00202C9F80020FFF7BFFB2022B5 +:102220002146284601F084FC0028AAD030469FE7CA +:1022300014200052102100521020005210B5084CFA +:10224000237828B11BB9FFF7C5FE0123237010BD09 +:10225000002BFCD02070BDE81040FFF7DDBE00BFB2 +:102260005E4100200244074BD2B210B5904200D12B +:1022700010BD441C00B253F8200041F8040BE0B23A +:10228000F4E700BF504000580E4B30B51C6F2404DB +:1022900005D41C6F1C671C6F44F400441C670A4C77 +:1022A00002442368D2B243F480732360074B904208 +:1022B00000D130BD441C51F8045B00B243F82050FB +:1022C000E0B2F4E700440258004802585040005879 +:1022D00007B5012201A90020FFF7C4FF019803B050 +:1022E0005DF804FB13B50446FFF7F2FFA04205D0EA +:1022F000012201A900200194FFF7C6FF02B010BD22 +:102300000144BFF34F8F064B884204D3BFF34F8F76 +:10231000BFF36F8F7047C3F85C022030F4E700BF53 +:1023200000ED00E0034B1A681AB9034AD2F8D02432 +:102330001A607047604100200040025808B5FFF75E +:10234000F1FF024B1868C0F3806008BD60410020B7 +:1023500070B5BFF34F8FBFF36F8F1A4A0021C2F8D9 +:102360005012BFF34F8FBFF36F8F536943F40033A5 +:102370005361BFF34F8FBFF36F8FC2F88410BFF369 +:102380004F8FD2F8803043F6E074C3F3C900C3F333 +:102390004E335B0103EA0406014646EA81750139C2 +:1023A000C2F86052F9D2203B13F1200FF2D1BFF3F3 +:1023B0004F8F536943F480335361BFF34F8FBFF3A3 +:1023C0006F8F70BD00ED00E0FEE70000214B22485A +:1023D000224A70B5904237D3214BC11EDA1C121A23 +:1023E00022F003028B4238BF00220021FEF748FD95 +:1023F0001C4A0023C2F88430BFF34F8FD2F88030DC +:1024000043F6E074C3F3C900C3F34E335B0103EA40 +:102410000406014646EA81750139C2F86C52F9D2C8 +:10242000203B13F1200FF2D1BFF34F8FBFF36F8F1B +:10243000BFF34F8FBFF36F8F0023C2F85032BFF34B +:102440004F8FBFF36F8F70BD53F8041B40F8041B10 +:10245000C0E700BFCC3E00083443002034430020D6 +:102460003443002000ED00E0074BD3F8D81021EAF8 +:102470000001C3F8D810D3F8002122EA0002C3F803 +:102480000021D3F8003170470044025870B5D0E9FC +:10249000244300224FF0FF359E6804EB42135101A4 +:1024A000D3F80009002805DAD3F8000940F080408D +:1024B000C3F80009D3F8000B002805DAD3F8000BA5 +:1024C00040F08040C3F8000B013263189642C3F815 +:1024D0000859C3F8085BE0D24FF00113C4F81C3868 +:1024E00070BD0000890141F02001016103699B0674 +:1024F000FCD41220FFF762BA10B50A4C2046FEF752 +:10250000FFFE094BC4F89030084BC4F89430084CD7 +:102510002046FEF7F5FE074BC4F89030064BC4F892 +:10252000943010BD6441002000000840183D0008B0 +:102530000042002000000440243D000870B50378EC +:102540000546012B5CD1434BD0F89040984258D1BE +:10255000414B0E216520D3F8D82042F00062C3F829 +:10256000D820D3F8002142F00062C3F80021D3F84C +:102570000021D3F8802042F00062C3F88020D3F815 +:10258000802022F00062C3F88020D3F8803000F071 +:10259000ADFC324BE360324BC4F800380023D5F871 +:1025A0009060C4F8003EC02323604FF40413A3637B +:1025B0003369002BFCDA01230C203361FFF7FEF9AD +:1025C0003369DB07FCD41220FFF7F8F93369002BDD +:1025D000FCDA00262846A660FFF758FF6B68C4F8AF +:1025E0001068DB68C4F81468C4F81C6883BB1D4B12 +:1025F000A3614FF0FF336361A36843F00103A3605D +:1026000070BD194B9842C9D1134B4FF08060D3F87D +:10261000D82042F00072C3F8D820D3F8002142F04D +:102620000072C3F80021D3F80021D3F8802042F0D3 +:102630000072C3F88020D3F8802022F00072C3F823 +:102640008020D3F88030FFF70FFF0E214D209EE74A +:10265000064BCDE76441002000440258401400407E +:1026600003002002003C30C000420020083C30C083 +:10267000F8B5D0F89040054600214FF0006620469E +:10268000FFF730FFD5F8941000234FF001128F6848 +:102690004FF0FF30C4F83438C4F81C2804EB431260 +:1026A00001339F42C2F80069C2F8006BC2F8080902 +:1026B000C2F8080BF2D20B68D5F89020C5F8983014 +:1026C000636210231361166916F01006FBD1122005 +:1026D000FFF774F9D4F8003823F4FE63C4F8003827 +:1026E000A36943F4402343F01003A3610923C4F812 +:1026F0001038C4F814380B4BEB604FF0C043C4F8EB +:10270000103B094BC4F8003BC4F81069C4F8003909 +:10271000D5F8983003F1100243F48013C5F89820DF +:10272000A362F8BDF43C000840800010D0F890206F +:1027300090F88A10D2F8003823F4FE6343EA0113BC +:10274000C2F80038704700002DE9F84300EB810320 +:10275000D0F890500C468046DA680FFA81F94801AB +:10276000166806F00306731E022B05EB41134FF0AB +:10277000000194BFB604384EC3F8101B4FF001019E +:1027800004F1100398BF06F1805601FA03F3916932 +:1027900098BF06F5004600293AD0578A04F158013F +:1027A000374349016F50D5F81C180B430021C5F879 +:1027B0001C382B180127C3F81019A7405369611E54 +:1027C0009BB3138A928B9B08012A88BF5343D8F886 +:1027D0009820981842EA034301F140022146C8F8C4 +:1027E0009800284605EB82025360FFF77BFE08EB5A +:1027F0008900C3681B8A43EA845348341E4364013A +:102800002E51D5F81C381F43C5F81C78BDE8F88355 +:1028100005EB4917D7F8001B21F40041C7F8001B4E +:10282000D5F81C1821EA0303C0E704F13F030B4A63 +:102830002846214605EB83035A60FFF753FE05EB5C +:102840004910D0F8003923F40043C0F80039D5F816 +:102850001C3823EA0707D7E70080001000040002B5 +:10286000D0F894201268C0F89820FFF70FBE00003F +:102870005831D0F8903049015B5813F4004004D02F +:1028800013F4001F0CBF0220012070474831D0F81C +:10289000903049015B5813F4004004D013F4001F3A +:1028A0000CBF02200120704700EB8101CB68196A40 +:1028B0000B6813604B6853607047000000EB8103A6 +:1028C00030B5DD68AA691368D36019B9402B84BF9D +:1028D000402313606B8A1468D0F890201C4402EBEC +:1028E0004110013C09B2B4FBF3F46343033323F01A +:1028F000030343EAC44343F0C043C0F8103B2B68D2 +:1029000003F00303012B0ED1D2F8083802EB41107B +:1029100013F4807FD0F8003B14BF43F0805343F0A2 +:102920000053C0F8003B02EB4112D2F8003B43F0E9 +:102930000443C2F8003B30BD2DE9F041D0F890606F +:1029400005460C4606EB4113D3F8087B3A07C3F85B +:10295000087B08D5D6F814381B0704D500EB810393 +:10296000DB685B689847FA071FD5D6F81438DB0791 +:102970001BD505EB8403D968CCB98B69488A5A68A2 +:10298000B2FBF0F600FB16228AB91868DA689042AA +:102990000DD2121AC3E90024302383F31188214693 +:1029A0002846FFF78BFF84F31188BDE8F0810123EF +:1029B00003FA04F26B8923EA02036B81CB68002BD4 +:1029C000F3D021462846BDE8F041184700EB8103CB +:1029D0004A0170B5DD68D0F890306C692668E66011 +:1029E00056BB1A444FF40020C2F810092A6802F0BE +:1029F0000302012A0AB20ED1D3F8080803EB4214ED +:102A000010F4807FD4F8000914BF40F0805040F0EB +:102A10000050C4F8000903EB4212D2F8000940F05C +:102A20000440C2F800090122D3F8340802FA01F187 +:102A30000143C3F8341870BD19B9402E84BF40203B +:102A4000206020681A442E8A8419013CB4FBF6F4F5 +:102A500040EAC44040F00050C6E700002DE9F843CA +:102A6000D0F8906005460C464F0106EB4113D3F8B1 +:102A7000088918F0010FC3F808891CD0D6F810385F +:102A8000DB0718D500EB8103D3F80CC0DCF8143059 +:102A9000D3F800E0DA68964530D2A2EB0E024FF090 +:102AA00000091A60C3F80490302383F31188FFF7FC +:102AB0008DFF89F3118818F0800F1DD0D6F83438B7 +:102AC0000126A640334217D005EB84030134D5F824 +:102AD0009050D3F80CC0E4B22F44DCF8142005EB7E +:102AE0000434D2F800E05168714514D3D5F8343875 +:102AF00023EA0606C5F83468BDE8F883012303FA23 +:102B000001F2038923EA02030381DCF80830002B79 +:102B1000D1D09847CFE7AEEB0103BCF81000834259 +:102B200028BF0346D7F8180980B2B3EB800FE3D86B +:102B30009068A0F1040959F8048FC4F80080A0EB54 +:102B400009089844B8F1040FF5D818440B44906074 +:102B50005360C8E72DE9F84FD0F8905004466E69ED +:102B6000AB691E4016F480586E6103D0BDE8F84F83 +:102B7000FEF736BC002E12DAD5F8003E9B0705D0D2 +:102B8000D5F8003E23F00303C5F8003ED5F804381D +:102B9000204623F00103C5F80438FEF74FFC370543 +:102BA00005D52046FFF772FC2046FEF735FCB00441 +:102BB0000CD5D5F8083813F0060FEB6823F47053E2 +:102BC0000CBF43F4105343F4A053EB6031071BD503 +:102BD0006368DB681BB9AB6923F00803AB6123783A +:102BE000052B0CD1D5F8003E9A0705D0D5F8003E4C +:102BF00023F00303C5F8003E2046FEF71FFC636880 +:102C0000DB680BB120469847F30200F1BA80B702A7 +:102C100026D5D4F8909000274FF0010A09EB47120F +:102C2000D2F8003B03F44023B3F5802F11D1D2F842 +:102C3000003B002B0DDA62890AFA07F322EA03034C +:102C4000638104EB8703DB68DB6813B139462046F8 +:102C500098470137D4F89430FFB29B689F42DDD982 +:102C6000F00619D5D4F89000026AC2F30A1702F0F0 +:102C70000F0302F4F012B2F5802F00F0CA80B2F513 +:102C8000402F09D104EB8303002200F58050DB685C +:102C90001B6A974240F0B0803003D5F8185835D5FC +:102CA000E90303D500212046FFF746FEAA0303D51A +:102CB00001212046FFF740FE6B0303D50221204689 +:102CC000FFF73AFE2F0303D503212046FFF734FE1A +:102CD000E80203D504212046FFF72EFEA90203D502 +:102CE00005212046FFF728FE6A0203D5062120466B +:102CF000FFF722FE2B0203D507212046FFF71CFE1B +:102D0000EF0103D508212046FFF716FE700340F1BE +:102D1000A780E90703D500212046FFF79FFEAA07F9 +:102D200003D501212046FFF799FE6B0703D5022149 +:102D30002046FFF793FE2F0703D503212046FFF718 +:102D40008DFEEE0603D504212046FFF787FEA80678 +:102D500003D505212046FFF781FE690603D506212C +:102D60002046FFF77BFE2A0603D507212046FFF702 +:102D700075FEEB0574D520460821BDE8F84FFFF736 +:102D80006DBED4F890904FF0000B4FF0010AD4F8CC +:102D900094305FFA8BF79B689F423FF638AF09EBA0 +:102DA0004713D3F8002902F44022B2F5802F20D136 +:102DB000D3F80029002A1CDAD3F8002942F0904207 +:102DC000C3F80029D3F80029002AFBDB3946D4F8E0 +:102DD0009000FFF787FB22890AFA07F322EA030330 +:102DE000238104EB8703DB689B6813B139462046D7 +:102DF00098470BF1010BCAE7910701D1D0F8008089 +:102E0000072A02F101029CBF03F8018B4FEA182840 +:102E10003FE704EB830300F58050DA68D2F818C06E +:102E2000DCF80820DCE9001CA1EB0C0C00218F422F +:102E300008D1DB689B699A683A449A605A683A44B8 +:102E40005A6029E711F0030F01D1D0F800808C45BA +:102E500001F1010184BF02F8018B4FEA1828E6E76F +:102E6000BDE8F88F08B50348FFF774FEBDE80840D9 +:102E700000F07ABB6441002008B50348FFF76AFE02 +:102E8000BDE8084000F070BB00420020D0F8903050 +:102E900003EB4111D1F8003B43F40013C1F8003BB0 +:102EA00070470000D0F8903003EB4111D1F80039A1 +:102EB00043F40013C1F8003970470000D0F8903097 +:102EC00003EB4111D1F8003B23F40013C1F8003BA0 +:102ED00070470000D0F8903003EB4111D1F8003971 +:102EE00023F40013C1F8003970470000090100F114 +:102EF0006043012203F56143C9B283F8001300F077 +:102F00001F039A4043099B0003F1604303F56143AB +:102F1000C3F880211A60704730B50433039C0172F6 +:102F2000002104FB0325C160C0E90653049B036331 +:102F3000059BC0E90000C0E90422C0E90842C0E9DD +:102F40000A11436330BD00000022416AC260C0E93B +:102F50000411C0E90A226FF00101FEF79FBD0000D5 +:102F6000D0E90432934201D1C2680AB9181D7047F2 +:102F700000207047036919600021C2680132C260F5 +:102F8000C269134482699342036124BF436A0361A7 +:102F9000FEF778BD38B504460D46E3683BB162697B +:102FA0000020131D1268A3621344E36207E0237A32 +:102FB00033B929462046FEF755FD0028EDDA38BD25 +:102FC0006FF00100FBE70000C368C269013BC3600A +:102FD0004369134482699342436124BF436A436156 +:102FE00000238362036B03B11847704770B5302329 +:102FF000044683F31188866A3EB9FFF7CBFF054686 +:1030000018B186F31188284670BDA36AE26A13F8E6 +:10301000015B9342A36202D32046FFF7D5FF002352 +:1030200083F31188EFE700002DE9F84F04460E46C0 +:10303000174698464FF0300989F311880025AA46B3 +:10304000D4F828B0BBF1000F09D141462046FFF764 +:10305000A1FF20B18BF311882846BDE8F88FD4E991 +:103060000A12A7EB050B521A934528BF9346BBF1F2 +:10307000400F1BD9334601F1400251F8040B914235 +:1030800043F8040BF9D1A36A403640354033A362BC +:10309000D4E90A239A4202D32046FFF795FF8AF328 +:1030A0001188BD42D8D289F31188C9E730465A4603 +:1030B000FDF7C0FEA36A5E445D445B44A362E7E79C +:1030C00010B5029C0433017203FB0421C460C0E903 +:1030D00006130023C0E90A33039B0363049BC0E982 +:1030E0000000C0E90422C0E90842436310BD0000AB +:1030F000026A6FF00101C260426AC0E90422002244 +:10310000C0E90A22FEF7CABCD0E904239A4201D1E1 +:10311000C26822B9184650F8043B0B607047002380 +:103120001846FAE7C3680021C2690133C3604369E6 +:10313000134482699342436124BF436A4361FEF7AB +:10314000A1BC000038B504460D46E3683BB12369D5 +:1031500000201A1DA262E2691344E36207E0237AA9 +:1031600033B929462046FEF77DFC0028EDDA38BD4C +:103170006FF00100FBE7000003691960C268013AC3 +:10318000C260C269134482699342036124BF436AE7 +:10319000036100238362036B03B11847704700008B +:1031A00070B530230D460446114683F31188866AB4 +:1031B0002EB9FFF7C7FF10B186F3118870BDA36A5F +:1031C0001D70A36AE26A01339342A36204D3E169EA +:1031D00020460439FFF7D0FF002080F31188EDE787 +:1031E0002DE9F84F04460D46904699464FF0300AB7 +:1031F0008AF311880026B346A76A4FB9494620468C +:10320000FFF7A0FF20B187F311883046BDE8F88FA3 +:10321000D4E90A073A1AA8EB0607974228BF1746CF +:10322000402F1BD905F1400355F8042B9D4240F86F +:10323000042BF9D1A36A40364033A362D4E90A23B0 +:103240009A4204D3E16920460439FFF795FF8BF3D6 +:1032500011884645D9D28AF31188CDE729463A46E6 +:10326000FDF7E8FDA36A3D443E443B44A362E5E725 +:10327000D0E904239A4217D1C3689BB1836A8BB10A +:10328000043B9B1A0ED01360C368013BC360C36943 +:103290001A4483699A42026124BF436A036100238E +:1032A00083620123184670470023FBE700F086B9CC +:1032B000014B586A704700BF000C0040034B0022CE +:1032C00058631A610222DA60704700BF000C0040A8 +:1032D000014B0022DA607047000C0040014B58633C +:1032E000704700BF000C0040FEE7000070B51B4BAC +:1032F0000025044686B058600E468562016300F0E2 +:103300000BF904F11003A560E562C4E904334FF042 +:10331000FF33C4E90044C4E90635FFF7C9FF2B4673 +:10332000024604F134012046C4E9082380230C4AF4 +:103330002565FEF74DFB01230A4AE0600092037504 +:10334000684672680192B268CDE90223064BCDE966 +:103350000435FEF765FB06B070BD00BF20260020D7 +:10336000303D0008353D0008E9320008024AD36AC2 +:103370001843D062704700BFB82300204B684360F9 +:103380008B688360CB68C3600B6943614B690362E0 +:103390008B6943620B6803607047000008B53C4BC3 +:1033A00040F2FF713B48D3F888200A43C3F88820D5 +:1033B000D3F8882022F4FF6222F00702C3F88820A5 +:1033C000D3F88820D3F8E0200A43C3F8E020D3F8EC +:1033D00008210A43C3F808212F4AD3F808311146BF +:1033E000FFF7CCFF00F5806002F11C01FFF7C6FF7C +:1033F00000F5806002F13801FFF7C0FF00F5806042 +:1034000002F15401FFF7BAFF00F5806002F170018C +:10341000FFF7B4FF00F5806002F18C01FFF7AEFF0B +:1034200000F5806002F1A801FFF7A8FF00F58060B9 +:1034300002F1C401FFF7A2FF00F5806002F1E00194 +:10344000FFF79CFF00F5806002F1FC01FFF796FF9B +:1034500002F58C7100F58060FFF790FF00F076F9BF +:103460000E4BD3F8902242F00102C3F89022D3F819 +:10347000942242F00102C3F894220522C3F8982056 +:103480004FF06052C3F89C20054AC3F8A02008BD45 +:1034900000440258000002583C3D000800ED00E0E6 +:1034A0001F00080308B500F025FBFEF755FA0F4B87 +:1034B000D3F8DC2042F04002C3F8DC20D3F804212A +:1034C00022F04002C3F80421D3F80431084B1A68F3 +:1034D00042F008021A601A6842F004021A60FEF70D +:1034E00021FFBDE80840FEF7C5BC00BF00440258FC +:1034F0000018024870470000EFF30983054968335C +:103500004A6B22F001024A6383F30988002383F3A4 +:103510001188704700EF00E0302080F3118862B618 +:103520000D4B0E4AD96821F4E0610904090C0A43E5 +:103530000B49DA60D3F8FC2042F08072C3F8FC201B +:10354000084AC2F8B01F116841F001011160202241 +:10355000DA7783F82200704700ED00E00003FA05F7 +:1035600055CEACC5001000E0302310B583F31188B0 +:103570000E4B5B6813F4006314D0F1EE103AEFF3D6 +:1035800009844FF08073683CE361094BDB6B236671 +:1035900084F30988FEF7B4F910B1064BA36110BD9E +:1035A000054BFBE783F31188F9E700BF00ED00E06E +:1035B00000EF00E02F04000832040008114BD3F89C +:1035C000E82042F00802C3F8E820D3F8102142F0C6 +:1035D0000802C3F810210C4AD3F81031D36B43F022 +:1035E0000803D363C722094B9A624FF0FF32DA62B5 +:1035F00000229A615A63DA605A6001225A611A60A5 +:10360000704700BF004402580010005C000C0040EE +:10361000094A08B51169D3680B40D9B29B076FEA14 +:103620000101116107D5302383F31188FEF7AAF950 +:10363000002383F3118808BD000C0040064BD3F82B +:10364000DC200243C3F8DC20D3F804211043C3F884 +:103650000401D3F804317047004402583A4B4FF04C +:10366000FF31D3F8802062F00042C3F88020D3F805 +:10367000802002F00042C3F88020D3F88020D3F8E5 +:103680008420C3F88410D3F884200022C3F8842057 +:10369000D3F88400D86F40F0FF4040F4FF0040F4BE +:1036A000DF4040F07F00D867D86F20F0FF4020F463 +:1036B000FF0020F4DF4020F07F00D867D86FD3F8F8 +:1036C00088006FEA40506FEA5050C3F88800D3F882 +:1036D0008800C0F30A00C3F88800D3F88800D3F844 +:1036E0009000C3F89010D3F89000C3F89020D3F85E +:1036F0009000D3F89400C3F89410D3F89400C3F862 +:103700009420D3F89400D3F89800C3F89810D3F815 +:103710009800C3F89820D3F89800D3F88C00C3F829 +:103720008C10D3F88C00C3F88C20D3F88C00D3F81D +:103730009C00C3F89C10D3F89C10C3F89C20D3F8CD +:103740009C3000F0AFB900BF0044025808B5012218 +:10375000534BC3F80821534BD3F8F42042F0020234 +:10376000C3F8F420D3F81C2142F00202C3F81C2154 +:103770000222D3F81C314C4BDA605A689104FCD514 +:103780004A4A1A6001229A60494ADA6000221A61A4 +:103790004FF440429A61444B9A699204FCD51A68EE +:1037A00042F480721A603F4B1A6F12F4407F04D0CB +:1037B0004FF480321A6700221A671A6842F0010239 +:1037C0001A60384B1A685007FCD500221A611A6932 +:1037D00012F03802FBD1012119604FF0804159608D +:1037E0005A67344ADA62344A1A611A6842F48032FB +:1037F0001A602C4B1A689103FCD51A6842F4805267 +:103800001A601A689204FCD52C4A2D499A6200224B +:103810005A63196301F57C01DA6301F5E771996375 +:103820005A64284A1A64284ADA621A6842F0A8528E +:103830001A601C4B1A6802F02852B2F1285FF9D1C5 +:1038400048229A614FF48862DA6140221A621F4A64 +:10385000DA641F4A1A651F4A5A651F4A9A6532235D +:103860001E4A1360136803F00F03022BFAD10D4AAE +:10387000136943F003031361136903F03803182B32 +:10388000FAD14FF00050FFF7D9FE4FF08040FFF71C +:10389000D5FE4FF00040BDE80840FFF7CFBE00BFA7 +:1038A00000800051004402580048025800C000F057 +:1038B000020000010000FF01008890083220600033 +:1038C00063020901470E0508DD0BBF01200000203F +:1038D000000001100910E00000010110002000525A +:1038E0004FF0B04208B5D2F8883003F00103C2F8B7 +:1038F000883023B1044A13680BB150689847BDE87B +:103900000840FFF731BE00BFB44200204FF0B04284 +:1039100008B5D2F8883003F00203C2F8883023B12A +:10392000044A93680BB1D0689847BDE80840FFF798 +:103930001BBE00BFB44200204FF0B04208B5D2F821 +:10394000883003F00403C2F8883023B1044A1369B5 +:103950000BB150699847BDE80840FFF705BE00BFAE +:10396000B44200204FF0B04208B5D2F8883003F0DE +:103970000803C2F8883023B1044A93690BB1D069B7 +:103980009847BDE80840FFF7EFBD00BFB4420020F4 +:103990004FF0B04208B5D2F8883003F01003C2F8F7 +:1039A000883023B1044A136A0BB1506A9847BDE8C6 +:1039B0000840FFF7D9BD00BFB44200204FF0B0432C +:1039C00010B5D3F8884004F47872C3F88820A306B1 +:1039D00004D5124A936A0BB1D06A9847600604D5A1 +:1039E0000E4A136B0BB1506B9847210604D50B4A56 +:1039F000936B0BB1D06B9847E20504D5074A136C63 +:103A00000BB1506C9847A30504D5044A936C0BB1D5 +:103A1000D06C9847BDE81040FFF7A6BDB442002027 +:103A20004FF0B04310B5D3F8884004F47C42C3F89B +:103A30008820620504D5164A136D0BB1506D984766 +:103A4000230504D5124A936D0BB1D06D9847E0045D +:103A500004D50F4A136E0BB1506E9847A10404D5DC +:103A60000B4A936E0BB1D06E9847620404D5084A96 +:103A7000136F0BB1506F9847230404D5044A936F1A +:103A80000BB1D06F9847BDE81040FFF76DBD00BF88 +:103A9000B442002008B5FFF7BBFDBDE80840FFF7C2 +:103AA00063BD0000062108B50846FFF71FFA06218E +:103AB0000720FFF71BFA06210820FFF717FA062157 +:103AC0000920FFF713FA06210A20FFF70FFA062153 +:103AD0001720FFF70BFA06212820FFF707FA092124 +:103AE0007A20FFF703FA07213220BDE80840FFF7EC +:103AF000FDB9000008B5FFF7B1FD00F00BF8FDF7C8 +:103B0000FDFBFDF7CFFAFFF7F5FCBDE80840FFF736 +:103B1000CDBB00000023054A19460133102BC2E932 +:103B2000001102F10802F8D1704700BFB442002032 +:103B300010B501390244904201D1002005E003781C +:103B400011F8014FA34201D0181B10BD0130F2E75C +:103B5000034611F8012B03F8012B002AF9D1704715 +:103B600053544D333248373F3F3F0053544D333267 +:103B7000483733782F3732780053544D3332483733 +:103B800034332F3735332F373530000001105A00CA +:103B900003105900012058000320560000000000C7 +:103BA000211000080D100008491000083510000809 +:103BB000411000082D100008191000080510000819 +:103BC0005510000800000000010000000000000087 +:103BD00063300000D03B0008102400202026002085 +:103BE0006D526F0025424F415244252D424C002515 +:103BF00053455249414C25000200000000000000DE +:103C000041120008B112000840004000D03E0020E0 +:103C1000E03E002002000000000000000300000061 +:103C200000000000F9120008000000001000000071 +:103C3000F03E002000000000010000000000000035 +:103C40006441002001010200111E0008211D00082E +:103C5000BD1D0008A11D000843000000603C0008D5 +:103C600009024300020100C03209040000010202FF +:103C700001000524001001052401000104240202B2 +:103C80000524060001070582030800FF090401005E +:103C9000020A00000007050102400000070581023A +:103CA0004000000012000000AC3C000812011001AE +:103CB0000200004009124157000201020301000006 +:103CC0000403090425424F41524425006D526F43BD +:103CD0005A65726F4F454D48372D626473686F7433 +:103CE0000030313233343536373839414243444578 +:103CF0004600000000000000551400080D170008E1 +:103D0000B9170008400040009C4200209C4200205F +:103D100001000000AC4200208000000040010000D3 +:103D20000800000000010000001000000800000072 +:103D30006D61696E0069646C650000000000802A96 +:103D400000000000AAAAAAAA00000024FFFF0000A9 +:103D50000000000000A00A00440040000000000035 +:103D6000AAAAAAAA00000000FFFF000000000000AD +:103D7000000000001000000000000000AAAAAAAA8B +:103D800010000000FFFF0000000000000000000025 +:103D90000040100000000000AAAA8AAA00401000FB +:103DA000FFFF0000000000000000000000000040D5 +:103DB00000000000AAAAAAAA00000040FFFF00001D +:103DC00000000000000000000010100000000000D3 +:103DD000AAAAAAAA00101000FFFF0000000000001D +:103DE000000000000000040000000000AAAAAAAA27 +:103DF00000000400FFFF00000000000000000000C1 +:103E00000000000000000000AAAAAAAA000000000A +:103E1000FFFF0000000000000000000000000000A4 +:103E200000000000AAAAAAAA00000000FFFF0000EC +:103E30000000000000000000000000000000000082 +:103E4000AAAAAAAA00000000FFFF000000000000CC +:103E5000000000000000000000000000AAAAAAAABA +:103E600000000000FFFF0000000000000000000054 +:103E7000000400000000000000001E000000000020 +:103E8000FF00000000000000603B00088304000009 +:103E90006B3B000850040000793B000800960000CE +:103EA0000000080096000000000800000400000068 +:103EB000C03C0008000000000000000000000000FE +:0C3EC000000000000000000000000000F6 +:00000001FF diff --git a/Tools/bootloaders/mRoControlZeroClassic_bl.bin b/Tools/bootloaders/mRoControlZeroClassic_bl.bin new file mode 100755 index 00000000000000..76a2270389542d Binary files /dev/null and b/Tools/bootloaders/mRoControlZeroClassic_bl.bin differ diff --git a/Tools/bootloaders/mRoControlZeroH7_bl.bin b/Tools/bootloaders/mRoControlZeroH7_bl.bin new file mode 100755 index 00000000000000..813c5a3a031bba Binary files /dev/null and b/Tools/bootloaders/mRoControlZeroH7_bl.bin differ diff --git a/Tools/bootloaders/rGNSS_bl.bin b/Tools/bootloaders/rGNSS_bl.bin index ac8843e0e3b027..11593c73e2fd52 100755 Binary files a/Tools/bootloaders/rGNSS_bl.bin and b/Tools/bootloaders/rGNSS_bl.bin differ diff --git a/Tools/bootloaders/sw-nav-f405_bl.bin b/Tools/bootloaders/sw-nav-f405_bl.bin new file mode 100755 index 00000000000000..308f76f1fb5f45 Binary files /dev/null and b/Tools/bootloaders/sw-nav-f405_bl.bin differ diff --git a/Tools/bootloaders/sw-nav-f405_bl.hex b/Tools/bootloaders/sw-nav-f405_bl.hex new file mode 100644 index 00000000000000..cb588d700be370 --- /dev/null +++ b/Tools/bootloaders/sw-nav-f405_bl.hex @@ -0,0 +1,1198 @@ +:020000040800F2 +:1000000000070020F5040008DD26000895260008FA +:10001000BD26000895260008B5260008F70400084C +:10002000F7040008F7040008F7040008D1360008B8 +:10003000F7040008F7040008F7040008F7040008B4 +:10004000F7040008F7040008F7040008F7040008A4 +:10005000F7040008F70400089D440008C5440008A0 +:10006000ED440008154500083D450008F704000868 +:10007000F7040008F7040008F7040008F704000874 +:10008000F7040008F7040008F704000849260008F0 +:100090007526000885260008F70400086545000855 +:1000A000F7040008F7040008F7040008F704000844 +:1000B00039460008F7040008F7040008F7040008B0 +:1000C000F7040008F7040008F7040008F704000824 +:1000D000F7040008F7040008F7040008F704000814 +:1000E000C9450008F7040008F7040008F7040008F1 +:1000F000F7040008F7040008F7040008F7040008F4 +:10010000F7040008F7040008F7040008F7040008E3 +:10011000F7040008F7040008F7040008F7040008D3 +:10012000F7040008F7040008F7040008F7040008C3 +:10013000F7040008F7040008F7040008F7040008B3 +:10014000F7040008F7040008F7040008F7040008A3 +:10015000F7040008F7040008F7040008F704000893 +:10016000F7040008F7040008F7040008F704000883 +:10017000F7040008F7040008F7040008F704000873 +:10018000F7040008F7040008F7040008F704000863 +:10019000F7040008F7040008F7040008F704000853 +:1001A000F7040008F7040008F7040008F704000843 +:1001B000F7040008F7040008F7040008F704000833 +:1001C000F7040008F7040008F7040008F704000823 +:1001D000F7040008F7040008F7040008F704000813 +:1001E000BD12000800000000000000000000000038 +:1001F00053B94AB9002908BF00281CBF4FF0FF318E +:100200004FF0FF3000F074B9ADF1080C6DE904CE89 +:1002100000F006F8DDF804E0DDE9022304B07047E1 +:100220002DE9F047089D04468E46002B4DD18A42A9 +:10023000944669D9B2FA82F252B101FA02F3C2F1DC +:10024000200120FA01F10CFA02FC41EA030E94406D +:100250004FEA1C48210CBEFBF8F61FFA8CF708FB8E +:1002600016E341EA034306FB07F199420AD91CEB66 +:10027000030306F1FF3080F01F81994240F21C8198 +:10028000023E63445B1AA4B2B3FBF8F008FB1033E0 +:1002900044EA034400FB07F7A7420AD91CEB040415 +:1002A00000F1FF3380F00A81A74240F207816444E5 +:1002B000023840EA0640E41B00261DB1D44000236A +:1002C000C5E900433146BDE8F0878B4209D9002DCE +:1002D00000F0EF800026C5E9000130463146BDE858 +:1002E000F087B3FA83F6002E4AD18B4202D38242C2 +:1002F00000F2F980841A61EB030301209E46002D71 +:10030000E0D0C5E9004EDDE702B9FFDEB2FA82F2C5 +:10031000002A40F09280A1EB0C014FEA1C471FFA23 +:100320008CFE0126200CB1FBF7F307FB131140EA0A +:1003300001410EFB03F0884208D91CEB010103F1D7 +:10034000FF3802D2884200F2CB804346091AA4B299 +:10035000B1FBF7F007FB101144EA01440EFB00FE6D +:10036000A64508D91CEB040400F1FF3102D2A645D2 +:1003700000F2BB800846A4EB0E0440EA03409CE771 +:10038000C6F12007B34022FA07FC4CEA030C20FA1E +:1003900007F401FA06F31C43F9404FEA1C4900FA3E +:1003A00006F3B1FBF9F8200C1FFA8CFE09FB1811BB +:1003B00040EA014108FB0EF0884202FA06F20BD92E +:1003C0001CEB010108F1FF3A80F08880884240F27E +:1003D0008580A8F102086144091AA4B2B1FBF9F0C2 +:1003E00009FB101144EA014100FB0EFE8E4508D9BD +:1003F0001CEB010100F1FF346CD28E456AD9023842 +:10040000614440EA0840A0FB0294A1EB0E01A14226 +:10041000C846A64656D353D05DB1B3EB080261EB94 +:100420000E0101FA07F722FA06F3F1401F43C5E96E +:10043000007100263146BDE8F087C2F12003D840A4 +:100440000CFA02FC21FA03F3914001434FEA1C47E6 +:100450001FFA8CFEB3FBF7F007FB10360B0C43EAD8 +:10046000064300FB0EF69E4204FA02F408D91CEB88 +:10047000030300F1FF382FD29E422DD90238634486 +:100480009B1B89B2B3FBF7F607FB163341EA034126 +:1004900006FB0EF38B4208D91CEB010106F1FF3875 +:1004A00016D28B4214D9023E6144C91A46EA00466C +:1004B00038E72E46284605E70646E3E61846F8E6FE +:1004C0004B45A9D2B9EB020864EB0C0E0138A3E747 +:1004D0004646EAE7204694E74046D1E7D0467BE728 +:1004E000023B614432E7304609E76444023842E7A0 +:1004F000704700BF02E000F000F8FEE772B6374830 +:1005000080F30888364880F3098836483649086001 +:1005100040F20000CCF200004EF63471CEF2000141 +:100520000860BFF34F8FBFF36F8F40F20000C0F23F +:10053000F0004EF68851CEF200010860BFF34F8FF5 +:10054000BFF36F8F4FF00000E1EE100A4EF63C71E2 +:10055000CEF200010860062080F31488BFF36F8F8D +:1005600003F0B2FD03F044FE4FF055301F491B4A23 +:1005700091423CBF41F8040BFAE71D49184A9142E9 +:100580003CBF41F8040BFAE71A491B4A1B4B9A423D +:100590003EBF51F8040B42F8040BF8E7002018495D +:1005A000184A91423CBF41F8040BFAE703F090FD72 +:1005B00003F072FE144C154DAC4203DA54F8041BE0 +:1005C0008847F9E700F042F8114C124DAC4203DACB +:1005D00054F8041B8847F9E703F078BD00070020B2 +:1005E000002300200000000808ED00E000010020CA +:1005F00000070020404A000800230020802300203C +:1006000080230020684D0020E0010008E40100087C +:10061000E4010008E40100082DE9F04F2DED108AF7 +:10062000C1F80CD0C3689D46BDEC108ABDE8F08FC0 +:10063000002383F311882846A047002003F0CAF95D +:10064000FEE703F02DF900DFFEE70000F8B500F04B +:1006500047FE03F0D3FC074603F022FD0546D0BB5E +:10066000294B9F4237D001339F4237D0274B27F089 +:10067000FF029A4235D1F8B200F03EFC2E4642F21B +:10068000107400F03FFC08B10024264601F014F974 +:1006900058B3032000F03EF80024264635B11C4B29 +:1006A0009F4203D003F0F4FC00242646002003F010 +:1006B000AFFC0EB100F044F800F090FC00F012FE28 +:1006C00002F014F80546B4B900F0D0FC4FF47A708B +:1006D00003F086F9F7E72E460024D2E70446012608 +:1006E000CFE7064641F28834CBE7002CD6D04FF452 +:1006F0007A740126D2E701F0F9FF431BA342E3D944 +:1007000000F01EF8DCE700BF010007B0000008B0F1 +:10071000263A09B0084B187003280CD8DFE800F01F +:1007200008050208022000F039BE022000F02EBEAB +:10073000024B00225A60704780230020842300204F +:1007400010B501F0B9F830B1204B03221A70204BDC +:1007500000225A6010BD1F4B1F4A1C461968013108 +:10076000F8D004339342F9D162681C4B9A42F1D914 +:100770001B4B9B6803F1006303F580339A42E9D277 +:1007800003F05AFC03F06CFC002000F0C5FD0220D1 +:10079000FFF7C0FF134B1A6C00221A64196E1A6619 +:1007A000196E596C5A64596E5A665B6E72B64FF088 +:1007B000E0233021C3F8084DD4E9003281F31188D9 +:1007C0009D4683F308881047C4E700BF80230020BC +:1007D000842300200000010820000108FFFF00081A +:1007E0000023002000380240094A136849F26900DA +:1007F00099B21B0C00FB01331360064B186844F2DE +:10080000506182B2000C01FB0200186080B2704798 +:10081000182300201423002010B5002110220446C4 +:1008200000F0D8FD034B03CB206061601868A06026 +:1008300010BD00BF107AFF1F2DE9F041ADF54C7DD2 +:100840000DF12C086AAC40F2751207460D460CA853 +:100850000021C8F8001000F0BDFD4FF4C472002163 +:10086000204600F0B7FD01F041FF274B4FF47A72AC +:10087000B0FBF2F0186093E80700022384E8070059 +:100880000DF5E5702382FFF7C7FF47F217231F49D5 +:10089000238407A803F0DCFF0E2384F832310DF225 +:1008A000DB2207AB0DF1240C1E4603CE664510601B +:1008B0005160334602F10802F6D130681060B38807 +:1008C000938041460122204600F0D0FD002303938F +:1008D000AB7E029305F11903019380B20123CDE9A8 +:1008E00004800093E97E06A3D3E90023384602F092 +:1008F000C5FA0DF54C7DBDE8F08100BFAFF3008077 +:100900009E6AC421818A46EE8C230020604800083C +:100910002DE9F0412C4C237ADAB080460D465BBBC2 +:1009200027A9284600F0B2FE0746002842D19DF8CC +:100930009D60C82E3ED801464FF4A662204600F0C6 +:1009400049FD4FF48073C4F8F8314FF40073C4F8D4 +:100950000C334FF44073C4F8203432460DF19E013D +:1009600004F1090000F024FD26449DF89C307772C4 +:1009700023720BB9EB7E23728122002106AC27A8DB +:1009800000F028FD0122214627A800F0BBFE00232D +:100990000393AB7E029305F1190380B201932823E0 +:1009A000CDE904400093E97E05A3D3E90023404646 +:1009B00002F064FA5AB0BDE8F08100BFAFF30080E6 +:1009C00026417272DF25D7B7A8440020F0B5254E26 +:1009D0004FF48A7505FB0065F1B096F8D83085F8BC +:1009E000DC300024D822214685F8E8403AA800F0FF +:1009F000F1FC06F1090000F0E5FCD5F8E4308DF8D3 +:100A0000F000C2B206AF06F109010DF1F100CDE927 +:100A10003A3400F0CDFC394601223AA800F09EFE9F +:100A200080B2CDE9047008230127CDE9023706F131 +:100A3000D803019330230093317A0B4807A3D3E9FD +:100A4000002302F01BFAA04206DD01F04FFEC5F8BC +:100A5000E000384671B0F0BD2046FBE778F6339FE2 +:100A600093CACD8DA8440020A43300202DE9F04185 +:100A70001D4D1E4E1E4F86B0284602F02BFA03462F +:100A800058B30024CDE90344ADF81440027B8DF83F +:100A9000142099684068029403AA03C21B68DFF817 +:100AA000548043F00043029301F022FE821941F189 +:100AB0000003009402A9384601F0E4F8A04205DDE5 +:100AC000284602F00BFA88F80040D5E798F8003085 +:100AD000072B05D8013388F8003006B0BDE8F08157 +:100AE000014802F0FBF9F8E7A433002040420F0070 +:100AF000D8330020DD49002070B50D4614461E464F +:100B000002F018F950B9022E10D1012C0ED112A307 +:100B1000D3E90023C5E90023012007E0282C10D0E9 +:100B200005D8012C09D0052C0FD0002070BD302C29 +:100B3000FBD10BA3D3E90023ECE70BA3D3E90023FC +:100B4000E8E70BA3D3E90023E4E70BA3D3E90023F1 +:100B5000E0E700BFAFF30080401DA12026812A0BF3 +:100B600078F6339F93CACD8D9E6AC421818A46EE62 +:100B700026417272DF25D7B7F017304A39059E56E5 +:100B800038B505460E4C0021013500F0E7FBA4F80E +:100B90002C55B4F82C0500F0C9FB78B1B4F82C053D +:100BA00000F0D4FB014648B9B4F82C0500F0D6FBA0 +:100BB000B4F82C350133A4F82C35EAE738BD00BF72 +:100BC000A844002010B50A4B0A4A1A6003F5805366 +:100BD00093F860203AB9DC6D2CB1204600F0EAFEB3 +:100BE000204603F075FDBDE81040034800F0E2BE6A +:100BF000D8330020AC480008204400202DE9F04FF5 +:100C00008FB000AF05460C4602F094F8002849D199 +:100C1000237E022B1BD1E38A012B18D101F066FD44 +:100C20000646FFF7E1FD03464FF4C870DFF8C482C3 +:100C3000B3FBF0F206F5167602FB103316FA83F3D7 +:100C4000C8F80030E37E33B9A34B00221A703C375A +:100C5000BD46BDE8F08F07F12401204600F0D4FC2A +:100C60000028F4D107F11400FFF7D6FD97F82640CD +:100C700007F11401224607F1270003F073FD002855 +:100C8000E2D10F2C08D8944B1C70D8F80030A3F593 +:100C90001673C8F80030DAE797F82410284602F0F7 +:100CA00041F8D4E7E38A282B2BD010D8012B23D08E +:100CB000052BCCD1BFF34F8F8849894BCA6802F40A +:100CC000E0621343CB60BFF34F8F00BFFDE7302BD3 +:100CD000BDD1844EE17E327A9142B8D1607E3146F8 +:100CE000002291F8DC50854200F0A5800132042AF0 +:100CF00001F58A71F5D1AAE721462846FFF79CFD48 +:100D0000A5E721462846FFF703FEA0E7B2F8EC501E +:100D10007B6005F103094FEA99094FEA8902D11D69 +:100D2000C908A8EBC1039D46EB460021584600F0D8 +:100D300051FB04F1EE012A463144584600F038FBDD +:100D40007B6813B9012000F0E7FA96F8D20000F0B2 +:100D5000EDFA044630B9307200F008FB204600F08E +:100D6000DBFAB1E0D6F8D4203AB996F8D200B6F85A +:100D70002C25824201D8FFF703FFD6F8D4202A445D +:100D8000944208D296F8D200B6F82C25013082425F +:100D900001D8FFF7F5FE70685FFA89F2594600F056 +:100DA00021FB08B9C54679E0726896F8D2002A445A +:100DB0007260D6F8D42005EB0209C6F8D49000F092 +:100DC000B5FA814509D396F8D220D6F8D40001327D +:100DD000001B86F8D220C6F8D400FF2D0FD80024BF +:100DE000347200F0C3FA204600F096FA00F064FD79 +:100DF0003D4B188108B9FFF7A3FCC54627E7BB6840 +:100E000096F8D9000AFB0362FB68D2F8E41082F876 +:100E1000E83001F58061C2F8E030C2F8E410FFF775 +:100E2000D5FDFFF723FE96F8D920013202F0030228 +:100E300086F8D920B6E74FF48A7A0AFB02F505F165 +:100E4000EA013144204600F0B5FCF86000287FF448 +:100E5000FEAE3544012285F8E82001F047FCD5F8C4 +:100E6000E020D6ED007ADFED216A801A192838BF1C +:100E7000192040F6B832904228BF1046B8EE677A83 +:100E800007EE900AF8EEE77A67EEA67ADFED186AC9 +:100E9000E7EE267AFCEEE77AC6ED007A96F8D930CE +:100EA000BB60BA6873680AFB02F4321992F8E81062 +:100EB00059B1D2F8E4108B42E8463FF427AF002145 +:100EC00082F8E810C2F8E010C5467368064A9B0A2B +:100ED00001331381BBE600BF9D33002000ED00E02D +:100EE0000400FA05A84400208C230020CDCCCC3D82 +:100EF0006666663FA0330020014B1870704700BF44 +:100F00009823002030B54FF000542B4B22689A42B2 +:100F100085B007D003F0CEF8044620BB002420465D +:100F200005B030BD254B627D25481A70237D0372C4 +:100F30004FF48073C0F8F8314FF40073C0F80C33ED +:100F400000254FF44073C0F820341E49C0F8E45027 +:100F5000C922093000F02CFA2046E022294600F090 +:100F600039FA0124DBE7184A184D136C43F000737B +:100F70001364AA6D164B9A42D0D12B6E013B7E2B87 +:100F8000CCD8144A07CA01AB83E8070018460321EE +:100F900000F060FC6B6D83424FF00003BED12A6D00 +:100FA0008A4201BFAB65054B2A6E1A7003BF0A4B1C +:100FB000EA6D1A601C46B2E79AAD44C5982300203A +:100FC000A8440020160000200038024000660040BF +:100FD0005041A0B0586600401023002037B51A4D8C +:100FE00000F06AFC02236B71184B288119681848BD +:100FF000012201F019FA00230193164B16490093C0 +:101000001648174B4FF4805201F064FE154B1978C7 +:1010100011B1124801F086FE01F068FB0446FFF7AB +:10102000E3FB4FF4C873B0FBF3F202FB130304F5C8 +:10103000167010FA83F00C4B186003F031F808B109 +:101040000F232B8103B030BD8C2300201023002000 +:10105000D8330020F90A00089C230020A433002084 +:10106000FD0B000898230020A03300202DE9F04F4D +:101070002DED028B0FF23829D9E90089834C93B00A +:101080000BAE9FED7E8BFFF7F1FC814FDFF828A2BE +:1010900000230A93ADF834300B9373604FF0000BCC +:1010A0005B468DED008B01250DF11D0207A9384629 +:1010B0008DF81C508DF81DB001F066F99DF81C30BC +:1010C000002B40F0A580204601F034FE06460028A3 +:1010D00045D1704F01F00AFB3B6898423FD301F0C5 +:1010E00005FB8246FFF780FB4FF4C873B0FBF3F2B9 +:1010F00002FB13030AF5167010FA83F03860664F8E +:1011000097F800B0CBF1100ABBF1000F14BF3346C3 +:101110002B465FFA8AFA0EA88DF82830FFF77CFB81 +:10112000BAF1060F28BF4FF0060A0EAB03EB0B0116 +:1011300052460DF1290000F03BF90AAB0393182346 +:1011400002930AF10102554BD2B2CDE90053049249 +:1011500020464CA3D3E9002301F032FE3E7001F09B +:10116000C5FA4F4A4F4D1368C31AB3F57A7F2ED391 +:10117000106001F0BDFA02460B46204601F0B8FEB1 +:10118000204601F0D7FD10B32B7A474E002B14BF39 +:1011900003230223737101F0A9FA0EAF4FF47A739F +:1011A0000122B0FBF3F039463060304600F004FA1B +:1011B000182302933D4B019380B240F25513CDE9C1 +:1011C0000370009342464B46204601F0F9FD2B7A0E +:1011D00093B101F08BFA002607464FF48A7A95F80E +:1011E000D900304400F003000AFB005393F8E820D4 +:1011F00092B30136042EF2D1C82002F0F1FB2B7A13 +:10120000002B7FF43DAF13B0BDEC028BBDE8F08F37 +:10121000DAF8143083F01003CAF81430594610225B +:101220000EA800F0D7F80DF11E0308AA0AA9384647 +:1012300000F026FE96E803000FAB83E803009DF85C +:1012400034308DF844300A9B0E930EA9DDE9082353 +:10125000204602F021F821E7D3F8E02042B12B68C4 +:10126000FA2B38BFFA23BA1A0533B2EB430FC0D3B7 +:10127000FFF7ACFB0028BCD1BEE700BF00000000B8 +:1012800000000000401DA12026812A0BA43300206D +:10129000D8330020A03300209D3300209C33002051 +:1012A000D8490020A84400208C230020DC490020DD +:1012B000F1C6A7C1D068080F0008024008B505486C +:1012C00000F078FEBDE80840034A0449002003F01E +:1012D000F9B900BFD8330020184A0020C50B000818 +:1012E0007047000070B502F023FD094E094D3080B3 +:1012F000002428683388834208D902F013FD2B6844 +:1013000004440133B4F5803F2B60F2D370BD00BFBD +:101310000C4A0020E049002002F0B8BD00F1006056 +:10132000920000F5803002F049BD0000054B1A68BC +:10133000054B1B889B1A834202D9104402F0F2BC71 +:1013400000207047E04900200C4A0020024B1B6837 +:10135000184402F0EFBC00BFE0490020024B1B68BC +:10136000184402F0FFBC00BFE0490020064991F894 +:10137000243033B10023086A81F824300822FFF7B3 +:10138000CDBF0120704700BFE4490020022802BF02 +:10139000014B10229A61704700080240022802BFE8 +:1013A000024B4FF480129A61704700BF0008024060 +:1013B00010B50023934203D0CC5CC4540133F9E749 +:1013C00010BD000003460246D01A12F9011B002985 +:1013D000FAD1704702440346934202D003F8011B3E +:1013E000FAE770472DE9F8431F4D144695F824207D +:1013F0000746884652BBDFF870909CB395F82430BE +:101400002BB92022FF2148462F62FFF7E3FF95F812 +:101410002400C0F10802A24228BF2246D6B24146AB +:10142000920005EB8000FFF7C3FF95F82430A41B62 +:101430001E44F6B2082E17449044E4B285F82460A6 +:10144000DBD1FFF793FF0028D7D108E02B6A03EB2D +:1014500082038342CFD0FFF789FF0028CBD1002041 +:10146000BDE8F8830120FBE7E44900202DE9F047BF +:101470000D46044600219046284640F27912FFF7B7 +:10148000A9FF234620220021284601F0A7FE231DA4 +:1014900002222021284601F0A1FE631D0322222101 +:1014A000284601F09BFEA31D03222521284601F0BA +:1014B00095FE04F1080310222821284601F08EFE33 +:1014C00004F1100308223821284601F087FE04F1B8 +:1014D000110308224021284601F080FE04F1120386 +:1014E00008224821284601F079FE04F11403202245 +:1014F0005021284601F072FE04F1180340227021A9 +:10150000284601F06BFE04F120030822B021284692 +:1015100001F064FE04F121030822B821284601F0FD +:101520005DFE04F12207C0263B46314608222846CC +:10153000083601F053FEB6F5A07F07F10107F3D19D +:1015400004F1320308223146284601F047FE002705 +:1015500004F1330A94F832304FEAC7099F4209F583 +:10156000A47615D3B8F1000F08D1314604F599736C +:101570000722284601F032FE09F24F16274694F85A +:1015800032213B1B93420CD3F01DC008BDE8F0870D +:101590000AEB070308223146284601F01FFE0137F7 +:1015A000D8E707F2331331460822284601F016FE29 +:1015B00008360137E3E7000013B50446084600216A +:1015C00001602346C0F803102022019001F006FEBE +:1015D0000198231D0222202101F000FE0198631DC5 +:1015E0000322222101F0FAFD0198A31D03222521E7 +:1015F00001F0F4FD019804F108031022282101F004 +:10160000EDFD072002B010BDF7B50023047F009167 +:101610000E4607221946054601F0A4FC731C0093F0 +:10162000012200230721284601F09CFCC4B9B31C09 +:101630000093052223460821284601F093FC0D243F +:101640003746B278BB1B934211D32B7FA88A07344D +:10165000E408BBB9844294BF0020012003B0F0BD70 +:10166000AB8ADB00083BDB08B3700824E8E7FB1C0F +:101670000093214600230822284601F073FC083419 +:101680000137DEE7201A18BF0120E7E7F7B500238E +:10169000047F00910E4608221946054601F062FCBF +:1016A000731CC4B90822009311462346284601F052 +:1016B00059FC1024012372785F1C013B934211D323 +:1016C0002B7FA88A0734E408BBB9844294BF00206A +:1016D000012003B0F0BDAB8ADB00083BDB08737070 +:1016E0000824E7E7F319009321460023082228463F +:1016F00001F038FC08343B46DDE7201A18BF012012 +:10170000E7E70000F8B50E460546144600218122A1 +:101710003046FFF75FFE2B4608220021304601F0DD +:101720005DFD7CB96B1C07220821304601F056FD97 +:101730000F2401236A785F1C013B934204D3E01D10 +:10174000C008F8BD0824F4E7EB192146082230460A +:1017500001F044FD08343B46ECE70000F8B50E46C6 +:10176000054614460021CE223046FFF733FE2B46B5 +:1017700028220021304601F031FD7CB905F1080333 +:1017800008222821304601F029FD30242F462A7AEC +:101790007B1B934204D3E01DC008F8BD2824F5E765 +:1017A00007F1090321460822304601F017FD0834ED +:1017B0000137ECE7F7B5047F00910E4601231022B4 +:1017C0000021054601F0CEFBC4B9B31C00930922E9 +:1017D00023461021284601F0C5FB1924374672889C +:1017E000BB1B9A4211D82B7FA88A0734E408BBB9E7 +:1017F000844294BF0020012003B0F0BDAB8ADB001F +:10180000103BDB0873801024E8E73B1D0093214662 +:1018100000230822284601F0A5FB08340137DEE743 +:10182000201A18BF0120E7E730B5094D0A4491425C +:101830000DD011F8013B5840082340F30004013B50 +:101840002C4013F0FF0384EA5000F6D1EFE730BDDF +:101850002083B8EDF7B54FF0FF33DFF854C0DFF861 +:1018600054E000EB81011A4688421CD050F8044B2A +:10187000019401AF042417F8015B82EA0562082590 +:10188000DB18164605F1FF355241002EBCBF83EA36 +:101890000C0382EA0E0215F0FF05F1D1013C14F0B1 +:1018A000FF04E8D1E0E7D843D14303B0F0BD00BF67 +:1018B0009336EAA9EBE1F042F7B5384A106851686F +:1018C0006B4603C36A4636493648082302F05AFF7E +:1018D0000446002833D10A25334A106851686B4604 +:1018E00003C36A4631492F48082302F04BFF0446E0 +:1018F000002849D00369B3F5702F45D8B0F86610B9 +:1019000041F2727291423FD1294A024402F15C01D4 +:101910008B4239D35C3B234900209E1AFFF784FF9A +:101920003246074604F164010020FFF77DFFA368FB +:101930009F4229D1E368984208BF002524E003694B +:10194000B3F5702F27D8418B41F27272914220D1AA +:10195000174A024402F110018B4218D3103B11497F +:1019600000209D1AFFF760FF2A46064604F1180181 +:101970000020FFF759FFA3689E4202D1E368984216 +:1019800001D00D25A8E70025284603B0F0BD10259D +:10199000A2E70C25A0E70B259EE700BF70480008D2 +:1019A000DCFF0E00000001087948000890FF0E00DF +:1019B0000800FFF710B5037C044613B9006802F075 +:1019C000C9FE204610BD00000023BFF35B8FC3603B +:1019D000BFF35B8FBFF35B8F8360BFF35B8F704799 +:1019E000BFF35B8F0068BFF35B8F704770B5054630 +:1019F0000C30FFF7F5FF05F1080604463046FFF707 +:101A0000EFFFA04206D930466D68FFF7E9FF254495 +:101A1000281A70BD3046FFF7E3FF201AF9E70000EF +:101A200070B50546406898B105F10800FFF7D8FF8A +:101A300005F10C0604463046FFF7D2FF84423046DB +:101A400094BF6D680025FFF7CBFF013C2C44201AA2 +:101A500070BD000038B50C460546FFF7C7FFA04231 +:101A600010D305F10800FFF7BBFF04446868B4FB1E +:101A7000F0F100FB1144BFF35B8F0120AC60BFF3BA +:101A80005B8F38BD0020FCE72DE9F0411446074686 +:101A90000D46FFF7C5FF844228BF0446D4B1B846BF +:101AA00058F80C6B4046FFF79BFF304428604046D7 +:101AB0007E68FFF795FF331A9C4203D86C600120C3 +:101AC000BDE8F0816B60A41B3B68AB602044E8601C +:101AD0000220F5E72046F3E738B50C460546FFF748 +:101AE0009FFFA04210D305F10C00FFF779FF0444DB +:101AF0006868B4FBF0F100FB1144BFF35B8F012079 +:101B0000EC60BFF35B8F38BD0020FCE72DE9FF419F +:101B1000884669460746FFF7B7FF6C4606B204EBF6 +:101B2000C6060025B44209D06268206808EB0501AA +:101B3000FFF73EFC636808341D44F3E72946384646 +:101B4000FFF7CAFF284604B0BDE8F081F8B50546A6 +:101B50000C300F46FFF744FF05F1080604463046F7 +:101B6000FFF73EFFA042304688BF6C68FFF738FFA2 +:101B7000201A386020B130462C68FFF731FF20442E +:101B8000F8BD000073B5144606460D46FFF72EFF5C +:101B9000844228BF04460190DCB101A93046FFF71A +:101BA000D5FF019B33B93268C5E90233C5E900248A +:101BB00001200CE09C4238BF0194286001986860C5 +:101BC0008442F5D93368AB60241AEC60022002B07D +:101BD00070BD2046FBE700002DE9FF410F46694636 +:101BE000FFF7D0FF6C4600B204EBC0050026AC4204 +:101BF00009D0D4F8048054F8081BB8194246FFF7FE +:101C0000D7FB4644F3E7304604B0BDE8F08100005E +:101C100038B50546FFF7E0FF044601462846FFF7C2 +:101C200019FF204638BD0000302383F3118862B6C7 +:101C300070470000002383F3118862B670470000EC +:101C400010B4026854681A4623465DF8044B1847DE +:101C50000120704700207047002070477047000047 +:101C6000002070470E20704700F5805090F8C800A3 +:101C7000C0F340007047000000F5805090F9C900A3 +:101C800070470000F7B50C68BDF8207014F00054E0 +:101C90001E466FD10B7B082B6CD8FFF7C5FF45693B +:101CA000AB685B010CD4AB681B0108D4AC6814F0C2 +:101CB00080545DD1FFF7BEFF204603B0F0BD012484 +:101CC0000B6804F1180C002BB8BFDB004FEA0C1CAA +:101CD000B4BF43F004035B0545F80C300B680FFA02 +:101CE00084FC13F0804F18BF05EB0C1E05EB0C1C99 +:101CF0001EBFDEF8803143F00203CEF880310B7B4B +:101D0000CCF8843105EB04158B68C5F88C314B6831 +:101D1000C5F88831DCF8803143F00103CCF880311C +:101D200000EB441541F268031D4403EB44130344E4 +:101D3000C5E9002608330D4601F10C0C55F804EBFB +:101D400043F804EB6545F9D184342D881D8000EB00 +:101D5000441407F00303257925F00B052B43237169 +:101D6000FFF768FF0097334600F0E2FC0120A4E78C +:101D70000224A5E74FF0FF309FE7000013B500F500 +:101D800080540191E06DFFF74BFE1F280AD901999D +:101D9000E06D2022FFF7BAFEA0F12003584258411F +:101DA00002B010BD0020FBE708B500F58050FFF73A +:101DB0003BFFC06DFFF708FEBDE80840FFF73ABFE4 +:101DC00000220260828142608260704710B500226A +:101DD0000023C0E900230023044603810C30FFF7F1 +:101DE000EFFF204610BD0000F0B5054600F580501D +:101DF0000C4690F8C83013F0040FC3F3800108BFFD +:101E0000114661F3820304F1840680F8C83005EBC3 +:101E1000461389B01B79D8072ED57AB319072DD46C +:101E20006846FFF7D3FF05EB441303F5835303F133 +:101E3000180703AA103318685968144603C40833F6 +:101E4000BB422246F7D1186820609B88A380DDE959 +:101E50000E23CDE900230123ADF808302B68694635 +:101E6000DB6B2846984705EB46152B791A075CBFB4 +:101E700043F008032B7101E0002AF4D109B0F0BD52 +:101E80002DE9F047074688B007F5805468469A4622 +:101E90008846FFF7C9FE9146FFF798FFE06DFFF710 +:101EA000A5FD1F2829D9E06D20226946FFF7B0FE65 +:101EB000202822D103AD444605AB2E4603CE9E42D8 +:101EC00020606160354604F10804F6D13068206076 +:101ED000B388A380DDE90023C9E90023BDF80830F9 +:101EE000AAF80030FFF7A6FE4A4653464146384658 +:101EF00008B0BDE8F04700F009BCFFF79BFE0020EA +:101F000008B0BDE8F08700002DE9F84F0023C0E9D4 +:101F10000133254B044640F8183B0F46FFF750FFAE +:101F200004F12800FFF752FF04F1480804F5825538 +:101F30004646083530462036FFF748FFAE42F9D115 +:101F400004F580554FF480534FF00009C5E913396B +:101F5000C5F848800123EE6504F5875804F58456DA +:101F6000C5F8549085F8583085F86030083608F187 +:101F700008084FF0000A4FF0000B46E908ABA6F145 +:101F80001800FFF71DFF203646F8289C4645F4D17F +:101F900085F8C97017B1054800F0A2FB044B6361D6 +:101FA0002046BDE8F88F00BFAC4800088448000810 +:101FB0000064004010B5044B197804464A1C1A709E +:101FC000FFF7A2FF204610BD144A00202DE9F0477C +:101FD000002950D0294B2A4FB7FBF1F599428CBF0D +:101FE0000A231123581EB5FBF3FC03FB1C53C4B298 +:101FF0002BB102280346F5D80020BDE8F0870CF18C +:10200000FF36B6F5806FF7D2C4EBC40E0EF10303B2 +:102010004FEAE309C3F3C703A4EB030809F1010A7C +:102020004FF47A755FFA88F009FB05555AFA88F87B +:10203000B5FBF8F5B5F5617FC1BF0EF1FF33C3F312 +:10204000C703E01AC0B25C1C50FA84F40CFB04F421 +:10205000B7FBF4F4A142CFD1013BDBB20F2BCBD8BD +:102060000138C0B20728C7D80021107116809170BE +:10207000D3700120C1E70846BFE700BF3F420F0011 +:1020800080DE800270B505460E464FF47A746B69A7 +:102090005B6803F00103B34207D04FF47A7001F09C +:1020A0009FFC013CF3D1204670BD0120FCE70000FD +:1020B00030B54269936913F0700F16D000230B4CB2 +:1020C000936103F1840200EB421211794D0709D5A7 +:1020D000890707D5416954F823508D60117941F083 +:1020E000040111710133032BEBD130BD9848000876 +:1020F00073B51D46436916469A68D207044609D54A +:102100009A6801219960C2F34002CDE9006500217F +:10211000FFF76AFE63699A68D1050BD59A684FF498 +:1021200080719960C2F34022CDE90065012120460B +:10213000FFF75AFE63699A68D2030BD59A684FF489 +:1021400080319960C2F34042CDE90065022120460A +:10215000FFF74AFE204602B0BDE87040FFF7A8BF77 +:10216000F8B50446466900296CD106F10C073868B9 +:1021700080076AD006EB01153868D5F8B00110F079 +:10218000040FD5F8B0011ABFC00840F00040400D60 +:10219000A061D5F8B0C11CF0020F1CBF40F0804018 +:1021A000A061D5F8B40106EB011100F00F0084F82E +:1021B0002400D1F8B8012077D1F8B801000A60777F +:1021C000D1F8B801000CA077D1F8B801000EE07783 +:1021D000D1F8BC0184F82000D1F8BC01000A84F8D1 +:1021E0002100D1F8BC01000C84F82200D1F8BC1108 +:1021F000090E84F823103821396004F1340004F109 +:10220000180104F1240551F8046B40F8046BA9424D +:10221000F9D109880180C4E90A23214600232386D5 +:1022200051F8283B2046DB6B984704F58052204646 +:1022300092F8C83043F0040382F8C830BDE8F84093 +:10224000FFF736BF06F1100791E7F8BD10B5044659 +:1022500000F04EFA02460B4652EA030102D0013A60 +:1022600063F100030449086820B12146BDE810402D +:10227000FFF776BF10BD00BF104A0020F8B500F58B +:1022800083511E46FFF7D0FCDFF844C0083100241C +:1022900004F1840500EB45152B795F070ED4DB06AE +:1022A0000CD5D1E900739742B34107D243695CF87A +:1022B00024709F602B7943F004032B710134032CAD +:1022C00001F12001E4D1BDE8F840FFF7B3BC00BF45 +:1022D0009848000808B5FFF7A7FCFFF7E9FEBDE83E +:1022E0000840FFF7A7BC0000F8B5436905469868A9 +:1022F00000F0E050B0F1E05F0F461FD0E8B1FFF70B +:1023000093FC05F583541034002606F1840305EB95 +:1023100043131B791A0706D50136032E04F1200456 +:10232000F3D1012007E05B07F6D42146384600F0E0 +:1023300039FA0028F0D1FFF77DFCF8BD0120FCE759 +:1023400000F5805008B5FFF76FFCC06DFFF74EFB3E +:10235000FFF770FC43090CBF0120002008BD0000FE +:10236000F8B51D46002313700F4606461446FFF7C6 +:10237000E7FF80F00100387025B129463046FFF7AD +:10238000B3FF2070F8BD00002DE9B8410C4615469A +:102390001F46804600F0ACF90B462178024609B989 +:1023A000287850B14046FFF769FFFFF793FF3B469F +:1023B0002A462146FFF7D4FF0120BDE8B88100007E +:1023C00010B5FFF731FC174B1A6C42F000721A641B +:1023D0001A6A42F000721A621A6A00F5805422F0FA +:1023E00000721A62FFF726FC94F8C830DB0718D495 +:1023F000B9B103211320FFF717FC01F0C7F903213E +:10240000142001F0C3F90321152001F0BFF994F85D +:10241000C83043F0010384F8C830BDE81040FFF72E +:1024200009BC10BD003802402DE9F04700F5805589 +:1024300088B095F8C930012B0446884616467FD8E7 +:10244000804F57F823200AB947F82300D7F800A097 +:10245000C4F80C802674BAF1000F63D095F8C93027 +:10246000012B6FD001212046FFF7AAFFFFF7DCFB0D +:102470006269136823F0020313606269136843F012 +:1024800001031360636900275F6101212046FFF7A4 +:10249000D1FBFFF7F7FD002800F09580E86DFFF70E +:1024A00093FA04F58359BA4609F10809202200215C +:1024B0006846FEF78FFF02A8FFF782FCCDF818A050 +:1024C0006A4609EB07030DF1180E9446BCE80300B9 +:1024D000F44518605960624603F10803F5D1DCF851 +:1024E0000000186020379CF804201A71602FDDD19D +:1024F00095F8C8306FF38203002785F8C8306A4624 +:1025000041462046ADF80070ADF802708DF80470B9 +:10251000FFF75CFD636948BB4FF400421A6008B0E6 +:10252000BDE8F08741F2D00002F0D4F8814610B146 +:102530005146FFF7E9FCC7F80090B9F1000F8DD1C3 +:102540000020ECE7386803681B6B984701460028B9 +:1025500088D13868FFF734FF3868036832465B6813 +:102560004146984700287FF47DAFE9E761221A6071 +:102570009DF802309DF803201B06120402F470221D +:1025800003F040731343BDF80020C2F30902134364 +:102590009DF804201205022E02F4E0020CBF4FF059 +:1025A00000410021134362690B43D3616369132225 +:1025B0005A616269136823F00103136039462046AB +:1025C000FFF760FD08B96369A6E795F8C93093BBCA +:1025D0006169D1F8002242F00102C1F8002261696C +:1025E000D1F8002222F47C5222F00E02C1F800221F +:1025F0006169D1F8002242F46062C1F80022626988 +:10260000C2F814326269C2F80432626941F6FF719D +:10261000C2F80C126269C2F840326269C2F84432F0 +:1026200063690122C3F81C226269D2F8003223F0E8 +:102630000103C2F8003295F8C83043F0020385F870 +:10264000C8306CE7104A002008B500F051F850EA95 +:102650000103024602D0421E61F10001044B1868DA +:1026600010B10B46FFF744FDBDE8084001F064B827 +:10267000104A002008B50020FFF7E8FDBDE808403B +:1026800001F05AB808B50120FFF7E0FDBDE80840A9 +:1026900001F052B800B59BB0EFF30981682268469B +:1026A000FEF786FEEFF30583014B9B6BFEE700BF51 +:1026B00000ED00E008B5FFF7EDFF000000B59BB0AE +:1026C000EFF3098168226846FEF772FEEFF3058397 +:1026D000014B5B6BFEE700BF00ED00E0FEE7000092 +:1026E0000FB408B5029801F011F9FEE701F024BC1F +:1026F00001F0FCBB13B56C4684E80600031D94E8AA +:10270000030083E80500012002B010BD73B58568A1 +:10271000019155B11B885B0707D4D0E900369B6B4C +:102720009847019AC1B23046A847012002B070BD57 +:10273000F0B5866889B005460C465EB1BDF8383004 +:102740005B070AD4D0E900379B6B98472246C1B299 +:102750003846B047012009B0F0BD00220023CDE982 +:1027600000230023ADF808300A4603AB01F1080648 +:10277000106851681C4603C40832B2422346F7D1A0 +:10278000106820609288A280FFF7B2FF0423ADF8A2 +:1027900008302B68CDE90001DB6B69462846984775 +:1027A000D8E7000030B503680968DD0FB5EBD17FCD +:1027B00023F0604421F060424FEAD1700BD0002B2F +:1027C000B8BFA40C0029B8BF920C944202D034BF09 +:1027D0000120002030BD944205D1C1F38070C3F3C5 +:1027E00080738342F6D194422CBF00200120F1E790 +:1027F0002DE9F041456A15B94162BDE8F0814B68A9 +:1028000023F06047C3F38A464FEAD37EC3F3807850 +:1028100016EA230638BF3E46AC462B465A68BEEB46 +:10282000D27F22F060440AD0002A18DAA40CB44205 +:1028300017D19D420FD10D60DEE71346EEE7A742A8 +:1028400007D102F08044C2F3807242450BD054B1EC +:10285000EFE708D2EDE7CCF800100B60CDE7B4420B +:1028600001D0B442E5D81A689C46002AE5D1196027 +:10287000C3E700002DE9F047089D01F007044FEA87 +:10288000D508224405F0070500EBD1004FF47F493D +:10289000944201D1BDE8F08704F0070705F0070A6C +:1028A00057453E4638BF5646C6F10806111B8E42B4 +:1028B00028BF0E46E10808EBD50E415C13F80EC0A8 +:1028C000B94029FA06F721FA0AF1FFB28CEA0101B0 +:1028D00047FA0AF739408CEA010C03F80EC0344479 +:1028E0003544D5E780EA0120082341F2210201B2F4 +:1028F0004000002980B203F1FF33B8BF504013F00D +:10290000FF03F4D17047000038B50C468D18A5427E +:1029100000D138BD14F8011BFFF7E4FFF7E7000012 +:1029200042684AB1136843604389818901339BB28D +:102930009942438138BF83811046704770B588B093 +:10294000202204460D4668460021FEF743FD20463E +:102950000495FFF7E5FF024658B16B46054608AE01 +:102960001C4603CCB44228606960234605F1080583 +:10297000F6D1104608B070BD082817D909280CD028 +:102980000A280CD00B280CD00C280CD00D280CD009 +:102990000E2814BF4020302070470C2070471020B4 +:1029A000704714207047182070472020704700009F +:1029B000082817D90C280CD910280CD914280CD9A0 +:1029C00018280CD920280CD930288CBF0F200E20B5 +:1029D0007047092070470A2070470B2070470C2071 +:1029E00070470D20704700002DE9F843078C072F32 +:1029F00004461ED9D0E9029800254FF6FF73C5F1B1 +:102A00002006A5F1200029FA05F108FA06F628FAB1 +:102A100000F031430143C9B21846FFF763FF0835A0 +:102A2000402D0346EBD1E1693A46BDE8F843FFF794 +:102A30006BBF4FF6FF70BDE8F883000010B54B6820 +:102A400023B9CA8A63F30902CA8210BD04691A68ED +:102A50001C600361C38A013BC3824A60EFE7000048 +:102A60002DE9F84F1D46CB8A0F46C3F3090105290E +:102A7000814692460B4630D00020AAB207F11A04D4 +:102A80009EB2042E1FFA80F80FD8904503F101037F +:102A900006D3FB8A0A4462F30903FB8201201AE091 +:102AA0001AF80060E6540130EAE79045F1D2A1F14E +:102AB000050B1C237C68BBFBF3F203FB12BB1FFA64 +:102AC0008BF6002C45D14846FFF72AFF044638B95B +:102AD00078606FF00200BDE8F88F4FF00008E6E77D +:102AE000002606607860ADB24FF0000B454510D966 +:102AF0000AEB0803221D13F8011B9155B1B208F12E +:102B000001081B291FFA88F82BD0454506F101065C +:102B1000F1D8FB8AC3F30902154465F30903BCE746 +:102B2000013292B21C462368002BF9D16B1F0B4473 +:102B30001C21B3FBF1F301339BB29A42D3D2BBF118 +:102B4000000FD0D14846FFF7EBFE20B9C4F800B023 +:102B5000BFE70122E7E7C0F800B05E462060044608 +:102B6000C1E74545D5D94846FFF7DAFE08B92060E8 +:102B7000AFE7C0F800B0002620600446B6E70000CA +:102B80002DE9F04F2DED028B1C4683B05B6901925D +:102B900007468846002B00F09A80238C2BB1E2690F +:102BA000002A00F09480072B35D807F10C00FFF7BE +:102BB000B7FE054638B96FF00205284603B0BDECF4 +:102BC000028BBDE8F08F14220021FEF703FC228C5B +:102BD000E16905F10800FEF7EBFB208C013080B2C3 +:102BE000FFF7E6FEFFF7C8FE013880B2208401300F +:102BF00028746369228C1B782A4403F01F0363F056 +:102C00003F0348F000411372384669602946FFF7D8 +:102C1000EFFD0125D1E700F10C034FF0000908EEAC +:102C2000103A4FF0800A4E464D4618EE100AFFF754 +:102C300077FE83460028BED014220021FEF7CAFB8F +:102C4000002E3AD1019BABF8083002220BF1080E9E +:102C50001FFA82FC0CF10100BCF1060F218C80B23E +:102C600001D88E422BD3FFF7A3FEFFF785FE6269E2 +:102C70001278013802F01F028E4208BF4FF0400A5E +:102C800042EA49121BFA80F14AEA020A013048F08E +:102C9000004281F808A08BF81000CBF804205946B8 +:102CA0003846FFF7A5FD238C0135B3422DB289F0DC +:102CB00001094FF0000AB8D17FE70022C6E7E169B9 +:102CC000895D0EF802100136B6B20132C0E76FF02E +:102CD000010572E7F8B515460E463022002104467C +:102CE0001F46FEF777FB069B6360B5F5001F079B49 +:102CF000A76034BF6A094FF6FF72A36297B2E6611C +:102D000004F1100000239A4206D800230360A78232 +:102D1000E3822383E360F8BD06600133304620364A +:102D2000F1E7000003781BB94BB2002BC8BF01705C +:102D30007047000000787047F8B50C46C96907462F +:102D400011B9238C002B37D1257E1F2D34D838782C +:102D500028BB228C072A2CD8268A36F003032BD1D5 +:102D60004FF6FF70FFF7D0FD20F001003102400464 +:102D700041EA0561400C41EA40254FF6FF722346C7 +:102D800029463846FFF7FCFE002807DD6269137804 +:102D90000133DBB21F2B88BF00231370F8BD218ADB +:102DA0002D0645EA012505432046FFF71DFE024694 +:102DB000E5E76FF00300F1E76FF00100EEE70000D8 +:102DC00070B58AB0044616460021282268461D4682 +:102DD000FEF700FBBDF83830ADF810300F9B0593BF +:102DE0009DF840308DF81830119B07936946BDF867 +:102DF0004830ADF820302046CDE90265FFF79CFF52 +:102E00000AB070BD2DE9F041D36905460C4616465F +:102E10000BB9138C5BBB377E1F2F28D895F8008029 +:102E2000B8F1000F26D03046FFF7DEFD33782102DF +:102E300041EAC33141EA0801338A41EA076141EAC4 +:102E400003410246334641F080012846FFF798FED1 +:102E500000280ADD3378012B07D17269137801331A +:102E6000DBB21F2B88BF00231370BDE8F0816FF029 +:102E70000100FAE76FF00300F7E70000F0B58BB050 +:102E800004460D4617460021282268461E46FEF7D6 +:102E9000A1FA9DF84C305A1E534253418DF8003030 +:102EA0009DF84030ADF81030119B05939DF84830E7 +:102EB0008DF81830149B07936A46BDF85430ADF86E +:102EC000203029462046CDE90276FFF79BFF0BB064 +:102ED000F0BD0000406A00B104307047436A1A68D0 +:102EE000426202691A600361C38A013BC382704770 +:102EF0002DE9F041D0F82080194E14461D46414678 +:102F0000002709B9BDE8F081D1E90223A21A65EBD7 +:102F10000303964277EB03031ED2036A8B420DD163 +:102F2000FFF78CFD036A1B68036203690B60C38AA9 +:102F30000161016A013BC3828846E2E7FFF77EFD3B +:102F40000B68C8F8003003690B60C38A0161013B5C +:102F5000C382D8F80010D4E788460968D1E700BFDB +:102F600080841E002DE9F04F8BB00D46DDF85090A7 +:102F700014469B468046002800F01981B9F1000FE5 +:102F800000F01581531E3F2B00F21181012A03D15D +:102F9000BBF1000F40F00B810023CDE90833B8F8F6 +:102FA0001430B5EBC30F4FEAC30703D300200BB0B7 +:102FB000BDE8F08F2B199F42D8F80C303ABF7F1B29 +:102FC000FFB227461BB9D8F81030002B7AD0272D36 +:102FD0004ED8C5F12806B7424FF000032CBFF6B219 +:102FE0003E4600932946D8F8080008AB3246FFF762 +:102FF00041FCA7EB060A35445FFA8AFAB8F81430A8 +:1030000003F10053053BDB000493D8F80C30039325 +:103010002821039B13B1BAF1000F2CD1D8F810006E +:1030200040B1BAF1000F05D0009608AB5246691ABC +:10303000FFF720FC38B2002FB8D066070AD00AABE1 +:1030400003EBD401624211F8083C02F0070213417D +:1030500001F8083C082C3CD9102C40F2B580202CFB +:1030600040F2B780BBF1000F00F09C80082334E0F1 +:10307000BA460026C2E7049BE02B28BFE023069354 +:103080000B44AB42059314D95A1B03980096924502 +:1030900034BF5246D2B2691A08AB04300792FFF728 +:1030A000E9FB079A1644AAEB020A1544F6B25FFA46 +:1030B0008AFA049B069A05999B1A0493039B1B6842 +:1030C0000393A6E70093D8F8080008AB3A462946D0 +:1030D000AEE7BBF1000F13D00123B4EBC30F6CD0EC +:1030E000082C12D89DF82030621E23FA02F2D50770 +:1030F00006D54FF0FF3202FA04F423438DF8203056 +:103100009DF8203089F8003051E7102C12D8BDF816 +:103110002030621E23FA02F2D10706D54FF0FF32AB +:1031200002FA04F42343ADF82030BDF82030A9F8AA +:1031300000303CE7202C0FD80899631E21FA03F3D6 +:10314000DA0705D54FF0FF3202FA04F40C43089475 +:10315000089BC9F800302AE7402C2BD0DDE9086530 +:10316000611EC4F12102A4F1210326FA01F105FA3E +:1031700002F225FA03F311431943CB0712D50122BA +:10318000A4F12003C4F1200102FA03F322FA01F1B1 +:10319000A240524243EA010363EB430332432B4311 +:1031A000CDE90823DDE90823C9E90023FFE66FF034 +:1031B0000100FCE66FF00800F9E6082CA0D9102CFD +:1031C000B3D9202CEED8C3E7BBF1000FADD002235A +:1031D00083E7BBF1000FBBD004237EE730B5012AA3 +:1031E000144638BF0124402C85B028BF4024002558 +:1031F000012ACDE9025518D81B788DF808306307ED +:103200000AD004AB03EBD405624215F8083C02F087 +:103210000702934005F8083C00910346224600212E +:1032200002A8FFF727FB05B030BD082AE4D9102A11 +:1032300003D81B88ADF80830E1E7202A8DBFD3E919 +:1032400000231B680293CDE90223D8E710B5CB68B1 +:103250001BB98B600B618B8210BD04691A681C60FE +:103260000361C38A013BC382CA60F0E703064CBF17 +:10327000C0F3C0300220704708B50246FFF7F6FFE2 +:10328000022806D15306C2F30F2001D100F003003B +:1032900008BDC2F30740FBE72DE9F04F93B0CDE93D +:1032A00003230A6804461046FFF7E0FF022814BF14 +:1032B000C2F306260026002A0D46824680F2F281DD +:1032C00012F0C04940F0EE81097B002900F0EA814C +:1032D000022803D02378B34240F0E781C2F30463AD +:1032E0000693104602F07F030593FFF7C5FF059B89 +:1032F00029444FEA834848EA0A4848EA4668CE78B3 +:1033000000230022CDE90823F309834648EA000898 +:10331000029367D0059B009302466768534608A94D +:103320002046B847002800F0C381276A4FB94146BC +:1033300004F10C00FFF702FB074690B96FF00200A2 +:1033400054E03B6998450DD03F68002FF9D14146C4 +:1033500004F10C00FFF7F2FA07460028EED0236ACA +:103360003B60276297F817C006F01F08CCF3840C67 +:10337000ACEB08001FFA80FE0028B8BF0EF1200059 +:10338000A8EB0C031FFA83FED7E90221B8BF00B2F5 +:10339000002B0793BEBF0EF120031BB2079352EA26 +:1033A000010338D0039BDFF824E39A1A049B4FF003 +:1033B000000C63EB010196457CEB01032BD36B7B87 +:1033C00097F81AE0734519D1029B002B78D0012899 +:1033D00021DC7868F8B9DFF8F0C2944570EB01039E +:1033E00016D337E0276A27B96FF00C0013B0BDE899 +:1033F000F08F3B699845B5D03F68F4E7B2489042FA +:103400007CEB010301D30020F0E7029B002BFAD0F4 +:10341000079B0F2B17DCFA7DB30002F0030203F0C9 +:103420007C031343FB7539462046FFF707FB6B7B94 +:10343000BB76029B3BB9FB7DC3F38402013262F38E +:103440008603FB75D0E76A7BBB7E9A42DBD1029B89 +:10345000002B35D0B309022B32D0039BBB60049BF9 +:10346000FB60142200210DA8FDF7B4FF039B0A9313 +:10347000049B0B932B1D0C932B7BADF83EB0013BB3 +:10348000DBB2ADF83C30069B8DF84230059B8DF8E1 +:10349000433094F82C308DF840A083F001038DF870 +:1034A00044308DF84180A3680AA920469847FB7DE7 +:1034B000C3F38403013303F01F039B02FB82A2E7E3 +:1034C000FB7DC6F34012B2EBD31F40F0F480C3F390 +:1034D0008403434540F0F280029A2B7BB609002A10 +:1034E0004DD0F2075DD4032B40F2EB80039BBB6011 +:1034F000049BFB602B7BAE1D033BDBB2324639469F +:1035000004F10C00FFF7ACFA00280CDA394620462B +:10351000FFF794FAFB7DC3F38403013303F01F0329 +:103520009B02FB820AE7DDE90884AB883B834FF608 +:10353000FF73C9F12000A9F1200228FA09F104FA69 +:1035400000F0014324FA02F211431846C9B2FFF712 +:10355000C9F909F10809B9F1400F0346E9D1B88268 +:103560002A7B033AD2B23146FFF7CEF9FB7DB8820F +:10357000DA43C2F3C01262F3C713FB7543E786B99F +:103580002E1D013BDBB23246394604F10C00FFF739 +:1035900067FA0028BADB2A7BB88A013AD2B23146F0 +:1035A000E2E7F98AC1F30901013B0429DAB25BD8E9 +:1035B000281D002307F11B069A4208D910F801CBF9 +:1035C00006F801C0013101330529DBB2F4D10399BA +:1035D0000A9104990B91934207F11B010C9138BF9A +:1035E000043379680D9134BF55FA83F300230E93A9 +:1035F000FB8AADF83EB0C3F309031A44069B8DF86D +:103600004230059B8DF8433094F82C30ADF83C20C7 +:1036100083F001038DF8443000238DF840A08DF82D +:1036200041807B602A7BB88A013A291DFFF76CF93B +:103630003B8BB882834203D1A3680AA920469847EE +:1036400020460AA9FFF702FEFB7DBA8AC3F3840372 +:10365000013303F01F039B02FB823B8B9A420CBF9A +:1036600000206FF01000C1E67B68002BAFD0052072 +:1036700001E01C3033461E68002EFAD1091A081DDD +:103680002E1D184401EB090CBCF11B0F5FFA89F3E6 +:103690009DD89A429BD916F8013B00F8013B09F1ED +:1036A0000109EFE76FF00900A0E66FF00A009DE660 +:1036B0006FF00B009AE66FF00D0097E66FF00E00CA +:1036C00094E66FF00F0091E640420F0080841E00E8 +:1036D000EFF3098305494A6B22F001024A6368331C +:1036E00083F30988002383F31188704700EF00E01B +:1036F000302080F3118862B60C4B0D4AD96821F452 +:10370000E0610904090C0A43DA60D3F8FC20094996 +:1037100042F08072C3F8FC200A6842F001020A609D +:103720002022DA7783F82200704700BF00ED00E026 +:103730000003FA05001000E010B5302383F3118870 +:103740000E4B5B6813F4006314D0F1EE103AEFF304 +:103750000984683C4FF08073E361094BDB6B23669F +:1037600084F3098800F090F810B1064BA36110BDF6 +:10377000054BFBE783F31188F9E700BF00ED00E09C +:1037800000EF00E0430600084606000800F1604331 +:1037900003F561430901C9B283F80013012200F067 +:1037A0001F039A4043099B0003F1604303F5614303 +:1037B000C3F880211A60704700230375826803698B +:1037C0001B6899689142FBD25A680360426010609E +:1037D0005860704700230375826803691B68996805 +:1037E0009142FBD85A68036042601060586070478D +:1037F00008B50846302383F311880B7D032B05D0D1 +:10380000042B0DD02BB983F3118808BD8B690022DE +:103810001A604FF0FF338361FFF7CEFF0023F2E71A +:10382000D1E9003213605A60F3E70000FFF7C4BF2C +:10383000054BD9680875186802681A605360012240 +:103840000275D860FCF7E8BE204A002030B50C4B6A +:10385000DD684B1C87B004460FD02B46094A6846EA +:1038600000F050F92046FFF7E3FF009B13B16846D4 +:1038700000F052F9A86907B030BDFFF7D9FFF9E7AA +:10388000204A0020F1370008044B1A68DB68906872 +:103890009B68984294BF002001207047204A002076 +:1038A000084B10B51C68D86822681A605360012262 +:1038B0002275DC60FFF78EFF01462046BDE8104010 +:1038C000FCF7AABE204A0020044B1A68DB68926805 +:1038D0009B689A4201D9FFF7E3BF7047204A002056 +:1038E00038B5074C07490848012300252370656057 +:1038F00000F026FC0223237085F3118838BD00BF39 +:10390000884C0020F0480008204A002008B572B614 +:10391000044B186500F0CEFA00F08CFB024B03223A +:103920001A70FEE7204A0020884C002000F02AB9D7 +:10393000EFF3118020B9EFF30583302282F3118871 +:103940007047000010B530B9EFF30584C4F30804E4 +:1039500014B180F3118810BDFFF7B6FF84F311880E +:10396000F9E700008B60022308618B8208467047EC +:103970008368A3F1840243F8142C026943F8442CB1 +:10398000426943F8402C094A43F8242CC26843F8A2 +:10399000182C022203F80C2C002203F80B2C044AEA +:1039A00043F8102CA3F12000704700BF3106000837 +:1039B000204A002008B5FFF7DBFFBDE80840FFF70D +:1039C00035BF0000024BDB6898610F20FFF730BF66 +:1039D000204A0020302383F31188FFF7F3BF000053 +:1039E00008B50146302383F311880820FFF72EFF26 +:1039F000002383F3118808BD10B503689C68A242B8 +:103A00000CD85C688A600B604C60216059609968D2 +:103A10008A1A9A604FF0FF33836010BD1B68121B37 +:103A2000ECE700000A2938BF0A2170B504460D46AC +:103A30000A26601900F07EFB00F06AFB041BA54219 +:103A400003D8751C2E460446F3E70A2E04D9BDE8B8 +:103A50007040012000F0B4BB70BD0000F8B5144BFD +:103A60000D46D96103F1100141600A2A196982608B +:103A700038BF0A22016048601861A818144600F097 +:103A80004BFB0A2700F044FB431BA342064606D328 +:103A90007C1C281900F04EFB27463546F2E70A2F1A +:103AA00004D9BDE8F840012000F08ABBF8BD00BF92 +:103AB000204A0020F8B506460D4600F029FB0F4AC3 +:103AC000134653F8107F9F4206D12A4601463046DE +:103AD000BDE8F840FFF7C2BFD169BB68441A2C1992 +:103AE00028BF2C46A34202D92946FFF79BFF224656 +:103AF00031460348BDE8F840FFF77EBF204A00206A +:103B0000304A002010B4C0E9032300235DF8044BC1 +:103B10004361FFF7CFBF000010B5194C23699842ED +:103B20000DD0D0E90032816813605A609A680A4467 +:103B30009A60002303604FF0FF33A36110BD23465A +:103B4000026843F8102F53600022026022699A42F3 +:103B500003D1BDE8104000F0E7BA936881680B44D8 +:103B6000936000F0D5FA2269E1699268441AA24292 +:103B7000E4D91144BDE81040091AFFF753BF00BF54 +:103B8000204A00202DE9F047DFF8BC8008F110073B +:103B90002C4ED8F8105000F0BBFAD8F81C40AA6898 +:103BA000031B9A423ED81444D5E900324FF0000975 +:103BB000C8F81C4013605A60C5F80090D8F810305F +:103BC000B34201D100F0B0FA89F31188D5E903318D +:103BD00028469847302383F311886B69002BD8D08F +:103BE00000F096FA6A69A0EB04094A4582460DD2B4 +:103BF000022000F0E5FA0022D8F81030B34208D1D4 +:103C000051462846BDE8F047FFF728BF121A224464 +:103C1000F2E712EB090938BF4A4629463846FFF752 +:103C2000EBFEB5E7D8F81030B34208D01444211A9F +:103C3000C8F81C00A960BDE8F047FFF7F3BEBDE877 +:103C4000F08700BF304A0020204A00200020704743 +:103C5000FEE70000704700004FF0FF3070470000A3 +:103C6000BFF34F8F024AD368DB03FCD4704700BF19 +:103C7000003C024008B5094B1B7873B9FFF7F0FF11 +:103C8000074B1A69002ABFBF064A5A6002F1883200 +:103C90005A601A6822F480621A6008BD904C0020B5 +:103CA000003C02402301674508B50B4B1B7893B9D4 +:103CB000FFF7D6FF094B1A6942F000421A611A68F1 +:103CC00042F480521A601A6822F480521A601A680C +:103CD00042F480621A6008BD904C0020003C024013 +:103CE0000B28F0B516D80C4C0C4923787BB90C4D39 +:103CF0000E460C234FF0006255F8047B46F8042B67 +:103D0000013B13F0FF033A44F6D10123237051F82D +:103D10002000F0BD0020FCE7C44C0020944C0020A3 +:103D2000FC480008014B53F820007047FC4800088D +:103D30000C2070470B2810B5044601D9002010BD97 +:103D4000FFF7CEFF064B53F824301844C21A0BB9C4 +:103D50000120F4E712680132F0D1043BF6E700BF1E +:103D6000FC4800080B2810B5044621D8FFF778FF5F +:103D7000FFF780FF0F4AF323D360C300DBB243F4A5 +:103D8000007343F002031361136943F4803313613A +:103D9000FFF766FFFFF7A4FF074B53F8241000F06E +:103DA00045F9FFF781FF2046BDE81040FFF7C2BF8D +:103DB000002010BD003C0240FC480008F8B512F09D +:103DC0000103144642D18218B2F1016F57D82D4B2E +:103DD0001B6813F0010352D02B4DFFF74BFFF32369 +:103DE000EB60FFF73DFF40F20127032C15D824F0CC +:103DF00001046618244C401A40F20117B1422369AD +:103E000000EB010524D123F001032361FFF74CFFF0 +:103E10000120F8BD043C0430E7E78307E7D12B69B4 +:103E200023F440732B612B693B432B6151F8046BE6 +:103E30000660BFF34F8FFFF713FF03689E42E9D080 +:103E40002B6923F001032B61FFF72EFF0020E0E731 +:103E500023F44073236123693B4323610B882B8048 +:103E6000BFF34F8FFFF7FCFE2D8831F8023BADB258 +:103E7000AB42C3D0236923F001032361E4E7184672 +:103E8000C7E700BF00380240003C0240084908B5BF +:103E90000B7828B11BB9FFF7EDFE01230B7008BDAD +:103EA000002BFCD0BDE808400870FFF7FDBE00BF46 +:103EB000904C002008B54FF400314FF0005000F056 +:103EC000B7F8BDE808404FF480314FF0805000F063 +:103ED000AFB800000846114600F01EBC012000F0FB +:103EE0001BBC0000084600F035BC000070B582B075 +:103EF000FFF71EFD0E4E054600F00AF932689042AB +:103F000037BF0C4A0B49516814682EBFD1E90041F4 +:103F1000013151600419034641F100012846019125 +:103F20003360FFF70FFD0199204602B070BD00BF5E +:103F3000C84C0020D04C002070B582B0FFF7F8FCD0 +:103F4000104E054600F0E4F83268904237BF0E4A42 +:103F50000D49516814682EBFD1E90041013151600B +:103F6000041941F100010346284601913360FFF72F +:103F7000E9FC01994FF47A7200232046FCF738F9E6 +:103F800002B070BDC84C0020D04C002010B50244D7 +:103F9000064BD2B2904200D110BD441C00B253F87F +:103FA000200041F8040BE0B2F4E700BF50280040C5 +:103FB0000F4B30B51C6F240407D41C6F44F40074FD +:103FC0001C671C6F44F400441C670A4C236843F4CC +:103FD000807323600244084BD2B2904200D130BDBE +:103FE000441C00B251F8045B43F82050E0B2F4E7FF +:103FF00000380240007000405028004007B5012200 +:1040000001A90020FFF7C2FF019803B05DF804FB8F +:1040100013B50446FFF7F2FFA04205D0012201A923 +:1040200000200194FFF7C4FF02B010BD70470000EC +:104030007047000070470000074B45F255521A6068 +:1040400002225A6040F6FF729A604CF6CC421A6027 +:10405000024B01221A70704700300040DC4C0020F7 +:10406000034B1B781BB1034B4AF6AA221A60704718 +:10407000DC4C002000300040034B1A681AB9034A98 +:10408000D2F874281A607047D84C002000300240E3 +:10409000024B4FF08072C3F8742870470030024022 +:1040A00008B5FFF7E9FF024B1868C0F3407008BD80 +:1040B000D84C002008B5FFF7DFFF024B1868C0F3AB +:1040C000007008BDD84C002070470000FEE70000DB +:1040D0000A4B0B480B4A90420BD30B4BDA1C121ABB +:1040E000C11E22F003028B4238BF00220021FDF7DF +:1040F00071B953F8041B40F8041BECE7C04A0008F0 +:10410000684D0020684D0020684D002000F0D0B8B8 +:104110004FF08043586A70474FF080430022586345 +:104120001A610222DA6070474FF080430022DA60A1 +:10413000704700004FF0804358637047FEE700006F +:1041400070B51B4B01630025044686B0586085623C +:104150000E46FFF7CDFA04F11003C4E904334FF023 +:10416000FF33C4E90635C4E90044A560E562FFF702 +:10417000CFFF2B460246C4E9082304F134010D4A5F +:10418000256580232046FFF7EDFB0123E0600A4A06 +:104190000375009272680192B268CDE90223074B61 +:1041A0006846CDE90435FFF705FC06B070BD00BFD9 +:1041B000884C00202C490008314900083D41000886 +:1041C000024AD36A1843D062704700BF204A0020D9 +:1041D0004B6843608B688360CB68C3600B69436145 +:1041E0004B6903628B6943620B6803607047000090 +:1041F00008B5264B26481A6940F2FF110A431A6196 +:104200001A6922F4FF7222F001021A611A691A6B0C +:104210000A431A631A6D0A431A651E4A1B6D11463A +:10422000FFF7D6FF02F11C0100F58060FFF7D0FF19 +:1042300002F1380100F58060FFF7CAFF02F1540176 +:1042400000F58060FFF7C4FF02F1700100F58060A7 +:10425000FFF7BEFF02F18C0100F58060FFF7B8FFA9 +:1042600002F1A80100F58060FFF7B2FF02F1C4017E +:1042700000F58060FFF7ACFF02F1E00100F580601F +:10428000FFF7A6FFBDE8084000F08EB800380240F6 +:10429000000002403849000808B500F0F9F9FFF7BE +:1042A0001FFBBDE80840FFF7E7BE000070470000B5 +:1042B0000F4B1A6C42F001021A641A6E42F00102AE +:1042C0001A660C4A1B6E936843F0010393604FF02B +:1042D000804353229A624FF0FF32DA6200229A61E1 +:1042E0005A63DA605A6001225A611A60704700BF4F +:1042F00000380240002004E04FF0804208B5116908 +:10430000D3680B40D9B2C9439B07116107D530234D +:1043100083F31188FFF70AFB002383F3118808BD9C +:104320001F4B1A696FEAC2526FEAD2521A611A69B8 +:10433000C2F308021A614FF0FF301A695A695861D6 +:1043400000215A6959615A691A6A62F080521A62E8 +:104350001A6A02F080521A621A6A5A6A58625A6AD3 +:1043600059625A6A1A6C42F080521A641A6E42F00C +:1043700080521A661A6E0B4A106840F48070106002 +:10438000186F00F44070B0F5007F1EBF4FF480300E +:1043900018671967536823F40073536000F054B929 +:1043A0000038024000700040334B4FF080521A64D6 +:1043B000324A4FF4404111601A6842F001021A601B +:1043C0001A689107FCD59A6822F003029A602A4B7A +:1043D0009A6812F00C02FBD1196801F0F90119601A +:1043E0009A601A6842F480321A601A689203FCD507 +:1043F0005A6F42F001025A671F4B5A6F9007FCD563 +:104400001F4A5A601A6842F080721A601B4A536849 +:104410005904FCD5184B1A689201FCD5194A9A60C8 +:10442000194B1A68194B9A42194B21D1194A116834 +:10443000194A91421CD140F205121A60144A1368BD +:1044400003F00F03052BFAD10B4B9A6842F00202DE +:104450009A609A6802F00C02082AFAD15A6C42F467 +:1044600080425A645A6E42F480425A665B6E7047CC +:1044700040F20572E1E700BF0038024000700040E2 +:104480000854400700948838002004E0116400209C +:10449000003C024000ED00E041C20F41074A08B570 +:1044A000536903F00103536123B1054A13680BB14B +:1044B00050689847BDE80840FFF73EB9003C01400E +:1044C000E04C0020074A08B5536903F0020353612A +:1044D00023B1054A93680BB1D0689847BDE80840FE +:1044E000FFF72AB9003C0140E04C0020074A08B51C +:1044F000536903F00403536123B1054A13690BB1F7 +:1045000050699847BDE80840FFF716B9003C0140E4 +:10451000E04C0020074A08B5536903F008035361D3 +:1045200023B1054A93690BB1D0699847BDE80840AB +:10453000FFF702B9003C0140E04C0020074A08B5F3 +:10454000536903F01003536123B1054A136A0BB199 +:10455000506A9847BDE80840FFF7EEB8003C0140BC +:10456000E04C0020164B10B55C6904F478725A6177 +:10457000A30604D5134A936A0BB1D06A9847600624 +:1045800004D5104A136B0BB1506B9847210604D524 +:104590000C4A936B0BB1D06B9847E20504D5094ADE +:1045A000136C0BB1506C9847A30504D5054A936C66 +:1045B0000BB1D06C9847BDE81040FFF7BDB800BF05 +:1045C000003C0140E04C0020194B10B55C6904F43C +:1045D0007C425A61620504D5164A136D0BB1506DC9 +:1045E0009847230504D5134A936D0BB1D06D9847B6 +:1045F000E00404D50F4A136E0BB1506E9847A10426 +:1046000004D50C4A936E0BB1D06E9847620404D562 +:10461000084A136F0BB1506F9847230404D5054A1D +:10462000936F0BB1D06F9847BDE81040FFF784B887 +:10463000003C0140E04C002008B5FFF75DFEBDE8FE +:104640000840FFF779B80000062108B50846FFF7D3 +:104650009DF806210720FFF799F806210820FFF7AB +:1046600095F806210920FFF791F806210A20FFF7A7 +:104670008DF806211720FFF789F806212820FFF77B +:1046800085F8BDE8084007211C20FFF77FB800002F +:1046900008B5FFF745FE00F007F8FFF707FEBDE895 +:1046A0000840FFF733BD00000023054A19460133D7 +:1046B000102BC2E9001102F10802F8D1704700BFC7 +:1046C000E04C00200B460146184600F02DB80000D3 +:1046D00000F040B8012838BF012010B5044620463C +:1046E00000F030F830B900F007F808B900F00CF825 +:1046F0008047F4E710BD0000024B1868BFF35B8FE2 +:10470000704700BF604D002008B5062000F084F817 +:104710000120FFF79DFA0000024B0A460146186887 +:10472000FFF7D8BB1C23002010B5054C13462CB155 +:104730000A4601460220AFF3008010BD2046FCE788 +:1047400000000000024B01461868FFF7C7BB00BF1E +:104750001C230020024B01461868FFF7C3BB00BFB3 +:104760001C23002010B501390244904201D10020E1 +:1047700005E0037811F8014FA34201D0181B10BDCA +:104780000130F2E72DE9F041A3B1C91A17780144CD +:10479000044603F1FF3C8C42204601D9002009E089 +:1047A0000578BD4204F10104F5D10CEB0405D618DF +:1047B000A54201D1BDE8F08115F8018D16F801ED93 +:1047C000F045F5D0E7E700001F2938B504460D464F +:1047D00004D9162303604FF0FF3038BD426C12B18C +:1047E00052F821304BB9204600F030F82A460146F5 +:1047F0002046BDE8384000F017B8012B0AD0591CFC +:1048000003D1162303600120E7E7002442F8254086 +:10481000284698470020E0E7024B01461868FFF75A +:10482000D3BF00BF1C23002038B5074D002304462A +:10483000084611462B60FFF70FFA431C02D12B6884 +:1048400003B1236038BD00BF644D0020FFF7FEB9FF +:10485000034611F8012B03F8012B002AF9D1704708 +:1048600073772D6E61762D663430352D626C0000C5 +:1048700040A2E4F1646891060041A3E5F265699203 +:10488000070000004261642043414E496661636550 +:1048900020696E6465782E008000000000800000B2 +:1048A000000080000000000000000000411C000823 +:1048B0002924000889230008511C0008851C0008D1 +:1048C000811E0008551C0008651C0008591C0008C2 +:1048D000611C00085D1C0008A91D0008691C000877 +:1048E000F5260008791C00087D1D000863300000D3 +:1048F000EC480008784A0020884C00200040000066 +:1049000000400000004000000040000000000100E6 +:10491000000002000000020000000200000002008F +:104920000000020000000200000002006D61696EDC +:104930000069646C650000005400806A000000009B +:10494000AAAAAA6A00000024F17F0000000000006B +:10495000009009000100000000000000AAAAAAAA15 +:1049600000000000FEFF000000000000000000004A +:104970000001000000000000AAAAAAAA000000008E +:10498000EFFF000000000000000000000000000039 +:1049900000000000AAAAAAAA00000000FFFF000071 +:1049A0000000000000000000000000000000000007 +:1049B000AAAAAAAA00000000FFFF00000000000051 +:1049C000000000000000000000000000AAAAAAAA3F +:1049D00000000000FFFF00000000000000000000D9 +:1049E0000000000000000000AAAAAAAA000000001F +:1049F000FFFF0000000000000000000000000000B9 +:104A0000000000000A000000000000000300000099 +:104A10000000000000000000000000000000000096 +:104A20000000000000000000000000000000000086 +:104A300000000000ECB7FF7F010000000000000054 +:104A4000721700000000000000000F0000000000CE +:104A500040420F00FE2A0100D20400002023002063 +:104A60000000000000000000000000000000000046 +:104A70000000000000000000000000000000000036 +:104A80000000000000000000000000000000000026 +:104A90000000000000000000000000000000000016 +:104AA0000000000000000000000000000000000006 +:104AB00000000000000000000000000000000000F6 +:00000001FF diff --git a/Tools/environment_install/install-prereqs-arch.sh b/Tools/environment_install/install-prereqs-arch.sh index 2681c38d9f32c5..4a1d69b82f9f8f 100755 --- a/Tools/environment_install/install-prereqs-arch.sh +++ b/Tools/environment_install/install-prereqs-arch.sh @@ -50,10 +50,25 @@ function maybe_prompt_user() { fi } -sudo usermod -a -G uucp $USER +sudo usermod -a -G uucp "$USER" -sudo pacman -Sy --noconfirm --needed $BASE_PKGS $SITL_PKGS $PX4_PKGS -pip3 -q install --user -U $PYTHON_PKGS +sudo pacman -Syu --noconfirm --needed $BASE_PKGS $SITL_PKGS $PX4_PKGS + +python3 -m venv "$HOME"/venv-ardupilot + +# activate it: +SOURCE_LINE="source $HOME/venv-ardupilot/bin/activate" +$SOURCE_LINE + +if [[ -z "${DO_PYTHON_VENV_ENV}" ]] && maybe_prompt_user "Make ArduPilot venv default for python [N/y]?" ; then + DO_PYTHON_VENV_ENV=1 +fi + +if [[ $DO_PYTHON_VENV_ENV -eq 1 ]]; then + echo "$SOURCE_LINE" >> ~/.bashrc +fi + +pip3 -q install -U $PYTHON_PKGS ( cd /usr/lib/ccache @@ -78,7 +93,7 @@ exportline="export PATH=$OPT/$ARM_ROOT/bin:\$PATH"; if ! grep -Fxq "$exportline" ~/.bashrc ; then if maybe_prompt_user "Add $OPT/$ARM_ROOT/bin to your PATH [N/y]?" ; then echo "$exportline" >> ~/.bashrc - . ~/.bashrc + . "$HOME/.bashrc" else echo "Skipping adding $OPT/$ARM_ROOT/bin to PATH." fi @@ -88,7 +103,7 @@ exportline2="export PATH=$CWD/$ARDUPILOT_TOOLS:\$PATH"; if ! grep -Fxq "$exportline2" ~/.bashrc ; then if maybe_prompt_user "Add $CWD/$ARDUPILOT_TOOLS to your PATH [N/y]?" ; then echo "$exportline2" >> ~/.bashrc - . ~/.bashrc + . "$HOME/.bashrc" else echo "Skipping adding $CWD/$ARDUPILOT_TOOLS to PATH." fi @@ -96,7 +111,7 @@ fi SCRIPT_DIR=$(dirname $(realpath ${BASH_SOURCE[0]})) ( - cd $SCRIPT_DIR + cd "$SCRIPT_DIR" git submodule update --init --recursive ) diff --git a/Tools/environment_install/install-prereqs-ubuntu.sh b/Tools/environment_install/install-prereqs-ubuntu.sh index b1eea1460d0e14..eea1db11fcb603 100755 --- a/Tools/environment_install/install-prereqs-ubuntu.sh +++ b/Tools/environment_install/install-prereqs-ubuntu.sh @@ -82,8 +82,8 @@ PIP=pip3 if [ ${RELEASE_CODENAME} == 'bionic' ] ; then SITLFML_VERSION="2.4" SITLCFML_VERSION="2.4" - PYTHON_V="python" - PIP=pip2 + PYTHON_V="python3" + PIP=pip3 elif [ ${RELEASE_CODENAME} == 'buster' ]; then SITLFML_VERSION="2.5" SITLCFML_VERSION="2.5" @@ -146,21 +146,13 @@ else fi # Lists of packages to install -BASE_PKGS="build-essential ccache g++ gawk git make wget" -if [ ${RELEASE_CODENAME} == 'bionic' ]; then - # use fixed version for package that drop python2 support - PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect flake8==3.7.9 requests==2.27.1 monotonic==1.6 geocoder empy ptyprocess configparser==4.0.2 click==7.1.2 decorator==4.4.2 dronecan" -else - PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect flake8 geocoder empy ptyprocess dronecan" -fi +BASE_PKGS="build-essential ccache g++ gawk git make wget valgrind screen" +PYTHON_PKGS="future lxml pymavlink pyserial MAVProxy pexpect geocoder empy ptyprocess dronecan" +PYTHON_PKGS="$PYTHON_PKGS flake8" # add some Python packages required for commonly-used MAVProxy modules and hex file generation: if [[ $SKIP_AP_EXT_ENV -ne 1 ]]; then - if [ ${RELEASE_CODENAME} == 'bionic' ]; then - PYTHON_PKGS="$PYTHON_PKGS pygame==2.0.3 intelhex" - else - PYTHON_PKGS="$PYTHON_PKGS pygame intelhex" - fi + PYTHON_PKGS="$PYTHON_PKGS pygame intelhex" fi ARM_LINUX_PKGS="g++-arm-linux-gnueabihf $INSTALL_PKG_CONFIG" # python-wxgtk packages are added to SITL_PKGS below @@ -176,7 +168,7 @@ fi # add some packages required for commonly-used MAVProxy modules: if [[ $SKIP_AP_GRAPHIC_ENV -ne 1 ]]; then if [ ${RELEASE_CODENAME} == 'lunar' ]; then - PYTHON_PKGS+=" matplotlib serial scipy opencv-python pyyaml" + PYTHON_PKGS+=" matplotlib scipy opencv-python pyyaml" SITL_PKGS+=" xterm libcsfml-dev libcsfml-audio${SITLCFML_VERSION} libcsfml-dev libcsfml-graphics${SITLCFML_VERSION} libcsfml-network${SITLCFML_VERSION} libcsfml-system${SITLCFML_VERSION} libcsfml-window${SITLCFML_VERSION} libsfml-audio${SITLFML_VERSION} libsfml-dev libsfml-graphics${SITLFML_VERSION} libsfml-network${SITLFML_VERSION} libsfml-system${SITLFML_VERSION} libsfml-window${SITLFML_VERSION}" else SITL_PKGS="$SITL_PKGS xterm ${PYTHON_V}-matplotlib ${PYTHON_V}-serial ${PYTHON_V}-scipy ${PYTHON_V}-opencv libcsfml-dev libcsfml-audio${SITLCFML_VERSION} libcsfml-dev libcsfml-graphics${SITLCFML_VERSION} libcsfml-network${SITLCFML_VERSION} libcsfml-system${SITLCFML_VERSION} libcsfml-window${SITLCFML_VERSION} libsfml-audio${SITLFML_VERSION} libsfml-dev libsfml-graphics${SITLFML_VERSION} libsfml-network${SITLFML_VERSION} libsfml-system${SITLFML_VERSION} libsfml-window${SITLFML_VERSION} ${PYTHON_V}-yaml" @@ -335,6 +327,7 @@ if $IS_DOCKER; then fi PIP_USER_ARGUMENT="--user" + # create a Python venv on more recent releases: if [ ${RELEASE_CODENAME} == 'lunar' ]; then $APT_GET install python3.11-venv @@ -354,14 +347,12 @@ if [ ${RELEASE_CODENAME} == 'lunar' ]; then fi fi -# Update Pip and Setuptools on old distro -if [ ${RELEASE_CODENAME} == 'bionic' ]; then - # use fixed version for package that drop python2 support - $PIP install --user -U pip==20.3 setuptools==44.0.0 -fi - # try update setuptools and wheel before installing pip package that may need compilation -$PIP install $PIP_USER_ARGUMENT -U setuptools wheel +$PIP install $PIP_USER_ARGUMENT -U pip setuptools wheel + +if [ "$GITHUB_ACTIONS" == "true" ]; then + PIP_USER_ARGUMENT+=" --progress-bar off" +fi if [ ${RELEASE_CODENAME} == 'lunar' ]; then # must do this ahead of wxPython pip3 run :-/ diff --git a/Tools/gittools/pre-commit.py b/Tools/gittools/pre-commit.py index f3647302fd3a62..bed43e06d14720 100755 --- a/Tools/gittools/pre-commit.py +++ b/Tools/gittools/pre-commit.py @@ -17,17 +17,14 @@ class AP_PreCommit(object): - def __init__(self): - pass - @staticmethod def progress(message): - print("***** %s" % (message, )) + print(f"***** {message}") @staticmethod def has_flake8_tag(filepath): - content = open(filepath).read() - return "AP_FLAKE8_CLEAN" in content + with open(filepath) as fp: + return "AP_FLAKE8_CLEAN" in fp.read() def files_are_flake8_clean(self, files_to_check): if files_to_check: @@ -36,7 +33,7 @@ def files_are_flake8_clean(self, files_to_check): try: subprocess.check_output(["flake8"] + files_to_check, stderr=subprocess.STDOUT) except subprocess.CalledProcessError as e: - self.progress("Flake8 check failed: (%s)" % (e.output)) + self.progress(f"Flake8 check failed: ({e.output})") return False return True @@ -44,7 +41,7 @@ def files_are_flake8_clean(self, files_to_check): def split_git_diff_output(output): '''split output from git-diff into a list of (status, filepath) tuples''' ret = [] - if type(output) == bytes: + if isinstance(output, bytes): output = output.decode('utf-8') for line in output.split("\n"): if len(line) == 0: @@ -72,7 +69,7 @@ def run(self): # rename, check destination (status, filepath) = (output_tuple[0], output_tuple[2]) else: - raise ValueError("Unknown status %s" % str(output_tuple[0])) + raise ValueError(f"Unknown status {output_tuple[0]}") else: (status, filepath) = output_tuple if filepath in dirty: diff --git a/Tools/mavproxy_modules/sitl_calibration.py b/Tools/mavproxy_modules/sitl_calibration.py index b1b36ae42bff7f..adeef80945824e 100644 --- a/Tools/mavproxy_modules/sitl_calibration.py +++ b/Tools/mavproxy_modules/sitl_calibration.py @@ -303,7 +303,7 @@ def mavlink_packet(self, m): # this is set to None so we can ensure we don't get # progress reports for completed compasses. self.last_progress[m.compass_id] = None - if len(self.last_progress.values()) and all(progress == None for progress in self.last_progress.values()): + if len(self.last_progress.values()) and all(progress is None for progress in self.last_progress.values()): self.stop() return diff --git a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py index 851ebf7027d930..e365eebaf91351 100755 --- a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py +++ b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py @@ -1,3 +1,4 @@ +#!/usr/bin/env python3 # Copyright 2023 ArduPilot.org. # # This program is free software: you can redistribute it and/or modify diff --git a/Tools/ros2/ardupilot_msgs/CMakeLists.txt b/Tools/ros2/ardupilot_msgs/CMakeLists.txt index 5887179c4eb711..5a56bd31cc3572 100644 --- a/Tools/ros2/ardupilot_msgs/CMakeLists.txt +++ b/Tools/ros2/ardupilot_msgs/CMakeLists.txt @@ -12,6 +12,7 @@ find_package(rosidl_default_generators REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} "srv/ArmMotors.srv" + "srv/ModeSwitch.srv" ADD_LINTER_TESTS ) diff --git a/Tools/ros2/ardupilot_msgs/srv/ArmMotors.srv b/Tools/ros2/ardupilot_msgs/srv/ArmMotors.srv index 79e2db6b0aaa12..671bc30795709e 100644 --- a/Tools/ros2/ardupilot_msgs/srv/ArmMotors.srv +++ b/Tools/ros2/ardupilot_msgs/srv/ArmMotors.srv @@ -4,5 +4,5 @@ # Set true to arm motors, false to disarm motors. bool arm --- -# True if the vehicle is armed. +# True if arming/disarming request for motors was successful , false otherwise. bool result diff --git a/Tools/ros2/ardupilot_msgs/srv/ModeSwitch.srv b/Tools/ros2/ardupilot_msgs/srv/ModeSwitch.srv new file mode 100644 index 00000000000000..7a11e3cf74bc2b --- /dev/null +++ b/Tools/ros2/ardupilot_msgs/srv/ModeSwitch.srv @@ -0,0 +1,15 @@ + +# This service requests the vehicle to switch its drive/flight mode + +# mode : Set the value to the drive/flight mode to be used +# Copter : https://mavlink.io/en/messages/ardupilotmega.html#COPTER_MODE +# Rover : https://mavlink.io/en/messages/ardupilotmega.html#ROVER_MODE +# Plane : https://mavlink.io/en/messages/ardupilotmega.html#PLANE_MODE + +uint8 mode +--- +# status : True if the request for mode switch was successful, False otherwise +# curr_mode : Returns the code for the current drive/flight mode , after the processing the request + +bool status +uint8 curr_mode diff --git a/Tools/ros2/ardupilot_sitl/package.xml b/Tools/ros2/ardupilot_sitl/package.xml index 21ae2dfa2975ed..2c3a375695013e 100644 --- a/Tools/ros2/ardupilot_sitl/package.xml +++ b/Tools/ros2/ardupilot_sitl/package.xml @@ -11,6 +11,8 @@ ament_cmake ament_cmake_python + micro_ros_agent + ament_cmake_pytest ament_lint_auto ament_lint_common diff --git a/Tools/scripts/CAN/fix2_gap.py b/Tools/scripts/CAN/fix2_gap.py index e72d6ccecab6e8..1d2f2dd4840d1c 100755 --- a/Tools/scripts/CAN/fix2_gap.py +++ b/Tools/scripts/CAN/fix2_gap.py @@ -26,7 +26,7 @@ def handle_fix2(msg): nodeid = msg.transfer.source_node_id tstamp = msg.transfer.ts_real - if not nodeid in last_fix2: + if nodeid not in last_fix2: last_fix2[nodeid] = tstamp return dt = tstamp - last_fix2[nodeid] diff --git a/Tools/scripts/apj_tool.py b/Tools/scripts/apj_tool.py index b4482ae5334556..55f6a9496f059c 100755 --- a/Tools/scripts/apj_tool.py +++ b/Tools/scripts/apj_tool.py @@ -108,7 +108,7 @@ def find(self): magic_str = "PARMDEF".encode('ascii') param_magic = [ 0x55, 0x37, 0xf4, 0xa0, 0x38, 0x5d, 0x48, 0x5b ] def u_ord(c): - return ord(c) if sys.version_info.major < 3 else c + return ord(c) if sys.version_info.major < 3 else c while True: i = self.firmware[self.offset:].find(magic_str) diff --git a/Tools/scripts/battery_fit.py b/Tools/scripts/battery_fit.py new file mode 100755 index 00000000000000..9cc17e38783692 --- /dev/null +++ b/Tools/scripts/battery_fit.py @@ -0,0 +1,192 @@ +#!/usr/bin/env python +''' +fit coefficients for battery percentate from resting voltage + +See AP_Scripting/applets/BattEstimate.lua +''' + +from argparse import ArgumentParser +parser = ArgumentParser(description=__doc__) +parser.add_argument("--no-graph", action='store_true', default=False, help='disable graph display') +parser.add_argument("--num-cells", type=int, default=0, help='cell count, zero for auto-detection') +parser.add_argument("--batidx", type=int, default=1, help='battery index') +parser.add_argument("--condition", default=None, help='match condition') +parser.add_argument("--final-pct", type=float, default=100.0, help='set final percentage in log') +parser.add_argument("--comparison", type=str, default=None, help='comparison coefficients') +parser.add_argument("log", metavar="LOG") + +args = parser.parse_args() + +import sys +import math +from pymavlink import mavutil +import numpy as np +import matplotlib.pyplot as pyplot + +def constrain(value, minv, maxv): + """Constrain a value to a range.""" + return max(min(value,maxv),minv) + +def SOC_model(cell_volt, c): + '''simple model of state of charge versus resting voltage. + With thanks to Roho for the form of the equation + https://electronics.stackexchange.com/questions/435837/calculate-battery-percentage-on-lipo-battery + ''' + p0 = 80.0 + p1 = c[2] + return constrain(c[0]*(1.0-1.0/math.pow(1+math.pow(cell_volt/c[1],p0),p1)),0,100) + +def fit_batt(data): + '''fit a set of battery data to the SOC model''' + from scipy import optimize + + def fit_error(p): + p = list(p) + ret = 0 + for (voltR,pct) in data: + error = pct - SOC_model(voltR, p) + ret += abs(error) + + ret /= len(data) + return ret + + p = [123.0, 3.7, 0.165] + bounds = [(100.0, 10000.0), (3.0,3.9), (0.001, 0.4)] + + (p,err,iterations,imode,smode) = optimize.fmin_slsqp(fit_error, p, bounds=bounds, iter=10000, full_output=True) + if imode != 0: + print("Fit failed: %s" % smode) + sys.exit(1) + return p + +def ExtractDataLog(logfile): + '''find battery fit parameters from a log file''' + print("Processing log %s" % logfile) + mlog = mavutil.mavlink_connection(logfile) + + Wh_total = 0.0 + last_t = None + data = [] + last_voltR = None + + while True: + msg = mlog.recv_match(type=['BAT'], condition=args.condition) + if msg is None: + break + + if msg.get_type() == 'BAT' and msg.Instance == args.batidx-1 and msg.VoltR > 1: + current = msg.Curr + voltR = msg.VoltR + if last_voltR is not None and voltR > last_voltR: + continue + last_voltR = voltR + power = current*voltR + t = msg.TimeUS*1.0e-6 + + if last_t is None: + last_t = t + continue + + dt = t - last_t + if dt < 0.5: + # 2Hz data is plenty + continue + last_t = t + Wh_total += (power*dt)/3600.0 + + data.append((voltR,Wh_total)) + + if len(data) == 0: + print("No data found") + sys.exit(1) + + # calculate total pack capacity based on final percentage + Wh_max = data[-1][1]/(args.final_pct*0.01) + + fit_data = [] + + for i in range(len(data)): + (voltR,Wh) = data[i] + SOC = 100-100*Wh/Wh_max + fit_data.append((voltR, SOC)) + + print("Loaded %u samples" % len(data)) + return fit_data + +def ExtractDataCSV(logfile): + '''find battery fit parameters from a CSV file''' + print("Processing CSV %s" % logfile) + lines = open(logfile,'r').readlines() + fit_data = [] + for line in lines: + line = line.strip() + if line.startswith("#"): + continue + v = line.split(',') + if len(v) != 2: + continue + if not v[0][0].isnumeric() or not v[1][0].isnumeric(): + continue + fit_data.append((float(v[1]),float(v[0]))) + return fit_data + +def BattFit(fit_data, num_cells): + + fit_data = [ (v/num_cells,p) for (v,p) in fit_data ] + + c = fit_batt(fit_data) + print("Coefficients C1=%.4f C2=%.4f C3=%.4f" % (c[0], c[1], c[2])) + + if args.no_graph: + return + + fig, axs = pyplot.subplots() + + np_volt = np.array([v for (v,p) in fit_data]) + np_pct = np.array([p for (v,p) in fit_data]) + axs.invert_xaxis() + axs.plot(np_volt, np_pct, label='SOC') + np_rem = np.zeros(0,dtype=float) + + # pad down to 3.2V to make it easier to visualise for logs that don't go to a low voltage + low_volt = np_volt[-1] + while low_volt > 3.2: + low_volt -= 0.1 + np_volt = np.append(np_volt, low_volt) + + for i in range(np_volt.size): + voltR = np_volt[i] + np_rem = np.append(np_rem, SOC_model(voltR, c)) + + axs.plot(np_volt, np_rem, label='SOC Fit') + + if args.comparison: + c2 = args.comparison.split(',') + c2 = [ float(x) for x in c2 ] + np_rem2 = np.zeros(0,dtype=float) + for i in range(np_volt.size): + voltR = np_volt[i] + np_rem2 = np.append(np_rem2, SOC_model(voltR, c2)) + axs.plot(np_volt, np_rem2, label='SOC Fit2') + + axs.legend(loc='upper left') + axs.set_title('Battery Fit') + + pyplot.show() + +def get_cell_count(data): + if args.num_cells != 0: + return args.num_cells + volts = [ v[0] for v in data ] + volts = sorted(volts) + num_cells = round(volts[-1]/4.2) + print("Max voltags %.1f num_cells %u" % (volts[-1], num_cells)) + return num_cells + +if args.log.upper().endswith(".CSV"): + fit_data = ExtractDataCSV(args.log) +else: + fit_data = ExtractDataLog(args.log) + +num_cells = get_cell_count(fit_data) +BattFit(fit_data, num_cells) diff --git a/Tools/scripts/build_binaries.py b/Tools/scripts/build_binaries.py index f340dc7f661f71..4d0c1c02f2bc27 100755 --- a/Tools/scripts/build_binaries.py +++ b/Tools/scripts/build_binaries.py @@ -664,6 +664,7 @@ def generate_manifest(self): generator.run() generator.write_manifest_json(os.path.join(self.binaries, "manifest.json")) + generator.write_features_json(os.path.join(self.binaries, "features.json")) self.progress("Manifest generation successful") self.progress("Generating stable releases") diff --git a/Tools/scripts/build_bootloaders.py b/Tools/scripts/build_bootloaders.py index 2cd9e07dfe5c63..2a44ce96948282 100755 --- a/Tools/scripts/build_bootloaders.py +++ b/Tools/scripts/build_bootloaders.py @@ -9,12 +9,14 @@ import subprocess import sys import fnmatch +import re # get command line arguments from argparse import ArgumentParser parser = ArgumentParser(description='make_secure_bl') parser.add_argument("--signing-key", type=str, default=None, help="signing key for secure bootloader") parser.add_argument("--debug", action='store_true', default=False, help="build with debug symbols") +parser.add_argument("--periph-only", action='store_true', default=False, help="only build AP_Periph boards") parser.add_argument("pattern", type=str, default='*', help="board wildcard pattern") args = parser.parse_args() @@ -27,6 +29,27 @@ failed_boards = set() +def read_hwdef(filepath): + '''read a hwdef file recursively''' + fh = open(filepath) + ret = [] + text = fh.readlines() + for line in text: + m = re.match(r"^\s*include\s+(.+)\s*$", line) + if m is not None: + ret += read_hwdef(os.path.join(os.path.dirname(filepath), m.group(1))) + else: + ret += [line] + return ret + +def is_ap_periph(hwdef): + '''return True if a hwdef is for a AP_Periph board''' + lines = read_hwdef(hwdef) + for line in lines: + if line.find('AP_PERIPH') != -1: + return True + return False + def get_board_list(): '''add boards based on existance of hwdef-bl.dat in subdirectories for ChibiOS''' board_list = [] @@ -34,6 +57,8 @@ def get_board_list(): for d in dirlist: hwdef = os.path.join(dirname, d, 'hwdef-bl.dat') if os.path.exists(hwdef): + if args.periph_only and not is_ap_periph(hwdef): + continue board_list.append(d) return board_list diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index a5a9c1c27b907e..4ae65daff8212a 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -130,7 +130,7 @@ for t in $CI_BUILD_TARGET; do fi if [ "$t" == "sitltest-can" ]; then echo "Building SITL Periph GPS" - $waf configure --board sitl --force-32bit + $waf configure --board sitl $waf copter run_autotest "Copter" "build.SITLPeriphGPS" "test.CAN" continue @@ -163,6 +163,10 @@ for t in $CI_BUILD_TARGET; do run_autotest "Sub" "build.Sub" "test.Sub" continue fi + if [ "$t" == "sitltest-blimp" ]; then + run_autotest "Blimp" "build.Blimp" "test.Blimp" + continue + fi if [ "$t" == "unit-tests" ]; then run_autotest "Unit Tests" "build.unit_tests" "run.unit_tests" @@ -267,7 +271,7 @@ for t in $CI_BUILD_TARGET; do $waf bootloader continue fi - + if [ "$t" == "stm32f7" ]; then echo "Building mRoX21-777/" $waf configure --Werror --board mRoX21-777 @@ -336,9 +340,10 @@ for t in $CI_BUILD_TARGET; do $waf clean $waf copter $waf plane + $waf tests continue fi - + if [ "$t" == "fmuv2-plane" ]; then echo "Building fmuv2 plane" $waf configure --board fmuv2 @@ -366,11 +371,11 @@ for t in $CI_BUILD_TARGET; do if [ "$t" == "replay" ]; then echo "Building replay" $waf configure --board sitl --debug --disable-scripting - + $waf replay echo "Building AP_DAL standalone test" $waf configure --board sitl --debug --disable-scripting --no-gcs - + $waf --target tool/AP_DAL_Standalone $waf clean continue @@ -406,7 +411,7 @@ for t in $CI_BUILD_TARGET; do ./Tools/scripts/build_bootloaders.py --signing-key testkey_public_key.dat MatekL431-DShot continue fi - + if [ "$t" == "python-cleanliness" ]; then echo "Checking Python code cleanliness" ./Tools/scripts/run_flake8.py @@ -415,7 +420,7 @@ for t in $CI_BUILD_TARGET; do if [ "$t" == "astyle-cleanliness" ]; then echo "Checking AStyle code cleanliness" - ./Tools/scripts/run_astyle.py + ./Tools/scripts/run_astyle.py --dry-run continue fi diff --git a/Tools/scripts/build_iofirmware.py b/Tools/scripts/build_iofirmware.py index 4ec5ea796e3acc..6d6c927addab35 100755 --- a/Tools/scripts/build_iofirmware.py +++ b/Tools/scripts/build_iofirmware.py @@ -29,6 +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-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-f103']) +run_program(["./waf", "clean"]) +run_program(["./waf", "iofirmware"]) +shutil.copy('build/iomcu-f103/bin/iofirmware_lowpolh.bin', 'Tools/IO_Firmware/iofirmware_f103_lowpolh.bin') +shutil.copy('build/iomcu-f103/bin/iofirmware_highpolh.bin', 'Tools/IO_Firmware/iofirmware_f103_highpolh.bin') + +run_program(["./waf", "configure", "--board", 'iomcu-f103-dshot']) +run_program(["./waf", "clean"]) +run_program(["./waf", "iofirmware"]) +shutil.copy('build/iomcu-f103-dshot/bin/iofirmware_lowpolh.bin', 'Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin') +shutil.copy('build/iomcu-f103-dshot/bin/iofirmware_highpolh.bin', 'Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin') + run_program(["./waf", "configure", "--board", 'iomcu_f103_8MHz']) run_program(["./waf", "clean"]) run_program(["./waf", "iofirmware"]) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 9c809d805d374d..d34f3844cb04e8 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -31,7 +31,7 @@ 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', 'AHRS_EXT_LORD', 'AP_EXTERNAL_AHRS_LORD_ENABLED', 'Enable LORD External AHRS', 0, "AHRS_EXT"), + Feature('AHRS', 'AHRS_EXT_MICROSTRAIN5', 'AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED', 'Enable MICROSTRAIN 5-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'), @@ -40,6 +40,7 @@ def __init__(self, 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', 'AC_AVOID_ENABLED', 'Enable Avoidance', 0, 'FENCE'), Feature('Safety', 'AC_OAPATHPLANNER', 'AC_OAPATHPLANNER_ENABLED', 'Enable Object Avoidance Path Planner', 0, 'FENCE'), @@ -49,17 +50,18 @@ def __init__(self, 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_OUTBOUND_ENABLED', 'AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED', 'Enable ability to put battery monitor data in ESC telem stream', 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'), - Feature('Ident', 'ADSB_SAGETECH_MXS', 'HAL_ADSB_SAGETECH_MXS_ENABLED', 'Enable SageTech MXS ADSB', 0, 'ADSB'), + Feature('Ident', 'ADSB_SAGETECH', 'HAL_ADSB_SAGETECH_ENABLED', 'Enable Sagetech ADSB', 0, 'ADSB'), + Feature('Ident', 'ADSB_SAGETECH_MXS', 'HAL_ADSB_SAGETECH_MXS_ENABLED', 'Enable Sagetech MXS ADSB', 0, 'ADSB'), Feature('Ident', 'ADSB_UAVIONIX', 'HAL_ADSB_UAVIONIX_MAVLINK_ENABLED', 'Enable UAvionix ADSB', 0, 'ADSB'), Feature('Ident', 'ADSB_UAVIONX_UCP', 'HAL_ADSB_UCP_ENABLED', 'Enable uAvionix UCP ADSB', 0 , 'ADSB'), Feature('Ident', 'AIS', 'AP_AIS_ENABLED', 'Enable AIS', 0, None), + Feature('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', 'HIGHLAT2', 'HAL_HIGH_LATENCY2_ENABLED', 'Enable HighLatency2 Support', 0, None), Feature('Telemetry', 'HOTT', 'HAL_HOTT_TELEM_ENABLED', 'Enable HOTT Telemetry', 0, None), Feature('Telemetry', 'SPEKTRUM', 'HAL_SPEKTRUM_TELEM_ENABLED', 'Enable Spektrum Telemetry', 0, None), Feature('Telemetry', 'LTM', 'AP_LTM_TELEM_ENABLED', 'Enable LTM Telemetry', 0, None), @@ -97,8 +99,8 @@ def __init__(self, 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_IE2400', 'AP_GENERATOR_IE2400_ENABLED', 'Enable IntelligentEnergy 2400', 0, "GENERATOR"), # noqa - Feature('Generator', 'GENERATOR_IE650', 'AP_GENERATOR_IE650_800_ENABLED', 'Enable IntelligentEnergy 650 and 800 support', 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('OSD', 'OSD', 'OSD_ENABLED', 'Enable OSD', 0, None), Feature('OSD', 'PLUSCODE', 'HAL_PLUSCODE_ENABLE', 'Enable PlusCode', 0, 'OSD'), @@ -177,11 +179,13 @@ def __init__(self, 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('Plane', 'ADVANCED_FAILSAFE', 'AP_ADVANCEDFAILSAFE_ENABLED', 'Enable Advanced Failsafe features', 0, None), Feature('Plane', 'QUADPLANE', 'HAL_QUADPLANE_ENABLED', 'Enable QuadPlane support', 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', '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 @@ -273,6 +277,7 @@ def __init__(self, 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', '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), @@ -282,10 +287,27 @@ def __init__(self, Feature('Other', 'DISPLAY', 'HAL_DISPLAY_ENABLED', 'Enable I2C Displays', 0, None), Feature('Other', 'NMEA_OUTPUT', 'HAL_NMEA_OUTPUT_ENABLED', 'Enable NMEA Output', 0, None), Feature('Other', 'BARO_WIND_COMP', 'HAL_BARO_WIND_COMP_ENABLED', 'Enable Baro Wind Compensation', 0, None), - Feature('Other', 'ADVANCED_FAILSAFE', 'AP_ADVANCEDFAILSAFE_ENABLED', 'Enable Advanced Failsafe features', 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', '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), + + # 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', 'AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', 'AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', 'Enable old AUTOPILOT_VERSION_REQUEST mesage', 0, None), # noqa + Feature('MAVLink', 'AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', 'AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', 'Enable old REQUEST_AUTOPILOT_CAPABILITIES command', 0, None), # noqa + Feature('MAVLink', 'AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', 'AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', 'Enable sending of RELAY_STATUS message', 0, 'RELAY'), # noqa + Feature('MAVLink', 'AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED', 'AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED', 'Enable handling of deprecated MOUNT_CONTROL message', 0, None), # noqa + Feature('MAVLink', 'AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED', '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', 'AP_MAVLINK_MSG_DEVICE_OP_ENABLED', 'AP_MAVLINK_MSG_DEVICE_OP_ENABLED', 'Enable handling of DeviceOp mavlink messages', 0, None), # noqa + Feature('MAVLink', 'AP_MAVLINK_SERVO_RELAY_ENABLED', 'AP_MAVLINK_SERVO_RELAY_ENABLED', 'Enable handling of ServoRelay mavlink messages', 0, 'SERVORELAY_EVENTS'), # noqa + Feature('MAVLink', 'AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED', 'AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED', 'Enable handling of Serial Control mavlink messages', 0, None), # 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), @@ -320,6 +342,8 @@ def __init__(self, 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('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 diff --git a/Tools/scripts/build_peripherals.py b/Tools/scripts/build_peripherals.py new file mode 100755 index 00000000000000..398a109bd9cbf7 --- /dev/null +++ b/Tools/scripts/build_peripherals.py @@ -0,0 +1,68 @@ +#!/usr/bin/env python + +""" +script to test build all of our peripheral firmwares +""" + +import os +import shutil +import subprocess +import sys +import fnmatch +import board_list + +# get command line arguments +from argparse import ArgumentParser +parser = ArgumentParser(description='build_peripherals') +parser.add_argument("pattern", type=str, default='*', help="board wildcard pattern") +parser.add_argument("--debug", action='store_true', default=False, help="build with debug symbols") +parser.add_argument("--stop", action='store_true', default=False, help="stop on a failed build") +parser.add_argument("--configure-only", action='store_true', default=False, help="only run configure") +parser.add_argument("--noclean", action='store_true', default=False, help="don't run waf clean") +args = parser.parse_args() + +os.environ['PYTHONUNBUFFERED'] = '1' + +failed_boards = set() + +def run_program(cmd_list): + print("Running (%s)" % " ".join(cmd_list)) + retcode = subprocess.call(cmd_list) + if retcode != 0: + print("Build failed: %s" % ' '.join(cmd_list)) + return False + return True + +def build_board(board): + configure_args = "--board %s --no-submodule-update --Werror" % board + configure_args = configure_args.split() + if args.debug: + print("Building with debug symbols") + configure_args.append("--debug") + if not run_program(["./waf", "configure"] + configure_args): + return False + if args.configure_only: + return True + if not args.noclean and not run_program(["./waf", "clean"]): + return False + if not run_program(["./waf", "AP_Periph"]): + return False + return True + +boards = board_list.BoardList().find_ap_periph_boards() + +for board in boards: + if not fnmatch.fnmatch(board, args.pattern): + continue + print("Building for %s" % board) + if not build_board(board): + failed_boards.add(board) + if args.stop: + break + continue + +if len(failed_boards): + print("Failed boards: %s" % list(failed_boards)) +else: + print("No failed builds") + diff --git a/Tools/scripts/build_tests/test_ccache.py b/Tools/scripts/build_tests/test_ccache.py index 428e8b1f43fc41..740390e0067668 100755 --- a/Tools/scripts/build_tests/test_ccache.py +++ b/Tools/scripts/build_tests/test_ccache.py @@ -11,6 +11,7 @@ parser = argparse.ArgumentParser(description='test ccache performance') parser.add_argument('--boards', default='MatekF405,MatekF405-bdshot', help='boards to test') parser.add_argument('--min-cache-pct', type=int, default=75, help='minimum acceptable ccache hit rate') +parser.add_argument('--display', action='store_true', help='parse and show ccache stats') args = parser.parse_args() @@ -24,9 +25,21 @@ def ccache_stats(): m = re.match(r"cache.hit\D*(\d+)$", line) if m is not None: hits += int(m.group(1)) + m = re.match(r"cache.miss\D*(\d+)", line) if m is not None: miss += int(m.group(1)) + + m = re.match(r"\s*Hits:\s*(\d+)", line) + if m is not None: + hits += int(m.group(1)) + + m = re.match(r"\s*Misses:\s*(\d+)", line) + if m is not None: + miss += int(m.group(1)) + + if line.startswith("Primary"): + break return (hits, miss) @@ -35,6 +48,11 @@ def build_board(boardname): subprocess.run(["./waf", "clean", "copter"]) +if args.display: + (hits, misses) = ccache_stats() + print("Hits=%u misses=%u" % (hits, misses)) + sys.exit(0) + boards = args.boards.split(",") if len(boards) != 2: print(boards) @@ -42,6 +60,7 @@ def build_board(boardname): sys.exit(1) os.environ['CCACHE_DIR'] = os.path.join(os.getcwd(), 'build', 'ccache') +subprocess.run(["ccache", "--version"]) subprocess.run(["ccache", "-C", "-z"]) build_board(boards[0]) subprocess.run(["ccache", "-z"]) diff --git a/Tools/scripts/configure_all.py b/Tools/scripts/configure_all.py index 6a799fbe9831e4..442f9bd3023be4 100755 --- a/Tools/scripts/configure_all.py +++ b/Tools/scripts/configure_all.py @@ -43,7 +43,7 @@ def get_board_list(): dirname, dirlist, filenames = next(os.walk('libraries/AP_HAL_ChibiOS/hwdef')) for d in dirlist: hwdef = os.path.join(dirname, d, 'hwdef.dat') - if os.path.exists(hwdef) and not d in omit: + if os.path.exists(hwdef) and d not in omit: board_list.append(d) return board_list diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index ae90ffe15562c2..61e670cc046043 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -35,7 +35,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): # FEATURE_NAME will have substitutions made from the match. # the substitutions will be upper-cased self.features = [ - ('AP_ADVANCEDFAILSAFE_ENABLED', 'AP::advancedfailsafe',), + ('AP_ADVANCEDFAILSAFE_ENABLED', r'AP_AdvancedFailsafe::heartbeat\b',), ('AP_BOOTLOADER_FLASHING_ENABLED', 'ChibiOS::Util::flash_bootloader',), ('AP_AIRSPEED_ENABLED', 'AP_Airspeed::AP_Airspeed',), ('AP_AIRSPEED_{type}_ENABLED', r'AP_Airspeed_(?P.*)::init',), @@ -94,6 +94,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('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',), ('HAL_MOUNT_ENABLED', 'AP_Mount::AP_Mount',), ('HAL_MOUNT_{type}_ENABLED', r'AP_Mount_(?P.*)::update\b',), @@ -125,6 +126,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('HAL_PARACHUTE_ENABLED', 'AP_Parachute::update',), ('AP_FENCE_ENABLED', r'AC_Fence::check\b',), + ('HAL_RALLY_ENABLED', r'AP_Rally::get_rally_max\b',), ('AC_AVOID_ENABLED', 'AC_Avoid::AC_Avoid',), ('AC_OAPATHPLANNER_ENABLED', 'AP_OAPathPlanner::AP_OAPathPlanner',), @@ -133,7 +135,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('AP_EFI_NWPWU_ENABLED', r'AP_EFI_NWPMU::update\b',), ('AP_EFI_CURRAWONG_ECU_ENABLED', r'AP_EFI_Currawong_ECU::update\b',), ('HAL_GENERATOR_ENABLED', 'AP_Generator::AP_Generator',), - ('AP_GENERATOR_{type}_ENABLED', r'AP_Generator_(?P.*)::update',), + ('AP_GENERATOR_{type}_ENABLED', r'AP_Generator_(?P.*)::init',), ('OSD_ENABLED', 'AP_OSD::update_osd',), ('HAL_PLUSCODE_ENABLE', 'AP_OSD_Screen::draw_pluscode',), @@ -144,6 +146,8 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('AP_SMARTAUDIO_ENABLED', 'AP_SmartAudio::AP_SmartAudio',), ('AP_TRAMP_ENABLED', 'AP_Tramp::AP_Tramp',), + ('AP_CHECK_FIRMWARE_ENABLED', 'AP_CheckFirmware::check_signed_bootloader',), + ('HAL_QUADPLANE_ENABLED', 'QuadPlane::QuadPlane',), ('QAUTOTUNE_ENABLED', 'ModeQAutotune::_enter',), ('HAL_SOARING_ENABLED', 'SoaringController::var_info',), @@ -170,6 +174,8 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('AP_RPM_ENABLED', 'AP_RPM::AP_RPM',), ('AP_RPM_{type}_ENABLED', r'AP_RPM_(?P.*)::update',), + ('AP_OPENDRONEID_ENABLED', 'AP_OpenDroneID::update',), + ('GPS_MOVING_BASELINE', r'AP_GPS_Backend::calculate_moving_base_yaw\b',), ('AP_DRONECAN_SEND_GPS', r'AP_GPS_DroneCAN::instance_exists\b',), @@ -199,6 +205,25 @@ def __init__(self, filename, nm="arm-none-eabi-nm"): ('AP_INERTIALSENSOR_KILL_IMU_ENABLED', r'AP_InertialSensor::kill_imu'), ('AP_CRASHDUMP_ENABLED', 'CrashCatcher_DumpMemory'), + ('AP_CAN_SLCAN_ENABLED', 'SLCAN::CANIface::var_info'), + ('AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT', 'AC_PolyFence_loader::handle_msg_fetch_fence_point'), + ('AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED', 'GCS_MAVLINK::handle_common_rally_message'), + + ('AP_SDCARD_STORAGE_ENABLED', 'StorageAccess::attach_file'), + ('AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED', 'GCS_MAVLINK::handle_send_autopilot_version'), + ('AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED', 'GCS_MAVLINK::handle_command_request_autopilot_capabilities'), # noqa + ('AP_MAVLINK_MSG_RELAY_STATUS_ENABLED', 'GCS_MAVLINK::send_relay_status'), + ('AP_MAVLINK_BATTERY2_ENABLED', 'GCS_MAVLINK::send_battery2'), + ('AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED', 'AP_Mount::handle_mount_control'), + ('AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED', 'AP_Mount::handle_mount_configure'), + ('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_DRONECAN_HIMARK_SERVO_SUPPORT', 'AP_DroneCAN::SRV_send_himark'), + ('AP_DRONECAN_HOBBYWING_ESC_SUPPORT', 'AP_DroneCAN::hobbywing_ESC_update'), + ('COMPASS_CAL_ENABLED', 'CompassCalibrator::stop'), + ('AP_TUNING_ENABLED', 'AP_Tuning::check_input'), ] def progress(self, msg): @@ -378,11 +403,20 @@ def create_string(self): ret = "" - for compiled_in_feature_define in sorted(compiled_in_feature_defines): - ret += compiled_in_feature_define + "\n" - for remaining in sorted(not_compiled_in_feature_defines): - ret += "!" + remaining + "\n" + combined = {} + for define in sorted(compiled_in_feature_defines): + combined[define] = True + for define in sorted(not_compiled_in_feature_defines): + combined[define] = False + + def squash_hal_to_ap(a): + return re.sub("^HAL_", "AP_", a) + for define in sorted(combined.keys(), key=squash_hal_to_ap): + bang = "" + if not combined[define]: + bang = "!" + ret += bang + define + "\n" return ret def run(self): diff --git a/Tools/scripts/gen_stable.py b/Tools/scripts/gen_stable.py index 178a12af2d2461..eb243eed8eba54 100755 --- a/Tools/scripts/gen_stable.py +++ b/Tools/scripts/gen_stable.py @@ -8,6 +8,8 @@ VEHICLES = ['AntennaTracker', 'Copter', 'Plane', 'Rover', 'Sub'] +# beta directories that may contain stable builds +BETA_DIRS = ['beta-4.3'] def make_stable(basedir, vehicle): '''make stable version for a vehicle''' @@ -34,11 +36,45 @@ def make_stable(basedir, vehicle): old_dir = os.path.join(stable_dir, b) shutil.copytree(old_dir, new_dir) +def make_stable_from_beta(basedir, vehicle, beta_dir): + '''make stable version from a beta with OFFICAL tag''' + beta_dir = os.path.join(basedir, vehicle, beta_dir) + if not os.path.exists(beta_dir): + return + for b in sorted(os.listdir(beta_dir)): + if not os.path.isdir(os.path.join(beta_dir, b)): + continue + vfile = os.path.join(beta_dir, b, "firmware-version.txt") + if not os.path.exists(vfile): + print("Missing %s" % vfile) + continue + vstr = open(vfile).read().strip() + a = vstr.split('-') + if len(a) != 2: + continue + version = a[0] + vtype = a[1] + #print(vfile, b, version, vtype) + if vtype != 'FIRMWARE_VERSION_TYPE_OFFICIAL': + # not a new stable + continue + new_dir_parent = os.path.join(basedir, vehicle, 'stable-%s' % version) + new_dir = os.path.join(new_dir_parent, b) + if os.path.exists(new_dir): + continue + if not os.path.exists(new_dir_parent): + os.mkdir(new_dir_parent) + print('Creating %s' % new_dir) + old_dir = os.path.join(beta_dir, b) + shutil.copytree(old_dir, new_dir) + def make_all_stable(basedir): '''make stable directory for all vehicles''' for v in VEHICLES: make_stable(basedir, v) + for b in BETA_DIRS: + make_stable_from_beta(basedir, v, b) if __name__ == "__main__": diff --git a/Tools/scripts/param_unpack.py b/Tools/scripts/param_unpack.py index 5d4c1c5e59ddd2..a439d1ce399217 100755 --- a/Tools/scripts/param_unpack.py +++ b/Tools/scripts/param_unpack.py @@ -54,7 +54,7 @@ flags = (ptype>>4) & 0x0F ptype &= 0x0F - if not ptype in data_types: + if ptype not in data_types: raise Exception("bad type 0x%x" % ptype) (type_len, type_format) = data_types[ptype] diff --git a/Tools/scripts/run_astyle.py b/Tools/scripts/run_astyle.py index ecf78a19e1ca40..bf6ff415c97c4f 100755 --- a/Tools/scripts/run_astyle.py +++ b/Tools/scripts/run_astyle.py @@ -14,15 +14,18 @@ import argparse os.environ['PYTHONUNBUFFERED'] = '1' +DRY_RUN_DEFAULT = False class AStyleChecker(object): - def __init__(self): + def __init__(self, *, dry_run=DRY_RUN_DEFAULT): self.retcode = 0 self.directories_to_check = [ 'libraries/AP_DDS', + 'libraries/AP_ExternalControl' ] self.files_to_check = [] + self.dry_run = dry_run def progress(self, string): print("****** %s" % (string,)) @@ -31,7 +34,10 @@ def check(self): '''run astyle on all files in self.files_to_check''' # for path in self.files_to_check: # self.progress("Checking (%s)" % path) - astyle_command = ["astyle", "--dry-run"] + astyle_command = ["astyle"] + if self.dry_run: + astyle_command.append("--dry-run") + astyle_command.append("--options=Tools/CodeStyle/astylerc") astyle_command.extend(self.files_to_check) ret = subprocess.run( @@ -58,8 +64,11 @@ def run(self): if __name__ == '__main__': parser = argparse.ArgumentParser(description='Check all Python files for astyle cleanliness') - # parser.add_argument('--build', action='store_true', default=False, help='build as well as configure') + parser.add_argument('--dry-run', + action='store_true', + default=DRY_RUN_DEFAULT, + help='Perform a trial run with no changes made to check for formatting') args = parser.parse_args() - checker = AStyleChecker() + checker = AStyleChecker(dry_run=args.dry_run) sys.exit(checker.run()) diff --git a/Tools/scripts/sensor_status_change.py b/Tools/scripts/sensor_status_change.py new file mode 100755 index 00000000000000..0b5e5ea28ca239 --- /dev/null +++ b/Tools/scripts/sensor_status_change.py @@ -0,0 +1,87 @@ +#!/usr/bin/env python + +""" +Parses a log file and shows how the SENSOR_STATUS flags changed over time + +AP_FLAKE8_CLEAN + +""" + +from __future__ import print_function + +import optparse +import sys +import time + +from pymavlink import mavutil + + +class SYS_STATUS_Change(object): + def __init__(self, master): + self.master = master + + def progress(self, text): + '''emit text with possible timestamps etc''' + print("%u: %s" % (time.time(), text)) + + def bit_description(self, bit_number): + if 1 << bit_number not in mavutil.mavlink.enums["MAV_SYS_STATUS_SENSOR"]: + return "UNKNOWN_BIT[%u]" % bit_number + + name = mavutil.mavlink.enums["MAV_SYS_STATUS_SENSOR"][1 << bit_number].name + # return name with common prefix removed: + return name[len("MAV_SYS_STATUS_"):] + + def run(self): + + self.progress("Creating connection") + self.conn = mavutil.mavlink_connection(master) + + fields = ['present', 'enabled', 'health'] + + current = dict() + for f in fields: + current[f] = 0 + while True: + m = self.conn.recv_match(type="SYS_STATUS") + if m is None: + break + + line = "" + for f in fields: + current_values = current[f] + new_values = getattr(m, "onboard_control_sensors_" + f) + for bit in range(0, 32): + mask = 1 << bit + old_bit_set = current_values & mask + new_bit_set = new_values & mask + if new_bit_set and not old_bit_set: + line += " %s+%s" % (f, self.bit_description(bit)) + elif not new_bit_set and old_bit_set: + line += " %s-%s" % (f, self.bit_description(bit)) + current[f] = new_values + + if len(line) == 0: + continue + + timestamp = getattr(m, '_timestamp', 0.0) + formatted_timestamp = "%s.%02u" % ( + time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(timestamp)), + int(timestamp * 100.0) % 100) + + print("%s: %s" % (formatted_timestamp, line)) + + +if __name__ == '__main__': + parser = optparse.OptionParser("sys_status_change.py [options]") + + (opts, args) = parser.parse_args() + + if len(args) < 1: + parser.print_help() + sys.exit(1) + + master = args[0] + + tester = SYS_STATUS_Change(master) + tester.run() diff --git a/Tools/scripts/size_compare_branches.py b/Tools/scripts/size_compare_branches.py index 622f661c207e79..41e93bc7a5c5ca 100755 --- a/Tools/scripts/size_compare_branches.py +++ b/Tools/scripts/size_compare_branches.py @@ -30,6 +30,11 @@ import time import board_list +try: + import queue as Queue +except ImportError: + import Queue + if sys.version_info[0] < 3: running_python3 = False else: @@ -147,7 +152,9 @@ def __init__(self, 'fmuv2', 'fmuv3-bdshot', 'iomcu', - 'iomcu', + 'iomcu-dshot', + 'iomcu-f103', + 'iomcu-f103-dshot', 'iomcu_f103_8MHz', 'luminousbee4', 'skyviper-v2450', @@ -156,6 +163,7 @@ def __init__(self, 'Pixhawk1-1M-bdshot', 'Pixhawk1-bdshot', 'SITL_arm_linux_gnueabihf', + 'RADIX2HD', ]) # blacklist all linux boards for bootloader build: @@ -408,7 +416,21 @@ def parallel_thread_main(self, thread_number): jobs = int(self.jobs / self.num_threads_remaining) if jobs <= 0: jobs = 1 - self.run_build_task(task, source_dir=my_source_dir, jobs=jobs) + try: + self.run_build_task(task, source_dir=my_source_dir, jobs=jobs) + except Exception as ex: + self.thread_exit_result_queue.put(f"{task}") + raise ex + + def check_result_queue(self): + while True: + try: + result = self.thread_exit_result_queue.get_nowait() + except Queue.Empty: + break + if result is None: + continue + self.failure_exceptions.append(result) def run_build_tasks_in_parallel(self, tasks): n_threads = self.parallel_copies @@ -419,6 +441,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() for i in range(0, n_threads): t = threading.Thread( target=self.parallel_thread_main, @@ -428,7 +451,12 @@ def run_build_tasks_in_parallel(self, tasks): t.start() threads.append(t) tstart = time.time() + self.failure_exceptions = [] + while len(threads): + + self.check_result_queue() + new_threads = [] for thread in threads: thread.join(0) @@ -436,7 +464,9 @@ def run_build_tasks_in_parallel(self, tasks): new_threads.append(thread) threads = new_threads self.num_threads_remaining = len(threads) - self.progress(f"remaining-tasks={len(self.parallel_tasks)} remaining-threads={len(threads)} elapsed={int(time.time() - tstart)}s") # noqa + self.progress( + f"remaining-tasks={len(self.parallel_tasks)} " + + f"remaining-threads={len(threads)} failed-threads={len(self.failure_exceptions)} elapsed={int(time.time() - tstart)}s") # noqa # write out a progress CSV: task_results = [] @@ -449,6 +479,13 @@ def run_build_tasks_in_parallel(self, tasks): time.sleep(1) self.progress("All threads returned") + self.check_result_queue() + + if len(self.failure_exceptions): + self.progress("Some threads failed:") + for ex in self.failure_exceptions: + print("Thread failure: %s" % str(ex)) + def run_all(self): '''run tests for boards and vehicles passed in constructor''' diff --git a/Tools/scripts/tempcal_IMU.py b/Tools/scripts/tempcal_IMU.py index dcee07b36d50bb..b75dda56071402 100755 --- a/Tools/scripts/tempcal_IMU.py +++ b/Tools/scripts/tempcal_IMU.py @@ -65,14 +65,14 @@ def set_gyro_poly(self, imu, axis, values): def set_acoeff(self, imu, axis, order, value): if imu not in self.acoef: self.acoef[imu] = {} - if not axis in self.acoef[imu]: + if axis not in self.acoef[imu]: self.acoef[imu][axis] = [0]*4 self.acoef[imu][axis][POLY_ORDER-order] = value def set_gcoeff(self, imu, axis, order, value): if imu not in self.gcoef: self.gcoef[imu] = {} - if not axis in self.gcoef[imu]: + if axis not in self.gcoef[imu]: self.gcoef[imu][axis] = [0]*4 self.gcoef[imu][axis][POLY_ORDER-order] = value @@ -107,7 +107,7 @@ def correction(self, coeff, imu, temperature, axis, cal_temp): return 0.0 if cal_temp < -80: return 0.0 - if not axis in coeff: + if axis not in coeff: return 0.0 temperature = constrain(temperature, self.tmin[imu], self.tmax[imu]) cal_temp = constrain(cal_temp, self.tmin[imu], self.tmax[imu]) diff --git a/Tools/scripts/uploader.py b/Tools/scripts/uploader.py index acc8aae658ef95..ee13ed62571091 100755 --- a/Tools/scripts/uploader.py +++ b/Tools/scripts/uploader.py @@ -90,6 +90,7 @@ '/dev/serial/by-id/usb-*_BL_*', '/dev/serial/by-id/usb-Swift-Flyer*', '/dev/serial/by-id/usb-CubePilot*', + '/dev/serial/by-id/usb-Qiotek*', '/dev/tty.usbmodem*'] if "cygwin" in _platform or is_WSL: diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index a64a277d883cfd..8d6060d06b5a65 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -45,7 +45,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = { // @Param: RATE_FF_ENAB // @DisplayName: Rate Feedforward Enable - // @Description: Controls whether body-frame rate feedfoward is enabled or disabled + // @Description: Controls whether body-frame rate feedforward is enabled or disabled // @Values: 0:Disabled, 1:Enabled // @User: Advanced AP_GROUPINFO("RATE_FF_ENAB", 5, AC_AttitudeControl, _rate_bf_ff_enabled, AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT), @@ -756,7 +756,7 @@ void AC_AttitudeControl::attitude_controller_run_quat() } // 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. +// The maximum error in the yaw axis is limited based on static output saturation. void AC_AttitudeControl::thrust_heading_rotation_angles(Quaternion& attitude_target, const Quaternion& attitude_body, Vector3f& attitude_error, float& thrust_angle, float& thrust_error_angle) const { Quaternion thrust_vector_correction; @@ -764,14 +764,17 @@ void AC_AttitudeControl::thrust_heading_rotation_angles(Quaternion& attitude_tar // Todo: Limit roll an pitch error based on output saturation and maximum error. - // Limit Yaw Error based on maximum acceleration - Update to include output saturation and maximum error. - // Currently the limit is based on the maximum acceleration using the linear part of the SQRT controller. - // This should be updated to be based on an angle limit, saturation, or unlimited based on user defined parameters. - Quaternion yaw_vec_correction_quat; - if (!is_zero(_p_angle_yaw.kP()) && fabsf(attitude_error.z) > AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS / _p_angle_yaw.kP()) { - attitude_error.z = constrain_float(wrap_PI(attitude_error.z), -AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS / _p_angle_yaw.kP(), AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS / _p_angle_yaw.kP()); - yaw_vec_correction_quat.from_axis_angle(Vector3f{0.0f, 0.0f, attitude_error.z}); - attitude_target = attitude_body * thrust_vector_correction * yaw_vec_correction_quat; + // Limit Yaw Error based to the maximum that would saturate the output when yaw rate is zero. + Quaternion heading_vec_correction_quat; + + float heading_accel_max = constrain_float(get_accel_yaw_max_radss() / 2.0f, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN_RADSS, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX_RADSS); + if (!is_zero(get_rate_yaw_pid().kP())) { + float heading_error_max = MIN(inv_sqrt_controller(1.0 / get_rate_yaw_pid().kP(), _p_angle_yaw.kP(), heading_accel_max), AC_ATTITUDE_YAW_MAX_ERROR_ANGLE); + if (!is_zero(_p_angle_yaw.kP()) && fabsf(attitude_error.z) > heading_error_max) { + attitude_error.z = constrain_float(wrap_PI(attitude_error.z), -heading_error_max, heading_error_max); + heading_vec_correction_quat.from_axis_angle(Vector3f{0.0f, 0.0f, attitude_error.z}); + attitude_target = attitude_body * thrust_vector_correction * heading_vec_correction_quat; + } } } @@ -782,7 +785,7 @@ void AC_AttitudeControl::thrust_vector_rotation_angles(const Quaternion& attitud // The direction of thrust is [0,0,-1] is any body-fixed frame, inc. body frame and target frame. const Vector3f thrust_vector_up{0.0f, 0.0f, -1.0f}; - // attitude_target and attitute_body are passive rotations from target / body frames to the NED frame + // attitude_target and attitude_body are passive rotations from target / body frames to the NED frame // Rotating [0,0,-1] by attitude_target expresses (gets a view of) the target thrust vector in the inertial frame Vector3f att_target_thrust_vec = attitude_target * thrust_vector_up; // target thrust vector @@ -910,6 +913,7 @@ Vector3f AC_AttitudeControl::euler_accel_limit(const Vector3f &euler_rad, const 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)) { @@ -919,7 +923,7 @@ Vector3f AC_AttitudeControl::euler_accel_limit(const Vector3f &euler_rad, const } 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), euler_accel.z / cos_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)); } return rot_accel; } @@ -1033,7 +1037,7 @@ Vector3f AC_AttitudeControl::update_ang_vel_target_from_att_error(const Vector3f rate_target_ang_vel.z = angleP_yaw * attitude_error_rot_vec_rad.z; } - // reset angle P scaling, saving used value for logging + // reset angle P scaling, saving used value _angle_P_scale_used = _angle_P_scale; _angle_P_scale = VECTORF_111; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index b9edc4a1708bde..a08dedda084c20 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -22,14 +22,12 @@ #define AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS 110000.0f // default maximum acceleration for roll/pitch axis in centidegrees/sec/sec #define AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS 27000.0f // default maximum acceleration for yaw axis in centidegrees/sec/sec -#define AC_ATTITUDE_RATE_CONTROLLER_TIMEOUT 1.0f // body-frame rate controller timeout in seconds #define AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX 1.0f // body-frame rate controller maximum output (for roll-pitch axis) #define AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX 1.0f // body-frame rate controller maximum output (for yaw axis) #define AC_ATTITUDE_RATE_RELAX_TC 0.16f // This is used to decay the rate I term to 5% in half a second. #define AC_ATTITUDE_THRUST_ERROR_ANGLE radians(30.0f) // Thrust angle error above which yaw corrections are limited - -#define AC_ATTITUDE_400HZ_DT 0.0025f // delta time in seconds for 400hz update rate +#define AC_ATTITUDE_YAW_MAX_ERROR_ANGLE radians(45.0f) // Thrust angle error above which yaw corrections are limited #define AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT 1 // body-frame rate feedforward enabled by default @@ -86,6 +84,9 @@ class AC_AttitudeControl { virtual AC_PID& get_rate_roll_pid() = 0; virtual AC_PID& get_rate_pitch_pid() = 0; virtual AC_PID& get_rate_yaw_pid() = 0; + virtual const AC_PID& get_rate_roll_pid() const = 0; + virtual const AC_PID& get_rate_pitch_pid() const = 0; + virtual const AC_PID& get_rate_yaw_pid() const = 0; // get the roll acceleration limit in centidegrees/s/s or radians/s/s float get_accel_roll_max_cdss() const { return _accel_roll_max; } @@ -394,8 +395,8 @@ class AC_AttitudeControl { // purposes void set_angle_P_scale_mult(const Vector3f &angle_P_scale) { _angle_P_scale *= angle_P_scale; } - // get the value of the angle P scale that was used in the last loop, for logging - const Vector3f &get_angle_P_scale_logging(void) const { return _angle_P_scale_used; } + // get the value of the angle P scale that was used in the last loop + const Vector3f &get_last_angle_P_scale(void) const { return _angle_P_scale_used; } // setup a one loop PD scale multiplier, multiplying by any // previously applied scale from this loop. This allows for more @@ -530,7 +531,7 @@ class AC_AttitudeControl { // angle P scaling vector for roll, pitch, yaw Vector3f _angle_P_scale{1,1,1}; - // angle scale used for last loop, used for logging + // angle scale used for last loop, used for logging and quadplane angle P scaling Vector3f _angle_P_scale_used; // PD scaling vector for roll, pitch, yaw diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index db5df861385491..e05d6e4af73747 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -403,19 +403,9 @@ void AC_AttitudeControl_Heli::rate_bf_to_motor_roll_pitch(const Vector3f &rate_r float roll_out = roll_pid + roll_ff; float pitch_out = pitch_pid + pitch_ff; - // constrain output and update limit flags - if (fabsf(roll_out) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX) { - roll_out = constrain_float(roll_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX); - _flags_heli.limit_roll = true; - } else { - _flags_heli.limit_roll = false; - } - if (fabsf(pitch_out) > AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX) { - pitch_out = constrain_float(pitch_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX); - _flags_heli.limit_pitch = true; - } else { - _flags_heli.limit_pitch = false; - } + // constrain output + roll_out = constrain_float(roll_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX); + pitch_out = constrain_float(pitch_out, -AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX); // output to motors _motors.set_roll(roll_out); @@ -457,13 +447,8 @@ float AC_AttitudeControl_Heli::rate_target_to_motor_yaw(float rate_yaw_actual_ra // add feed forward float yaw_out = pid + vff; - // constrain output and update limit flag - if (fabsf(yaw_out) > AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX) { - yaw_out = constrain_float(yaw_out, -AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX); - _flags_heli.limit_yaw = true; - } else { - _flags_heli.limit_yaw = false; - } + // constrain output + yaw_out = constrain_float(yaw_out, -AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX, AC_ATTITUDE_RATE_YAW_CONTROLLER_OUT_MAX); // output to motors return yaw_out; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h index 0b3619f7104456..c20b2fe5a2aab6 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h @@ -42,26 +42,22 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl { AP_Param::setup_object_defaults(this, var_info); // initialise flags - _flags_heli.limit_roll = false; - _flags_heli.limit_pitch = false; - _flags_heli.limit_yaw = false; _flags_heli.leaky_i = true; _flags_heli.flybar_passthrough = false; _flags_heli.tail_passthrough = false; - _flags_heli.do_piro_comp = false; } // pid accessors AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; } AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; } AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; } + const AC_PID& get_rate_roll_pid() const override { return _pid_rate_roll; } + const AC_PID& get_rate_pitch_pid() const override { return _pid_rate_pitch; } + const AC_PID& get_rate_yaw_pid() const override { return _pid_rate_yaw; } // passthrough_bf_roll_pitch_rate_yaw - roll and pitch are passed through directly, body-frame rate target for yaw void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds) override; - // Integrate vehicle rate into _att_error_rot_vec_rad - void integrate_bf_rate_error_to_angle_errors(); - // subclass non-passthrough too, for external gyro, no flybar void input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) override; @@ -82,9 +78,6 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl { _flags_heli.tail_passthrough = tail_passthrough; } - // do_piro_comp - controls whether piro-comp is active or not - void do_piro_comp(bool piro_comp) { _flags_heli.do_piro_comp = piro_comp; } - // set_hover_roll_scalar - scales Hover Roll Trim parameter. To be used by vehicle code according to vehicle condition. void set_hover_roll_trim_scalar(float scalar) override {_hover_roll_trim_scalar = constrain_float(scalar, 0.0f, 1.0f);} @@ -112,15 +105,14 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl { // To-Do: move these limits flags into the heli motors class struct AttControlHeliFlags { - uint8_t limit_roll : 1; // 1 if we have requested larger roll angle than swash can physically move - uint8_t limit_pitch : 1; // 1 if we have requested larger pitch angle than swash can physically move - uint8_t limit_yaw : 1; // 1 if we have requested larger yaw angle than tail servo can physically move uint8_t leaky_i : 1; // 1 if we should use leaky i term for body-frame rate to motor stage uint8_t flybar_passthrough : 1; // 1 if we should pass through pilots roll & pitch input directly to swash-plate uint8_t tail_passthrough : 1; // 1 if we should pass through pilots yaw input to tail - uint8_t do_piro_comp : 1; // 1 if we should do pirouette compensation on roll/pitch } _flags_heli; + // Integrate vehicle rate into _att_error_rot_vec_rad + void integrate_bf_rate_error_to_angle_errors(); + // // body-frame rate controller // diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index d17b2ec17dd3a9..2254ebd7b6f0a3 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -1,6 +1,7 @@ #include "AC_AttitudeControl_Multi.h" #include #include +#include // table of user settable parameters const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { @@ -73,6 +74,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: RAT_RLL_PDMX + // @DisplayName: Roll axis rate controller PD sum maximum + // @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Advanced + AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Multi, AC_PID), // @Param: RAT_PIT_P @@ -141,6 +149,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: RAT_PIT_PDMX + // @DisplayName: Pitch axis rate controller PD sum maximum + // @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Advanced + AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Multi, AC_PID), // @Param: RAT_YAW_P @@ -209,6 +224,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: RAT_YAW_PDMX + // @DisplayName: Yaw axis rate controller PD sum maximum + // @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Advanced + AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Multi, AC_PID), // @Param: THR_MIX_MIN @@ -244,10 +266,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors) : AC_AttitudeControl(ahrs, aparm, motors), - _motors_multi(motors), - _pid_rate_roll(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ), - _pid_rate_pitch(AC_ATC_MULTI_RATE_RP_P, AC_ATC_MULTI_RATE_RP_I, AC_ATC_MULTI_RATE_RP_D, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ), - _pid_rate_yaw(AC_ATC_MULTI_RATE_YAW_P, AC_ATC_MULTI_RATE_YAW_I, AC_ATC_MULTI_RATE_YAW_D, 0.0f, AC_ATC_MULTI_RATE_YAW_IMAX, AC_ATC_MULTI_RATE_RP_FILT_HZ, AC_ATC_MULTI_RATE_YAW_FILT_HZ, 0.0f) + _motors_multi(motors) { AP_Param::setup_object_defaults(this, var_info); } diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h index 883c6193bf4924..8c85c666c20cca 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h @@ -50,6 +50,9 @@ class AC_AttitudeControl_Multi : public AC_AttitudeControl { AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; } AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; } AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; } + const AC_PID& get_rate_roll_pid() const override { return _pid_rate_roll; } + const AC_PID& get_rate_pitch_pid() const override { return _pid_rate_pitch; } + const AC_PID& get_rate_yaw_pid() const override { return _pid_rate_yaw; } // Update Alt_Hold angle maximum void update_althold_lean_angle_max(float throttle_in) override; @@ -93,9 +96,49 @@ class AC_AttitudeControl_Multi : 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; + AC_PID _pid_rate_roll { + AC_PID::Defaults{ + .p = AC_ATC_MULTI_RATE_RP_P, + .i = AC_ATC_MULTI_RATE_RP_I, + .d = AC_ATC_MULTI_RATE_RP_D, + .ff = 0.0f, + .imax = AC_ATC_MULTI_RATE_RP_IMAX, + .filt_T_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ, + .filt_E_hz = 0.0f, + .filt_D_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ, + .srmax = 0, + .srtau = 1.0 + } + }; + AC_PID _pid_rate_pitch{ + AC_PID::Defaults{ + .p = AC_ATC_MULTI_RATE_RP_P, + .i = AC_ATC_MULTI_RATE_RP_I, + .d = AC_ATC_MULTI_RATE_RP_D, + .ff = 0.0f, + .imax = AC_ATC_MULTI_RATE_RP_IMAX, + .filt_T_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ, + .filt_E_hz = 0.0f, + .filt_D_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ, + .srmax = 0, + .srtau = 1.0 + } + }; + + AC_PID _pid_rate_yaw{ + AC_PID::Defaults{ + .p = AC_ATC_MULTI_RATE_YAW_P, + .i = AC_ATC_MULTI_RATE_YAW_I, + .d = AC_ATC_MULTI_RATE_YAW_D, + .ff = 0.0f, + .imax = AC_ATC_MULTI_RATE_YAW_IMAX, + .filt_T_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ, + .filt_E_hz = AC_ATC_MULTI_RATE_YAW_FILT_HZ, + .filt_D_hz = 0.0f, + .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_Multi_6DoF.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp index ade5317e2a9787..c1fe903b698414 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.cpp @@ -7,7 +7,7 @@ #include // 6DoF control is extracted from the existing copter code by treating desired angles as thrust angles rather than vehicle attitude. -// Vehicle attitude is then set separately, typically the vehicle would matain 0 roll and pitch. +// Vehicle attitude is then set separately, typically the vehicle would maintain 0 roll and pitch. // rate commands result in the vehicle behaving as a ordinary copter. // run lowest level body-frame rate controller and send outputs to the motors diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h index f089f01d4669da..8023985eabb969 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi_6DoF.h @@ -20,10 +20,10 @@ 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 implementaiton is not overlooked + // 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; /* - override input functions to attitude controller and convert desired angles into thrust angles and substitute for osset angles + override input functions to attitude controller and convert desired angles into thrust angles and substitute for offset angles */ // Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp index 08cb1057be3174..cc7f7c566e66c4 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp @@ -73,6 +73,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: RAT_RLL_PDMX + // @DisplayName: Roll axis rate controller PD sum maximum + // @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Advanced + AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Sub, AC_PID), // @Param: RAT_PIT_P @@ -141,6 +148,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: RAT_PIT_PDMX + // @DisplayName: Pitch axis rate controller PD sum maximum + // @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Advanced + AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Sub, AC_PID), // @Param: RAT_YAW_P @@ -209,6 +223,13 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: RAT_YAW_PDMX + // @DisplayName: Yaw axis rate controller PD sum maximum + // @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Advanced + AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Sub, AC_PID), // @Param: THR_MIX_MIN @@ -378,3 +399,33 @@ void AC_AttitudeControl_Sub::parameter_sanity_check() _thr_mix_max.set_and_save(AC_ATTITUDE_CONTROL_MAX_DEFAULT); } } + +// This function ensures that the ROV reaches the target orientation with the desired yaw rate +void AC_AttitudeControl_Sub::input_euler_angle_roll_pitch_slew_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, float target_yaw_rate) +{ + // Convert from centidegrees on public interface to radians + const float euler_yaw_angle = wrap_PI(radians(euler_yaw_angle_cd * 0.01f)); + + const float current_yaw = AP::ahrs().get_yaw(); + + // Compute angle error + const float yaw_error = wrap_PI(euler_yaw_angle - current_yaw); + + int direction = 0; + if (yaw_error < 0){ + direction = -1; + } else { + direction = 1; + } + + target_yaw_rate *= direction; + + + if (fabsf(yaw_error) > MAX_YAW_ERROR) { + // rotate the rov with desired yaw rate towards the target yaw + input_euler_angle_roll_pitch_euler_rate_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, target_yaw_rate); + } else { + // holds the rov's angles + input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_angle_cd, true); + } +} diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h index ee98bca30635bd..18a627a3d7282e 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h @@ -23,6 +23,8 @@ #define AC_ATC_SUB_RATE_YAW_IMAX 0.222f #define AC_ATC_SUB_RATE_YAW_FILT_HZ 5.0f +#define MAX_YAW_ERROR radians(5) + class AC_AttitudeControl_Sub : public AC_AttitudeControl { public: AC_AttitudeControl_Sub(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsMulticopter& motors); @@ -34,6 +36,9 @@ class AC_AttitudeControl_Sub : public AC_AttitudeControl { AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; } AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; } AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; } + const AC_PID& get_rate_roll_pid() const override { return _pid_rate_roll; } + const AC_PID& get_rate_pitch_pid() const override { return _pid_rate_pitch; } + const AC_PID& get_rate_yaw_pid() const override { return _pid_rate_yaw; } // Update Alt_Hold angle maximum void update_althold_lean_angle_max(float throttle_in) override; @@ -60,6 +65,9 @@ class AC_AttitudeControl_Sub : public AC_AttitudeControl { // sanity check parameters. should be called once before take-off void parameter_sanity_check() override; + // This function ensures that the ROV reaches the target orientation with the desired yaw rate + void input_euler_angle_roll_pitch_slew_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, float slew_yaw); + // user settable parameters static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AC_AttitudeControl/AC_CommandModel.cpp b/libraries/AC_AttitudeControl/AC_CommandModel.cpp index 0efe05f36cab94..caf06d826ebcea 100644 --- a/libraries/AC_AttitudeControl/AC_CommandModel.cpp +++ b/libraries/AC_AttitudeControl/AC_CommandModel.cpp @@ -1,7 +1,7 @@ #include "AC_CommandModel.h" #include -// The Commmand Model class holds parameters that shape the pilot desired angular rate input. This class can +// The Command Model class holds parameters that shape the pilot desired angular rate input. This class can // be expanded to hold the methods that shape the pilot desired input. extern const AP_HAL::HAL& hal; diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 83bc5cbd4d21cc..06eed5ddba4612 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -204,6 +204,13 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: _ACCZ_PDMX + // @DisplayName: Acceleration (vertical) controller PD sum maximum + // @Description: Acceleration (vertical) controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 1000 + // @Units: d% + // @User: Advanced + AP_SUBGROUPINFO(_pid_accel_z, "_ACCZ_", 4, AC_PosControl, AC_PID), // @Param: _POSXY_P @@ -649,6 +656,13 @@ void AC_PosControl::update_xy_controller() if (!limit_accel_xy(_vel_desired.xy(), _accel_target.xy(), accel_max)) { // _accel_target was not limited so we can zero the xy limit vector _limit_vector.xy().zero(); + } else { + // Check for pitch limiting in the forward direction + const float accel_fwd_unlimited = _limit_vector.x * _ahrs.cos_yaw() + _limit_vector.y * _ahrs.sin_yaw(); + const float pitch_target_unlimited = accel_to_angle(- MIN(accel_fwd_unlimited, accel_max) * 0.01f) * 100; + const float accel_fwd_limited = _accel_target.x * _ahrs.cos_yaw() + _accel_target.y * _ahrs.sin_yaw(); + const float pitch_target_limited = accel_to_angle(- accel_fwd_limited * 0.01f) * 100; + _fwd_pitch_is_limited = is_negative(pitch_target_unlimited) && pitch_target_unlimited < pitch_target_limited; } // update angle targets that will be passed to stabilize controller diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 5284f3f36fabc7..8863125ac4c7b2 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -394,6 +394,9 @@ class AC_PosControl // get earth-frame Z-axis acceleration with gravity removed in cm/s/s with +ve being up float get_z_accel_cmss() const { return -(_ahrs.get_accel_ef().z + GRAVITY_MSS) * 100.0f; } + /// 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; } + static const struct AP_Param::GroupInfo var_info[]; protected: @@ -462,6 +465,8 @@ class AC_PosControl Vector3f _accel_target; // acceleration target in NEU cm/s/s Vector3f _limit_vector; // the direction that the position controller is limited, zero when not limited + 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 diff --git a/libraries/AC_AttitudeControl/AC_WeatherVane.cpp b/libraries/AC_AttitudeControl/AC_WeatherVane.cpp index fd6ad741b3e499..087f4b2274c51d 100644 --- a/libraries/AC_AttitudeControl/AC_WeatherVane.cpp +++ b/libraries/AC_AttitudeControl/AC_WeatherVane.cpp @@ -23,7 +23,7 @@ const AP_Param::GroupInfo AC_WeatherVane::var_info[] = { // @Param: ENABLE // @DisplayName: Enable - // @Description: Enable weather vaning. When active, the aircraft will automatically yaw into wind when in a VTOL position controlled mode. Pilot yaw commands overide the weathervaning action. + // @Description: Enable weather vaning. When active, the aircraft will automatically yaw into wind when in a VTOL position controlled mode. Pilot yaw commands override the weathervaning action. // @Values: -1:Only use during takeoffs or landing see weathervane takeoff and land override parameters,0:Disabled,1:Nose into wind,2:Nose or tail into wind,3:Side into wind,4:tail into wind // @User: Standard AP_GROUPINFO_FLAGS("ENABLE", 1, AC_WeatherVane, _direction, WVANE_PARAM_ENABLED, AP_PARAM_FLAG_ENABLE), @@ -139,7 +139,7 @@ bool AC_WeatherVane::get_yaw_out(float &yaw_output, const int16_t pilot_yaw, con if (is_positive(_max_vel_xy) || is_positive(_max_vel_z)) { Vector3f vel_ned; if (!AP::ahrs().get_velocity_NED(vel_ned) || // need speed estimate - (is_positive(_max_vel_xy) && (vel_ned.xy().length_squared() > (_max_vel_xy*_max_vel_xy))) || // check xy speeed + (is_positive(_max_vel_xy) && (vel_ned.xy().length_squared() > (_max_vel_xy*_max_vel_xy))) || // check xy speed (is_positive(_max_vel_z) && (fabsf(vel_ned.z) > _max_vel_z))) { // check z speed reset(); return false; diff --git a/libraries/AC_AttitudeControl/AC_WeatherVane.h b/libraries/AC_AttitudeControl/AC_WeatherVane.h index c4585b21c1c652..38d7ecb039dca7 100644 --- a/libraries/AC_AttitudeControl/AC_WeatherVane.h +++ b/libraries/AC_AttitudeControl/AC_WeatherVane.h @@ -36,7 +36,7 @@ class AC_WeatherVane { PITCH_ENABLE = (1<<0), }; - // Paramaters + // Parameters AP_Int8 _direction; AP_Float _gain; AP_Float _min_dz_ang_deg; diff --git a/libraries/AC_AutoTune/AC_AutoTune.h b/libraries/AC_AutoTune/AC_AutoTune.h index 206050f7022131..e152af499993f8 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.h +++ b/libraries/AC_AutoTune/AC_AutoTune.h @@ -158,7 +158,7 @@ class AC_AutoTune AP_AHRS_View *ahrs_view, AP_InertialNav *inertial_nav); - // send intermittant updates to user on status of tune + // send intermittent updates to user on status of tune virtual void do_gcs_announcements() = 0; // send post test updates to user diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp index 346a8143fe5115..d72a6db6fe4c09 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp @@ -678,7 +678,7 @@ void AC_AutoTune_Heli::report_final_gains(AxisType test_axis) const } } -// report gain formating helper +// 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); @@ -1353,7 +1353,7 @@ 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 acheived +// 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) { @@ -1565,7 +1565,7 @@ void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, float *freq, float *ga // 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 acheived + // 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; @@ -1837,7 +1837,7 @@ void AC_AutoTune_Heli::Log_Write_AutoTuneSweep(float freq, float gain, float pha phase); } -// reset the test vaariables for each vehicle +// reset the test variables for each vehicle void AC_AutoTune_Heli::reset_vehicle_test_variables() { // reset dwell test variables if sweep was interrupted in order to restart sweep diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.h b/libraries/AC_AutoTune/AC_AutoTune_Heli.h index cf941737919c97..6329563b02bae7 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.h @@ -60,7 +60,7 @@ class AC_AutoTune_Heli : public AC_AutoTune // load test gains void load_test_gains() override; - // reset the test vaariables for heli + // reset the test variables for heli void reset_vehicle_test_variables() override; // reset the update gain variables for heli @@ -111,7 +111,7 @@ class AC_AutoTune_Heli : public AC_AutoTune void Log_AutoTuneSweep() override; void Log_Write_AutoTuneSweep(float freq, float gain, float phase); - // send intermittant updates to user on status of tune + // send intermittent updates to user on status of tune void do_gcs_announcements() override; // send post test updates to user @@ -161,7 +161,7 @@ class AC_AutoTune_Heli : public AC_AutoTune void dwell_test_run(uint8_t freq_resp_input, float start_frq, float stop_frq, float &dwell_gain, float &dwell_phase, DwellType dwell_type); // updating_rate_ff_up - adjust FF to ensure the target is reached - // FF is adjusted until rate requested is acheived + // 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); // 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 @@ -185,7 +185,7 @@ class AC_AutoTune_Heli : public AC_AutoTune // exceeded_freq_range - ensures tuning remains inside frequency range bool exceeded_freq_range(float frequency); - // report gain formating helper + // 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 diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp index 6e414b76d8b914..bf988c187ae9f2 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp @@ -484,7 +484,7 @@ void AC_AutoTune_Multi::report_final_gains(AxisType test_axis) const } } -// report gain formating helper +// 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); diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.h b/libraries/AC_AutoTune/AC_AutoTune_Multi.h index 5374a432f849a0..b2a02fcdc6bce8 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.h @@ -53,7 +53,7 @@ class AC_AutoTune_Multi : public AC_AutoTune // load test gains void load_test_gains() override; - // reset the test vaariables for multi + // reset the test variables for multi void reset_vehicle_test_variables() override {}; // reset the update gain variables for multi @@ -62,7 +62,7 @@ class AC_AutoTune_Multi : public AC_AutoTune void test_init() override; void test_run(AxisType test_axis, const float dir_sign) override; - // send intermittant updates to user on status of tune + // send intermittent updates to user on status of tune void do_gcs_announcements() override; // send post test updates to user @@ -160,7 +160,7 @@ class AC_AutoTune_Multi : public AC_AutoTune // P is increased until we achieve our target within a reasonable time void 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); - // report gain formating helper + // report gain formatting helper 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 diff --git a/libraries/AC_Autorotation/AC_Autorotation.cpp b/libraries/AC_Autorotation/AC_Autorotation.cpp index 69f9a6dcbb5cb7..7ce790517d942b 100644 --- a/libraries/AC_Autorotation/AC_Autorotation.cpp +++ b/libraries/AC_Autorotation/AC_Autorotation.cpp @@ -101,7 +101,7 @@ const AP_Param::GroupInfo AC_Autorotation::var_info[] = { // @Param: FW_V_P // @DisplayName: Velocity (horizontal) P gain - // @Description: Velocity (horizontal) P gain. Determines the propotion of the target acceleration based on the velocity error. + // @Description: Velocity (horizontal) P gain. Determines the proportion of the target acceleration based on the velocity error. // @Range: 0.1 6.0 // @Increment: 0.1 // @User: Advanced @@ -153,7 +153,7 @@ bool AC_Autorotation::update_hs_glide_controller(float dt) _flags.bad_rpm = false; _flags.bad_rpm_warning = false; - // Get current rpm and update healthly signal counters + // Get current rpm and update healthy signal counters _current_rpm = get_rpm(true); if (_unhealthy_rpm_counter <=30) { @@ -220,7 +220,7 @@ float AC_Autorotation::get_rpm(bool update_counter) //Get RPM value uint8_t instance = _param_rpm_instance; - //Check RPM sesnor is returning a healthy status + //Check RPM sensor is returning a healthy status if (!rpm->get_rpm(instance, current_rpm) || current_rpm <= -1) { //unhealthy, rpm unreliable _flags.bad_rpm = true; @@ -322,7 +322,7 @@ void AC_Autorotation::update_forward_speed_controller(void) _delta_speed_fwd = _speed_forward - _speed_forward_last; //(cm/s) _speed_forward_last = _speed_forward; //(cm/s) - // Limitng the target velocity based on the max acceleration limit + // Limiting the target velocity based on the max acceleration limit if (_cmd_vel < _vel_target) { _cmd_vel += _accel_max * _dt; if (_cmd_vel > _vel_target) { diff --git a/libraries/AC_Autorotation/AC_Autorotation.h b/libraries/AC_Autorotation/AC_Autorotation.h index d89fe88dc42379..d5cfa52097b3f1 100644 --- a/libraries/AC_Autorotation/AC_Autorotation.h +++ b/libraries/AC_Autorotation/AC_Autorotation.h @@ -32,7 +32,7 @@ class AC_Autorotation float get_last_collective() const { return _collective_out; } bool is_enable(void) { return _param_enable; } void Log_Write_Autorotation(void) const; - void update_forward_speed_controller(void); // Update foward speed controller + void update_forward_speed_controller(void); // Update forward speed controller void set_desired_fwd_speed(void) { _vel_target = _param_target_speed; } // Overloaded: Set desired speed for forward controller to parameter value void set_desired_fwd_speed(float speed) { _vel_target = speed; } // Overloaded: Set desired speed to argument value int32_t get_pitch(void) const { return _pitch_target; } // Get pitch target diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index 7b2e5fdf20f490..8e5067f3be6935 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -143,7 +143,7 @@ void AC_Avoid::adjust_velocity_fence(float kP, float accel_cmss, Vector3f &desir adjust_velocity_circle_fence(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt); find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel); - // backup_vel_fence is set to zero after each fence incase the velocity is unset from previous methods + // backup_vel_fence is set to zero after each fence in case the velocity is unset from previous methods backup_vel_fence.zero(); adjust_velocity_inclusion_and_exclusion_polygons(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt); find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel); @@ -229,7 +229,7 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa } // 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 seperately. For eg, user is doing fine in "x" direction but might need backing up in "y". + // 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)) { if (is_positive(desired_backup_vel.x)) { desired_vel_cms.x = MAX(desired_vel_cms.x, desired_backup_vel.x); @@ -505,7 +505,7 @@ void AC_Avoid::limit_velocity_3D(float kP, float accel_cmss, Vector3f &desired_v return; } // create a margin_cm length vector in the direction of desired_vel_cms - // this will create larger margin towards the direction vehicle is traveling in + // this will create larger margin towards the direction vehicle is travelling in const Vector3f margin_vector = desired_vel_cms.normalized() * margin_cm; const Vector2f limit_direction_xy{obstacle_vector.x, obstacle_vector.y}; diff --git a/libraries/AC_Avoidance/AC_Avoid.h b/libraries/AC_Avoidance/AC_Avoid.h index 2f9f048dae2a80..6bccfb846d58b9 100644 --- a/libraries/AC_Avoidance/AC_Avoid.h +++ b/libraries/AC_Avoidance/AC_Avoid.h @@ -18,7 +18,7 @@ #define AC_AVOID_NONGPS_DIST_MAX_DEFAULT 5.0f // objects over 5m away are ignored (default value for DIST_MAX parameter) #define AC_AVOID_ANGLE_MAX_PERCENT 0.75f // object avoidance max lean angle as a percentage (expressed in 0 ~ 1 range) of total vehicle max lean angle -#define AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS 500 // if limiting is active if last limit is happend in the last x ms +#define AC_AVOID_ACTIVE_LIMIT_TIMEOUT_MS 500 // if limiting is active if last limit is happened in the last x ms #define AC_AVOID_ACCEL_TIMEOUT_MS 200 // stored velocity used to calculate acceleration will be reset if avoidance is active after this many ms /* @@ -213,7 +213,7 @@ class AC_Avoid { 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 accelration while simple avoidance is active + 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) diff --git a/libraries/AC_Avoidance/AP_OABendyRuler.h b/libraries/AC_Avoidance/AP_OABendyRuler.h index b90b7d6cbb8e46..e282e647221942 100644 --- a/libraries/AC_Avoidance/AP_OABendyRuler.h +++ b/libraries/AC_Avoidance/AP_OABendyRuler.h @@ -74,7 +74,7 @@ class AP_OABendyRuler { // BendyRuler parameters AP_Float _lookahead; // object avoidance will look this many meters ahead of vehicle AP_Float _bendy_ratio; // object avoidance will avoid major directional change if change in margin ratio is less than this param - AP_Int16 _bendy_angle; // object avoidance will try avoding change in direction over this much angle + AP_Int16 _bendy_angle; // object avoidance will try avoiding change in direction over this much angle AP_Int8 _bendy_type; // Type of BendyRuler to run // internal variables used by background thread diff --git a/libraries/AC_Avoidance/AP_OADatabase.cpp b/libraries/AC_Avoidance/AP_OADatabase.cpp index cb0153fbbea909..aeae78098b9abc 100644 --- a/libraries/AC_Avoidance/AP_OADatabase.cpp +++ b/libraries/AC_Avoidance/AP_OADatabase.cpp @@ -125,7 +125,7 @@ void AP_OADatabase::init() dist_to_radius_scalar = tanf(radians(MAX(_beam_width, 1.0f))); if (!healthy()) { - gcs().send_text(MAV_SEVERITY_INFO, "DB init failed . Sizes queue:%u, db:%u", (unsigned int)_queue.size, (unsigned int)_database.size); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "DB init failed . Sizes queue:%u, db:%u", (unsigned int)_queue.size, (unsigned int)_database.size); delete _queue.items; delete[] _database.items; return; @@ -230,7 +230,7 @@ uint8_t AP_OADatabase::get_send_to_gcs_flags(const OA_DbItemImportance importanc return 0x0; } -// returns true when there's more work inthe queue to do +// returns true when there's more work in the queue to do bool AP_OADatabase::process_queue() { if (!healthy()) { @@ -365,6 +365,7 @@ bool AP_OADatabase::is_close_to_item_in_database(const uint16_t index, const OA_ return ((distance_sq < sq(item.radius)) || (distance_sq < sq(_database.items[index].radius))); } +#if HAL_GCS_ENABLED // send ADSB_VEHICLE mavlink messages void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ms) { @@ -469,6 +470,7 @@ void AP_OADatabase::send_adsb_vehicle(mavlink_channel_t chan, uint16_t interval_ num_sent++; } } +#endif // HAL_GCS_ENABLED // singleton instance AP_OADatabase *AP_OADatabase::_singleton; diff --git a/libraries/AC_Avoidance/AP_OADijkstra.cpp b/libraries/AC_Avoidance/AP_OADijkstra.cpp index 6ebca1e0fc7b44..749cb140ee24a1 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.cpp +++ b/libraries/AC_Avoidance/AP_OADijkstra.cpp @@ -247,7 +247,8 @@ void AP_OADijkstra::report_error(AP_OADijkstra_Error error_id) if ((error_id != AP_OADijkstra_Error::DIJKSTRA_ERROR_NONE) && ((error_id != _error_last_id) || ((now_ms - _error_last_report_ms) > OA_DIJKSTRA_ERROR_REPORTING_INTERVAL_MS))) { const char* error_msg = get_error_msg(error_id); - gcs().send_text(MAV_SEVERITY_CRITICAL, "Dijkstra: %s", error_msg); + (void)error_msg; // in case !HAL_GCS_ENABLED + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Dijkstra: %s", error_msg); _error_last_id = error_id; _error_last_report_ms = now_ms; } @@ -924,7 +925,7 @@ bool AP_OADijkstra::calc_shortest_path(const Location &origin, const Location &d } } } - // report error incase path not found + // report error in case path not found if (!success) { err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_COULD_NOT_FIND_PATH; } diff --git a/libraries/AC_Avoidance/AP_OADijkstra.h b/libraries/AC_Avoidance/AP_OADijkstra.h index f95405ad711ede..48e91f6cc1269c 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.h +++ b/libraries/AC_Avoidance/AP_OADijkstra.h @@ -197,6 +197,6 @@ class AP_OADijkstra { uint8_t _log_num_points; uint8_t _log_visgraph_version; - // refernce to AP_OAPathPlanner options param + // reference to AP_OAPathPlanner options param AP_Int16 &_options; }; diff --git a/libraries/AC_CustomControl/AC_CustomControl.h b/libraries/AC_CustomControl/AC_CustomControl.h index c11a51fb00833a..bf0628302b72ad 100644 --- a/libraries/AC_CustomControl/AC_CustomControl.h +++ b/libraries/AC_CustomControl/AC_CustomControl.h @@ -32,7 +32,7 @@ class AC_CustomControl { bool is_safe_to_run(void); void log_switch(void); - // zero index controller type param, only use it to acces _backend or _backend_var_info array + // zero index controller type param, only use it to access _backend or _backend_var_info array uint8_t get_type() { return _controller_type > 0 ? (_controller_type - 1) : 0; }; // User settable parameters diff --git a/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp b/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp index d11caabc7eca56..222510c4f471d9 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl_Empty.cpp @@ -8,19 +8,19 @@ const AP_Param::GroupInfo AC_CustomControl_Empty::var_info[] = { // @Param: PARAM1 // @DisplayName: Empty param1 - // @Description: Dumy parameter for empty custom controller backend + // @Description: Dummy parameter for empty custom controller backend // @User: Advanced AP_GROUPINFO("PARAM1", 1, AC_CustomControl_Empty, param1, 0.0f), // @Param: PARAM2 // @DisplayName: Empty param2 - // @Description: Dumy parameter for empty custom controller backend + // @Description: Dummy parameter for empty custom controller backend // @User: Advanced AP_GROUPINFO("PARAM2", 2, AC_CustomControl_Empty, param2, 0.0f), // @Param: PARAM3 // @DisplayName: Empty param3 - // @Description: Dumy parameter for empty custom controller backend + // @Description: Dummy parameter for empty custom controller backend // @User: Advanced AP_GROUPINFO("PARAM3", 3, AC_CustomControl_Empty, param3, 0.0f), @@ -54,7 +54,7 @@ Vector3f AC_CustomControl_Empty::update(void) break; } - // arducopter main attitude controller already runned + // arducopter main attitude controller already ran // we don't need to do anything else gcs().send_text(MAV_SEVERITY_INFO, "empty custom controller working"); diff --git a/libraries/AC_CustomControl/AC_CustomControl_PID.cpp b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp index 29e2163cbb6ea3..e468e8f0be0f2a 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_PID.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp @@ -94,6 +94,13 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @Range: 0 200 // @Increment: 0.5 // @User: Advanced + + // @Param: RAT_RLL_PDMX + // @DisplayName: Roll axis rate controller PD sum maximum + // @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Advanced AP_SUBGROUPINFO(_pid_atti_rate_roll, "RAT_RLL_", 4, AC_CustomControl_PID, AC_PID), // @Param: RAT_PIT_P @@ -161,6 +168,13 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @Range: 0 200 // @Increment: 0.5 // @User: Advanced + + // @Param: RAT_PIT_PDMX + // @DisplayName: Pitch axis rate controller PD sum maximum + // @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Advanced AP_SUBGROUPINFO(_pid_atti_rate_pitch, "RAT_PIT_", 5, AC_CustomControl_PID, AC_PID), @@ -229,6 +243,13 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @Range: 0 200 // @Increment: 0.5 // @User: Advanced + + // @Param: RAT_YAW_PDMX + // @DisplayName: Yaw axis rate controller PD sum maximum + // @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0 1 + // @Increment: 0.01 + // @User: Advanced AP_SUBGROUPINFO(_pid_atti_rate_yaw, "RAT_YAW_", 6, AC_CustomControl_PID, AC_PID), AP_GROUPEND diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index f9bdb7733010f9..aaec44932bd4ed 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -35,7 +35,7 @@ extern const AP_HAL::HAL& hal; #define AC_FENCE_MANUAL_RECOVERY_TIME_MIN 10000 // pilot has 10seconds to recover during which time the autopilot will not attempt to re-take control #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) -#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 100.0 // after fence is broken we recreate the fence 50m further out +#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 100.0 // after fence is broken we recreate the fence 100m further out #else #define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 20.0 // after fence is broken we recreate the fence 20m further out #endif @@ -52,8 +52,8 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = { // @Param: TYPE // @DisplayName: Fence Type // @Description: Enabled fence types held as bitmask - // @Bitmask{Rover}: 1:Circle,2:Polygon - // @Bitmask{Copter, Plane, Sub}: 0:Max altitude,1:Circle,2:Polygon,3:Min altitude + // @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), @@ -137,8 +137,8 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = { // @Param{Plane}: OPTIONS // @DisplayName: Fence options - // @Description: 0:Disable mode change following fence action until fence breach is cleared - // @Bitmask: 0:Disable mode change following fence action until fence breach is cleared + // @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. + // @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), @@ -494,7 +494,7 @@ bool AC_Fence::check_fence_polygon() /// check_fence_circle - returns true if the circle fence (defined via /// parameters) has been freshly breached. May also set up a backup /// fence outside the fence and return a fresh breach if that backup -/// fence is breaced. +/// fence is breached. bool AC_Fence::check_fence_circle() { if (!(_enabled_fences & AC_FENCE_TYPE_CIRCLE)) { @@ -518,7 +518,7 @@ bool AC_Fence::check_fence_circle() if (!(_breached_fences & AC_FENCE_TYPE_CIRCLE) || (!is_zero(_circle_radius_backup) && _home_distance >= _circle_radius_backup)) { // new breach - // create a backup fence 20m further out + // create a backup fence 20m or 100m further out record_breach(AC_FENCE_TYPE_CIRCLE); _circle_radius_backup = _home_distance + AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE; return true; @@ -638,7 +638,7 @@ void AC_Fence::record_breach(uint8_t fence_type) // emit a message indicated we're newly-breached, but not too often if (now - _last_breach_notify_sent_ms > 1000) { _last_breach_notify_sent_ms = now; - gcs().send_message(MSG_FENCE_STATUS); + GCS_SEND_MESSAGE(MSG_FENCE_STATUS); } } diff --git a/libraries/AC_Fence/AC_Fence.h b/libraries/AC_Fence/AC_Fence.h index d4c042c082834a..1e8bd1d37c5b6f 100644 --- a/libraries/AC_Fence/AC_Fence.h +++ b/libraries/AC_Fence/AC_Fence.h @@ -32,6 +32,7 @@ class AC_Fence { public: + friend class AC_PolyFence_loader; enum class AutoEnable { @@ -146,10 +147,14 @@ class AC_Fence const AC_PolyFence_loader &polyfence() const; enum class OPTIONS { - DISABLE_MODE_CHANGE = 1 << 0, + DISABLE_MODE_CHANGE = 1U << 0, + INCLUSION_UNION = 1U << 1, }; + static bool option_enabled(OPTIONS opt, const AP_Int16 &options) { + return (options.get() & int16_t(opt)) != 0; + } bool option_enabled(OPTIONS opt) const { - return (_options.get() & int16_t(opt)) != 0; + return option_enabled(opt, _options); } static const struct AP_Param::GroupInfo var_info[]; @@ -219,7 +224,7 @@ class AC_Fence uint32_t _manual_recovery_start_ms; // system time in milliseconds that pilot re-took manual control - AC_PolyFence_loader _poly_loader{_total}; // polygon fence + AC_PolyFence_loader _poly_loader{_total, _options}; // polygon fence }; namespace AP { diff --git a/libraries/AC_Fence/AC_Fence_config.h b/libraries/AC_Fence/AC_Fence_config.h index 5c8494f7ad1403..dbc607afa755da 100644 --- a/libraries/AC_Fence/AC_Fence_config.h +++ b/libraries/AC_Fence/AC_Fence_config.h @@ -9,3 +9,7 @@ #ifndef AP_FENCE_ENABLED #define AP_FENCE_ENABLED 2 #endif + +#ifndef AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT +#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT AP_FENCE_ENABLED +#endif diff --git a/libraries/AC_Fence/AC_PolyFence_loader.cpp b/libraries/AC_Fence/AC_PolyFence_loader.cpp index 242ed7c40fbf38..1b42ded2738094 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.cpp +++ b/libraries/AC_Fence/AC_PolyFence_loader.cpp @@ -13,6 +13,7 @@ #include #include #include +#include #include @@ -189,21 +190,6 @@ bool AC_PolyFence_loader::read_latlon_from_storage(uint16_t &read_offset, Vector return true; } -// load boundary point from eeprom, returns true on successful load -// only used for converting from old storage to new storage -bool AC_PolyFence_loader::load_point_from_eeprom(uint16_t i, Vector2l& point) const -{ - // sanity check index - if (i >= max_items()) { - return false; - } - - // read fence point - point.x = fence_storage.read_uint32(i * sizeof(Vector2l)); - point.y = fence_storage.read_uint32(i * sizeof(Vector2l) + sizeof(uint32_t)); - return true; -} - bool AC_PolyFence_loader::breached() const { Location loc; @@ -226,11 +212,14 @@ bool AC_PolyFence_loader::breached(const Location& loc) const pos.x = loc.lat; pos.y = loc.lng; + const uint16_t num_inclusion = _num_loaded_circle_inclusion_boundaries + _num_loaded_inclusion_boundaries; + uint16_t num_inclusion_outside = 0; + // check we are inside each inclusion zone: for (uint8_t i=0; i<_num_loaded_inclusion_boundaries; i++) { const InclusionBoundary &boundary = _loaded_inclusion_boundary[i]; if (Polygon_outside(pos, boundary.points_lla, boundary.count)) { - return true; + num_inclusion_outside++; } } @@ -260,6 +249,21 @@ bool AC_PolyFence_loader::breached(const Location& loc) const circle_center.lng = circle.point.y; const float diff_cm = loc.get_distance(circle_center)*100.0f; if (diff_cm > circle.radius * 100.0f) { + num_inclusion_outside++; + } + } + + if (AC_Fence::option_enabled(AC_Fence::OPTIONS::INCLUSION_UNION, _options)) { + // using union of inclusion areas, we are outside the fence if + // there is at least one inclusion areas and we are outside + // all of them + if (num_inclusion > 0 && num_inclusion == num_inclusion_outside) { + return true; + } + } else { + // using intersection of inclusion areas. We are outside if we + // are outside any of them + if (num_inclusion_outside > 0) { return true; } } @@ -294,70 +298,6 @@ bool AC_PolyFence_loader::format() return write_eos_to_storage(offset); } -bool AC_PolyFence_loader::convert_to_new_storage() -{ - // sanity check total - _total.set(constrain_int16(_total, 0, max_items())); - // FIXME: ensure the fence was closed and don't load it if it was not - if (_total < 5) { - // fence was invalid. Just format it and move on - return format(); - } - - if (hal.util->available_memory() < 100U + _total * sizeof(Vector2l)) { - return false; - } - - Vector2l *_tmp_boundary = new Vector2l[_total]; - if (_tmp_boundary == nullptr) { - return false; - } - - // load each point from eeprom - bool ret = false; - for (uint16_t index=0; index<_total; index++) { - // load boundary point as lat/lon point - if (!load_point_from_eeprom(index, _tmp_boundary[index])) { - goto out; - } - } - - // now store: - if (!format()) { - goto out; - } - { - uint16_t offset = 4; // skip magic - // write return point - if (!write_type_to_storage(offset, AC_PolyFenceType::RETURN_POINT)) { - return false; - } - if (!write_latlon_to_storage(offset, _tmp_boundary[0])) { - return false; - } - // write out polygon fence - fence_storage.write_uint8(offset, (uint8_t)AC_PolyFenceType::POLYGON_INCLUSION); - offset++; - fence_storage.write_uint8(offset, (uint8_t)_total-2); - offset++; - for (uint8_t i=1; i<_total-1; i++) { - if (!write_latlon_to_storage(offset, _tmp_boundary[i])) { - goto out; - } - } - // write eos marker - if (!write_eos_to_storage(offset)) { - goto out; - } - } - - ret = true; - -out: - delete[] _tmp_boundary; - return ret; -} - bool AC_PolyFence_loader::scale_latlon_from_origin(const Location &origin, const Vector2l &point, Vector2f &pos_cm) { Location tmp_loc; @@ -522,7 +462,7 @@ void AC_PolyFence_loader::scan_eeprom_index_fences(const AC_PolyFenceType type, bool AC_PolyFence_loader::index_eeprom() { if (!formatted()) { - if (!convert_to_new_storage()) { + if (!format()) { return false; } } @@ -1202,7 +1142,6 @@ bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_ } -#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT bool AC_PolyFence_loader::get_return_point(Vector2l &ret) { if (!check_indexed()) { @@ -1277,7 +1216,6 @@ bool AC_PolyFence_loader::get_return_point(Vector2l &ret) return true; } -#endif AC_PolyFence_loader::FenceIndex *AC_PolyFence_loader::find_first_fence(const AC_PolyFenceType type) const { diff --git a/libraries/AC_Fence/AC_PolyFence_loader.h b/libraries/AC_Fence/AC_PolyFence_loader.h index 4c74bd7e2c3e9e..5c87b5b4a78ef5 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.h +++ b/libraries/AC_Fence/AC_PolyFence_loader.h @@ -6,7 +6,7 @@ // CIRCLE_INCLUSION_INT stores the radius an a 32-bit integer in // metres. This was a bug, and CIRCLE_INCLUSION was created to store // as a 32-bit float instead. We save as _INT in the case that the -// radius looks like an integer as a backwards-compatability measure. +// radius looks like an integer as a backwards-compatibility measure. // For 4.2 we might consider only loading _INT and always saving as // float, and in 4.3 considering _INT invalid enum class AC_PolyFenceType { @@ -39,15 +39,14 @@ class AC_PolyFenceItem { #include #include -#define AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT 1 - class AC_PolyFence_loader { public: - AC_PolyFence_loader(AP_Int8 &total) : - _total(total) {} + AC_PolyFence_loader(AP_Int8 &total, const AP_Int16 &options) : + _total(total), + _options(options) {} /* Do not allow copies */ CLASS_NO_COPY(AC_PolyFence_loader); @@ -173,12 +172,10 @@ class AC_PolyFence_loader // call @10Hz to check for fence load being valid void update(); -#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT // get_return_point - returns latitude/longitude of return point. // This works with storage - the returned vector is absolute // lat/lon. bool get_return_point(Vector2l &ret) WARN_IF_UNUSED; -#endif // return total number of fences - polygons and circles uint16_t total_fence_count() const { @@ -353,21 +350,9 @@ class AC_PolyFence_loader Vector2f *&next_storage_point, Vector2l *&next_storage_point_lla) WARN_IF_UNUSED; - /* - * Upgrade functions - attempt to keep user's fences when - * upgrading to new firmware - */ - // convert_to_new_storage - will attempt to change a pre-existing - // stored fence to the new storage format (so people don't lose - // their fences when upgrading) - bool convert_to_new_storage() WARN_IF_UNUSED; - // load boundary point from eeprom, returns true on successful load - bool load_point_from_eeprom(uint16_t i, Vector2l& point) const WARN_IF_UNUSED; - - #if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT /* - * FENCE_POINT protocol compatability + * FENCE_POINT protocol compatibility */ void handle_msg_fetch_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg); void handle_msg_fence_point(GCS_MAVLINK &link, const mavlink_message_t& msg); @@ -395,8 +380,9 @@ class AC_PolyFence_loader bool write_eos_to_storage(uint16_t &offset); // _total - reference to FENCE_TOTAL parameter. This is used - // solely for compatability with the FENCE_POINT protocol + // solely for compatibility with the FENCE_POINT protocol AP_Int8 &_total; + const AP_Int16 &_options; uint8_t _old_total; diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index 51b216c42d7cd6..bf154a59d7c7c0 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -64,6 +64,12 @@ const AP_Param::GroupInfo AC_PID::var_info[] = { // @User: Advanced AP_GROUPINFO_FLAGS_DEFAULT_POINTER("SMAX", 12, AC_PID, _slew_rate_max, default_slew_rate_max), + // @Param: PDMX + // @DisplayName: PD sum maximum + // @Description: The maximum/minimum value that the sum of the P and D term can output + // @User: Advanced + AP_GROUPINFO("PDMX", 13, AC_PID, _kpdmax, 0), + AP_GROUPEND }; @@ -166,13 +172,24 @@ float AC_PID::update_all(float target, float measurement, float dt, bool limit, P_out *= boost; D_out *= boost; + // Apply PD sum limit if enabled + if (is_positive(_kpdmax)) { + const float PD_sum_abs = fabsf(P_out + D_out); + if (PD_sum_abs > _kpdmax) { + const float PD_scale = _kpdmax / PD_sum_abs; + P_out *= PD_scale; + D_out *= PD_scale; + _pid_info.PD_limit = true; + } + } + _pid_info.target = _target; _pid_info.actual = measurement; _pid_info.error = _error; _pid_info.P = P_out; _pid_info.D = D_out; - return P_out + _integrator + D_out; + return P_out + D_out + _integrator; } // update_error - set error input to PID controller and calculate outputs @@ -188,44 +205,17 @@ float AC_PID::update_error(float error, float dt, bool limit) return 0.0f; } - _target = 0.0f; - - // reset input filter to value received - if (_flags._reset_filter) { - _flags._reset_filter = false; - _error = error; - _derivative = 0.0f; - } else { - float error_last = _error; - _error += get_filt_E_alpha(dt) * (error - _error); - - // calculate and filter derivative - if (is_positive(dt)) { - float derivative = (_error - error_last) / dt; - _derivative += get_filt_D_alpha(dt) * (derivative - _derivative); - } - } - - // update I term - update_i(dt, limit); + // Reuse update all code path, zero target and pass negative error as measurement + // Passing as measurement bypasses any target filtering to maintain behaviour + // Negate as update all calculates error as target - measurement + _target = 0.0; + const float output = update_all(0.0, -error, dt, limit); - float P_out = (_error * _kp); - float D_out = (_derivative * _kd); - - // calculate slew limit modifier for P+D - _pid_info.Dmod = _slew_limiter.modifier((_pid_info.P + _pid_info.D) * _slew_limit_scale, dt); - _pid_info.slew_rate = _slew_limiter.get_slew_rate(); - - P_out *= _pid_info.Dmod; - D_out *= _pid_info.Dmod; - - _pid_info.target = 0.0f; - _pid_info.actual = 0.0f; - _pid_info.error = _error; - _pid_info.P = P_out; - _pid_info.D = D_out; + // Make sure logged target and actual are still 0 to maintain behaviour + _pid_info.target = 0.0; + _pid_info.actual = 0.0; - return P_out + _integrator + D_out; + return output; } // update_i - update the integral @@ -279,6 +269,8 @@ void AC_PID::load_gains() _kff.load(); _kimax.load(); _kimax.set(fabsf(_kimax)); + _kpdmax.load(); + _kpdmax.set(fabsf(_kpdmax)); _filt_T_hz.load(); _filt_E_hz.load(); _filt_D_hz.load(); diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index ca2941daa6e085..7ae4592473109e 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -21,9 +21,36 @@ class AC_PID { public: + struct Defaults { + float p; + float i; + float d; + float ff; + float imax; + float filt_T_hz; + float filt_E_hz; + float filt_D_hz; + float srmax; + float srtau; + }; + // Constructor for PID AC_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, float initial_srmax=0, float initial_srtau=1.0); + AC_PID(const AC_PID::Defaults &defaults) : + AC_PID( + defaults.p, + defaults.i, + defaults.d, + defaults.ff, + defaults.imax, + defaults.filt_T_hz, + defaults.filt_E_hz, + defaults.filt_D_hz, + defaults.srmax, + defaults.srtau + ) + { } CLASS_NO_COPY(AC_PID); @@ -71,10 +98,12 @@ class AC_PID { void operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz); // get accessors + const AP_Float &kP() const { return _kp; } AP_Float &kP() { return _kp; } AP_Float &kI() { return _ki; } AP_Float &kD() { return _kd; } AP_Float &kIMAX() { return _kimax; } + AP_Float &kPDMAX() { return _kpdmax; } AP_Float &ff() { return _kff;} AP_Float &filt_T_hz() { return _filt_T_hz; } AP_Float &filt_E_hz() { return _filt_E_hz; } @@ -82,6 +111,7 @@ class AC_PID { AP_Float &slew_limit() { return _slew_rate_max; } float imax() const { return _kimax.get(); } + float pdmax() const { return _kpdmax.get(); } float get_filt_T_alpha(float dt) const; float get_filt_E_alpha(float dt) const; float get_filt_D_alpha(float dt) const; @@ -92,6 +122,7 @@ class AC_PID { 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); @@ -132,6 +163,7 @@ class AC_PID { AP_Float _kd; AP_Float _kff; AP_Float _kimax; + AP_Float _kpdmax; AP_Float _filt_T_hz; // PID target filter frequency in Hz AP_Float _filt_E_hz; // PID error filter frequency in Hz AP_Float _filt_D_hz; // PID derivative filter frequency in Hz diff --git a/libraries/AC_PID/AC_PID_2D.cpp b/libraries/AC_PID/AC_PID_2D.cpp index 48f11f60965a4f..a79c20678f53db 100644 --- a/libraries/AC_PID/AC_PID_2D.cpp +++ b/libraries/AC_PID/AC_PID_2D.cpp @@ -97,6 +97,10 @@ Vector2f AC_PID_2D::update_all(const Vector2f &target, const Vector2f &measureme // update I term update_i(dt, limit); + // calculate slew limit + _slew_calc.update(Vector2f{_pid_info_x.P + _pid_info_x.D, _pid_info_y.P + _pid_info_y.D}, dt); + _pid_info_x.slew_rate = _pid_info_y.slew_rate = _slew_calc.get_slew_rate(); + _pid_info_x.target = _target.x; _pid_info_x.actual = measurement.x; _pid_info_x.error = _error.x; diff --git a/libraries/AC_PID/AC_PID_2D.h b/libraries/AC_PID/AC_PID_2D.h index 0fd7e8a6ec63eb..8213997df1f84d 100644 --- a/libraries/AC_PID/AC_PID_2D.h +++ b/libraries/AC_PID/AC_PID_2D.h @@ -8,6 +8,7 @@ #include #include #include +#include /// @class AC_PID_2D /// @brief Copter PID control class @@ -72,6 +73,9 @@ class AC_PID_2D { void set_integrator(const Vector3f& i) { set_integrator(Vector2f{i.x, i.y}); } void set_integrator(const Vector2f& i); + // return current slew rate of slew limiter. Will return 0 if SMAX is zero + float get_slew_rate(void) const { return _slew_calc.get_slew_rate(); } + const AP_PIDInfo& get_pid_info_x(void) const { return _pid_info_x; } const AP_PIDInfo& get_pid_info_y(void) const { return _pid_info_y; } @@ -99,6 +103,8 @@ class AC_PID_2D { AP_PIDInfo _pid_info_x; AP_PIDInfo _pid_info_y; + SlewCalculator2D _slew_calc; // 2D slew rate calculator + private: const float default_kp; const float default_ki; diff --git a/libraries/AC_PID/AC_PI_2D.h b/libraries/AC_PID/AC_PI_2D.h index 2020134babafa8..c031104531b5f5 100644 --- a/libraries/AC_PID/AC_PI_2D.h +++ b/libraries/AC_PID/AC_PI_2D.h @@ -87,7 +87,7 @@ class AC_PI_2D { } _flags; // internal variables - float _dt; // timestep in seconds + float _dt; // time step in seconds Vector2f _integrator; // integrator value Vector2f _input; // last input for derivative float _filt_alpha; // input filter alpha diff --git a/libraries/AC_PID/AP_PIDInfo.h b/libraries/AC_PID/AP_PIDInfo.h index 98a05f879d0e25..4ba52fe37d8546 100644 --- a/libraries/AC_PID/AP_PIDInfo.h +++ b/libraries/AC_PID/AP_PIDInfo.h @@ -16,5 +16,6 @@ struct AP_PIDInfo { float FF; float Dmod; float slew_rate; - bool limit; + bool limit; + bool PD_limit; }; diff --git a/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp b/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp index bc641acd80c53b..7b7b088e48d24d 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 @@ -8,7 +8,7 @@ #include #include -// we need a boardconfig created so that the io processor is available +// we need a board config created so that the io processor is available #if HAL_WITH_IO_MCU #include #include diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 398286b878aca5..57223e1f666c93 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -150,7 +150,7 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = { // @Param: TIMEOUT // @DisplayName: PrecLand retry timeout - // @Description: Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attemp a landing retry depending on PLND_STRICT parameter. + // @Description: Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attempt a landing retry depending on PLND_STRICT parameter. // @Range: 0 20 // @Units: s AP_GROUPINFO("TIMEOUT", 13, AC_PrecLand, _retry_timeout_sec, 4), @@ -178,7 +178,7 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = { // @Param: OPTIONS // @DisplayName: Precision Landing Extra Options // @Description: Precision Landing Extra Options - // @Bitmask: 0: Moving Landing Target, 1: Allow Precision Landing after manual reposition + // @Bitmask: 0: Moving Landing Target, 1: Allow Precision Landing after manual reposition, 2: Maintain high speed in final descent // @User: Advanced AP_GROUPINFO("OPTIONS", 17, AC_PrecLand, _options, 0), @@ -400,7 +400,7 @@ bool AC_PrecLand::target_acquired() { if ((AP_HAL::millis()-_last_update_ms) > LANDING_TARGET_TIMEOUT_MS) { if (_target_acquired) { - // just lost the landing target, inform the user. This message will only be sent once everytime target is lost + // just lost the landing target, inform the user. This message will only be sent once every time target is lost gcs().send_text(MAV_SEVERITY_CRITICAL, "PrecLand: Target Lost"); } // not had a sensor update since a long time @@ -622,7 +622,7 @@ bool AC_PrecLand::retrieve_los_meas(Vector3f& target_vec_unit_body) } - // rotate vector based on sensor oriention to get correct body frame vector + // rotate vector based on sensor orientation to get correct body frame vector if (_orient != ROTATION_PITCH_270) { // by default, the vector is constructed downwards in body frame // hence, we do not do any rotation if the orientation is downwards diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index 6826bded51fdaf..a25b30c71f4f42 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -114,6 +114,7 @@ class AC_PrecLand AC_PrecLand_StateMachine::RetryAction get_retry_behaviour() const { return static_cast(_retry_behave.get()); } bool allow_precland_after_reposition() const { return _options & PLND_OPTION_PRECLAND_AFTER_REPOSITION; } + bool do_fast_descend() const { return _options & PLND_OPTION_FAST_DESCEND; } // parameter var table static const struct AP_Param::GroupInfo var_info[]; @@ -145,6 +146,7 @@ class AC_PrecLand PLND_OPTION_DISABLED = 0, PLND_OPTION_MOVING_TARGET = (1 << 0), PLND_OPTION_PRECLAND_AFTER_REPOSITION = (1 << 1), + PLND_OPTION_FAST_DESCEND = (1 << 2), }; // check the status of the target @@ -186,7 +188,7 @@ class AC_PrecLand AP_Float _xy_max_dist_desc; // Vehicle doing prec land will only descent vertically when horizontal error (in m) is below this limit AP_Int8 _strict; // PrecLand strictness AP_Int8 _retry_max; // PrecLand Maximum number of retires to a failed landing - AP_Float _retry_timeout_sec; // Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attemp a landing retry depending on PLND_STRICT param. + AP_Float _retry_timeout_sec; // Time for which vehicle continues descend even if target is lost. After this time period, vehicle will attempt a landing retry depending on PLND_STRICT param. AP_Int8 _retry_behave; // Action to do when trying a landing retry AP_Float _sensor_min_alt; // PrecLand minimum height required for detecting target AP_Float _sensor_max_alt; // PrecLand maximum height the sensor can detect target diff --git a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp index c456288ca2d368..0d38584cee7770 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp @@ -7,11 +7,11 @@ #include #include -static const float MAX_POS_ERROR_M = 0.75f; // Maximum possition error for retry locations +static const float MAX_POS_ERROR_M = 0.75f; // Maximum position error for retry locations static const uint32_t FAILSAFE_INIT_TIMEOUT_MS = 7000; // Timeout in ms before failsafe measures are started. During this period vehicle is completely stopped to give user the time to take over static const float RETRY_OFFSET_ALT_M = 1.5f; // This gets added to the altitude of the retry location -// Initialize the state machine. This is called everytime vehicle switches mode +// Initialize the state machine. This is called every time vehicle switches mode void AC_PrecLand_StateMachine::init() { AC_PrecLand *_precland = AP::ac_precland(); @@ -24,14 +24,14 @@ void AC_PrecLand_StateMachine::init() // precland is not enabled, prec land state machine methods should not be called! return; } - // init is only called ONCE per mode change. So in a particuar mode we can retry only a finite times. + // init is only called ONCE per mode change. So in a particular mode we can retry only a finite times. // The counter will be reset if the statemachine is called from a different mode _retry_count = 0; // reset every other statemachine reset_failed_landing_statemachine(); } -// Reset the landing statemachines. This needs to be called everytime the landing target is back in sight. +// Reset the landing statemachines. This needs to be called every time the landing target is back in sight. // So that if the landing target goes out of sight again, we can start the failed landing procedure back from the beginning stage void AC_PrecLand_StateMachine::reset_failed_landing_statemachine() { diff --git a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h index 8479be3c6abf7e..e52e3effc9b0da 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h +++ b/libraries/AC_PrecLand/AC_PrecLand_StateMachine.h @@ -23,7 +23,7 @@ class AC_PrecLand_StateMachine { // Do not allow copies CLASS_NO_COPY(AC_PrecLand_StateMachine); - // Initialize the state machine. This is called everytime vehicle switches mode + // Initialize the state machine. This is called every time vehicle switches mode void init(); // Current status of the precland state machine @@ -78,7 +78,7 @@ class AC_PrecLand_StateMachine { // Vector3f "retry_pos_m" is filled with the required location. Status retry_landing(Vector3f &retry_pos_m); - // Reset the landing statemachine. This needs to be called everytime the landing target is back in sight. + // Reset the landing statemachine. This needs to be called every time the landing target is back in sight. // So that if the landing target goes out of sight again, we can start the failed landing procedure back from the beginning stage void reset_failed_landing_statemachine(); diff --git a/libraries/AC_Sprayer/AC_Sprayer.cpp b/libraries/AC_Sprayer/AC_Sprayer.cpp index 7eaa91a09bfea8..c6b026eb5628df 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.cpp +++ b/libraries/AC_Sprayer/AC_Sprayer.cpp @@ -21,7 +21,7 @@ const AP_Param::GroupInfo AC_Sprayer::var_info[] = { // @Param: PUMP_RATE // @DisplayName: Pump speed - // @Description: Desired pump speed when traveling 1m/s expressed as a percentage + // @Description: Desired pump speed when travelling 1m/s expressed as a percentage // @Units: % // @Range: 0 100 // @User: Standard @@ -174,7 +174,7 @@ void AC_Sprayer::update() _speed_over_min_time = 0; } - // if testing pump output speed as if traveling at 1m/s + // if testing pump output speed as if travelling at 1m/s if (_flags.testing) { ground_speed = 100.0f; should_be_spraying = true; diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index 752699a5291cc9..ca804a54916c94 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -174,7 +174,7 @@ bool AC_Circle::update(float climb_rate_cms) _angular_vel = MAX(_angular_vel, _angular_vel_max); } - // update the target angle and total angle traveled + // update the target angle and total angle travelled float angle_change = _angular_vel * dt; _angle += angle_change; _angle = wrap_PI(_angle); diff --git a/libraries/AC_WPNav/AC_Circle.h b/libraries/AC_WPNav/AC_Circle.h index 498241e0252304..d76fcc90ce64e6 100644 --- a/libraries/AC_WPNav/AC_Circle.h +++ b/libraries/AC_WPNav/AC_Circle.h @@ -153,7 +153,7 @@ class AC_Circle float _rate; // rotation speed of circle in deg/sec. +ve for cw turn float _yaw; // yaw heading (normally towards circle center) float _angle; // current angular position around circle in radians (0=directly north of the center of the circle) - float _angle_total; // total angle traveled in radians + float _angle_total; // total angle travelled in radians float _angular_vel; // angular velocity in radians/sec float _angular_vel_max; // maximum velocity in radians/sec float _angular_accel; // angular acceleration in radians/sec/sec diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index e63b9fc4450c99..116e85911c0e2f 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -482,7 +482,7 @@ bool AC_WPNav::advance_wp_target_along_track(float dt) } // Use vel_scaler_dt to slow down the trajectory time - // vel_scaler_dt scales the velocity and acceleration to be kinematically constent + // vel_scaler_dt scales the velocity and acceleration to be kinematically consistent float vel_scaler_dt = 1.0; if (is_positive(_wp_desired_speed_xy_cms)) { update_vel_accel(_offset_vel, _offset_accel, dt, 0.0, 0.0); diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index c8008b61d4ee95..0cc30e59cb6269 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -424,9 +424,17 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg) } // setup filters to be suitable for time constant and gyro filter - rpid.filt_T_hz().set(10.0/(current.tau * 2 * M_PI)); + // filtering T can prevent P/D oscillation being seen, so allow the + // user to switch it off + if (!has_option(DISABLE_FLTT_UPDATE)) { + rpid.filt_T_hz().set(10.0/(current.tau * 2 * M_PI)); + } rpid.filt_E_hz().set(0); - rpid.filt_D_hz().set(AP::ins().get_gyro_filter_hz()*0.5); + // filtering D at the same level as VTOL can allow unwanted oscillations to be seen, + // so allow the user to switch it off and select their own (usually lower) value + if (!has_option(DISABLE_FLTD_UPDATE)) { + rpid.filt_D_hz().set(AP::ins().get_gyro_filter_hz()*0.5); + } current.FF = FF; current.P = P; diff --git a/libraries/APM_Control/AP_AutoTune.h b/libraries/APM_Control/AP_AutoTune.h index 1859a2489f269e..67b6cf07f9036f 100644 --- a/libraries/APM_Control/AP_AutoTune.h +++ b/libraries/APM_Control/AP_AutoTune.h @@ -25,6 +25,11 @@ class AP_AutoTune AUTOTUNE_YAW = 2, }; + enum Options { + DISABLE_FLTD_UPDATE = 0, + DISABLE_FLTT_UPDATE = 1 + }; + struct PACKED log_ATRP { LOG_PACKET_HEADER; uint64_t time_us; @@ -116,6 +121,10 @@ class AP_AutoTune // update rmax and tau towards target void update_rmax(); + bool has_option(Options option) { + return (aparm.autotune_options.get() & uint32_t(1< #include -extern const AP_HAL::HAL& hal; - #define AR_POSCON_TIMEOUT_MS 100 // timeout after 0.1 sec #define AR_POSCON_POS_P 0.2f // default position P gain #define AR_POSCON_VEL_P 1.0f // default velocity P gain @@ -35,6 +33,10 @@ extern const AP_HAL::HAL& hal; #define AR_POSCON_VEL_FILT_D 5.0f // default velocity D term filter #define AR_POSCON_DT 0.02f // default dt for PID controllers +extern const AP_HAL::HAL& hal; + +AR_PosControl *AR_PosControl::_singleton; + const AP_Param::GroupInfo AR_PosControl::var_info[] = { // @Param: _POS_P @@ -103,6 +105,7 @@ AR_PosControl::AR_PosControl(AR_AttitudeControl& atc) : _p_pos(AR_POSCON_POS_P), _pid_vel(AR_POSCON_VEL_P, AR_POSCON_VEL_I, AR_POSCON_VEL_D, AR_POSCON_VEL_FF, AR_POSCON_VEL_IMAX, AR_POSCON_VEL_FILT, AR_POSCON_VEL_FILT_D) { + _singleton = this; AP_Param::setup_object_defaults(this, var_info); } @@ -349,6 +352,13 @@ Vector2p AR_PosControl::get_pos_error() const return (_pos_target - curr_pos_NE.topostype()); } +// get the slew rate value for velocity. used for oscillation detection in lua scripts +void AR_PosControl::get_srate(float &velocity_srate) +{ + // slew rate is the same for x and y axis + velocity_srate = _pid_vel.get_pid_info_x().slew_rate; +} + // write PSC logs void AR_PosControl::write_log() { diff --git a/libraries/APM_Control/AR_PosControl.h b/libraries/APM_Control/AR_PosControl.h index d06d852fc4164f..40748fce30771f 100644 --- a/libraries/APM_Control/AR_PosControl.h +++ b/libraries/APM_Control/AR_PosControl.h @@ -11,6 +11,11 @@ class AR_PosControl { // constructor AR_PosControl(AR_AttitudeControl& atc); + // do not allow copying + CLASS_NO_COPY(AR_PosControl); + + static AR_PosControl *get_singleton() { return _singleton; } + // update navigation void update(float dt); @@ -73,6 +78,9 @@ class AR_PosControl { AC_P_2D& get_pos_p() { return _p_pos; } AC_PID_2D& get_vel_pid() { return _pid_vel; } + // get the slew rate value for velocity. used for oscillation detection in lua scripts + void get_srate(float &velocity_srate); + // write PSC logs void write_log(); @@ -81,6 +89,8 @@ class AR_PosControl { private: + static AR_PosControl *_singleton; + // initialise and check for ekf position resets void init_ekf_xy_reset(); void handle_ekf_xy_reset(); diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 47e7cabf53d76f..9d82e541a4f928 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -103,7 +103,7 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = { // @Param: OFFSET_LAT // @DisplayName: GPS antenna lateral offset - // @Description: GPS antenna lateral offset. This describes the physical location offest from center of the GPS antenna on the aircraft. + // @Description: GPS antenna lateral offset. This describes the physical location offset from center of the GPS antenna on the aircraft. // @Values: 0:NoData,1:Left2m,2:Left4m,3:Left6m,4:Center,5:Right2m,6:Right4m,7:Right6m // @User: Advanced AP_GROUPINFO("OFFSET_LAT", 7, AP_ADSB, out_state.cfg.gpsOffsetLat, UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M), @@ -198,7 +198,7 @@ void AP_ADSB::init(void) if (in_state.vehicle_list == nullptr) { // dynamic RAM allocation of in_state.vehicle_list[] failed _init_failed = true; // this keeps us from constantly trying to init forever in main update - gcs().send_text(MAV_SEVERITY_INFO, "ADSB: Unable to initialize ADSB vehicle list"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: Unable to initialize ADSB vehicle list"); return; } in_state.list_size_allocated = in_state.list_size_param; @@ -222,7 +222,7 @@ void AP_ADSB::init(void) if (detected_num_instances == 0) { _init_failed = true; - gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB: Unable to initialize ADSB driver"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB: Unable to initialize ADSB driver"); } } @@ -563,7 +563,9 @@ void AP_ADSB::set_vehicle(const uint16_t index, const adsb_vehicle_t &vehicle) } in_state.vehicle_list[index] = vehicle; +#if HAL_LOGGING_ENABLED write_log(vehicle); +#endif } void AP_ADSB::send_adsb_vehicle(const mavlink_channel_t chan) @@ -632,7 +634,7 @@ void AP_ADSB::handle_out_cfg(const mavlink_uavionix_adsb_out_cfg_t &packet) // guard against string with non-null end char const char c = out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1]; out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = 0; - gcs().send_text(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", (int)out_state.cfg.ICAO_id, out_state.cfg.callsign); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", (int)out_state.cfg.ICAO_id, out_state.cfg.callsign); out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = c; // send now @@ -666,7 +668,7 @@ void AP_ADSB::handle_out_control(const mavlink_uavionix_adsb_out_control_t &pack void AP_ADSB::handle_transceiver_report(const mavlink_channel_t chan, const mavlink_uavionix_adsb_transceiver_health_report_t &packet) { if (out_state.chan != chan) { - gcs().send_text(MAV_SEVERITY_DEBUG, "ADSB: Found transceiver on channel %d", chan); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "ADSB: Found transceiver on channel %d", chan); } out_state.chan_last_ms = AP_HAL::millis(); @@ -820,6 +822,7 @@ bool AP_ADSB::get_vehicle_by_ICAO(const uint32_t icao, adsb_vehicle_t &vehicle) return false; } +#if HAL_LOGGING_ENABLED /* * Write vehicle to log */ @@ -854,6 +857,7 @@ void AP_ADSB::write_log(const adsb_vehicle_t &vehicle) const }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#endif // HAL_LOGGING_ENABLED /** * @brief Convert base 8 or 16 to decimal. Used to convert an octal/hexadecimal value stored on a GCS as a string field in different format, but then transmitted over mavlink as a float which is always a decimal. diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index fb204f170a3979..f9210a559a6b6d 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -108,8 +108,6 @@ class AP_ADSB { void set_is_auto_mode(const bool is_in_auto_mode) { out_state.is_in_auto_mode = is_in_auto_mode; } void set_is_flying(const bool is_flying) { out_state.is_flying = is_flying; } - UAVIONIX_ADSB_RF_HEALTH get_transceiver_status(void) const { return out_state.status; } - // extract a location out of a vehicle item Location get_location(const adsb_vehicle_t &vehicle) const; @@ -157,7 +155,7 @@ class AP_ADSB { static uint32_t convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNumber); // Trigger a Mode 3/A transponder IDENT. This should only be done when requested to do so by an Air Traffic Controller. - // See wikipedia for IDENT explaination https://en.wikipedia.org/wiki/Transponder_(aeronautics) + // See wikipedia for IDENT explanation https://en.wikipedia.org/wiki/Transponder_(aeronautics) bool ident_start() { if (!healthy() || ((out_state.cfg.rfSelect & UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED) == 0)) { return false; diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp b/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp index 940228fe345f30..a5ebfea68c2dc0 100644 --- a/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp @@ -19,8 +19,12 @@ #if HAL_ADSB_SAGETECH_ENABLED #include +#include +#include #include +#include #include +#include #include #include #include @@ -190,7 +194,7 @@ void AP_ADSB_Sagetech::handle_ack(const Packet_XP &msg) if (prev_transponder_mode != last_ack_transponder_mode) { static const char *mode_names[] = {"OFF", "STBY", "ON", "ON-ALT"}; if (last_ack_transponder_mode < ARRAY_SIZE(mode_names)) { - gcs().send_text(MAV_SEVERITY_INFO, "ADSB: RF Mode: %s", mode_names[last_ack_transponder_mode]); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: RF Mode: %s", mode_names[last_ack_transponder_mode]); } } } @@ -510,6 +514,7 @@ void AP_ADSB_Sagetech::send_msg_GPS() hemisphere |= (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) ? 0x80 : 0; // isInvalid pkt.payload[35] = hemisphere; +#if AP_RTC_ENABLED // time uint64_t time_usec; if (AP::rtc().get_utc_usec(time_usec)) { @@ -522,6 +527,9 @@ void AP_ADSB_Sagetech::send_msg_GPS() } else { memset(&pkt.payload[36],' ', 10); } +#else + memset(&pkt.payload[36],' ', 10); +#endif send_msg(pkt); } diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp index 3186a09f911bb4..fdd8431e3e9e51 100644 --- a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp @@ -26,6 +26,8 @@ #if HAL_ADSB_SAGETECH_MXS_ENABLED #include #include +#include +#include #include #include #include @@ -109,7 +111,7 @@ void AP_ADSB_Sagetech_MXS::update() } } else if (last.packet_initialize_ms > MXS_INIT_TIMEOUT && !mxs_state.init_failed) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB Sagetech MXS: Initialization Timeout. Failed to initialize."); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Sagetech MXS: Initialization Timeout. Failed to initialize."); mxs_state.init_failed = true; } @@ -312,7 +314,7 @@ void AP_ADSB_Sagetech_MXS::msg_write(const uint8_t *data, const uint16_t len) co void AP_ADSB_Sagetech_MXS::auto_config_operating() { -// Configure the Default Operation Message Data + // Configure the Default Operation Message Data mxs_state.op.squawk = AP_ADSB::convert_base_to_decimal(8, _frontend.out_state.cfg.squawk_octal); mxs_state.op.opMode = sg_op_mode_t::modeOff; // MXS needs to start in OFF mode to accept installation message mxs_state.op.savePowerUp = true; // Save power-up state in non-volatile @@ -421,15 +423,15 @@ void AP_ADSB_Sagetech_MXS::auto_config_flightid() void AP_ADSB_Sagetech_MXS::handle_ack(const sg_ack_t ack) { if ((ack.ackId != last.msg.id) || (ack.ackType != last.msg.type)) { - // gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: ACK: Message %d of type %02x not acknowledged.", last.msg.id, last.msg.type); + // GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: ACK: Message %d of type %02x not acknowledged.", last.msg.id, last.msg.type); } // System health if (ack.failXpdr && !last.failXpdr) { - gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: Transponder Failure"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: Transponder Failure"); _frontend.out_state.tx_status.fault |= UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL; } if (ack.failSystem && !last.failSystem) { - gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: System Failure"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: System Failure"); _frontend.out_state.tx_status.fault |= UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL; } last.failXpdr = ack.failXpdr; @@ -529,7 +531,7 @@ void AP_ADSB_Sagetech_MXS::send_install_msg() { // MXS must be in OFF mode to change ICAO or Registration if (mxs_state.op.opMode != modeOff) { - // gcs().send_text(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: unable to send installation data while not in OFF mode."); + // GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "ADSB Sagetech MXS: unable to send installation data while not in OFF mode."); return; } @@ -679,6 +681,7 @@ void AP_ADSB_Sagetech_MXS::send_gps_msg() gps.gpsValid = (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) ? false : true; // If the status is not OK, gpsValid is false. +#if AP_RTC_ENABLED uint64_t time_usec; if (AP::rtc().get_utc_usec(time_usec)) { const time_t time_sec = time_usec * 1E-6; @@ -688,6 +691,9 @@ void AP_ADSB_Sagetech_MXS::send_gps_msg() } else { strncpy(gps.timeOfFix, " . ", 11); } +#else + strncpy(gps.timeOfFix, " . ", 11); +#endif int32_t height; if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, height)) { diff --git a/libraries/AP_ADSB/AP_ADSB_config.h b/libraries/AP_ADSB/AP_ADSB_config.h index 0f07f1b42f1b1a..5e21ad9c217cc3 100644 --- a/libraries/AP_ADSB/AP_ADSB_config.h +++ b/libraries/AP_ADSB/AP_ADSB_config.h @@ -2,24 +2,29 @@ #include +#include #ifndef HAL_ADSB_ENABLED #define HAL_ADSB_ENABLED BOARD_FLASH_SIZE > 1024 #endif +#ifndef HAL_ADSB_BACKEND_DEFAULT_ENABLED +#define HAL_ADSB_BACKEND_DEFAULT_ENABLED HAL_ADSB_ENABLED +#endif + #ifndef HAL_ADSB_UAVIONIX_MAVLINK_ENABLED -#define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED HAL_ADSB_ENABLED +#define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED HAL_ADSB_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED #endif #ifndef HAL_ADSB_SAGETECH_ENABLED -#define HAL_ADSB_SAGETECH_ENABLED HAL_ADSB_ENABLED +#define HAL_ADSB_SAGETECH_ENABLED HAL_ADSB_BACKEND_DEFAULT_ENABLED #endif #ifndef HAL_ADSB_UCP_ENABLED -#define HAL_ADSB_UCP_ENABLED HAL_ADSB_ENABLED +#define HAL_ADSB_UCP_ENABLED HAL_ADSB_BACKEND_DEFAULT_ENABLED #endif #ifndef HAL_ADSB_SAGETECH_MXS_ENABLED // this feature is only enabled by default by select hardware - #define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL + #define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL #endif diff --git a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp index eeeec516bc0bf0..571f265905f7e4 100644 --- a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp +++ b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp @@ -45,7 +45,7 @@ void AP_ADSB_uAvionix_MAVLink::update() // haven't gotten a heartbeat health status packet in a while, assume hardware failure _frontend.out_state.chan = -1; _frontend.out_state.chan_last_ms = 0; // if the time isn't reset we spam the message - gcs().send_text(MAV_SEVERITY_ERROR, "ADSB: Transceiver heartbeat timed out"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "ADSB: Transceiver heartbeat timed out"); } else if (_frontend.out_state.chan >= 0 && !_frontend._my_loc.is_zero() && _frontend.out_state.chan < MAVLINK_COMM_NUM_BUFFERS) { const mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0 + _frontend.out_state.chan); if (now - _frontend.out_state.last_config_ms >= 5000 && HAVE_PAYLOAD_SPACE(chan, UAVIONIX_ADSB_OUT_CFG)) { @@ -140,7 +140,7 @@ void AP_ADSB_uAvionix_MAVLink::send_dynamic_out(const mavlink_channel_t chan) co /* * To expand functionality in their HW, uAvionix has extended a few of the unused MAVLink bits to pack in more new features * This function will override the MSB byte of the 24bit ICAO address. To ensure an invalid >24bit ICAO is never broadcasted, - * this function is used to create the encoded verison without ever writing to the actual ICAO number. It's created on-demand + * this function is used to create the encoded version without ever writing to the actual ICAO number. It's created on-demand */ uint32_t AP_ADSB_uAvionix_MAVLink::encode_icao(const uint32_t icao_id) const { @@ -253,4 +253,4 @@ void AP_ADSB_uAvionix_MAVLink::send_configure(const mavlink_channel_t chan) (uint8_t)_frontend.out_state.cfg.rfSelect); } -#endif // HAL_ADSB_ENABLED +#endif // HAL_ADSB_UAVIONIX_MAVLINK_ENABLED diff --git a/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp b/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp index b4cae2a3d270b8..e16a6a6a6bfb4a 100644 --- a/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp +++ b/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp @@ -253,7 +253,7 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg) _frontend.out_state.ctrl.x_bit = rx.decoded.transponder_status.x_bit; } run_state.last_packet_Transponder_Status_ms = AP_HAL::millis(); - gcs().send_message(MSG_UAVIONIX_ADSB_OUT_STATUS); + GCS_SEND_MESSAGE(MSG_UAVIONIX_ADSB_OUT_STATUS); break; #endif // AP_ADSB_UAVIONIX_UCP_CAPTURE_ALL_RX_PACKETS diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 49b2a0d85ca5da..cf702b9da423f2 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -79,7 +79,7 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = { // @Param: WIND_MAX // @DisplayName: Maximum wind - // @Description: This sets the maximum allowable difference between ground speed and airspeed. This allows the plane to cope with a failing airspeed sensor. A value of zero means to use the airspeed as is. See ARSPD_OPTIONS and ARSPD_MAX_WIND to disable airspeed sensors. + // @Description: This sets the maximum allowable difference between ground speed and airspeed. A value of zero means to use the airspeed as is. This allows the plane to cope with a failing airspeed sensor by clipping it to groundspeed plus/minus this limit. See ARSPD_OPTIONS and ARSPD_WIND_MAX to disable airspeed sensors. // @Range: 0 127 // @Units: m/s // @Increment: 1 @@ -196,7 +196,7 @@ AP_AHRS::AP_AHRS(uint8_t flags) : // Copter and Sub force the use of EKF _ekf_flags |= AP_AHRS::FLAG_ALWAYS_USE_EKF; #endif - _dcm_matrix.identity(); + state.dcm_matrix.identity(); // initialise the controller-to-autopilot-body trim state: _last_trim = _trim.get(); @@ -234,13 +234,15 @@ void AP_AHRS::init() last_active_ekf_type = (EKFType)_ekf_type.get(); // init backends +#if AP_AHRS_DCM_ENABLED dcm.init(); +#endif #if HAL_EXTERNAL_AHRS_ENABLED external.init(); #endif #if !APM_BUILD_TYPE(APM_BUILD_AP_Periph) - // convert to new custom rotaton + // convert to new custom rotation // PARAMETER_CONVERSION - Added: Nov-2021 if (_board_orientation == ROTATION_CUSTOM_OLD) { _board_orientation.set_and_save(ROTATION_CUSTOM_1); @@ -274,22 +276,25 @@ void AP_AHRS::update_trim_rotation_matrices() _rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed(); } -// return the smoothed gyro vector corrected for drift -const Vector3f &AP_AHRS::get_gyro(void) const +// return a Quaternion representing our current attitude in NED frame +void AP_AHRS::get_quat_body_to_ned(Quaternion &quat) const { - return _gyro_estimate; + quat.from_rotation_matrix(get_rotation_body_to_ned()); } -const Matrix3f &AP_AHRS::get_rotation_body_to_ned(void) const +// convert a vector from body to earth frame +Vector3f AP_AHRS::body_to_earth(const Vector3f &v) const { - return _dcm_matrix; + return get_rotation_body_to_ned() * v; } -const Vector3f &AP_AHRS::get_gyro_drift(void) const +// convert a vector from earth to body frame +Vector3f AP_AHRS::earth_to_body(const Vector3f &v) const { - return _gyro_drift; + return get_rotation_body_to_ned().mul_transpose(v); } + // reset the current gyro drift estimate // should be called if gyro offsets are recalculated void AP_AHRS::reset_gyro_drift(void) @@ -298,7 +303,9 @@ void AP_AHRS::reset_gyro_drift(void) WITH_SEMAPHORE(_rsem); // update DCM +#if AP_AHRS_DCM_ENABLED dcm.reset_gyro_drift(); +#endif #if HAL_EXTERNAL_AHRS_ENABLED external.reset_gyro_drift(); #endif @@ -312,6 +319,32 @@ void AP_AHRS::reset_gyro_drift(void) #endif } +/* + update state structure after each update() + */ +void AP_AHRS::update_state(void) +{ + state.primary_IMU = _get_primary_IMU_index(); + state.primary_gyro = _get_primary_gyro_index(); + state.primary_accel = _get_primary_accel_index(); + state.primary_core = _get_primary_core_index(); + state.wind_estimate_ok = _wind_estimate(state.wind_estimate); + state.EAS2TAS = AP_AHRS_Backend::get_EAS2TAS(); + state.airspeed_ok = _airspeed_estimate(state.airspeed, state.airspeed_estimate_type); + state.airspeed_true_ok = _airspeed_estimate_true(state.airspeed_true); + state.airspeed_vec_ok = _airspeed_vector_true(state.airspeed_vec); + state.quat_ok = _get_quaternion(state.quat); + state.secondary_attitude_ok = _get_secondary_attitude(state.secondary_attitude); + state.secondary_quat_ok = _get_secondary_quaternion(state.secondary_quat); + state.location_ok = _get_location(state.location); + state.secondary_pos_ok = _get_secondary_position(state.secondary_pos); + state.ground_speed_vec = _groundspeed_vector(); + state.ground_speed = _groundspeed(); + _getCorrectedDeltaVelocityNED(state.corrected_dv, state.corrected_dv_dt); + state.origin_ok = _get_origin(state.origin); + state.velocity_NED_ok = _get_velocity_NED(state.velocity_NED); +} + void AP_AHRS::update(bool skip_ins_update) { // periodically checks to see if we should update the AHRS @@ -341,7 +374,9 @@ void AP_AHRS::update(bool skip_ins_update) // update autopilot-body-to-vehicle-body from _trim parameters: update_trim_rotation_matrices(); +#if AP_AHRS_DCM_ENABLED update_DCM(); +#endif // update takeoff/touchdown flags update_flags(); @@ -392,14 +427,17 @@ void AP_AHRS::update(bool skip_ins_update) // update AOA and SSA update_AOA_SSA(); - EKFType active = active_EKF_type(); - if (active != last_active_ekf_type) { - last_active_ekf_type = active; +#if HAL_GCS_ENABLED + state.active_EKF = _active_EKF_type(); + if (state.active_EKF != last_active_ekf_type) { + last_active_ekf_type = state.active_EKF; const char *shortname = "???"; - switch ((EKFType)active) { - case EKFType::NONE: + switch ((EKFType)state.active_EKF) { +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: shortname = "DCM"; break; +#endif #if AP_AHRS_SIM_ENABLED case EKFType::SIM: shortname = "SIM"; @@ -423,6 +461,10 @@ void AP_AHRS::update(bool skip_ins_update) } GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AHRS: %s active", shortname); } +#endif // HAL_GCS_ENABLED + + // update published state + update_state(); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL /* @@ -446,18 +488,19 @@ void AP_AHRS::copy_estimates_from_backend_estimates(const AP_AHRS_Backend::Estim pitch = results.pitch_rad; yaw = results.yaw_rad; - _dcm_matrix = results.dcm_matrix; + state.dcm_matrix = results.dcm_matrix; - _gyro_estimate = results.gyro_estimate; - _gyro_drift = results.gyro_drift; + state.gyro_estimate = results.gyro_estimate; + state.gyro_drift = results.gyro_drift; - _accel_ef = results.accel_ef; - _accel_bias = results.accel_bias; + state.accel_ef = results.accel_ef; + state.accel_bias = results.accel_bias; update_cd_values(); update_trig(); } +#if AP_AHRS_DCM_ENABLED void AP_AHRS::update_DCM() { dcm.update(); @@ -468,10 +511,11 @@ void AP_AHRS::update_DCM() // an EKF or external AHRS. This is long-held behaviour, but this // really shouldn't be doing this. - // if (active_EKF_type() == EKFType::NONE) { + // if (active_EKF_type() == EKFType::DCM) { copy_estimates_from_backend_estimates(dcm_estimates); // } } +#endif #if AP_AHRS_SIM_ENABLED void AP_AHRS::update_SITL(void) @@ -479,7 +523,7 @@ void AP_AHRS::update_SITL(void) sim.update(); sim.get_results(sim_estimates); - if (active_EKF_type() == EKFType::SIM) { + if (_active_EKF_type() == EKFType::SIM) { copy_estimates_from_backend_estimates(sim_estimates); } } @@ -516,9 +560,9 @@ void AP_AHRS::update_EKF2(void) } if (_ekf2_started) { EKF2.UpdateFilter(); - if (active_EKF_type() == EKFType::TWO) { + if (_active_EKF_type() == EKFType::TWO) { Vector3f eulers; - EKF2.getRotationBodyToNED(_dcm_matrix); + EKF2.getRotationBodyToNED(state.dcm_matrix); EKF2.getEulerAngles(eulers); roll = eulers.x; pitch = eulers.y; @@ -535,21 +579,21 @@ void AP_AHRS::update_EKF2(void) // get gyro bias for primary EKF and change sign to give gyro drift // Note sign convention used by EKF is bias = measurement - truth - _gyro_drift.zero(); - EKF2.getGyroBias(_gyro_drift); - _gyro_drift = -_gyro_drift; + Vector3f drift; + EKF2.getGyroBias(drift); + state.gyro_drift = -drift; // use the same IMU as the primary EKF and correct for gyro drift - _gyro_estimate = _ins.get_gyro(primary_gyro) + _gyro_drift; + state.gyro_estimate = _ins.get_gyro(primary_gyro) + state.gyro_drift; // get z accel bias estimate from active EKF (this is usually for the primary IMU) - float &abias = _accel_bias.z; + float &abias = state.accel_bias.z; EKF2.getAccelZBias(abias); - // This EKF is currently using primary_imu, and abias applies to only that IMU + // This EKF is currently using primary_imu, and a bias applies to only that IMU Vector3f accel = _ins.get_accel(primary_accel); accel.z -= abias; - _accel_ef = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel; + state.accel_ef = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel; nav_filter_status filt_state; EKF2.getFilterStatus(filt_state); @@ -582,9 +626,9 @@ void AP_AHRS::update_EKF3(void) } if (_ekf3_started) { EKF3.UpdateFilter(); - if (active_EKF_type() == EKFType::THREE) { + if (_active_EKF_type() == EKFType::THREE) { Vector3f eulers; - EKF3.getRotationBodyToNED(_dcm_matrix); + EKF3.getRotationBodyToNED(state.dcm_matrix); EKF3.getEulerAngles(eulers); roll = eulers.x; pitch = eulers.y; @@ -602,21 +646,21 @@ void AP_AHRS::update_EKF3(void) // get gyro bias for primary EKF and change sign to give gyro drift // Note sign convention used by EKF is bias = measurement - truth - _gyro_drift.zero(); - EKF3.getGyroBias(-1,_gyro_drift); - _gyro_drift = -_gyro_drift; + Vector3f drift; + EKF3.getGyroBias(-1, drift); + state.gyro_drift = -drift; // use the same IMU as the primary EKF and correct for gyro drift - _gyro_estimate = _ins.get_gyro(primary_gyro) + _gyro_drift; + state.gyro_estimate = _ins.get_gyro(primary_gyro) + state.gyro_drift; - // get 3-axis accel bias festimates for active EKF (this is usually for the primary IMU) - Vector3f &abias = _accel_bias; + // get 3-axis accel bias estimates for active EKF (this is usually for the primary IMU) + Vector3f &abias = state.accel_bias; EKF3.getAccelBias(-1,abias); // use the primary IMU for accel earth frame Vector3f accel = _ins.get_accel(primary_accel); accel -= abias; - _accel_ef = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel; + state.accel_ef = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * accel; nav_filter_status filt_state; EKF3.getFilterStatus(filt_state); @@ -632,7 +676,7 @@ void AP_AHRS::update_external(void) external.update(); external.get_results(external_estimates); - if (active_EKF_type() == EKFType::EXTERNAL) { + if (_active_EKF_type() == EKFType::EXTERNAL) { copy_estimates_from_backend_estimates(external_estimates); } } @@ -643,7 +687,9 @@ void AP_AHRS::reset() // support locked access functions to AHRS data WITH_SEMAPHORE(_rsem); +#if AP_AHRS_DCM_ENABLED dcm.reset(); +#endif #if AP_AHRS_SIM_ENABLED sim.reset(); #endif @@ -665,12 +711,13 @@ void AP_AHRS::reset() } // dead-reckoning support -bool AP_AHRS::get_location(Location &loc) const +bool AP_AHRS::_get_location(Location &loc) const { switch (active_EKF_type()) { - case EKFType::NONE: - return dcm.get_location(loc); - +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: + return dcm_estimates.get_location(loc); +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: if (EKF2.getLLH(loc)) { @@ -689,40 +736,50 @@ bool AP_AHRS::get_location(Location &loc) const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: - return sim.get_location(loc); + return sim_estimates.get_location(loc); #endif #if HAL_EXTERNAL_AHRS_ENABLED - case EKFType::EXTERNAL: { - return external.get_location(loc); - } + case EKFType::EXTERNAL: + return external_estimates.get_location(loc); #endif } +#if AP_AHRS_DCM_ENABLED // fall back to position from DCM if (!always_use_EKF()) { - return dcm.get_location(loc); + return dcm_estimates.get_location(loc); } +#endif + return false; } // status reporting of estimated errors float AP_AHRS::get_error_rp(void) const { +#if AP_AHRS_DCM_ENABLED return dcm.get_error_rp(); +#endif + return 0; } float AP_AHRS::get_error_yaw(void) const { +#if AP_AHRS_DCM_ENABLED return dcm.get_error_yaw(); +#endif + return 0; } // return a wind estimation vector, in m/s -bool AP_AHRS::wind_estimate(Vector3f &wind) const +bool AP_AHRS::_wind_estimate(Vector3f &wind) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.wind_estimate(wind); +#endif #if AP_AHRS_SIM_ENABLED case EKFType::SIM: @@ -747,19 +804,13 @@ bool AP_AHRS::wind_estimate(Vector3f &wind) const } return false; } -Vector3f AP_AHRS::wind_estimate(void) const -{ - Vector3f ret; - UNUSED_RESULT(wind_estimate(ret)); - return ret; -} /* return true if a real airspeed sensor is enabled */ bool AP_AHRS::airspeed_sensor_enabled(void) const { - if (!dcm.airspeed_sensor_enabled()) { + if (!AP_AHRS_Backend::airspeed_sensor_enabled()) { return false; } nav_filter_status filter_status; @@ -770,7 +821,7 @@ bool AP_AHRS::airspeed_sensor_enabled(void) const // special case for when backend is rejecting airspeed data in // an armed fly_forward state and not dead reckoning. Then the // airspeed data is highly suspect and will be rejected. We - // will use the synthentic airspeed instead + // will use the synthetic airspeed instead return false; } return true; @@ -778,11 +829,9 @@ bool AP_AHRS::airspeed_sensor_enabled(void) const // return an airspeed estimate if available. return true // if we have an estimate -bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const +bool AP_AHRS::_airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &airspeed_estimate_type) const { - bool ret = false; - -#if AP_AIRSPEED_ENABLED +#if AP_AIRSPEED_ENABLED && AP_GPS_ENABLED if (airspeed_sensor_enabled()) { uint8_t idx = get_active_airspeed_index(); airspeed_ret = AP::airspeed()->get_airspeed(idx); @@ -797,12 +846,13 @@ bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const gnd_speed + _wind_max); airspeed_ret = true_airspeed / get_EAS2TAS(); } - + airspeed_estimate_type = AirspeedEstimateType::AIRSPEED_SENSOR; return true; } #endif if (!get_wind_estimation_enabled()) { + airspeed_estimate_type = AirspeedEstimateType::NO_NEW_ESTIMATE; return false; } @@ -810,38 +860,49 @@ bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const // get wind estimates Vector3f wind_vel; + bool have_wind = false; + switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: + airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC; return dcm.airspeed_estimate(get_active_airspeed_index(), airspeed_ret); +#endif #if AP_AHRS_SIM_ENABLED case EKFType::SIM: + airspeed_estimate_type = AirspeedEstimateType::SIM; return sim.airspeed_estimate(airspeed_ret); #endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: +#if AP_AHRS_DCM_ENABLED + airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC; return dcm.airspeed_estimate(get_active_airspeed_index(), airspeed_ret); +#else + return false; +#endif #endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: - ret = EKF3.getWind(wind_vel); + have_wind = EKF3.getWind(wind_vel); break; #endif #if HAL_EXTERNAL_AHRS_ENABLED case EKFType::EXTERNAL: - return false; + airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC; + return dcm.airspeed_estimate(get_active_airspeed_index(), airspeed_ret); #endif } // estimate it via nav velocity and wind estimates Vector3f nav_vel; - float true_airspeed; - if (ret && have_inertial_nav() && get_velocity_NED(nav_vel)) { + if (have_wind && have_inertial_nav() && get_velocity_NED(nav_vel)) { Vector3f true_airspeed_vec = nav_vel - wind_vel; - true_airspeed = true_airspeed_vec.length(); + float true_airspeed = true_airspeed_vec.length(); float gnd_speed = nav_vel.length(); if (_wind_max > 0) { float tas_lim_lower = MAX(0.0f, (gnd_speed - _wind_max)); @@ -851,19 +912,26 @@ bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const true_airspeed = MAX(0.0f, true_airspeed); } airspeed_ret = true_airspeed / get_EAS2TAS(); - } else { - // fallback to DCM if airspeed estimate if EKF has wind but no velocity estimate - ret = dcm.airspeed_estimate(get_active_airspeed_index(), airspeed_ret); + airspeed_estimate_type = AirspeedEstimateType::EKF3_SYNTHETIC; + return true; } - return ret; +#if AP_AHRS_DCM_ENABLED + // fallback to DCM + airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC; + return dcm.airspeed_estimate(get_active_airspeed_index(), airspeed_ret); +#endif + + return false; } -bool AP_AHRS::airspeed_estimate_true(float &airspeed_ret) const +bool AP_AHRS::_airspeed_estimate_true(float &airspeed_ret) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.airspeed_estimate_true(airspeed_ret); +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: #endif @@ -888,11 +956,13 @@ bool AP_AHRS::airspeed_estimate_true(float &airspeed_ret) const // return estimate of true airspeed vector in body frame in m/s // returns false if estimate is unavailable -bool AP_AHRS::airspeed_vector_true(Vector3f &vec) const +bool AP_AHRS::_airspeed_vector_true(Vector3f &vec) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: break; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: return EKF2.getAirSpdVec(vec); @@ -921,8 +991,10 @@ bool AP_AHRS::airspeed_vector_true(Vector3f &vec) const bool AP_AHRS::airspeed_health_data(float &innovation, float &innovationVariance, uint32_t &age_ms) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: break; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: break; @@ -952,15 +1024,20 @@ bool AP_AHRS::airspeed_health_data(float &innovation, float &innovationVariance, // on failure. bool AP_AHRS::synthetic_airspeed(float &ret) const { +#if AP_AHRS_DCM_ENABLED return dcm.synthetic_airspeed(ret); +#endif + return false; } // true if compass is being used bool AP_AHRS::use_compass(void) { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: break; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: return EKF2.use_compass(); @@ -981,20 +1058,25 @@ bool AP_AHRS::use_compass(void) break; #endif } +#if AP_AHRS_DCM_ENABLED return dcm.use_compass(); +#endif + return false; } // return the quaternion defining the rotation from NED to XYZ (body) axes -bool AP_AHRS::get_quaternion(Quaternion &quat) const +bool AP_AHRS::_get_quaternion(Quaternion &quat) const { // backends always return in autopilot XYZ frame; rotate result // according to trim switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: if (!dcm.get_quaternion(quat)) { return false; } break; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: if (!_ekf2_started) { @@ -1031,21 +1113,23 @@ bool AP_AHRS::get_quaternion(Quaternion &quat) const } // return secondary attitude solution if available, as eulers in radians -bool AP_AHRS::get_secondary_attitude(Vector3f &eulers) const +bool AP_AHRS::_get_secondary_attitude(Vector3f &eulers) const { EKFType secondary_ekf_type; - if (!get_secondary_EKF_type(secondary_ekf_type)) { + if (!_get_secondary_EKF_type(secondary_ekf_type)) { return false; } switch (secondary_ekf_type) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: // DCM is secondary eulers[0] = dcm_estimates.roll_rad; eulers[1] = dcm_estimates.pitch_rad; eulers[2] = dcm_estimates.yaw_rad; return true; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -1084,21 +1168,23 @@ bool AP_AHRS::get_secondary_attitude(Vector3f &eulers) const // return secondary attitude solution if available, as quaternion -bool AP_AHRS::get_secondary_quaternion(Quaternion &quat) const +bool AP_AHRS::_get_secondary_quaternion(Quaternion &quat) const { EKFType secondary_ekf_type; - if (!get_secondary_EKF_type(secondary_ekf_type)) { + if (!_get_secondary_EKF_type(secondary_ekf_type)) { return false; } switch (secondary_ekf_type) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: // DCM is secondary if (!dcm.get_quaternion(quat)) { return false; } break; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -1139,19 +1225,24 @@ bool AP_AHRS::get_secondary_quaternion(Quaternion &quat) const } // return secondary position solution if available -bool AP_AHRS::get_secondary_position(Location &loc) const +bool AP_AHRS::_get_secondary_position(Location &loc) const { EKFType secondary_ekf_type; - if (!get_secondary_EKF_type(secondary_ekf_type)) { + if (!_get_secondary_EKF_type(secondary_ekf_type)) { return false; } switch (secondary_ekf_type) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: // return DCM position - dcm.get_location(loc); + loc = dcm_estimates.location; + // FIXME: we intentionally do not return whether location is + // actually valid here so we continue to send mavlink messages + // and log data: return true; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -1176,7 +1267,7 @@ bool AP_AHRS::get_secondary_position(Location &loc) const #if HAL_EXTERNAL_AHRS_ENABLED case EKFType::EXTERNAL: // External is secondary - return external.get_location(loc); + return external_estimates.get_location(loc); #endif } @@ -1185,24 +1276,28 @@ bool AP_AHRS::get_secondary_position(Location &loc) const } // EKF has a better ground speed vector estimate -Vector2f AP_AHRS::groundspeed_vector(void) +Vector2f AP_AHRS::_groundspeed_vector(void) { - Vector3f vec; - switch (active_EKF_type()) { - case EKFType::NONE: - break; +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: + return dcm.groundspeed_vector(); +#endif #if HAL_NAVEKF2_AVAILABLE - case EKFType::TWO: + case EKFType::TWO: { + Vector3f vec; EKF2.getVelNED(vec); return vec.xy(); + } #endif #if HAL_NAVEKF3_AVAILABLE - case EKFType::THREE: + case EKFType::THREE: { + Vector3f vec; EKF3.getVelNED(vec); return vec.xy(); + } #endif #if AP_AHRS_SIM_ENABLED @@ -1215,14 +1310,16 @@ Vector2f AP_AHRS::groundspeed_vector(void) } #endif } - return dcm.groundspeed_vector(); + return Vector2f(); } -float AP_AHRS::groundspeed(void) +float AP_AHRS::_groundspeed(void) { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.groundspeed(); +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: #endif @@ -1258,8 +1355,10 @@ bool AP_AHRS::set_origin(const Location &loc) // return success if active EKF's origin was set switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return false; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -1300,17 +1399,21 @@ bool AP_AHRS::handle_external_position_estimate(const Location &loc, float pos_a // return true if inertial navigation is active bool AP_AHRS::have_inertial_nav(void) const { - return active_EKF_type() != EKFType::NONE; +#if AP_AHRS_DCM_ENABLED + return active_EKF_type() != EKFType::DCM; +#endif + return true; } // return a ground velocity in meters/second, North/East/Down // order. Must only be called if have_inertial_nav() is true -bool AP_AHRS::get_velocity_NED(Vector3f &vec) const +bool AP_AHRS::_get_velocity_NED(Vector3f &vec) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: break; - +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: EKF2.getVelNED(vec); @@ -1332,16 +1435,20 @@ bool AP_AHRS::get_velocity_NED(Vector3f &vec) const return external.get_velocity_NED(vec); #endif } +#if AP_AHRS_DCM_ENABLED return dcm.get_velocity_NED(vec); +#endif + return false; } // returns the expected NED magnetic field bool AP_AHRS::get_mag_field_NED(Vector3f &vec) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return false; - +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: EKF2.getMagNED(vec); @@ -1370,9 +1477,10 @@ bool AP_AHRS::get_mag_field_NED(Vector3f &vec) const bool AP_AHRS::get_mag_field_correction(Vector3f &vec) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return false; - +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: EKF2.getMagXYZ(vec); @@ -1399,12 +1507,14 @@ bool AP_AHRS::get_mag_field_correction(Vector3f &vec) const } // Get a derivative of the vertical position 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 verical position due to the various errors that are being corrected for. +// 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. bool AP_AHRS::get_vert_pos_rate_D(float &velocity) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.get_vert_pos_rate_D(velocity); +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -1435,9 +1545,10 @@ bool AP_AHRS::get_vert_pos_rate_D(float &velocity) const bool AP_AHRS::get_hagl(float &height) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return false; - +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: return EKF2.getHAGL(height); @@ -1462,14 +1573,16 @@ bool AP_AHRS::get_hagl(float &height) const return false; } -// return a relative ground position to the origin in meters -// North/East/Down order. +/* + return a relative NED position from the origin in meters +*/ bool AP_AHRS::get_relative_position_NED_origin(Vector3f &vec) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.get_relative_position_NED_origin(vec); - +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: { Vector2f posNE; @@ -1514,33 +1627,30 @@ bool AP_AHRS::get_relative_position_NED_origin(Vector3f &vec) const return false; } -// return a relative ground position to the home in meters -// North/East/Down order. +/* + return a relative ground position from home in meters +*/ bool AP_AHRS::get_relative_position_NED_home(Vector3f &vec) const { - Location originLLH; - Vector3f originNED; - if (!get_relative_position_NED_origin(originNED) || - !get_origin(originLLH)) { + Location loc; + if (!_home_is_set || + !get_location(loc)) { return false; } - - const Vector3f offset = originLLH.get_distance_NED(_home); - - vec.x = originNED.x - offset.x; - vec.y = originNED.y - offset.y; - vec.z = originNED.z - offset.z; + vec = _home.get_distance_NED(loc); return true; } -// write a relative ground position estimate to the origin in meters, North/East order -// return true if estimate is valid +/* + return a relative position estimate from the origin in meters +*/ bool AP_AHRS::get_relative_position_NE_origin(Vector2f &posNE) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.get_relative_position_NE_origin(posNE); - +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: { bool position_is_valid = EKF2.getPosNE(posNE); @@ -1569,35 +1679,34 @@ bool AP_AHRS::get_relative_position_NE_origin(Vector2f &posNE) const return false; } -// return a relative ground position to the home in meters -// North/East order. +/* + return a relative ground position from home in meters North/East +*/ bool AP_AHRS::get_relative_position_NE_home(Vector2f &posNE) const { - Location originLLH; - Vector2f originNE; - if (!get_relative_position_NE_origin(originNE) || - !get_origin(originLLH)) { + Location loc; + if (!_home_is_set || + !get_location(loc)) { return false; } - const Vector2f offset = originLLH.get_distance_NE(_home); - - posNE.x = originNE.x - offset.x; - posNE.y = originNE.y - offset.y; + posNE = _home.get_distance_NE(loc); return true; } // write a relative ground position estimate to the origin in meters, North/East order -// write a relative ground position to the origin in meters, Down -// return true if the estimate is valid +/* + return a relative ground position from the origin in meters, down +*/ bool AP_AHRS::get_relative_position_D_origin(float &posD) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.get_relative_position_D_origin(posD); - +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: { bool position_is_valid = EKF2.getPosD(posD); @@ -1625,8 +1734,9 @@ bool AP_AHRS::get_relative_position_D_origin(float &posD) const return false; } -// write a relative ground position to home in meters, Down -// will use the barometer if the EKF isn't available +/* + return relative position from home in meters +*/ void AP_AHRS::get_relative_position_D_home(float &posD) const { if (!_home_is_set) { @@ -1639,14 +1749,16 @@ void AP_AHRS::get_relative_position_D_home(float &posD) const Location originLLH; float originD; if (!get_relative_position_D_origin(originD) || - !get_origin(originLLH)) { + !_get_origin(originLLH)) { +#if AP_GPS_ENABLED 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; - } else { - posD = -AP::baro().get_altitude(); + return; } +#endif + posD = -AP::baro().get_altitude(); return; } @@ -1677,7 +1789,8 @@ AP_AHRS::EKFType AP_AHRS::ekf_type(void) const case EKFType::THREE: return type; #endif - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: if (always_use_EKF()) { #if HAL_NAVEKF2_AVAILABLE return EKFType::TWO; @@ -1685,7 +1798,8 @@ AP_AHRS::EKFType AP_AHRS::ekf_type(void) const return EKFType::THREE; #endif } - return EKFType::NONE; + return EKFType::DCM; +#endif } // we can get to here if the user has mis-set AHRS_EKF_TYPE - any // value above 3 will get to here. TWO is returned here for no @@ -1694,24 +1808,28 @@ AP_AHRS::EKFType AP_AHRS::ekf_type(void) const return EKFType::TWO; #elif HAL_NAVEKF3_AVAILABLE return EKFType::THREE; +#elif AP_AHRS_DCM_ENABLED + return EKFType::DCM; #else - return EKFType::NONE; + #error "no default backend available" #endif } -AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const +AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const { - EKFType ret = EKFType::NONE; + EKFType ret = fallback_active_EKF_type(); switch (ekf_type()) { - case EKFType::NONE: - return EKFType::NONE; +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: + return EKFType::DCM; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: { // do we have an EKF2 yet? if (!_ekf2_started) { - return EKFType::NONE; + return fallback_active_EKF_type(); } if (always_use_EKF()) { uint16_t ekf2_faults; @@ -1730,7 +1848,7 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const case EKFType::THREE: { // do we have an EKF3 yet? if (!_ekf3_started) { - return EKFType::NONE; + return fallback_active_EKF_type(); } if (always_use_EKF()) { uint16_t ekf3_faults; @@ -1757,6 +1875,7 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const #endif } +#if AP_AHRS_DCM_ENABLED /* fixed wing and rover will fall back to DCM if the EKF doesn't have GPS. This is the safest option as DCM is very robust. Note @@ -1764,7 +1883,7 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const and we are disarmed. This is to ensure that the arming checks do wait for good GPS position on fixed wing and rover */ - if (ret != EKFType::NONE && + if (ret != EKFType::DCM && (_vehicle_class == VehicleClass::FIXED_WING || _vehicle_class == VehicleClass::GROUND)) { if (!dcm.yaw_source_available() && !fly_forward) { @@ -1807,15 +1926,15 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const // prefer to use the GPS position from DCM. This is a // safety net while some issues with the EKF get sorted // out - return EKFType::NONE; + return EKFType::DCM; } if (hal.util->get_soft_armed() && filt_state.flags.const_pos_mode) { - return EKFType::NONE; + return EKFType::DCM; } if (!filt_state.flags.attitude || !filt_state.flags.vert_vel || !filt_state.flags.vert_pos) { - return EKFType::NONE; + return EKFType::DCM; } if (!filt_state.flags.horiz_vel || (!filt_state.flags.horiz_pos_abs && !filt_state.flags.horiz_pos_rel)) { @@ -1832,18 +1951,55 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const return ret; } } - return EKFType::NONE; + return EKFType::DCM; } } +#endif + return ret; } +AP_AHRS::EKFType AP_AHRS::fallback_active_EKF_type(void) const +{ +#if AP_AHRS_DCM_ENABLED + return EKFType::DCM; +#endif + +#if HAL_NAVEKF3_AVAILABLE + if (_ekf3_started) { + return EKFType::THREE; + } +#endif + +#if HAL_NAVEKF2_AVAILABLE + if (_ekf2_started) { + return EKFType::TWO; + } +#endif + +#if HAL_EXTERNAL_AHRS_ENABLED + if (external.healthy()) { + return EKFType::EXTERNAL; + } +#endif + + // so nobody is ready yet. Return something, even if it is not ready: +#if HAL_NAVEKF3_AVAILABLE + return EKFType::THREE; +#elif HAL_NAVEKF2_AVAILABLE + return EKFType::TWO; +#elif HAL_EXTERNAL_AHRS_ENABLED + return EKFType::EXTERNAL; +#endif +} + // get secondary EKF type. returns false if no secondary (i.e. only using DCM) -bool AP_AHRS::get_secondary_EKF_type(EKFType &secondary_ekf_type) const +bool AP_AHRS::_get_secondary_EKF_type(EKFType &secondary_ekf_type) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: // EKF2, EKF3 or External is secondary #if HAL_NAVEKF3_AVAILABLE if ((EKFType)_ekf_type.get() == EKFType::THREE) { @@ -1864,7 +2020,7 @@ bool AP_AHRS::get_secondary_EKF_type(EKFType &secondary_ekf_type) const } #endif return false; - +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: #endif @@ -1878,7 +2034,7 @@ bool AP_AHRS::get_secondary_EKF_type(EKFType &secondary_ekf_type) const case EKFType::EXTERNAL: #endif // DCM is secondary - secondary_ekf_type = EKFType::NONE; + secondary_ekf_type = fallback_active_EKF_type(); return true; } @@ -1895,8 +2051,11 @@ bool AP_AHRS::healthy(void) const // sensor data. If EKF reversion is inhibited, we only switch across if the EKF encounters // an internal processing error, but not for bad sensor data. switch (ekf_type()) { - case EKFType::NONE: + +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.healthy(); +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: { @@ -1942,7 +2101,7 @@ bool AP_AHRS::healthy(void) const #endif } - return dcm.healthy(); + return false; } // returns false if we fail arming checks, in which case the buffer will be populated with a failure message @@ -1959,7 +2118,7 @@ bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f #if HAL_EXTERNAL_AHRS_ENABLED // Always check external AHRS if enabled - // it is a source for IMU data even if not being used as direct AHRS replacment + // it is a source for IMU data even if not being used as direct AHRS replacement if (AP::externalAHRS().enabled() || (ekf_type() == EKFType::EXTERNAL)) { if (!AP::externalAHRS().pre_arm_check(failure_msg, failure_msg_len)) { return false; @@ -1982,8 +2141,11 @@ bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f case EKFType::SIM: return ret; #endif - case EKFType::NONE: + +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.pre_arm_check(requires_position, failure_msg, failure_msg_len) && ret; +#endif #if HAL_EXTERNAL_AHRS_ENABLED case EKFType::EXTERNAL: @@ -2018,8 +2180,10 @@ bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f bool AP_AHRS::initialised(void) const { switch (ekf_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return true; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2049,8 +2213,10 @@ bool AP_AHRS::initialised(void) const bool AP_AHRS::get_filter_status(nav_filter_status &status) const { switch (ekf_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.get_filter_status(status); +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2142,9 +2308,11 @@ void AP_AHRS::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeSt void AP_AHRS::getControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: dcm.get_control_limits(ekfGndSpdLimit, ekfNavVelGainScaler); break; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2178,11 +2346,13 @@ void AP_AHRS::getControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler */ float AP_AHRS::getControlScaleZ(void) const { - if (active_EKF_type() == EKFType::NONE) { +#if AP_AHRS_DCM_ENABLED + if (active_EKF_type() == EKFType::DCM) { // when flying on DCM lower gains by 4x to cope with the high // lag return 0.25; } +#endif return 1; } @@ -2191,9 +2361,10 @@ float AP_AHRS::getControlScaleZ(void) const bool AP_AHRS::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const { switch (ekf_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return false; - +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: return EKF2.getMagOffsets(mag_idx, magOffsets); @@ -2218,13 +2389,15 @@ bool AP_AHRS::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const } // Retrieves the NED delta velocity corrected -void AP_AHRS::getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const +void AP_AHRS::_getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const { int8_t imu_idx = -1; Vector3f accel_bias; switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: break; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: imu_idx = EKF2.getPrimaryCoreIMUIndex(); @@ -2246,17 +2419,22 @@ void AP_AHRS::getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const break; #endif } + ret.zero(); if (imu_idx == -1) { - dcm.getCorrectedDeltaVelocityNED(ret, dt); + AP::ins().get_delta_velocity(ret, dt); return; } - ret.zero(); AP::ins().get_delta_velocity((uint8_t)imu_idx, ret, dt); ret -= accel_bias*dt; - ret = _dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * ret; + ret = state.dcm_matrix * get_rotation_autopilot_body_to_vehicle_body() * ret; ret.z += GRAVITY_MSS*dt; } +void AP_AHRS::set_failure_inconsistent_message(const char *estimator, const char *axis, float diff_rad, char *failure_msg, const uint8_t failure_msg_len) const +{ + hal.util->snprintf(failure_msg, failure_msg_len, "%s %s inconsistent %d deg. Wait or reboot", estimator, axis, (int)degrees(diff_rad)); +} + // check all cores providing consistent attitudes for prearm checks bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const { @@ -2277,7 +2455,7 @@ bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_ // check roll and pitch difference const float rp_diff_rad = primary_quat.roll_pitch_difference(ekf2_quat); if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) { - hal.util->snprintf(failure_msg, failure_msg_len, "EKF2 Roll/Pitch inconsistent by %d deg", (int)degrees(rp_diff_rad)); + set_failure_inconsistent_message("EKF2", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len); return false; } @@ -2286,7 +2464,7 @@ bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_ primary_quat.angular_difference(ekf2_quat).to_axis_angle(angle_diff); const float yaw_diff = fabsf(angle_diff.z); if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) { - hal.util->snprintf(failure_msg, failure_msg_len, "EKF2 Yaw inconsistent by %d deg", (int)degrees(yaw_diff)); + set_failure_inconsistent_message("EKF2", "Yaw", yaw_diff, failure_msg, failure_msg_len); return false; } } @@ -2304,7 +2482,7 @@ bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_ // check roll and pitch difference const float rp_diff_rad = primary_quat.roll_pitch_difference(ekf3_quat); if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) { - hal.util->snprintf(failure_msg, failure_msg_len, "EKF3 Roll/Pitch inconsistent by %d deg", (int)degrees(rp_diff_rad)); + set_failure_inconsistent_message("EKF3", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len); return false; } @@ -2313,7 +2491,7 @@ bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_ primary_quat.angular_difference(ekf3_quat).to_axis_angle(angle_diff); const float yaw_diff = fabsf(angle_diff.z); if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) { - hal.util->snprintf(failure_msg, failure_msg_len, "EKF3 Yaw inconsistent by %d deg", (int)degrees(yaw_diff)); + set_failure_inconsistent_message("EKF3", "Yaw", yaw_diff, failure_msg, failure_msg_len); return false; } } @@ -2321,6 +2499,7 @@ bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_ } #endif +#if AP_AHRS_DCM_ENABLED // check primary vs dcm if (!always_use_EKF() || (total_ekf_cores == 1)) { Quaternion dcm_quat; @@ -2329,7 +2508,7 @@ bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_ // check roll and pitch difference const float rp_diff_rad = primary_quat.roll_pitch_difference(dcm_quat); if (rp_diff_rad > ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD) { - hal.util->snprintf(failure_msg, failure_msg_len, "DCM Roll/Pitch inconsistent by %d deg", (int)degrees(rp_diff_rad)); + set_failure_inconsistent_message("DCM", "Roll/Pitch", rp_diff_rad, failure_msg, failure_msg_len); return false; } @@ -2344,11 +2523,12 @@ bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_ primary_quat.angular_difference(dcm_quat).to_axis_angle(angle_diff); const float yaw_diff = fabsf(angle_diff.z); if (check_yaw && (yaw_diff > ATTITUDE_CHECK_THRESH_YAW_RAD)) { - hal.util->snprintf(failure_msg, failure_msg_len, "DCM Yaw inconsistent by %d deg", (int)degrees(yaw_diff)); + set_failure_inconsistent_message("DCM", "Yaw", yaw_diff, failure_msg, failure_msg_len); return false; } } } +#endif return true; } @@ -2359,8 +2539,10 @@ uint32_t AP_AHRS::getLastYawResetAngle(float &yawAng) { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.getLastYawResetAngle(yawAng); +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2390,8 +2572,10 @@ uint32_t AP_AHRS::getLastPosNorthEastReset(Vector2f &pos) { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return 0; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2421,8 +2605,10 @@ uint32_t AP_AHRS::getLastVelNorthEastReset(Vector2f &vel) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return 0; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2452,8 +2638,10 @@ uint32_t AP_AHRS::getLastVelNorthEastReset(Vector2f &vel) const uint32_t AP_AHRS::getLastPosDownReset(float &posDelta) { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return 0; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2489,7 +2677,8 @@ bool AP_AHRS::resetHeightDatum(void) switch (ekf_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: #if HAL_NAVEKF3_AVAILABLE EKF3.resetHeightDatum(); #endif @@ -2497,6 +2686,7 @@ bool AP_AHRS::resetHeightDatum(void) EKF2.resetHeightDatum(); #endif return false; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2526,15 +2716,16 @@ bool AP_AHRS::resetHeightDatum(void) return false; } -// send a EKF_STATUS_REPORT for current EKF +// send a EKF_STATUS_REPORT for configured EKF void AP_AHRS::send_ekf_status_report(GCS_MAVLINK &link) const { switch (ekf_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: // send zero status report dcm.send_ekf_status_report(link); break; - +#endif #if AP_AHRS_SIM_ENABLED case EKFType::SIM: sim.send_ekf_status_report(link); @@ -2562,11 +2753,13 @@ void AP_AHRS::send_ekf_status_report(GCS_MAVLINK &link) const } // return origin for a specified EKF type -bool AP_AHRS::get_origin(EKFType type, Location &ret) const +bool AP_AHRS::_get_origin(EKFType type, Location &ret) const { switch (type) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: return dcm.get_origin(ret); +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2598,26 +2791,84 @@ bool AP_AHRS::get_origin(EKFType type, Location &ret) const This copes with users force arming a plane that is running on DCM as the EKF has not fully initialised */ -bool AP_AHRS::get_origin(Location &ret) const +bool AP_AHRS::_get_origin(Location &ret) const { - if (get_origin(ekf_type(), ret)) { + if (_get_origin(ekf_type(), ret)) { return true; } - if (hal.util->get_soft_armed() && get_origin(active_EKF_type(), ret)) { + if (hal.util->get_soft_armed() && _get_origin(active_EKF_type(), ret)) { return true; } return false; } +bool AP_AHRS::set_home(const Location &loc) +{ + WITH_SEMAPHORE(_rsem); + // check location is valid + if (loc.lat == 0 && loc.lng == 0 && loc.alt == 0) { + return false; + } + if (!loc.check_latlng()) { + return false; + } + // home must always be global frame at the moment as .alt is + // accessed directly by the vehicles and they may not be rigorous + // in checking the frame type. + Location tmp = loc; + if (!tmp.change_alt_frame(Location::AltFrame::ABSOLUTE)) { + return false; + } + +#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) + if (!_home_is_set) { + // record home is set + AP::logger().Write_Event(LogEvent::SET_HOME); + } +#endif + + _home = tmp; + _home_is_set = true; + + Log_Write_Home_And_Origin(); + + // send new home and ekf origin to GCS + GCS_SEND_MESSAGE(MSG_HOME); + GCS_SEND_MESSAGE(MSG_ORIGIN); + + AP_HAL::Util::PersistentData &pd = hal.util->persistent_data; + pd.home_lat = loc.lat; + pd.home_lon = loc.lng; + pd.home_alt_cm = loc.alt; + + return true; +} + +/* if this was a watchdog reset then get home from backup registers */ +void AP_AHRS::load_watchdog_home() +{ + const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data; + if (hal.util->was_watchdog_reset() && (pd.home_lat != 0 || pd.home_lon != 0)) { + _home.lat = pd.home_lat; + _home.lng = pd.home_lon; + _home.set_alt_cm(pd.home_alt_cm, Location::AltFrame::ABSOLUTE); + _home_is_set = true; + _home_locked = true; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Restored watchdog home"); + } +} + // get_hgt_ctrl_limit - get maximum height to be observed by the control loops in metres and a validity flag // this is used to limit height during optical flow navigation // it will return false when no limiting is required bool AP_AHRS::get_hgt_ctrl_limit(float& limit) const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: // We are not using an EKF so no limiting applies return false; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2672,14 +2923,16 @@ void AP_AHRS::set_terrain_hgt_stable(bool stable) #endif } -// return the innovations for the primariy EKF +// return the innovations for the primarily EKF // boolean false is returned if innovations are not available bool AP_AHRS::get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const { switch (ekf_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: // We are not using an EKF so no data return false; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2715,7 +2968,9 @@ bool AP_AHRS::is_vibration_affected() const case EKFType::THREE: return EKF3.isVibrationAffected(); #endif - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: #endif @@ -2732,14 +2987,16 @@ bool AP_AHRS::is_vibration_affected() const // get_variances - provides the innovations normalised using the innovation variance where a value of 0 // indicates prefect consistency between the measurement and the EKF solution and a value of 1 is the maximum -// inconsistency that will be accpeted by the filter +// inconsistency that will be accepted by the filter // boolean false is returned if variances are not available bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar) const { switch (ekf_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: // We are not using an EKF so no data return false; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: { @@ -2776,9 +3033,11 @@ bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3 bool AP_AHRS::get_vel_innovations_and_variances_for_source(uint8_t source, Vector3f &innovations, Vector3f &variances) const { switch (ekf_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: // We are not using an EKF so no data return false; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2835,13 +3094,14 @@ uint8_t AP_AHRS::get_active_airspeed_index() const } // get the index of the current primary IMU -uint8_t AP_AHRS::get_primary_IMU_index() const +uint8_t AP_AHRS::_get_primary_IMU_index() const { int8_t imu = -1; switch (active_EKF_type()) { - case EKFType::NONE: - imu = AP::ins().get_primary_gyro(); +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: break; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: // let EKF2 choose primary IMU @@ -2864,24 +3124,30 @@ uint8_t AP_AHRS::get_primary_IMU_index() const #endif } if (imu == -1) { - imu = AP::ins().get_primary_accel(); + imu = AP::ins().get_primary_gyro(); } return imu; } // return the index of the primary core or -1 if no primary core selected -int8_t AP_AHRS::get_primary_core_index() const +int8_t AP_AHRS::_get_primary_core_index() const { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: + // we have only one core + return 0; +#endif #if AP_AHRS_SIM_ENABLED case EKFType::SIM: + // we have only one core + return 0; #endif #if HAL_EXTERNAL_AHRS_ENABLED case EKFType::EXTERNAL: -#endif // we have only one core return 0; +#endif #if HAL_NAVEKF2_AVAILABLE case EKFType::TWO: @@ -2900,29 +3166,25 @@ int8_t AP_AHRS::get_primary_core_index() const } // get the index of the current primary accelerometer sensor -uint8_t AP_AHRS::get_primary_accel_index(void) const +uint8_t AP_AHRS::_get_primary_accel_index(void) const { - if (ekf_type() != EKFType::NONE) { - return get_primary_IMU_index(); - } - return AP::ins().get_primary_accel(); + return _get_primary_IMU_index(); } // get the index of the current primary gyro sensor -uint8_t AP_AHRS::get_primary_gyro_index(void) const +uint8_t AP_AHRS::_get_primary_gyro_index(void) const { - if (ekf_type() != EKFType::NONE) { - return get_primary_IMU_index(); - } - return AP::ins().get_primary_gyro(); + return _get_primary_IMU_index(); } // see if EKF lane switching is possible to avoid EKF failsafe void AP_AHRS::check_lane_switch(void) { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: break; +#endif #if AP_AHRS_SIM_ENABLED case EKFType::SIM: @@ -2952,9 +3214,10 @@ void AP_AHRS::check_lane_switch(void) void AP_AHRS::request_yaw_reset(void) { switch (active_EKF_type()) { - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: break; - +#endif #if AP_AHRS_SIM_ENABLED case EKFType::SIM: break; @@ -3022,7 +3285,9 @@ bool AP_AHRS::using_noncompass_for_yaw(void) const case EKFType::TWO: return EKF2.isExtNavUsedForYaw(); #endif - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: +#endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: return EKF3.using_noncompass_for_yaw(); @@ -3047,7 +3312,9 @@ bool AP_AHRS::using_extnav_for_yaw(void) const case EKFType::TWO: return EKF2.isExtNavUsedForYaw(); #endif - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: +#endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: return EKF3.using_extnav_for_yaw(); @@ -3083,7 +3350,14 @@ const EKFGSF_yaw *AP_AHRS::get_yaw_estimator(void) const case EKFType::TWO: return EKF2.get_yawEstimator(); #endif - case EKFType::NONE: +#if AP_AHRS_DCM_ENABLED + case EKFType::DCM: +#if HAL_NAVEKF3_AVAILABLE + return EKF3.get_yawEstimator(); +#else + return nullptr; +#endif +#endif #if HAL_NAVEKF3_AVAILABLE case EKFType::THREE: return EKF3.get_yawEstimator(); @@ -3100,6 +3374,100 @@ const EKFGSF_yaw *AP_AHRS::get_yaw_estimator(void) const return nullptr; } +// get current location estimate +bool AP_AHRS::get_location(Location &loc) const +{ + loc = state.location; + return state.location_ok; +} + +// return a wind estimation vector, in m/s; returns 0,0,0 on failure +bool AP_AHRS::wind_estimate(Vector3f &wind) const +{ + wind = state.wind_estimate; + return state.wind_estimate_ok; +} + +// return an airspeed estimate if available. return true +// if we have an estimate +bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const +{ + airspeed_ret = state.airspeed; + return state.airspeed_ok; +} + +// return an airspeed estimate if available. return true +// if we have an estimate +bool AP_AHRS::airspeed_estimate(float &airspeed_ret, AP_AHRS::AirspeedEstimateType &type) const +{ + airspeed_ret = state.airspeed; + type = state.airspeed_estimate_type; + return state.airspeed_ok; +} + +// return a true airspeed estimate (navigation airspeed) if +// available. return true if we have an estimate +bool AP_AHRS::airspeed_estimate_true(float &airspeed_ret) const +{ + airspeed_ret = state.airspeed_true; + return state.airspeed_true_ok; +} + +// return estimate of true airspeed vector in body frame in m/s +// returns false if estimate is unavailable +bool AP_AHRS::airspeed_vector_true(Vector3f &vec) const +{ + vec = state.airspeed_vec; + return state.airspeed_vec_ok; +} + +// return the quaternion defining the rotation from NED to XYZ (body) axes +bool AP_AHRS::get_quaternion(Quaternion &quat) const +{ + quat = state.quat; + return state.quat_ok; +} + +// returns the inertial navigation origin in lat/lon/alt +bool AP_AHRS::get_origin(Location &ret) const +{ + ret = state.origin; + return state.origin_ok; +} + +// return a ground velocity in meters/second, North/East/Down +// order. Must only be called if have_inertial_nav() is true +bool AP_AHRS::get_velocity_NED(Vector3f &vec) const +{ + vec = state.velocity_NED; + return state.velocity_NED_ok; +} + +// 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 +{ + if (!get_origin(loc)) { + return false; + } + loc.offset(offset_ned); + + return true; +} + +// 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 +{ + if (!home_is_set()) { + return false; + } + loc = get_home(); + loc.offset(offset_ned); + + return true; +} + // singleton instance AP_AHRS *AP_AHRS::_singleton; diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index c32ba042c1cf02..8ab6bca0457cb1 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -76,10 +76,10 @@ class AP_AHRS { } // return the smoothed gyro vector corrected for drift - const Vector3f &get_gyro(void) const; + const Vector3f &get_gyro(void) const { return state.gyro_estimate; } // return the current drift correction integrator value - const Vector3f &get_gyro_drift(void) const; + const Vector3f &get_gyro_drift(void) const { return state.gyro_drift; } // reset the current gyro drift estimate // should be called if gyro offsets are recalculated @@ -88,7 +88,7 @@ class AP_AHRS { void update(bool skip_ins_update=false); void reset(); - // dead-reckoning support + // get current location estimate bool get_location(Location &loc) const; // get latest altitude estimate above ground level in meters and validity flag @@ -109,10 +109,17 @@ class AP_AHRS { bool get_wind_estimation_enabled() const { return wind_estimation_enabled; } // return a wind estimation vector, in m/s; returns 0,0,0 on failure - Vector3f wind_estimate() const; + const Vector3f &wind_estimate() const { return state.wind_estimate; } + + // return a wind estimation vector, in m/s; returns 0,0,0 on failure + bool wind_estimate(Vector3f &wind) const; // instruct DCM to update its wind estimate: - void estimate_wind() { dcm.estimate_wind(); } + void estimate_wind() { +#if AP_AHRS_DCM_ENABLED + dcm.estimate_wind(); +#endif + } // return the parameter AHRS_WIND_MAX in metres per second uint8_t get_max_wind() const { @@ -125,13 +132,25 @@ class AP_AHRS { // get apparent to true airspeed ratio float get_EAS2TAS(void) const { - // FIXME: make this is a method on the active backend - return dcm.get_EAS2TAS(); + return state.EAS2TAS; } // return an airspeed estimate if available. return true // if we have an estimate bool airspeed_estimate(float &airspeed_ret) const; + + enum AirspeedEstimateType : uint8_t { + NO_NEW_ESTIMATE = 0, + AIRSPEED_SENSOR = 1, + DCM_SYNTHETIC = 2, + EKF3_SYNTHETIC = 3, + SIM = 4, + }; + + // return an airspeed estimate if available. return true + // if we have an estimate + bool airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &type) const; + // return a true airspeed estimate (navigation airspeed) if // available. return true if we have an estimate bool airspeed_estimate_true(float &airspeed_ret) const; @@ -152,7 +171,7 @@ class AP_AHRS { // opposed to an IMU estimate bool airspeed_sensor_enabled(uint8_t airspeed_index) const { // FIXME: make this a method on the active backend - return dcm.airspeed_sensor_enabled(airspeed_index); + return AP_AHRS_Backend::airspeed_sensor_enabled(airspeed_index); } // return a synthetic airspeed estimate (one derived from sensors @@ -168,26 +187,38 @@ class AP_AHRS { bool get_quaternion(Quaternion &quat) const WARN_IF_UNUSED; // return secondary attitude solution if available, as eulers in radians - bool get_secondary_attitude(Vector3f &eulers) const; + bool get_secondary_attitude(Vector3f &eulers) const { + eulers = state.secondary_attitude; + return state.secondary_attitude_ok; + } // return secondary attitude solution if available, as quaternion - bool get_secondary_quaternion(Quaternion &quat) const; + bool get_secondary_quaternion(Quaternion &quat) const { + quat = state.secondary_quat; + return state.secondary_quat_ok; + } // return secondary position solution if available - bool get_secondary_position(Location &loc) const; + bool get_secondary_position(Location &loc) const { + loc = state.secondary_pos; + return state.secondary_pos_ok; + } // EKF has a better ground speed vector estimate - Vector2f groundspeed_vector(); + const Vector2f &groundspeed_vector() const { return state.ground_speed_vec; } // return ground speed estimate in meters/second. Used by ground vehicles. - float groundspeed(void); + float groundspeed(void) const { return state.ground_speed; } const Vector3f &get_accel_ef() const { - return _accel_ef; + return state.accel_ef; } // Retrieves the corrected NED delta velocity in use by the inertial navigation - void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const; + void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const { + ret = state.corrected_dv; + dt = state.corrected_dv_dt; + } // set the EKF's origin location in 10e7 degrees. This should only // be called when the EKF has no absolute position reference (i.e. GPS) @@ -214,21 +245,26 @@ class AP_AHRS { // order. Must only be called if have_inertial_nav() is true bool get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED; - // return the relative position NED to either home or origin + // return the relative position NED from either home or origin // return true if the estimate is valid bool get_relative_position_NED_home(Vector3f &vec) const WARN_IF_UNUSED; bool get_relative_position_NED_origin(Vector3f &vec) const WARN_IF_UNUSED; - // return the relative position NE to either home or origin + // return the relative position NE from home or origin // return true if the estimate is valid bool get_relative_position_NE_home(Vector2f &posNE) const WARN_IF_UNUSED; bool get_relative_position_NE_origin(Vector2f &posNE) const WARN_IF_UNUSED; - // return the relative position down to either home or origin + // return the relative position down from home or origin // baro will be used for the _home relative one if the EKF isn't void get_relative_position_D_home(float &posD) const; bool get_relative_position_D_origin(float &posD) const WARN_IF_UNUSED; + // 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; + // 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. bool get_vert_pos_rate_D(float &velocity) const; @@ -265,10 +301,12 @@ class AP_AHRS { // true if the AHRS has completed initialisation bool initialised() const; +#if AP_AHRS_DCM_ENABLED // return true if *DCM* yaw has been initialised bool dcm_yaw_initialised(void) const { return dcm.yaw_initialised(); } +#endif // get_filter_status - returns filter status as a series of flags bool get_filter_status(nav_filter_status &status) const; @@ -343,13 +381,13 @@ class AP_AHRS { uint8_t get_active_airspeed_index() const; // return the index of the primary core or -1 if no primary core selected - int8_t get_primary_core_index() const; + int8_t get_primary_core_index() const { return state.primary_core; } // get the index of the current primary accelerometer sensor - uint8_t get_primary_accel_index(void) const; + uint8_t get_primary_accel_index(void) const { return state.primary_accel; } // get the index of the current primary gyro sensor - uint8_t get_primary_gyro_index(void) const; + uint8_t get_primary_gyro_index(void) const { return state.primary_gyro; } // see if EKF lane switching is possible to avoid EKF failsafe void check_lane_switch(void); @@ -507,18 +545,18 @@ class AP_AHRS { int32_t pitch_sensor; int32_t yaw_sensor; - const Matrix3f &get_rotation_body_to_ned(void) const; + const Matrix3f &get_rotation_body_to_ned(void) const { return state.dcm_matrix; } // return a Quaternion representing our current attitude in NED frame - void get_quat_body_to_ned(Quaternion &quat) const { - quat.from_rotation_matrix(get_rotation_body_to_ned()); - } + void get_quat_body_to_ned(Quaternion &quat) const; +#if AP_AHRS_DCM_ENABLED // get rotation matrix specifically from DCM backend (used for // compass calibrator) const Matrix3f &get_DCM_rotation_body_to_ned(void) const { return dcm_estimates.dcm_matrix; } +#endif // rotate a 2D vector from earth frame to body frame // in result, x is forward, y is right @@ -529,14 +567,10 @@ class AP_AHRS { Vector2f body_to_earth2D(const Vector2f &bf) const; // convert a vector from body to earth frame - Vector3f body_to_earth(const Vector3f &v) const { - return get_rotation_body_to_ned() * v; - } + Vector3f body_to_earth(const Vector3f &v) const; // convert a vector from earth to body frame - Vector3f earth_to_body(const Vector3f &v) const { - return get_rotation_body_to_ned().mul_transpose(v); - } + Vector3f earth_to_body(const Vector3f &v) const; /* * methods for the benefit of LUA bindings @@ -553,7 +587,7 @@ class AP_AHRS { // get_accel() vector to get best current body frame accel // estimate const Vector3f &get_accel_bias(void) const { - return _accel_bias; + return state.accel_bias; } /* @@ -646,7 +680,9 @@ class AP_AHRS { AP_Int8 _gps_minsats; enum class EKFType { - NONE = 0, +#if AP_AHRS_DCM_ENABLED + DCM = 0, +#endif #if HAL_NAVEKF3_AVAILABLE THREE = 3, #endif @@ -660,11 +696,7 @@ class AP_AHRS { EXTERNAL = 11, #endif }; - EKFType active_EKF_type(void) const; - - // if successful returns true and sets secondary_ekf_type to None (for DCM), EKF3 or EKF3 - // returns false if no secondary (i.e. only using DCM) - bool get_secondary_EKF_type(EKFType &secondary_ekf_type) const; + EKFType active_EKF_type(void) const { return state.active_EKF; } bool always_use_EKF() const { return _ekf_flags & FLAG_ALWAYS_USE_EKF; @@ -672,6 +704,8 @@ class AP_AHRS { // check all cores providing consistent attitudes for prearm checks bool attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const; + // convenience method for setting error string: + void set_failure_inconsistent_message(const char *estimator, const char *axis, float diff_rad, char *failure_msg, const uint8_t failure_msg_len) const; /* * Attitude-related private methods and attributes: @@ -688,9 +722,6 @@ class AP_AHRS { // update roll_sensor, pitch_sensor and yaw_sensor void update_cd_values(void); - // return origin for a specified EKF type - bool get_origin(EKFType type, Location &ret) const; - // helper trig variables float _cos_roll{1.0f}; float _cos_pitch{1.0f}; @@ -709,12 +740,7 @@ class AP_AHRS { #endif // rotation from vehicle body to NED frame - Matrix3f _dcm_matrix; - Vector3f _gyro_drift; - Vector3f _gyro_estimate; - Vector3f _accel_ef; - Vector3f _accel_bias; const uint16_t startup_delay_ms = 1000; uint32_t start_time_ms; @@ -723,9 +749,6 @@ class AP_AHRS { EKFType ekf_type(void) const; void update_DCM(); - // get the index of the current primary IMU - uint8_t get_primary_IMU_index(void) const; - /* * home-related state */ @@ -797,9 +820,6 @@ class AP_AHRS { */ bool wind_estimation_enabled; - // return a wind estimation vector, in m/s - bool wind_estimate(Vector3f &wind) const WARN_IF_UNUSED; - /* * fly_forward is set by the vehicles to indicate the vehicle * should generally be moving in the direction of its heading. @@ -811,11 +831,145 @@ class AP_AHRS { // poke AP_Notify based on values from status void update_notify_from_filter_status(const nav_filter_status &status); + /* + * copy results from a backend over AP_AHRS canonical results. + * This updates member variables like roll and pitch, as well as + * updating derived values like sin_roll and sin_pitch. + */ + void copy_estimates_from_backend_estimates(const AP_AHRS_Backend::Estimates &results); + + // write out secondary estimates: + void Write_AHRS2(void) const; + // write POS (canonical vehicle position) message out: + void Write_POS(void) const; + + // return an airspeed estimate if available. return true + // if we have an estimate + bool _airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &status) const; + + // return secondary attitude solution if available, as eulers in radians + bool _get_secondary_attitude(Vector3f &eulers) const; + + // return secondary attitude solution if available, as quaternion + bool _get_secondary_quaternion(Quaternion &quat) const; + + // get ground speed 2D + Vector2f _groundspeed_vector(void); + + // get active EKF type + EKFType _active_EKF_type(void) const; + + // return a wind estimation vector, in m/s + bool _wind_estimate(Vector3f &wind) const WARN_IF_UNUSED; + + // return a true airspeed estimate (navigation airspeed) if + // available. return true if we have an estimate + bool _airspeed_estimate_true(float &airspeed_ret) const; + + // return estimate of true airspeed vector in body frame in m/s + // returns false if estimate is unavailable + bool _airspeed_vector_true(Vector3f &vec) const; + + // return the quaternion defining the rotation from NED to XYZ (body) axes + bool _get_quaternion(Quaternion &quat) const WARN_IF_UNUSED; + + // return secondary position solution if available + bool _get_secondary_position(Location &loc) const; + + // return ground speed estimate in meters/second. Used by ground vehicles. + float _groundspeed(void); + + // Retrieves the corrected NED delta velocity in use by the inertial navigation + void _getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const; + + // returns the inertial navigation origin in lat/lon/alt + bool _get_origin(Location &ret) const WARN_IF_UNUSED; + + // return origin for a specified EKF type + bool _get_origin(EKFType type, Location &ret) const; + + // return a ground velocity in meters/second, North/East/Down + // order. Must only be called if have_inertial_nav() is true + bool _get_velocity_NED(Vector3f &vec) const WARN_IF_UNUSED; + + // get secondary EKF type. returns false if no secondary (i.e. only using DCM) + bool _get_secondary_EKF_type(EKFType &secondary_ekf_type) const; + + // return the index of the primary core or -1 if no primary core selected + int8_t _get_primary_core_index() const; + + // get the index of the current primary accelerometer sensor + uint8_t _get_primary_accel_index(void) const; + + // get the index of the current primary gyro sensor + uint8_t _get_primary_gyro_index(void) const; + + // get the index of the current primary IMU + uint8_t _get_primary_IMU_index(void) const; + + // get current location estimate + bool _get_location(Location &loc) const; + + /* + update state structure + */ + void update_state(void); + + // returns an EKF type to be used as active if we decide the + // primary is not good enough. + EKFType fallback_active_EKF_type(void) const; + + /* + state updated at the end of each update() call + */ + struct { + EKFType active_EKF; + uint8_t primary_IMU; + uint8_t primary_gyro; + uint8_t primary_accel; + uint8_t primary_core; + Vector3f gyro_estimate; + Matrix3f dcm_matrix; + Vector3f gyro_drift; + Vector3f accel_ef; + Vector3f accel_bias; + Vector3f wind_estimate; + bool wind_estimate_ok; + float EAS2TAS; + bool airspeed_ok; + float airspeed; + AirspeedEstimateType airspeed_estimate_type; + bool airspeed_true_ok; + float airspeed_true; + Vector3f airspeed_vec; + bool airspeed_vec_ok; + Quaternion quat; + bool quat_ok; + Vector3f secondary_attitude; + bool secondary_attitude_ok; + Quaternion secondary_quat; + bool secondary_quat_ok; + Location location; + bool location_ok; + Location secondary_pos; + bool secondary_pos_ok; + Vector2f ground_speed_vec; + float ground_speed; + Vector3f corrected_dv; + float corrected_dv_dt; + Location origin; + bool origin_ok; + Vector3f velocity_NED; + bool velocity_NED_ok; + } state; + /* * backends (and their results) */ +#if AP_AHRS_DCM_ENABLED AP_AHRS_DCM dcm{_kp_yaw, _kp, gps_gain, beta, _gps_use, _gps_minsats}; struct AP_AHRS_Backend::Estimates dcm_estimates; +#endif #if AP_AHRS_SIM_ENABLED #if HAL_NAVEKF3_AVAILABLE AP_AHRS_SIM sim{EKF3}; @@ -830,17 +984,6 @@ class AP_AHRS { struct AP_AHRS_Backend::Estimates external_estimates; #endif - /* - * copy results from a backend over AP_AHRS canonical results. - * This updates member variables like roll and pitch, as well as - * updating derived values like sin_roll and sin_pitch. - */ - void copy_estimates_from_backend_estimates(const AP_AHRS_Backend::Estimates &results); - - // write out secondary estimates: - void Write_AHRS2(void) const; - // write POS (canonical vehicle position) message out: - void Write_POS(void) const; }; namespace AP { diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.cpp b/libraries/AP_AHRS/AP_AHRS_Backend.cpp index fe74611a1ee57b..763716e148c694 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Backend.cpp @@ -90,74 +90,6 @@ void AP_AHRS::update_orientation() AP::compass().set_board_orientation(orientation); } -// return a ground speed estimate in m/s -Vector2f AP_AHRS_DCM::groundspeed_vector(void) -{ - // Generate estimate of ground speed vector using air data system - Vector2f gndVelADS; - Vector2f gndVelGPS; - float airspeed = 0; - const bool gotAirspeed = airspeed_estimate_true(airspeed); - const bool gotGPS = (AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D); - if (gotAirspeed) { - const Vector2f airspeed_vector{_cos_yaw * airspeed, _sin_yaw * airspeed}; - Vector3f wind; - UNUSED_RESULT(wind_estimate(wind)); - gndVelADS = airspeed_vector + wind.xy(); - } - - // Generate estimate of ground speed vector using GPS - if (gotGPS) { - const float cog = radians(AP::gps().ground_course()); - gndVelGPS = Vector2f(cosf(cog), sinf(cog)) * AP::gps().ground_speed(); - } - // If both ADS and GPS data is available, apply a complementary filter - if (gotAirspeed && gotGPS) { - // The LPF is applied to the GPS and the HPF is applied to the air data estimate - // before the two are summed - //Define filter coefficients - // alpha and beta must sum to one - // beta = dt/Tau, where - // dt = filter time step (0.1 sec if called by nav loop) - // Tau = cross-over time constant (nominal 2 seconds) - // More lag on GPS requires Tau to be bigger, less lag allows it to be smaller - // To-Do - set Tau as a function of GPS lag. - const float alpha = 1.0f - beta; - // Run LP filters - _lp = gndVelGPS * beta + _lp * alpha; - // Run HP filters - _hp = (gndVelADS - _lastGndVelADS) + _hp * alpha; - // Save the current ADS ground vector for the next time step - _lastGndVelADS = gndVelADS; - // Sum the HP and LP filter outputs - return _hp + _lp; - } - // Only ADS data is available return ADS estimate - if (gotAirspeed && !gotGPS) { - return gndVelADS; - } - // Only GPS data is available so return GPS estimate - if (!gotAirspeed && gotGPS) { - return gndVelGPS; - } - - if (airspeed > 0) { - // we have a rough airspeed, and we have a yaw. For - // dead-reckoning purposes we can create a estimated - // groundspeed vector - Vector2f ret{_cos_yaw, _sin_yaw}; - ret *= airspeed; - // adjust for estimated wind - Vector3f wind; - UNUSED_RESULT(wind_estimate(wind)); - ret.x += wind.x; - ret.y += wind.y; - return ret; - } - - return Vector2f(0.0f, 0.0f); -} - /* calculate sin and cos of roll/pitch/yaw from a body_to_ned rotation matrix */ @@ -330,7 +262,7 @@ void AP_AHRS::Log_Write_Home_And_Origin() } // get apparent to true airspeed ratio -float AP_AHRS_Backend::get_EAS2TAS(void) const { +float AP_AHRS_Backend::get_EAS2TAS(void) { return AP::baro().get_EAS2TAS(); } diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index 6675a9c288dd5e..0fb02eae9b2761 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -24,6 +24,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 @@ -57,6 +58,14 @@ class AP_AHRS_Backend Vector3f gyro_drift; Vector3f accel_ef; Vector3f accel_bias; + + Location location; + bool location_valid; + + bool get_location(Location &loc) const { + loc = location; + return location_valid; + }; }; // init sets up INS board orientation @@ -109,10 +118,6 @@ class AP_AHRS_Backend // reset the current attitude, used on new IMU calibration virtual void reset() = 0; - // get our current position estimate. Return true if a position is available, - // otherwise false. This call fills in lat, lng and alt - virtual bool get_location(class Location &loc) const WARN_IF_UNUSED = 0; - // get latest altitude estimate above ground level in meters and validity flag virtual bool get_hagl(float &height) const WARN_IF_UNUSED { return false; } @@ -141,11 +146,11 @@ class AP_AHRS_Backend } // get apparent to true airspeed ratio - float get_EAS2TAS(void) const; + static float get_EAS2TAS(void); // return true if airspeed comes from an airspeed sensor, as // opposed to an IMU estimate - bool airspeed_sensor_enabled(void) const { + static bool airspeed_sensor_enabled(void) { #if AP_AIRSPEED_ENABLED const AP_Airspeed *_airspeed = AP::airspeed(); return _airspeed != nullptr && _airspeed->use() && _airspeed->healthy(); @@ -156,7 +161,7 @@ class AP_AHRS_Backend // return true if airspeed comes from a specific airspeed sensor, as // opposed to an IMU estimate - bool airspeed_sensor_enabled(uint8_t airspeed_index) const { + static bool airspeed_sensor_enabled(uint8_t airspeed_index) { #if AP_AIRSPEED_ENABLED const AP_Airspeed *_airspeed = AP::airspeed(); return _airspeed != nullptr && _airspeed->use(airspeed_index) && _airspeed->healthy(airspeed_index); @@ -304,12 +309,6 @@ class AP_AHRS_Backend virtual void send_ekf_status_report(class GCS_MAVLINK &link) const = 0; - // Retrieves the corrected NED delta velocity in use by the inertial navigation - virtual void getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const { - ret.zero(); - AP::ins().get_delta_velocity(ret, dt); - } - // get_hgt_ctrl_limit - get maximum height to be observed by the // control loops in meters and a validity flag. It will return // false when no limiting is required diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index ce8b038334cfa3..df722c5cc52b07 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -20,6 +20,11 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ + +#include "AP_AHRS_config.h" + +#if AP_AHRS_DCM_ENABLED + #include "AP_AHRS.h" #include #include @@ -51,22 +56,6 @@ AP_AHRS_DCM::reset_gyro_drift(void) _omega_I_sum_time = 0; } - -/* if this was a watchdog reset then get home from backup registers */ -void AP_AHRS::load_watchdog_home() -{ - const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data; - if (hal.util->was_watchdog_reset() && (pd.home_lat != 0 || pd.home_lon != 0)) { - _home.lat = pd.home_lat; - _home.lng = pd.home_lon; - _home.set_alt_cm(pd.home_alt_cm, Location::AltFrame::ABSOLUTE); - _home_is_set = true; - _home_locked = true; - gcs().send_text(MAV_SEVERITY_INFO, "Restored watchdog home"); - } -} - - // run a full DCM update round void AP_AHRS_DCM::update() @@ -124,6 +113,8 @@ void AP_AHRS_DCM::get_results(AP_AHRS_Backend::Estimates &results) results.gyro_estimate = _omega; results.gyro_drift = _omega_I; results.accel_ef = _accel_ef; + + results.location_valid = get_location(results.location); } /* @@ -185,7 +176,7 @@ AP_AHRS_DCM::reset(bool recover_eulers) pitch = pd.pitch_rad; yaw = pd.yaw_rad; _dcm_matrix.from_euler(roll, pitch, yaw); - gcs().send_text(MAV_SEVERITY_INFO, "Restored watchdog attitude %.0f %.0f %.0f", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Restored watchdog attitude %.0f %.0f %.0f", degrees(roll), degrees(pitch), degrees(yaw)); } else if (recover_eulers && !isnan(roll) && !isnan(pitch) && !isnan(yaw)) { _dcm_matrix.from_euler(roll, pitch, yaw); @@ -280,7 +271,7 @@ AP_AHRS_DCM::renorm(Vector3f const &a, Vector3f &result) // additional error buildup. // Note that we can get significant renormalisation values - // when we have a larger delta_t due to a glitch eleswhere in + // when we have a larger delta_t due to a glitch elsewhere in // APM, such as a I2c timeout or a set of EEPROM writes. While // we would like to avoid these if possible, if it does happen // we don't want to compound the error by making DCM less @@ -437,7 +428,7 @@ bool AP_AHRS_DCM::use_compass(void) return false; } if (!AP::ahrs().get_fly_forward() || !have_gps()) { - // we don't have any alterative to the compass + // we don't have any alternative to the compass return true; } if (AP::gps().ground_speed() < GPS_SPEED_MIN) { @@ -472,7 +463,7 @@ bool AP_AHRS_DCM::get_quaternion(Quaternion &quat) const } // yaw drift correction using the compass or GPS -// this function prodoces the _omega_yaw_P vector, and also +// this function produces the _omega_yaw_P vector, and also // contributes to the _omega_I.z long term yaw drift estimate void AP_AHRS_DCM::drift_correction_yaw(void) @@ -485,10 +476,12 @@ AP_AHRS_DCM::drift_correction_yaw(void) Compass &compass = AP::compass(); +#if COMPASS_CAL_ENABLED if (compass.is_calibrating()) { // don't do any yaw correction while calibrating return; } +#endif if (AP_AHRS_DCM::use_compass()) { /* @@ -580,8 +573,8 @@ AP_AHRS_DCM::drift_correction_yaw(void) // that depends on the spin rate. See the fastRotations.pdf // paper from Bill Premerlani // We also adjust the gain depending on the rate of change of horizontal velocity which - // is proportional to how observable the heading is from the acceerations and GPS velocity - // The accelration derived heading will be more reliable in turns than compass or GPS + // is proportional to how observable the heading is from the accelerations and GPS velocity + // The acceleration derived heading will be more reliable in turns than compass or GPS _omega_yaw_P.z = error_z * _P_gain(spin_rate) * _kp_yaw * _yaw_gain(); if (use_fast_gains()) { @@ -1068,7 +1061,7 @@ bool AP_AHRS_DCM::airspeed_estimate(float &airspeed_ret) const bool AP_AHRS_DCM::airspeed_estimate(uint8_t airspeed_index, float &airspeed_ret) const { // airspeed_ret: will always be filled-in by get_unconstrained_airspeed_estimate which fills in airspeed_ret in this order: - // airspeed as filled-in by an enabled airsped sensor + // airspeed as filled-in by an enabled airspeed sensor // if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation // Or if none of the above, fills-in using the previous airspeed estimate // Return false: if we are using the previous airspeed estimate @@ -1092,7 +1085,7 @@ bool AP_AHRS_DCM::airspeed_estimate(uint8_t airspeed_index, float &airspeed_ret) } // airspeed_ret: will always be filled-in by get_unconstrained_airspeed_estimate which fills in airspeed_ret in this order: -// airspeed as filled-in by an enabled airsped sensor +// airspeed as filled-in by an enabled airspeed sensor // if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation // Or if none of the above, fills-in using the previous airspeed estimate // Return false: if we are using the previous airspeed estimate @@ -1117,48 +1110,6 @@ bool AP_AHRS_DCM::get_unconstrained_airspeed_estimate(uint8_t airspeed_index, fl return false; } -bool AP_AHRS::set_home(const Location &loc) -{ - WITH_SEMAPHORE(_rsem); - // check location is valid - if (loc.lat == 0 && loc.lng == 0 && loc.alt == 0) { - return false; - } - if (!loc.check_latlng()) { - return false; - } - // home must always be global frame at the moment as .alt is - // accessed directly by the vehicles and they may not be rigorous - // in checking the frame type. - Location tmp = loc; - if (!tmp.change_alt_frame(Location::AltFrame::ABSOLUTE)) { - return false; - } - -#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) - if (!_home_is_set) { - // record home is set - AP::logger().Write_Event(LogEvent::SET_HOME); - } -#endif - - _home = tmp; - _home_is_set = true; - - Log_Write_Home_And_Origin(); - - // send new home and ekf origin to GCS - gcs().send_message(MSG_HOME); - gcs().send_message(MSG_ORIGIN); - - AP_HAL::Util::PersistentData &pd = hal.util->persistent_data; - pd.home_lat = loc.lat; - pd.home_lon = loc.lng; - pd.home_alt_cm = loc.alt; - - return true; -} - /* check if the AHRS subsystem is healthy */ @@ -1181,6 +1132,74 @@ bool AP_AHRS_DCM::get_velocity_NED(Vector3f &vec) const return true; } +// return a ground speed estimate in m/s +Vector2f AP_AHRS_DCM::groundspeed_vector(void) +{ + // Generate estimate of ground speed vector using air data system + Vector2f gndVelADS; + Vector2f gndVelGPS; + float airspeed = 0; + const bool gotAirspeed = airspeed_estimate_true(airspeed); + const bool gotGPS = (AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D); + if (gotAirspeed) { + const Vector2f airspeed_vector{_cos_yaw * airspeed, _sin_yaw * airspeed}; + Vector3f wind; + UNUSED_RESULT(wind_estimate(wind)); + gndVelADS = airspeed_vector + wind.xy(); + } + + // Generate estimate of ground speed vector using GPS + if (gotGPS) { + const float cog = radians(AP::gps().ground_course()); + gndVelGPS = Vector2f(cosf(cog), sinf(cog)) * AP::gps().ground_speed(); + } + // If both ADS and GPS data is available, apply a complementary filter + if (gotAirspeed && gotGPS) { + // The LPF is applied to the GPS and the HPF is applied to the air data estimate + // before the two are summed + //Define filter coefficients + // alpha and beta must sum to one + // beta = dt/Tau, where + // dt = filter time step (0.1 sec if called by nav loop) + // Tau = cross-over time constant (nominal 2 seconds) + // More lag on GPS requires Tau to be bigger, less lag allows it to be smaller + // To-Do - set Tau as a function of GPS lag. + const float alpha = 1.0f - beta; + // Run LP filters + _lp = gndVelGPS * beta + _lp * alpha; + // Run HP filters + _hp = (gndVelADS - _lastGndVelADS) + _hp * alpha; + // Save the current ADS ground vector for the next time step + _lastGndVelADS = gndVelADS; + // Sum the HP and LP filter outputs + return _hp + _lp; + } + // Only ADS data is available return ADS estimate + if (gotAirspeed && !gotGPS) { + return gndVelADS; + } + // Only GPS data is available so return GPS estimate + if (!gotAirspeed && gotGPS) { + return gndVelGPS; + } + + if (airspeed > 0) { + // we have a rough airspeed, and we have a yaw. For + // dead-reckoning purposes we can create a estimated + // groundspeed vector + Vector2f ret{_cos_yaw, _sin_yaw}; + ret *= airspeed; + // adjust for estimated wind + Vector3f wind; + UNUSED_RESULT(wind_estimate(wind)); + ret.x += wind.x; + ret.y += wind.y; + return ret; + } + + return Vector2f(0.0f, 0.0f); +} + // 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. bool AP_AHRS_DCM::get_vert_pos_rate_D(float &velocity) const @@ -1267,3 +1286,5 @@ void AP_AHRS_DCM::get_control_limits(float &ekfGndSpdLimit, float &ekfNavVelGain ekfGndSpdLimit = 50.0; ekfNavVelGainScaler = 0.5; } + +#endif // AP_AHRS_DCM_ENABLED diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 168cbbaa3362fd..690ef22810bed0 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -21,6 +21,10 @@ * */ +#include "AP_AHRS_config.h" + +#if AP_AHRS_DCM_ENABLED + #include "AP_AHRS_Backend.h" class AP_AHRS_DCM : public AP_AHRS_Backend { @@ -60,9 +64,6 @@ class AP_AHRS_DCM : public AP_AHRS_Backend { return have_initial_yaw; } - // dead-reckoning support - virtual bool get_location(Location &loc) const override; - // status reporting float get_error_rp() const { return _error_rp; @@ -132,6 +133,9 @@ class AP_AHRS_DCM : public AP_AHRS_Backend { private: + // dead-reckoning support + bool get_location(Location &loc) const; + // settable parameters AP_Float &_kp_yaw; AP_Float &_kp; @@ -168,7 +172,7 @@ class AP_AHRS_DCM : public AP_AHRS_Backend { void reset(bool recover_eulers); // airspeed_ret: will always be filled-in by get_unconstrained_airspeed_estimate which fills in airspeed_ret in this order: - // airspeed as filled-in by an enabled airsped sensor + // airspeed as filled-in by an enabled airspeed sensor // if no airspeed sensor: airspeed estimated using the GPS speed & wind_speed_estimation // Or if none of the above, fills-in using the previous airspeed estimate // Return false: if we are using the previous airspeed estimate @@ -283,3 +287,5 @@ class AP_AHRS_DCM : public AP_AHRS_Backend { float _sin_yaw; float _cos_yaw; }; + +#endif // AP_AHRS_DCM_ENABLED diff --git a/libraries/AP_AHRS/AP_AHRS_External.cpp b/libraries/AP_AHRS/AP_AHRS_External.cpp index 0c1a01b2c7bbc9..0c4be3d5bd614e 100644 --- a/libraries/AP_AHRS/AP_AHRS_External.cpp +++ b/libraries/AP_AHRS/AP_AHRS_External.cpp @@ -36,12 +36,8 @@ void AP_AHRS_External::get_results(AP_AHRS_Backend::Estimates &results) const Vector3f accel = AP::externalAHRS().get_accel(); const Vector3f accel_ef = results.dcm_matrix * AP::ahrs().get_rotation_autopilot_body_to_vehicle_body() * accel; results.accel_ef = accel_ef; -} - -bool AP_AHRS_External::get_location(struct Location &loc) const -{ - return AP::externalAHRS().get_location(loc); + results.location_valid = AP::externalAHRS().get_location(results.location); } bool AP_AHRS_External::get_quaternion(Quaternion &quat) const diff --git a/libraries/AP_AHRS/AP_AHRS_External.h b/libraries/AP_AHRS/AP_AHRS_External.h index 999ed05fed08be..4d63a0702907de 100644 --- a/libraries/AP_AHRS/AP_AHRS_External.h +++ b/libraries/AP_AHRS/AP_AHRS_External.h @@ -43,9 +43,6 @@ class AP_AHRS_External : public AP_AHRS_Backend { void get_results(Estimates &results) override; void reset() override {} - // dead-reckoning support - virtual bool get_location(struct Location &loc) const override; - // return a wind estimation vector, in m/s bool wind_estimate(Vector3f &ret) const override { return false; diff --git a/libraries/AP_AHRS/AP_AHRS_Logging.cpp b/libraries/AP_AHRS/AP_AHRS_Logging.cpp index 62d7a3f451c1c5..8d602b81cedd10 100644 --- a/libraries/AP_AHRS/AP_AHRS_Logging.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Logging.cpp @@ -106,9 +106,9 @@ void AP_AHRS::write_video_stabilisation() const const struct log_Video_Stabilisation pkt { LOG_PACKET_HEADER_INIT(LOG_VIDEO_STABILISATION_MSG), time_us : AP_HAL::micros64(), - gyro_x : _gyro_estimate.x, - gyro_y : _gyro_estimate.y, - gyro_z : _gyro_estimate.z, + gyro_x : state.gyro_estimate.x, + gyro_y : state.gyro_estimate.y, + gyro_z : state.gyro_estimate.z, accel_x : accel.x, accel_y : accel.y, accel_z : accel.z, @@ -168,7 +168,7 @@ void AP_AHRS_View::Write_Rate(const AP_Motors &motors, const AC_AttitudeControl /* log P/PD gain scale if not == 1.0 */ - const Vector3f &scale = attitude_control.get_angle_P_scale_logging(); + 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 { diff --git a/libraries/AP_AHRS/AP_AHRS_SIM.cpp b/libraries/AP_AHRS/AP_AHRS_SIM.cpp index ed6cd01bb8099b..ff7e042d47109e 100644 --- a/libraries/AP_AHRS/AP_AHRS_SIM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_SIM.cpp @@ -181,6 +181,7 @@ bool AP_AHRS_SIM::get_mag_offsets(uint8_t mag_idx, Vector3f &magOffsets) const void AP_AHRS_SIM::send_ekf_status_report(GCS_MAVLINK &link) const { +#if HAL_GCS_ENABLED // send status report with everything looking good const uint16_t flags = EKF_ATTITUDE | /* Set if EKF's attitude estimate is good. | */ @@ -194,6 +195,7 @@ void AP_AHRS_SIM::send_ekf_status_report(GCS_MAVLINK &link) const EKF_PRED_POS_HORIZ_REL | /* Set if EKF's predicted horizontal position (relative) estimate is good. | */ EKF_PRED_POS_HORIZ_ABS; /* Set if EKF's predicted horizontal position (absolute) estimate is good. | */ mavlink_msg_ekf_status_report_send(link.get_chan(), flags, 0, 0, 0, 0, 0, 0); +#endif // HAL_GCS_ENABLED } bool AP_AHRS_SIM::get_origin(Location &ret) const @@ -253,6 +255,8 @@ void AP_AHRS_SIM::get_results(AP_AHRS_Backend::Estimates &results) const Vector3f &accel = _ins.get_accel(); results.accel_ef = results.dcm_matrix * AP::ahrs().get_rotation_autopilot_body_to_vehicle_body() * accel; + results.location_valid = get_location(results.location); + #if HAL_NAVEKF3_AVAILABLE if (_sitl->odom_enable) { // use SITL states to write body frame odometry data at 20Hz diff --git a/libraries/AP_AHRS/AP_AHRS_SIM.h b/libraries/AP_AHRS/AP_AHRS_SIM.h index 340a8877b6f336..037b64c388c805 100644 --- a/libraries/AP_AHRS/AP_AHRS_SIM.h +++ b/libraries/AP_AHRS/AP_AHRS_SIM.h @@ -60,9 +60,6 @@ class AP_AHRS_SIM : public AP_AHRS_Backend { void get_results(Estimates &results) override; void reset() override { return; } - // dead-reckoning support - virtual bool get_location(Location &loc) const override; - // get latest altitude estimate above ground level in meters and validity flag bool get_hagl(float &hagl) const override WARN_IF_UNUSED; @@ -119,6 +116,9 @@ class AP_AHRS_SIM : public AP_AHRS_Backend { private: + // dead-reckoning support + bool get_location(Location &loc) const; + #if HAL_NAVEKF3_AVAILABLE // a reference to the EKF3 backend that we can use to send in // body-frame-odometry data into the EKF. Rightfully there should diff --git a/libraries/AP_AHRS/AP_AHRS_config.h b/libraries/AP_AHRS/AP_AHRS_config.h index 9d35d8a9ef0f35..0be9f0cdd828bd 100644 --- a/libraries/AP_AHRS/AP_AHRS_config.h +++ b/libraries/AP_AHRS/AP_AHRS_config.h @@ -1,11 +1,20 @@ #pragma once #include +#include #ifndef AP_AHRS_ENABLED #define AP_AHRS_ENABLED 1 #endif +#ifndef AP_AHRS_BACKEND_DEFAULT_ENABLED +#define AP_AHRS_BACKEND_DEFAULT_ENABLED AP_AHRS_ENABLED +#endif + +#ifndef AP_AHRS_DCM_ENABLED +#define AP_AHRS_DCM_ENABLED AP_AHRS_BACKEND_DEFAULT_ENABLED && AP_INERTIALSENSOR_ENABLED +#endif + #ifndef HAL_NAVEKF2_AVAILABLE // only default to EK2 enabled on boards with over 1M flash #define HAL_NAVEKF2_AVAILABLE (BOARD_FLASH_SIZE>1024) diff --git a/libraries/AP_AIS/AP_AIS.cpp b/libraries/AP_AIS/AP_AIS.cpp index 897e3e6679e28c..c08a4dea0318f9 100644 --- a/libraries/AP_AIS/AP_AIS.cpp +++ b/libraries/AP_AIS/AP_AIS.cpp @@ -141,7 +141,7 @@ void AP_AIS::update() uint8_t msg_parts[_incoming.num - 1]; for (uint8_t i = 0; i < AIVDM_BUFFER_SIZE; i++) { // look for the rest of the message from the start of the buffer - // we assume the mesage has be received in the correct order + // we assume the message has be received in the correct order if (_AIVDM_buffer[i].num == (index + 1) && _AIVDM_buffer[i].total == _incoming.total && _AIVDM_buffer[i].ID == _incoming.ID) { msg_parts[index] = i; index++; @@ -349,11 +349,11 @@ void AP_AIS::clear_list_item(uint16_t index) } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -// Functions for decoding AIVDM payload mesages +// Functions for decoding AIVDM payload messages bool AP_AIS::payload_decode(const char *payload) { - // the mesage type is defined by the first character + // the message type is defined by the first character const uint8_t type = payload_char_decode(payload[0]); switch (type) { @@ -674,7 +674,7 @@ uint32_t AP_AIS::get_bits(const char *payload, uint16_t low, uint16_t high) } // read the specified bits from the char array each char giving 6 bits -// As the values are a arbitrary length the sign bit is in the wrong place for standard length varables +// As the values are a arbitrary length the sign bit is in the wrong place for standard length variables int32_t AP_AIS::get_bits_signed(const char *payload, uint16_t low, uint16_t high) { uint32_t value = get_bits(payload, low, high); @@ -829,7 +829,7 @@ AP_AIS *AP_AIS::get_singleton() { #else // Dummy methods are required to allow functionality to be enabled for Rover. -// It is not posible to compile in or out the full code based on vehicle type due to limitations +// It is not possible to compile in or out the full code based on vehicle type due to limitations // of the handling of `APM_BUILD_TYPE` define. // These dummy methods minimise flash cost in that case. diff --git a/libraries/AP_AIS/AP_AIS.h b/libraries/AP_AIS/AP_AIS.h index 2707de2bf11fc7..d55a08c82f8beb 100644 --- a/libraries/AP_AIS/AP_AIS.h +++ b/libraries/AP_AIS/AP_AIS.h @@ -125,7 +125,7 @@ class AP_AIS // decode each term bool decode_latest_term() WARN_IF_UNUSED; - // varables for decoding NMEA sentence + // variables for decoding NMEA sentence char _term[AIVDM_PAYLOAD_SIZE]; // 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 diff --git a/libraries/AP_AccelCal/AccelCalibrator.cpp b/libraries/AP_AccelCal/AccelCalibrator.cpp index 5e90912bda77e6..2cca0cb009f794 100644 --- a/libraries/AP_AccelCal/AccelCalibrator.cpp +++ b/libraries/AP_AccelCal/AccelCalibrator.cpp @@ -36,7 +36,7 @@ _sample_buffer(nullptr) /* Select options, initialise variables and initiate accel calibration Options: - Fit Type: Will assume that if accelerometer static samples around all possible orientatio + Fit Type: Will assume that if accelerometer static samples around all possible orientation are spread in space will cover a surface of AXIS_ALIGNED_ELLIPSOID or any general ELLIPSOID as chosen @@ -173,7 +173,7 @@ bool AccelCalibrator::get_sample(uint8_t i, Vector3f& s) const { return true; } -// returns truen and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure +// returns true and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure // returns false if no correct parameter exists to be applied along with existing sample without corrections bool AccelCalibrator::get_sample_corrected(uint8_t i, Vector3f& s) const { if (_status != ACCEL_CAL_SUCCESS || !get_sample(i,s)) { @@ -199,7 +199,7 @@ void AccelCalibrator::check_for_timeout() { } } -// returns spherical fit paramteters +// returns spherical fit parameters void AccelCalibrator::get_calibration(Vector3f& offset) const { offset = -_param.s.offset; } @@ -288,7 +288,7 @@ void AccelCalibrator::set_status(enum accel_cal_status_t status) { break; case ACCEL_CAL_COLLECTING_SAMPLE: - // Calibrator is waiting on collecting samples from acceleromter for amount of + // Calibrator is waiting on collecting samples from accelerometer for amount of // time as requested by user/GCS if (_status != ACCEL_CAL_WAITING_FOR_ORIENTATION) { break; @@ -309,7 +309,7 @@ void AccelCalibrator::set_status(enum accel_cal_status_t status) { case ACCEL_CAL_FAILED: // Calibration has failed with reasons that can range from - // bad sample data leading to faillure in tolerance test to lack of distinct samples + // bad sample data leading to failure in tolerance test to lack of distinct samples if (_status == ACCEL_CAL_NOT_STARTED) { break; } diff --git a/libraries/AP_AccelCal/AccelCalibrator.h b/libraries/AP_AccelCal/AccelCalibrator.h index df06da578dbfea..3e3a04ffb52bd0 100644 --- a/libraries/AP_AccelCal/AccelCalibrator.h +++ b/libraries/AP_AccelCal/AccelCalibrator.h @@ -64,7 +64,7 @@ class AccelCalibrator { // to averaged acc over time bool get_sample(uint8_t i, Vector3f& s) const; - // returns truen and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure + // returns true and sample corrected with diag offdiag parameters as calculated by LSq estimation procedure // returns false if no correct parameter exists to be applied along with existing sample without corrections bool get_sample_corrected(uint8_t i, Vector3f& s) const; diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp index dce629b7a9755e..2c71ba01589a7a 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp @@ -162,6 +162,20 @@ const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = { // @User: Advanced // @Units: km AP_GROUPINFO("MAX_RANGE", 20, AP_AdvancedFailsafe, _max_range_km, 0), + + // @Param: OPTIONS + // @DisplayName: AFS options + // @Description: See description for each bitmask bit description + // @Bitmask: 0: Continue the mission even after comms are recovered (does not go to the mission item at the time comms were lost) + // @Bitmask: 1: Enable AFS for all autonomous modes (not just AUTO) + AP_GROUPINFO("OPTIONS", 21, AP_AdvancedFailsafe, options, 0), + + // @Param: GCS_TIMEOUT + // @DisplayName: GCS timeout + // @Description: The time (in seconds) of persistent data link loss before GCS failsafe occurs. + // @User: Advanced + // @Units: s + AP_GROUPINFO("GCS_TIMEOUT", 22, AP_AdvancedFailsafe, _gcs_fail_time_seconds, 10), AP_GROUPEND }; @@ -213,7 +227,7 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms) const uint32_t last_heartbeat_ms = gcs().sysid_myggcs_last_seen_time_ms(); uint32_t now = AP_HAL::millis(); - bool gcs_link_ok = ((now - last_heartbeat_ms) < 10000); + bool gcs_link_ok = ((now - last_heartbeat_ms) < (_gcs_fail_time_seconds*1000.0f)); bool gps_lock_ok = ((now - AP::gps().last_fix_time_ms()) < 3000); AP_Mission *_mission = AP::mission(); @@ -240,6 +254,9 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms) if (_wp_comms_hold) { _saved_wp = mission.get_current_nav_cmd().index; mission.set_current_cmd(_wp_comms_hold); + if (mode == AFS_AUTO && option_is_set(Option::GCS_FS_ALL_AUTONOMOUS_MODES)) { + set_mode_auto(); + } } // if two events happen within 30s we consider it to be part of the same event if (now - _last_comms_loss_ms > 30*1000UL) { @@ -277,6 +294,11 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms) } else if (gcs_link_ok) { _state = STATE_AUTO; gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GCS now OK"); + + if (option_is_set(Option::CONTINUE_AFTER_RECOVERED)) { + break; + } + // we only return to the mission if we have not exceeded AFS_MAX_COM_LOSS if (_saved_wp != 0 && (_max_comms_loss <= 0 || diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h index ecf50386c6ccd0..a16375362bed72 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h @@ -105,6 +105,9 @@ class AP_AdvancedFailsafe // return the AFS mapped control mode virtual enum control_mode afs_mode(void) = 0; + //to force entering auto mode when datalink loss + virtual void set_mode_auto(void) = 0; + enum state _state; AP_Int8 _enable; @@ -123,6 +126,7 @@ class AP_AdvancedFailsafe AP_Int32 _amsl_limit; AP_Int32 _amsl_margin_gps; AP_Float _rc_fail_time_seconds; + AP_Float _gcs_fail_time_seconds; AP_Int8 _max_gps_loss; AP_Int8 _max_comms_loss; AP_Int8 _enable_geofence_fs; @@ -162,6 +166,15 @@ class AP_AdvancedFailsafe // update maximum range check void max_range_update(); + + AP_Int16 options; + enum class Option { + CONTINUE_AFTER_RECOVERED = (1U<<0), + GCS_FS_ALL_AUTONOMOUS_MODES = (1U<<1), + }; + bool option_is_set(Option option) const { + return (options.get() & int16_t(option)) != 0; + } }; namespace AP { diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 2f8e201e54dfde..a13480b531c7e9 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -156,7 +156,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 calibraions 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 ASPD_FBW_MIN. 0 disables. Helps warn of calibrations without pitot being covered. // @Range: 0.0 10.0 // @Units: % // @User: Advanced @@ -609,6 +609,14 @@ void AP_Airspeed::read(uint8_t i) return; } +#ifndef HAL_BUILD_AP_PERIPH + /* + get the healthy state before we call get_pressure() as + get_pressure() overwrites the healthy state + */ + bool prev_healthy = state[i].healthy; +#endif + float raw_pressure = get_pressure(i); float airspeed_pressure = raw_pressure - get_offset(i); @@ -616,7 +624,6 @@ void AP_Airspeed::read(uint8_t i) state[i].corrected_pressure = airspeed_pressure; #ifndef HAL_BUILD_AP_PERIPH - bool prev_healthy = state[i].healthy; if (state[i].cal.start_ms != 0) { update_calibration(i, raw_pressure); } @@ -625,7 +632,7 @@ void AP_Airspeed::read(uint8_t i) if (!prev_healthy) { // if the previous state was not healthy then we should not // use an IIR filter, otherwise a bad reading will last for - // some time after the sensor becomees healthy again + // some time after the sensor becomes healthy again state[i].filtered_pressure = airspeed_pressure; } else { state[i].filtered_pressure = 0.7f * state[i].filtered_pressure + 0.3f * airspeed_pressure; diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index 564d59981465e0..5574f807557a67 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -56,7 +56,7 @@ class Airspeed_Calibration { private: // state of kalman filter for airspeed ratio estimation - Matrix3f P; // covarience matrix + Matrix3f P; // covariance matrix const float Q0; // process noise matrix top left and middle element const float Q1; // process noise matrix bottom right element Vector3f state; // state vector diff --git a/libraries/AP_Airspeed/AP_Airspeed_Backend.h b/libraries/AP_Airspeed/AP_Airspeed_Backend.h index 5836270bf49567..2deeb427c09c34 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Backend.h +++ b/libraries/AP_Airspeed/AP_Airspeed_Backend.h @@ -42,7 +42,7 @@ class AP_Airspeed_Backend { // return the current temperature in degrees C, if available virtual bool get_temperature(float &temperature) = 0; - // true if sensor reads airspeed directly, not via pressue + // true if sensor reads airspeed directly, not via pressure virtual bool has_airspeed() {return false;} // return airspeed in m/s if available diff --git a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp index 4b5db8bd0e1f42..fc143b11c00d70 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_DroneCAN.cpp @@ -148,7 +148,7 @@ bool AP_Airspeed_DroneCAN::get_differential_pressure(float &pressure) { WITH_SEMAPHORE(_sem_airspeed); - if ((AP_HAL::millis() - _last_sample_time_ms) > 100) { + if ((AP_HAL::millis() - _last_sample_time_ms) > 250) { return false; } diff --git a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp index 3da9c968e2f829..c0a8e6aedce1c3 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp @@ -96,7 +96,7 @@ bool AP_Airspeed_NMEA::get_airspeed(float &airspeed) } // return the current temperature in degrees C -// the main update is done in the get_pressue function +// the main update is done in the get_pressure function // this just reports the value bool AP_Airspeed_NMEA::get_temperature(float &temperature) { diff --git a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp index e68fc3cd210f06..bf17969f37fea5 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp @@ -261,7 +261,7 @@ float AP_Airspeed_SDP3X::_correct_pressure(float press) flow_SDP3X = 0.0f; } - // diffential pressure through pitot tube + // differential pressure through pitot tube float dp_pitot = 28557670.0f * (1.0f - 1.0f / (1.0f + (float)powf((flow_SDP3X / 5027611.0f), 1.227924f))); // uncorrected pressure diff --git a/libraries/AP_Airspeed/Airspeed_Calibration.cpp b/libraries/AP_Airspeed/Airspeed_Calibration.cpp index 3c5e1dc5b7a6aa..1cafcfc6e45f96 100644 --- a/libraries/AP_Airspeed/Airspeed_Calibration.cpp +++ b/libraries/AP_Airspeed/Airspeed_Calibration.cpp @@ -168,6 +168,7 @@ void AP_Airspeed::update_calibration(const Vector3f &vground, int16_t max_airspe } +#if HAL_GCS_ENABLED void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground) { #if AP_AIRSPEED_AUTOCAL_ENABLE @@ -189,5 +190,6 @@ void AP_Airspeed::send_airspeed_calibration(const Vector3f &vground) (const char *)&packet); #endif // AP_AIRSPEED_AUTOCAL_ENABLE } +#endif // HAL_GCS_ENABLED #endif // AP_AIRSPEED_ENABLED diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index c735236b6adce0..898f566d0f2723 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include #include @@ -72,6 +73,7 @@ #define AP_ARMING_COMPASS_MAGFIELD_MAX 875 // 1.65 * 530 milligauss #define AP_ARMING_BOARD_VOLTAGE_MAX 5.8f #define AP_ARMING_ACCEL_ERROR_THRESHOLD 0.75f +#define AP_ARMING_MAGFIELD_ERROR_THRESHOLD 100 #define AP_ARMING_AHRS_GPS_ERROR_MAX 10 // accept up to 10m difference between AHRS and GPS #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) @@ -144,6 +146,14 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = { // @User: Advanced AP_GROUPINFO("OPTIONS", 9, AP_Arming, _arming_options, 0), + // @Param: MAGTHRESH + // @DisplayName: Compass magnetic field strength error threshold vs earth magnetic model + // @Description: Compass magnetic field strength error threshold vs earth magnetic model. X and y axis are compared using this threhold, Z axis uses 2x this threshold. 0 to disable check + // @Units: mGauss + // @Range: 0 500 + // @User: Advanced + AP_GROUPINFO("MAGTHRESH", 10, AP_Arming, magfield_error_threshold, AP_ARMING_MAGFIELD_ERROR_THRESHOLD), + AP_GROUPEND }; @@ -560,6 +570,25 @@ bool AP_Arming::compass_checks(bool report) check_failed(ARMING_CHECK_COMPASS, report, "Compasses inconsistent"); return false; } + + // if ahrs is using compass and we have location, check mag field versus expected earth magnetic model + Location ahrs_loc; + AP_AHRS &ahrs = AP::ahrs(); + if ((magfield_error_threshold > 0) && ahrs.use_compass() && ahrs.get_location(ahrs_loc)) { + const Vector3f veh_mag_field_ef = ahrs.get_rotation_body_to_ned() * _compass.get_field(); + const Vector3f earth_field_mgauss = AP_Declination::get_earth_field_ga(ahrs_loc) * 1000.0; + const Vector3f diff_mgauss = veh_mag_field_ef - earth_field_mgauss; + if (MAX(fabsf(diff_mgauss.x), fabsf(diff_mgauss.y)) > magfield_error_threshold) { + check_failed(ARMING_CHECK_COMPASS, report, "Check mag field (xy diff:%.0f>%d)", + (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) { + 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; + } + } } return true; @@ -618,10 +647,12 @@ bool AP_Arming::gps_checks(bool report) (double)distance_m); return false; } +#if defined(GPS_BLENDED_INSTANCE) 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) { @@ -842,7 +873,7 @@ bool AP_Arming::mission_checks(bool report) } RallyLocation rally_loc = {}; if (!rally->find_nearest_rally_point(ahrs_loc, rally_loc)) { - check_failed(ARMING_CHECK_MISSION, report, "No sufficently close rally point located"); + check_failed(ARMING_CHECK_MISSION, report, "No sufficiently close rally point located"); return false; } #else @@ -1189,13 +1220,25 @@ bool AP_Arming::can_checks(bool report) #endif break; } - case AP_CAN::Protocol::EFI_NWPMU: case AP_CAN::Protocol::USD1: + case AP_CAN::Protocol::TOFSenseP: + case AP_CAN::Protocol::NanoRadar_NRA24: + case AP_CAN::Protocol::Benewake: + { + for (uint8_t j = i; j; j--) { + if (AP::can().get_driver_type(i) == AP::can().get_driver_type(j-1)) { + check_failed(ARMING_CHECK_SYSTEM, report, "Same rfnd on different CAN ports"); + return false; + } + } + break; + } + case AP_CAN::Protocol::EFI_NWPMU: case AP_CAN::Protocol::None: case AP_CAN::Protocol::Scripting: case AP_CAN::Protocol::Scripting2: - case AP_CAN::Protocol::Benewake: case AP_CAN::Protocol::KDECAN: + break; } } @@ -1549,16 +1592,6 @@ bool AP_Arming::arm_checks(AP_Arming::Method method) } } -#if AP_FENCE_ENABLED - AC_Fence *fence = AP::fence(); - if (fence != nullptr) { - // If a fence is set to auto-enable, turn on the fence - if(fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) { - fence->enable(true); - } - } -#endif - // note that this will prepare AP_Logger to start logging // so should be the last check to be done before arming @@ -1636,6 +1669,19 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks) } #endif +#if AP_FENCE_ENABLED + if (armed) { + auto *fence = AP::fence(); + if (fence != nullptr) { + // If a fence is set to auto-enable, turn on the fence + if (fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) { + fence->enable(true); + gcs().send_text(MAV_SEVERITY_INFO, "Fence: auto-enabled"); + } + } + } +#endif + return armed; } @@ -1827,6 +1873,7 @@ void AP_Arming::check_forced_logging(const AP_Arming::Method method) case Method::TOYMODELANDTHROTTLE: case Method::TOYMODELANDFORCE: case Method::LANDING: + case Method::DDS: case Method::UNKNOWN: AP::logger().set_long_log_persist(false); return; diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 0423f943837fa1..0a94fc8be668ad 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -78,6 +78,7 @@ class AP_Arming { LANDING = 32, // only disarm uses this... DEADRECKON_FAILSAFE = 33, // only disarm uses this... BLACKBOX = 34, + DDS = 35, UNKNOWN = 100, }; @@ -144,6 +145,9 @@ class AP_Arming { return (_arming_options & uint32_t(option)) != 0; } + static bool method_is_GCS(Method method) { + return (method == Method::MAVLINK || method == Method::DDS); + } protected: // Parameters @@ -153,6 +157,7 @@ class AP_Arming { AP_Int8 _rudder_arming; AP_Int32 _required_mission_items; AP_Int32 _arming_options; + AP_Int16 magfield_error_threshold; // internal members bool armed; diff --git a/libraries/AP_Avoidance/AP_Avoidance.cpp b/libraries/AP_Avoidance/AP_Avoidance.cpp index dfa1c6bf4f1ff3..45f28874fc10c5 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.cpp +++ b/libraries/AP_Avoidance/AP_Avoidance.cpp @@ -325,11 +325,11 @@ float closest_approach_z(const Location &my_loc, } debug(" time_horizon: (%d)", time_horizon); - debug(" delta pos: (%f) metres", delta_pos_d/100.0f); + debug(" delta pos: (%f) metres", delta_pos_d*0.01f); debug(" delta vel: (%f) m/s", delta_vel_d); - debug(" closest: (%f) metres", ret/100.0f); + debug(" closest: (%f) metres", ret*0.01f); - return ret/100.0f; + return ret*0.01f; } void AP_Avoidance::update_threat_level(const Location &my_loc, @@ -657,7 +657,7 @@ bool AP_Avoidance::get_vector_perpendicular(const AP_Avoidance::Obstacle *obstac Vector3f AP_Avoidance::perpendicular_xyz(const Location &p1, const Vector3f &v1, const Location &p2) { const Vector2f delta_p_2d = p1.get_distance_NE(p2); - Vector3f delta_p_xyz = Vector3f(delta_p_2d[0],delta_p_2d[1],(p2.alt-p1.alt)/100.0f); //check this line + Vector3f delta_p_xyz = Vector3f(delta_p_2d[0],delta_p_2d[1],(p2.alt-p1.alt)*0.01f); //check this line Vector3f v1_xyz = Vector3f(v1[0], v1[1], -v1[2]); Vector3f ret = Vector3f::perpendicular(delta_p_xyz, v1_xyz); return ret; diff --git a/libraries/AP_BLHeli/AP_BLHeli.cpp b/libraries/AP_BLHeli/AP_BLHeli.cpp index 1563a2fd95a3f0..66577622a7cd40 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.cpp +++ b/libraries/AP_BLHeli/AP_BLHeli.cpp @@ -51,7 +51,7 @@ extern const AP_HAL::HAL& hal; // the MSP protocol on hal.console #define BLHELI_UART_LOCK_KEY 0x20180402 -// if no packets are received for this time and motor control is active BLH will disconect (stoping motors) +// if no packets are received for this time and motor control is active BLH will disconnect (stoping motors) #define MOTOR_ACTIVE_TIMEOUT 1000 const AP_Param::GroupInfo AP_BLHeli::var_info[] = { @@ -395,7 +395,7 @@ void AP_BLHeli::msp_process_command(void) break; case MSP_UID: - // MCU identifer + // MCU identifier debug("MSP_UID"); msp_send_reply(msp.cmdMSP, (const uint8_t *)UDID_START, 12); break; @@ -1421,7 +1421,7 @@ void AP_BLHeli::init(uint32_t mask, AP_HAL::RCOutput::output_mode otype) motor_mask = mask; debug("ESC: %u motors mask=0x%08lx", num_motors, mask); - // check if we have a combination of reversable and normal + // check if we have a combination of reversible and normal mixed_type = (mask != (mask & channel_reversible_mask.get())) && (channel_reversible_mask.get() != 0); if (num_motors != 0 && telem_rate > 0) { @@ -1460,7 +1460,14 @@ void AP_BLHeli::read_telemetry_packet(void) const uint8_t motor_idx = motor_map[last_telem_esc]; // we have received valid data, mark the ESC as now active hal.rcout->set_active_escs_mask(1<get_semaphore(); - // take i2c bus sempahore + // take i2c bus semaphore WITH_SEMAPHORE(sem); if (BMP085_EOC >= 0) { @@ -177,7 +177,7 @@ bool AP_Baro_BMP085::_read_prom(uint16_t *prom) } /* - This is a state machine. Acumulate a new sensor reading. + This is a state machine. Accumulate a new sensor reading. */ void AP_Baro_BMP085::_timer(void) { diff --git a/libraries/AP_Baro/AP_Baro_BMP280.cpp b/libraries/AP_Baro/AP_Baro_BMP280.cpp index 005000b169260f..1c89ac0a4b9557 100644 --- a/libraries/AP_Baro/AP_Baro_BMP280.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP280.cpp @@ -127,7 +127,7 @@ bool AP_Baro_BMP280::_init() -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_BMP280::_timer(void) { uint8_t buf[6]; diff --git a/libraries/AP_Baro/AP_Baro_BMP388.cpp b/libraries/AP_Baro/AP_Baro_BMP388.cpp index 25ea7ab41e97bd..6b48d9e7831676 100644 --- a/libraries/AP_Baro/AP_Baro_BMP388.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP388.cpp @@ -130,7 +130,7 @@ bool AP_Baro_BMP388::init() -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_BMP388::timer(void) { uint8_t buf[7]; diff --git a/libraries/AP_Baro/AP_Baro_Backend.cpp b/libraries/AP_Baro/AP_Baro_Backend.cpp index 15c75b65a9228f..f315bcd2b97266 100644 --- a/libraries/AP_Baro/AP_Baro_Backend.cpp +++ b/libraries/AP_Baro/AP_Baro_Backend.cpp @@ -67,7 +67,7 @@ void AP_Baro_Backend::_copy_to_frontend(uint8_t instance, float pressure, float static constexpr float FILTER_KOEF = 0.1f; /* Check that the baro value is valid by using a mean filter. If the - * value is further than filtrer_range from mean value, it is + * value is further than filter_range from mean value, it is * rejected. */ bool AP_Baro_Backend::pressure_ok(float press) diff --git a/libraries/AP_Baro/AP_Baro_Backend.h b/libraries/AP_Baro/AP_Baro_Backend.h index 476473bf5ddef4..94b155e4836bd7 100644 --- a/libraries/AP_Baro/AP_Baro_Backend.h +++ b/libraries/AP_Baro/AP_Baro_Backend.h @@ -20,7 +20,7 @@ class AP_Baro_Backend void backend_update(uint8_t instance); // Check that the baro valid by using a mean filter. - // If the value further that filtrer_range from mean value, it is rejected. + // If the value further that filter_range from mean value, it is rejected. bool pressure_ok(float press); uint32_t get_error_count() const { return _error_count; } diff --git a/libraries/AP_Baro/AP_Baro_DPS280.cpp b/libraries/AP_Baro/AP_Baro_DPS280.cpp index 5103fb20bc3b39..fe34ca0bd048f0 100644 --- a/libraries/AP_Baro/AP_Baro_DPS280.cpp +++ b/libraries/AP_Baro/AP_Baro_DPS280.cpp @@ -60,7 +60,7 @@ AP_Baro_Backend *AP_Baro_DPS280::probe(AP_Baro &baro, if (sensor) { sensor->is_dps310 = _is_dps310; } - if (!sensor || !sensor->init()) { + if (!sensor || !sensor->init(_is_dps310)) { delete sensor; return nullptr; } @@ -153,7 +153,7 @@ void AP_Baro_DPS280::set_config_registers(void) } } -bool AP_Baro_DPS280::init() +bool AP_Baro_DPS280::init(bool _is_dps310) { if (!dev) { return false; @@ -190,8 +190,11 @@ bool AP_Baro_DPS280::init() set_config_registers(); instance = _frontend.register_sensor(); - - dev->set_device_type(DEVTYPE_BARO_DPS280); + if(_is_dps310) { + dev->set_device_type(DEVTYPE_BARO_DPS310); + } else { + dev->set_device_type(DEVTYPE_BARO_DPS280); + } set_bus_id(instance, dev->get_bus_id()); dev->get_semaphore()->give(); @@ -243,7 +246,7 @@ void AP_Baro_DPS280::check_health(void) } } -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_DPS280::timer(void) { uint8_t buf[6]; diff --git a/libraries/AP_Baro/AP_Baro_DPS280.h b/libraries/AP_Baro/AP_Baro_DPS280.h index 799d71a600b61b..79769261a498c3 100644 --- a/libraries/AP_Baro/AP_Baro_DPS280.h +++ b/libraries/AP_Baro/AP_Baro_DPS280.h @@ -29,7 +29,7 @@ class AP_Baro_DPS280 : public AP_Baro_Backend { static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr dev, bool _is_dps310=false); protected: - bool init(void); + bool init(bool _is_dps310); bool read_calibration(void); void timer(void); void calculate_PT(int32_t UT, int32_t UP, float &pressure, float &temperature); diff --git a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp index ee1ee9e427ba91..6812480d7a0ef0 100644 --- a/libraries/AP_Baro/AP_Baro_DroneCAN.cpp +++ b/libraries/AP_Baro/AP_Baro_DroneCAN.cpp @@ -88,7 +88,7 @@ AP_Baro_DroneCAN* AP_Baro_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_droneca if (create_new) { bool already_detected = false; - //Check if there's an empty spot for possible registeration + //Check if there's an empty spot for possible registration for (uint8_t i = 0; i < BARO_MAX_DRIVERS; i++) { if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id) { //Already Detected diff --git a/libraries/AP_Baro/AP_Baro_FBM320.cpp b/libraries/AP_Baro/AP_Baro_FBM320.cpp index 20b8edcd710764..7ad9a7b0c89ae6 100644 --- a/libraries/AP_Baro/AP_Baro_FBM320.cpp +++ b/libraries/AP_Baro/AP_Baro_FBM320.cpp @@ -179,7 +179,7 @@ void AP_Baro_FBM320::calculate_PT(int32_t UT, int32_t UP, int32_t &pressure, int pressure = ((X31 + X32) >> 15) + PP4 + 99880; } -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_FBM320::timer(void) { uint8_t buf[3]; diff --git a/libraries/AP_Baro/AP_Baro_ICP101XX.cpp b/libraries/AP_Baro/AP_Baro_ICP101XX.cpp old mode 100755 new mode 100644 diff --git a/libraries/AP_Baro/AP_Baro_ICP101XX.h b/libraries/AP_Baro/AP_Baro_ICP101XX.h old mode 100755 new mode 100644 diff --git a/libraries/AP_Baro/AP_Baro_ICP201XX.cpp b/libraries/AP_Baro/AP_Baro_ICP201XX.cpp old mode 100755 new mode 100644 diff --git a/libraries/AP_Baro/AP_Baro_ICP201XX.h b/libraries/AP_Baro/AP_Baro_ICP201XX.h old mode 100755 new mode 100644 diff --git a/libraries/AP_Baro/AP_Baro_LPS2XH.cpp b/libraries/AP_Baro/AP_Baro_LPS2XH.cpp index 11016e585ab642..6db9acdc3d5447 100644 --- a/libraries/AP_Baro/AP_Baro_LPS2XH.cpp +++ b/libraries/AP_Baro/AP_Baro_LPS2XH.cpp @@ -212,7 +212,7 @@ bool AP_Baro_LPS2XH::_check_whoami(void) return false; } -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_LPS2XH::_timer(void) { uint8_t status; diff --git a/libraries/AP_Baro/AP_Baro_SPL06.cpp b/libraries/AP_Baro/AP_Baro_SPL06.cpp index 0ceb27dd955344..baca15dee2d20f 100644 --- a/libraries/AP_Baro/AP_Baro_SPL06.cpp +++ b/libraries/AP_Baro/AP_Baro_SPL06.cpp @@ -179,7 +179,7 @@ int32_t AP_Baro_SPL06::raw_value_scale_factor(uint8_t oversampling) } } -// acumulate a new sensor reading +// accumulate a new sensor reading void AP_Baro_SPL06::_timer(void) { uint8_t buf[3]; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index f6044e8ea356e4..ca73aab478e86e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -237,6 +237,164 @@ const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { AP_SUBGROUPVARPTR(drivers[8], "9_", 49, AP_BattMonitor, backend_var_info[8]), #endif +#if AP_BATT_MONITOR_MAX_INSTANCES > 9 + // @Group: A_ + // @Path: AP_BattMonitor_Params.cpp + AP_SUBGROUPINFO(_params[9], "A_", 32, AP_BattMonitor, AP_BattMonitor_Params), + + // @Group: A_ + // @Path: AP_BattMonitor_Analog.cpp + // @Group: A_ + // @Path: AP_BattMonitor_SMBus.cpp + // @Group: A_ + // @Path: AP_BattMonitor_Sum.cpp + // @Group: A_ + // @Path: AP_BattMonitor_DroneCAN.cpp + // @Group: A_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp + // @Group: A_ + // @Path: AP_BattMonitor_Synthetic_Current.cpp + // @Group: A_ + // @Path: AP_BattMonitor_INA2xx.cpp + AP_SUBGROUPVARPTR(drivers[9], "A_", 50, AP_BattMonitor, backend_var_info[9]), +#endif + +#if AP_BATT_MONITOR_MAX_INSTANCES > 10 + // @Group: B_ + // @Path: AP_BattMonitor_Params.cpp + AP_SUBGROUPINFO(_params[10], "B_", 33, AP_BattMonitor, AP_BattMonitor_Params), + + // @Group: B_ + // @Path: AP_BattMonitor_Analog.cpp + // @Group: B_ + // @Path: AP_BattMonitor_SMBus.cpp + // @Group: B_ + // @Path: AP_BattMonitor_Sum.cpp + // @Group: B_ + // @Path: AP_BattMonitor_DroneCAN.cpp + // @Group: B_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp + // @Group: B_ + // @Path: AP_BattMonitor_Synthetic_Current.cpp + // @Group: B_ + // @Path: AP_BattMonitor_INA2xx.cpp + AP_SUBGROUPVARPTR(drivers[10], "B_", 51, AP_BattMonitor, backend_var_info[10]), +#endif + +#if AP_BATT_MONITOR_MAX_INSTANCES > 11 + // @Group: C_ + // @Path: AP_BattMonitor_Params.cpp + AP_SUBGROUPINFO(_params[11], "C_", 34, AP_BattMonitor, AP_BattMonitor_Params), + + // @Group: C_ + // @Path: AP_BattMonitor_Analog.cpp + // @Group: C_ + // @Path: AP_BattMonitor_SMBus.cpp + // @Group: C_ + // @Path: AP_BattMonitor_Sum.cpp + // @Group: C_ + // @Path: AP_BattMonitor_DroneCAN.cpp + // @Group: C_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp + // @Group: C_ + // @Path: AP_BattMonitor_Synthetic_Current.cpp + // @Group: C_ + // @Path: AP_BattMonitor_INA2xx.cpp + AP_SUBGROUPVARPTR(drivers[11], "C_", 52, AP_BattMonitor, backend_var_info[11]), +#endif + +#if AP_BATT_MONITOR_MAX_INSTANCES > 12 + // @Group: D_ + // @Path: AP_BattMonitor_Params.cpp + AP_SUBGROUPINFO(_params[12], "D_", 35, AP_BattMonitor, AP_BattMonitor_Params), + + // @Group: D_ + // @Path: AP_BattMonitor_Analog.cpp + // @Group: D_ + // @Path: AP_BattMonitor_SMBus.cpp + // @Group: D_ + // @Path: AP_BattMonitor_Sum.cpp + // @Group: D_ + // @Path: AP_BattMonitor_DroneCAN.cpp + // @Group: D_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp + // @Group: D_ + // @Path: AP_BattMonitor_Synthetic_Current.cpp + // @Group: D_ + // @Path: AP_BattMonitor_INA2xx.cpp + AP_SUBGROUPVARPTR(drivers[12], "D_", 53, AP_BattMonitor, backend_var_info[12]), +#endif + +#if AP_BATT_MONITOR_MAX_INSTANCES > 13 + // @Group: E_ + // @Path: AP_BattMonitor_Params.cpp + AP_SUBGROUPINFO(_params[13], "E_", 36, AP_BattMonitor, AP_BattMonitor_Params), + + // @Group: E_ + // @Path: AP_BattMonitor_Analog.cpp + // @Group: E_ + // @Path: AP_BattMonitor_SMBus.cpp + // @Group: E_ + // @Path: AP_BattMonitor_Sum.cpp + // @Group: E_ + // @Path: AP_BattMonitor_DroneCAN.cpp + // @Group: E_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp + // @Group: E_ + // @Path: AP_BattMonitor_Synthetic_Current.cpp + // @Group: E_ + // @Path: AP_BattMonitor_INA2xx.cpp + AP_SUBGROUPVARPTR(drivers[13], "E_", 54, AP_BattMonitor, backend_var_info[13]), +#endif + +#if AP_BATT_MONITOR_MAX_INSTANCES > 14 + // @Group: F_ + // @Path: AP_BattMonitor_Params.cpp + AP_SUBGROUPINFO(_params[14], "F_", 37, AP_BattMonitor, AP_BattMonitor_Params), + + // @Group: F_ + // @Path: AP_BattMonitor_Analog.cpp + // @Group: F_ + // @Path: AP_BattMonitor_SMBus.cpp + // @Group: F_ + // @Path: AP_BattMonitor_Sum.cpp + // @Group: F_ + // @Path: AP_BattMonitor_DroneCAN.cpp + // @Group: F_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp + // @Group: F_ + // @Path: AP_BattMonitor_Synthetic_Current.cpp + // @Group: F_ + // @Path: AP_BattMonitor_INA2xx.cpp + AP_SUBGROUPVARPTR(drivers[14], "F_", 55, AP_BattMonitor, backend_var_info[14]), +#endif + +#if AP_BATT_MONITOR_MAX_INSTANCES > 15 + // @Group: G_ + // @Path: AP_BattMonitor_Params.cpp + AP_SUBGROUPINFO(_params[15], "G_", 38, AP_BattMonitor, AP_BattMonitor_Params), + + // @Group: G_ + // @Path: AP_BattMonitor_Analog.cpp + // @Group: G_ + // @Path: AP_BattMonitor_SMBus.cpp + // @Group: G_ + // @Path: AP_BattMonitor_Sum.cpp + // @Group: G_ + // @Path: AP_BattMonitor_DroneCAN.cpp + // @Group: G_ + // @Path: AP_BattMonitor_FuelLevel_Analog.cpp + // @Group: G_ + // @Path: AP_BattMonitor_Synthetic_Current.cpp + // @Group: G_ + // @Path: AP_BattMonitor_INA2xx.cpp + AP_SUBGROUPVARPTR(drivers[15], "G_", 56, AP_BattMonitor, backend_var_info[15]), +#endif + +#if AP_BATT_MONITOR_MAX_INSTANCES > 16 + #error "AP_BATT_MONITOR_MAX_INSTANCES too large, reset_remaining_mask() will cause an assert above 16" +#endif + AP_GROUPEND }; @@ -496,6 +654,10 @@ void AP_BattMonitor::read() drivers[i]->read(); drivers[i]->update_resistance_estimate(); +#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED + drivers[i]->update_esc_telem_outbound(); +#endif + #if HAL_LOGGING_ENABLED if (logger != nullptr && logger->should_log(_log_battery_bit)) { const uint64_t time_us = AP_HAL::micros64(); @@ -562,7 +724,11 @@ bool AP_BattMonitor::current_amps(float ¤t, uint8_t instance) const { /// consumed_mah - returns total current drawn since start-up in milliampere.hours bool AP_BattMonitor::consumed_mah(float &mah, const uint8_t instance) const { if ((instance < _num_instances) && (drivers[instance] != nullptr) && drivers[instance]->has_current()) { - mah = state[instance].consumed_mah; + const float consumed_mah = state[instance].consumed_mah; + if (isnan(consumed_mah)) { + return false; + } + mah = consumed_mah; return true; } else { return false; @@ -644,7 +810,7 @@ void AP_BattMonitor::check_failsafes(void) #endif state[i].failsafe = type; - // map the desired failsafe action to a prioritiy level + // map the desired failsafe action to a priority level int8_t priority = 0; if (_failsafe_priorities != nullptr) { while (_failsafe_priorities[priority] != -1) { @@ -713,18 +879,9 @@ bool AP_BattMonitor::get_temperature(float &temperature, const uint8_t instance) { if (instance >= _num_instances || drivers[instance] == nullptr) { return false; - } - -#if AP_TEMPERATURE_SENSOR_ENABLED - if (state[instance].temperature_external_use) { - temperature = state[instance].temperature_external; - return true; } -#endif - - temperature = state[instance].temperature; - return drivers[instance]->has_temperature(); + return drivers[instance]->get_temperature(temperature); } #if AP_TEMPERATURE_SENSOR_ENABLED diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index 8f28212a21a204..bcd802bcce0710 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -107,6 +107,7 @@ class AP_BattMonitor Analog_Volt_Synthetic_Current = 25, INA239_SPI = 26, EFI = 27, + // AD7091R5_I2C_Analog = 28, reserve ID for future use }; FUNCTOR_TYPEDEF(battery_failsafe_handler_fn_t, void, const char *, const int8_t); diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp index 6eccda0078c6f6..c137aa2c146ef0 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp @@ -18,6 +18,10 @@ #include "AP_BattMonitor.h" #include "AP_BattMonitor_Backend.h" +#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED +#include "AP_ESC_Telem/AP_ESC_Telem.h" +#endif + /* base class constructor. This incorporates initialisation as well. @@ -233,6 +237,56 @@ void AP_BattMonitor_Backend::check_failsafe_types(bool &low_voltage, bool &low_c } } +#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED +void AP_BattMonitor_Backend::update_esc_telem_outbound() +{ + const uint8_t esc_index = _params._esc_telem_outbound_index; + if (esc_index == 0 || !_state.healthy) { + // Disabled if there's no ESC identified to route the data to or if the battery is unhealthy + return; + } + + AP_ESC_Telem_Backend::TelemetryData telem {}; + + uint16_t type = AP_ESC_Telem_Backend::TelemetryType::VOLTAGE; + telem.voltage = _state.voltage; // all battery backends have voltage + + if (has_current()) { + telem.current = _state.current_amps; + type |= AP_ESC_Telem_Backend::TelemetryType::CURRENT; + } + + if (has_consumed_energy()) { + telem.consumption_mah = _state.consumed_mah; + type |= AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION; + } + + float temperature_c; + if (_mon.get_temperature(temperature_c, _state.instance)) { + // get the temperature from the frontend so we check for external temperature + telem.temperature_cdeg = temperature_c * 100; + type |= AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE; + } + + AP::esc_telem().update_telem_data(esc_index-1, telem, type); +} +#endif + +// returns true if battery monitor provides temperature +bool AP_BattMonitor_Backend::get_temperature(float &temperature) const +{ +#if AP_TEMPERATURE_SENSOR_ENABLED + if (_state.temperature_external_use) { + temperature = _state.temperature_external; + return true; + } +#endif + + temperature = _state.temperature; + + return has_temperature(); +} + /* default implementation for reset_remaining(). This sets consumed_wh and consumed_mah based on the given percentage. Use percentage=100 diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h index 1506e4d6a2276c..85d62127708c82 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h @@ -48,6 +48,9 @@ class AP_BattMonitor_Backend // returns true if battery monitor provides temperature virtual bool has_temperature() const { return false; } + // returns true if temperature retrieved successfully + virtual bool get_temperature(float &temperature) const; + // capacity_remaining_pct - returns true if the battery % is available and writes to the percentage argument // returns false if the battery is unhealthy, does not have current monitoring, or the pack_capacity is too small virtual bool capacity_remaining_pct(uint8_t &percentage) const WARN_IF_UNUSED; @@ -81,6 +84,9 @@ class AP_BattMonitor_Backend // set desired MPPT powered state (enabled/disabled) virtual void mppt_set_powered_state(bool power_on) {}; + // Update an ESC telemetry channel's power information + void update_esc_telem_outbound(); + // amps: current (A) // dt_us: time between samples (micro-seconds) static float calculate_mah(float amps, float dt_us) { return (float) (amps * dt_us * AUS_TO_MAH); } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp index 75bbebcae62303..9907a798afcb0d 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp @@ -103,7 +103,7 @@ float AP_BattMonitor_Bebop::_filter_voltage(float vbat_raw) _prev_vbat = vbat_raw; only_once = 0; } else if (vbat_raw > 0.0f) { - /* 1st order fitler */ + /* 1st order filter */ vbat = b[0] * vbat_raw + b[1] * _prev_vbat_raw - a[1] * _prev_vbat; _prev_vbat_raw = vbat_raw; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp index 3130a8bdf32403..c7514f8fb333e6 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -33,8 +33,7 @@ const AP_Param::GroupInfo AP_BattMonitor_DroneCAN::var_info[] = { /// Constructor AP_BattMonitor_DroneCAN::AP_BattMonitor_DroneCAN(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, BattMonitor_DroneCAN_Type type, AP_BattMonitor_Params ¶ms) : - AP_BattMonitor_Backend(mon, mon_state, params), - _type(type) + AP_BattMonitor_Backend(mon, mon_state, params) { AP_Param::setup_object_defaults(this,var_info); _state.var_info = var_info; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h index 543aeb3b6daec9..2b70f5d244bfdf 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h @@ -87,7 +87,6 @@ class AP_BattMonitor_DroneCAN : public AP_BattMonitor_Backend bool use_CAN_SoC() const; AP_BattMonitor::BattMonitor_State _interim_state; - BattMonitor_DroneCAN_Type _type; HAL_Semaphore _sem_battmon; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp index f9ee6d2bbf64ae..eb292ea6dea55a 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Generator.cpp @@ -32,7 +32,7 @@ bool AP_BattMonitor_Generator_FuelLevel::has_current(void) const return has_consumed_energy(); } -// This is where we tell the battery monitor 'we have consummed energy' if we want to report a fuel level remaining +// This is where we tell the battery monitor 'we have consumed energy' if we want to report a fuel level remaining bool AP_BattMonitor_Generator_FuelLevel::has_consumed_energy(void) const { // Get pointer to generator singleton @@ -149,7 +149,7 @@ AP_BattMonitor::Failsafe AP_BattMonitor_Generator_Elec::update_failsafes() AP_Generator *generator = AP::generator(); - // Only check for failsafes on the electrical moniter + // Only check for failsafes on the electrical monitor // no point in having the same failsafe on two battery monitors if (generator != nullptr) { failsafe = generator->update_failsafes(); diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Generator.h b/libraries/AP_BattMonitor/AP_BattMonitor_Generator.h index bacd1e399a9dd8..db7d17c4b235ca 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Generator.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Generator.h @@ -44,7 +44,7 @@ class AP_BattMonitor_Generator_FuelLevel : public AP_BattMonitor_Backend // This is where we tell the battery monitor 'we have current' if we want to report a fuel level remaining bool has_current(void) const override; - // This is where we tell the battery monitor 'we have consummed energy' if we want to report a fuel level remaining + // This is where we tell the battery monitor 'we have consumed energy' if we want to report a fuel level remaining bool has_consumed_energy(void) const override; }; #endif diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_INA239.h b/libraries/AP_BattMonitor/AP_BattMonitor_INA239.h index c03eea23f88cfb..3f5f87ee2114ea 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_INA239.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_INA239.h @@ -18,7 +18,6 @@ class AP_BattMonitor_INA239 : public AP_BattMonitor_Backend bool has_cell_voltages() const override { return false; } bool has_temperature() const override { return false; } bool has_current() const override { return true; } - bool reset_remaining(float percentage) override { return false; } bool get_cycle_count(uint16_t &cycles) const override { return false; } void init(void) override; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp index 0a504132aa83a8..cab13b302f191a 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.cpp @@ -46,6 +46,10 @@ extern const AP_HAL::HAL& hal; #define DEFAULT_BATTMON_INA2XX_MAX_AMPS 90.0 #endif +#ifndef DEFAULT_BATTMON_INA2XX_SHUNT +#define DEFAULT_BATTMON_INA2XX_SHUNT 0.0005 +#endif + #ifndef HAL_BATTMON_INA2XX_BUS #define HAL_BATTMON_INA2XX_BUS 0 #endif @@ -80,8 +84,15 @@ const AP_Param::GroupInfo AP_BattMonitor_INA2XX::var_info[] = { // @Range: 1 400 // @Units: A // @User: Advanced - // @RebootRequired: True AP_GROUPINFO("MAX_AMPS", 27, AP_BattMonitor_INA2XX, max_amps, DEFAULT_BATTMON_INA2XX_MAX_AMPS), + + // @Param: SHUNT + // @DisplayName: Battery monitor shunt resistor + // @Description: This sets the shunt resistor used in the device + // @Range: 0.0001 0.01 + // @Units: Ohm + // @User: Advanced + AP_GROUPINFO("SHUNT", 28, AP_BattMonitor_INA2XX, rShunt, DEFAULT_BATTMON_INA2XX_SHUNT), AP_GROUPEND }; @@ -114,7 +125,6 @@ bool AP_BattMonitor_INA2XX::configure(DevType dtype) case DevType::INA226: { // configure for MAX_AMPS const uint16_t conf = (0x2<<9) | (0x5<<6) | (0x5<<3) | 0x7; // 2ms conv time, 16x sampling - const float rShunt = 0.0005; current_LSB = max_amps / 32768.0; voltage_LSB = 0.00125; // 1.25mV/bit const uint16_t cal = uint16_t(0.00512 / (current_LSB * rShunt)); @@ -130,7 +140,6 @@ bool AP_BattMonitor_INA2XX::configure(DevType dtype) case DevType::INA228: { // configure for MAX_AMPS voltage_LSB = 195.3125e-6; // 195.3125 uV/LSB - const float rShunt = 0.0005; current_LSB = max_amps / (1<<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 @@ -145,7 +154,6 @@ bool AP_BattMonitor_INA2XX::configure(DevType dtype) case DevType::INA238: { // configure for MAX_AMPS voltage_LSB = 3.125e-3; // 3.125mV/LSB - const float rShunt = 0.0005; current_LSB = max_amps / (1<<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 diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h index 8418ca30731bd6..d49e7c82746da3 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_INA2xx.h @@ -19,7 +19,6 @@ class AP_BattMonitor_INA2XX : public AP_BattMonitor_Backend bool has_cell_voltages() const override { return false; } bool has_temperature() const override { return false; } bool has_current() const override { return true; } - bool reset_remaining(float percentage) override { return false; } bool get_cycle_count(uint16_t &cycles) const override { return false; } void init(void) override; @@ -53,6 +52,7 @@ class AP_BattMonitor_INA2XX : public AP_BattMonitor_Backend AP_Int8 i2c_bus; AP_Int8 i2c_address; AP_Float max_amps; + AP_Float rShunt; uint32_t failed_reads; struct { diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.h b/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.h index 93b378d52d486d..e365c3aa11b6f2 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_LTC2946.h @@ -16,7 +16,6 @@ class AP_BattMonitor_LTC2946 : public AP_BattMonitor_Backend bool has_cell_voltages() const override { return false; } bool has_temperature() const override { return false; } bool has_current() const override { return true; } - bool reset_remaining(float percentage) override { return false; } bool get_cycle_count(uint16_t &cycles) const override { return false; } virtual void init(void) override; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp index f6c8633699d5f1..f5595d321aca32 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp @@ -10,6 +10,12 @@ void AP_BattMonitor_Backend::Log_Write_BAT(const uint8_t instance, const uint64_ uint8_t percent = -1; IGNORE_RETURN(capacity_remaining_pct(percent)); + float temperature; + int16_t temperature_cd = 0; + if (get_temperature(temperature)) { + temperature_cd = temperature * 100.0; + } + const struct log_BAT pkt{ LOG_PACKET_HEADER_INIT(LOG_BAT_MSG), time_us : time_us, @@ -19,9 +25,10 @@ void AP_BattMonitor_Backend::Log_Write_BAT(const uint8_t instance, const uint64_ current_amps : has_curr ? _state.current_amps : AP::logger().quiet_nanf(), current_total : has_curr ? _state.consumed_mah : AP::logger().quiet_nanf(), consumed_wh : has_curr ? _state.consumed_wh : AP::logger().quiet_nanf(), - temperature : (int16_t) ( has_temperature() ? _state.temperature * 100 : 0), + temperature : temperature_cd, resistance : _state.resistance, rem_percent : percent, + health : _state.healthy }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp index 60c9a8ac67fe91..01ec3bbded590d 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp @@ -9,6 +9,10 @@ #define DEFAULT_LOW_BATTERY_VOLTAGE 0.0f #endif // APM_BUILD_COPTER_OR_HELI +#ifndef AP_BATT_MONITOR_BATTERY_CAPACITY + #define AP_BATT_MONITOR_BATTERY_CAPACITY 3300 +#endif + const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @Param: MONITOR // @DisplayName: Battery monitoring @@ -28,15 +32,15 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // 6 was AMP_OFFSET -#ifndef HAL_BUILD_AP_PERIPH // @Param: CAPACITY // @DisplayName: Battery capacity // @Description: Capacity of the battery in mAh when full // @Units: mAh // @Increment: 50 // @User: Standard - AP_GROUPINFO("CAPACITY", 7, AP_BattMonitor_Params, _pack_capacity, 3300), + AP_GROUPINFO("CAPACITY", 7, AP_BattMonitor_Params, _pack_capacity, AP_BATT_MONITOR_BATTERY_CAPACITY), +#ifndef HAL_BUILD_AP_PERIPH // @Param{Plane}: WATT_MAX // @DisplayName: Maximum allowed power (Watts) // @Description: If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable. @@ -151,6 +155,16 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0), #endif // HAL_BUILD_AP_PERIPH +#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED + // @Param: ESC_INDEX + // @DisplayName: ESC Telemetry Index to write to + // @Description: ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable. + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced + AP_GROUPINFO("ESC_INDEX", 22, AP_BattMonitor_Params, _esc_telem_outbound_index, 0), +#endif + AP_GROUPEND }; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h index 7b3223f3eea559..9366965328cd7a 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h @@ -1,6 +1,7 @@ #pragma once #include +#include "AP_BattMonitor_config.h" class AP_BattMonitor_Params { public: @@ -43,4 +44,7 @@ class AP_BattMonitor_Params { AP_Int8 _failsafe_voltage_source; /// voltage type used for detection of low voltage event AP_Int8 _failsafe_low_action; /// action to preform on a low battery failsafe AP_Int8 _failsafe_critical_action; /// action to preform on a critical battery failsafe +#if AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED + AP_Int8 _esc_telem_outbound_index; /// bitmask of ESCs to forward voltage, current, consumption and temperature to. +#endif }; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp index 9fc708a9740ed0..2cd58b765b0e27 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Generic.cpp @@ -88,7 +88,7 @@ void AP_BattMonitor_SMBus_Generic::timer() } } - // we loop over something limted by + // we loop over something limited by // BATTMONITOR_SMBUS_NUM_CELLS_MAX but assign into something // limited by AP_BATT_MONITOR_CELLS_MAX - so make sure we won't // over-write: diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp index 6d4589d1fa6717..4b4af9c5937ad5 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.cpp @@ -11,9 +11,11 @@ #include "AP_BattMonitor_SMBus_Solo.h" #define BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE 0x28 // cell voltage register +#define BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE_EXT 0x29 // cell voltage register up to 6s #define BATTMONITOR_SMBUS_SOLO_CURRENT 0x2a // current register #define BATTMONITOR_SMBUS_SOLO_BUTTON_DEBOUNCE 6 // button held down for 5 intervals will cause a power off event #define BATTMONITOR_SMBUS_SOLO_NUM_CELLS 4 // solo's battery pack is 4S +#define BATTMONITOR_SMBUS_SOLO_NUM_CELLS_EXT 6 // extended BMS supports up to 6s /* * Other potentially useful registers, listed here for future use @@ -39,12 +41,12 @@ AP_BattMonitor_SMBus_Solo::AP_BattMonitor_SMBus_Solo(AP_BattMonitor &mon, void AP_BattMonitor_SMBus_Solo::timer() { - uint8_t buff[8]; + uint8_t buff[12]; uint32_t tnow = AP_HAL::micros(); // read cell voltages - if (read_block(BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE, buff, 8)) { + if (!_use_extended && read_block(BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE, buff, 8)) { float pack_voltage_mv = 0.0f; for (uint8_t i = 0; i < BATTMONITOR_SMBUS_SOLO_NUM_CELLS; i++) { uint16_t cell = buff[(i * 2) + 1] << 8 | buff[i * 2]; @@ -55,13 +57,32 @@ void AP_BattMonitor_SMBus_Solo::timer() // accumulate the pack voltage out of the total of the cells // because the Solo's I2C bus is so noisy, it's worth not spending the - // time and bus bandwidth to request the pack voltage as a seperate + // time and bus bandwidth to request the pack voltage as a separate // transaction _state.voltage = pack_voltage_mv * 1e-3f; _state.last_time_micros = tnow; _state.healthy = true; } + + // read extended cell voltages + if (read_block(BATTMONITOR_SMBUS_SOLO_CELL_VOLTAGE_EXT, buff, 12)) { + float pack_voltage_mv = 0.0f; + for (uint8_t i = 0; i < BATTMONITOR_SMBUS_SOLO_NUM_CELLS_EXT; i++) { + uint16_t cell = buff[(i * 2) + 1] << 8 | buff[i * 2]; + _state.cell_voltages.cells[i] = cell; + pack_voltage_mv += (float)cell; + } + _has_cell_voltages = true; + + // accumulate the pack voltage out of the total of the cells + _state.voltage = pack_voltage_mv * 1e-3f; + _state.last_time_micros = tnow; + _state.healthy = true; + // stop requesting 4-cell packets. + _use_extended = true; + } + // timeout after 5 seconds if ((tnow - _state.last_time_micros) > AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS) { _state.healthy = false; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.h b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.h index f14b0e16c0bae1..b9083f574722c1 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_Solo.h @@ -18,6 +18,7 @@ class AP_BattMonitor_SMBus_Solo : public AP_BattMonitor_SMBus void timer(void) override; uint8_t _button_press_count; + bool _use_extended; }; #endif // AP_BATTERY_SMBUS_SOLO_ENABLED diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Synthetic_Current.h b/libraries/AP_BattMonitor/AP_BattMonitor_Synthetic_Current.h index 212ae607bea59e..0a49d0b40538cd 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Synthetic_Current.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Synthetic_Current.h @@ -26,6 +26,6 @@ class AP_BattMonitor_Synthetic_Current : public AP_BattMonitor_Analog protected: - AP_Float _max_voltage; /// maximum battery voltage used in current caluculation + AP_Float _max_voltage; /// maximum battery voltage used in current calculation }; #endif diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Torqeedo.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Torqeedo.cpp index 424264644e9e8c..dfb7921abe5ebe 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Torqeedo.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Torqeedo.cpp @@ -49,7 +49,7 @@ void AP_BattMonitor_Torqeedo::read(void) const uint32_t tnow_us = AP_HAL::micros(); const uint32_t diff_us = tnow_us - _state.last_time_micros; if (diff_us < AP_BATTMON_TORQEEDO_TIMEOUT_US) { - _state.consumed_mah += _state.current_amps * diff_us / 1000000.0 / 3600.0 * 1000.0; + _state.consumed_mah += _state.current_amps * diff_us * 1e-6f / 3600.0 * 1000.0; } _state.last_time_micros = tnow_us; _state.healthy = true; @@ -77,4 +77,3 @@ bool AP_BattMonitor_Torqeedo::capacity_remaining_pct(uint8_t &percentage) const } #endif // AP_BATTERY_TORQEEDO_ENABLED - diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_config.h b/libraries/AP_BattMonitor/AP_BattMonitor_config.h index 8a6e3706732cac..7b14fea17fb3bc 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_config.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_config.h @@ -30,6 +30,10 @@ #define AP_BATTERY_ESC_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && HAL_WITH_ESC_TELEM #endif +#ifndef AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED +#define AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED 0 +#endif + #ifndef AP_BATTERY_SMBUS_ENABLED #define AP_BATTERY_SMBUS_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED #endif diff --git a/libraries/AP_BattMonitor/LogStructure.h b/libraries/AP_BattMonitor/LogStructure.h index 1b7afc07e31ad3..fdc97512ef0065 100644 --- a/libraries/AP_BattMonitor/LogStructure.h +++ b/libraries/AP_BattMonitor/LogStructure.h @@ -9,7 +9,7 @@ // @LoggerMessage: BAT // @Description: Gathered battery data // @Field: TimeUS: Time since system startup -// @Field: Instance: battery instance number +// @Field: Inst: battery instance number // @Field: Volt: measured voltage // @Field: VoltR: estimated resting voltage // @Field: Curr: measured current @@ -18,6 +18,7 @@ // @Field: Temp: measured temperature // @Field: Res: estimated battery resistance // @Field: RemPct: remaining percentage +// @Field: H: health struct PACKED log_BAT { LOG_PACKET_HEADER; uint64_t time_us; @@ -30,6 +31,7 @@ struct PACKED log_BAT { int16_t temperature; // degrees C * 100 float resistance; uint8_t rem_percent; + uint8_t health; }; // @LoggerMessage: BCL @@ -59,6 +61,6 @@ struct PACKED log_BCL { #define LOG_STRUCTURE_FROM_BATTMONITOR \ { LOG_BAT_MSG, sizeof(log_BAT), \ - "BAT", "QBfffffcfB", "TimeUS,Instance,Volt,VoltR,Curr,CurrTot,EnrgTot,Temp,Res,RemPct", "s#vvAaXOw%", "F-000C0?00" , true }, \ + "BAT", "QBfffffcfBB", "TimeUS,Inst,Volt,VoltR,Curr,CurrTot,EnrgTot,Temp,Res,RemPct,H", "s#vvAaXOw%-", "F-000C0?000" , true }, \ { LOG_BCL_MSG, sizeof(log_BCL), \ "BCL", "QBfHHHHHHHHHHHH", "TimeUS,Instance,Volt,V1,V2,V3,V4,V5,V6,V7,V8,V9,V10,V11,V12", "s#vvvvvvvvvvvvv", "F-0CCCCCCCCCCCC" , true }, diff --git a/libraries/AP_Beacon/AP_Beacon_Nooploop.h b/libraries/AP_Beacon/AP_Beacon_Nooploop.h index e903eb47fb7baa..222c7731492ca5 100644 --- a/libraries/AP_Beacon/AP_Beacon_Nooploop.h +++ b/libraries/AP_Beacon/AP_Beacon_Nooploop.h @@ -33,7 +33,7 @@ class AP_Beacon_Nooploop : public AP_Beacon_Backend // send setting_frame0 to tag. tag will ack setting_frame0 with anchor position filled void request_setting(); - // pase node_frame2 to get tag position and distance + // parse node_frame2 to get tag position and distance void parse_node_frame2(); // parse setting_frame0 to get anchor position diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.cpp b/libraries/AP_BoardConfig/AP_BoardConfig.cpp index 4d3b377e2a1bf7..cbd3292236c230 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.cpp +++ b/libraries/AP_BoardConfig/AP_BoardConfig.cpp @@ -238,9 +238,11 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { // @User: Standard AP_GROUPINFO("SAFETYOPTION", 13, AP_BoardConfig, state.safety_option, BOARD_SAFETY_OPTION_DEFAULT), +#if AP_RTC_ENABLED // @Group: RTC // @Path: ../AP_RTC/AP_RTC.cpp AP_SUBGROUPINFO(rtc, "RTC", 14, AP_BoardConfig, AP_RTC), +#endif #if HAL_HAVE_BOARD_VOLTAGE // @Param: VBUS_MIN @@ -278,7 +280,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { #ifdef HAL_GPIO_PWM_VOLT_PIN // @Param: PWM_VOLT_SEL // @DisplayName: Set PWM Out Voltage - // @Description: This sets the voltage max for PWM output pulses. 0 for 3.3V and 1 for 5V output. On boards with an IOMCU that support this parameter this option only affects the 8 main outputs, not the 6 auxilliary outputs. Using 5V output can help to reduce the impact of ESC noise interference corrupting signals to the ESCs. + // @Description: This sets the voltage max for PWM output pulses. 0 for 3.3V and 1 for 5V output. On boards with an IOMCU that support this parameter this option only affects the 8 main outputs, not the 6 auxiliary outputs. Using 5V output can help to reduce the impact of ESC noise interference corrupting signals to the ESCs. // @Values: 0:3.3V,1:5V // @User: Advanced AP_GROUPINFO("PWM_VOLT_SEL", 18, AP_BoardConfig, _pwm_volt_sel, 0), @@ -358,6 +360,16 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { // index 26 used by SER3_RTSCTS // index 27 used by SER4_RTSCTS + +#if HAL_WITH_IO_MCU_DSHOT + // @Param: IO_DSHOT + // @DisplayName: Load DShot FW on IO + // @Description: This loads the DShot firmware on the IO co-processor + // @Values: 0:StandardFW,1:DshotFW + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("IO_DSHOT", 28, AP_BoardConfig, state.io_dshot, 0), +#endif AP_GROUPEND }; @@ -368,7 +380,9 @@ void AP_BoardConfig::init() board_setup(); +#if AP_RTC_ENABLED AP::rtc().set_utc_usec(hal.util->get_hw_rtc(), AP_RTC::SOURCE_HW); +#endif if (_boot_delay_ms > 0) { uint16_t delay_ms = uint16_t(_boot_delay_ms.get()); diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.h b/libraries/AP_BoardConfig/AP_BoardConfig.h index 60e97cfbf1ed67..d0a89c490df4c8 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.h +++ b/libraries/AP_BoardConfig/AP_BoardConfig.h @@ -92,6 +92,14 @@ class AP_BoardConfig { #endif } + static bool io_dshot(void) { +#if HAL_WITH_IO_MCU_DSHOT + return io_enabled() && _singleton?_singleton->state.io_dshot.get():false; +#else + return false; +#endif + } + // get alternative config selection uint8_t get_alt_config(void) { return uint8_t(_alt_config.get()); @@ -218,6 +226,7 @@ class AP_BoardConfig { #endif AP_Int8 board_type; AP_Int8 io_enable; + AP_Int8 io_dshot; } state; #if AP_SDCARD_STORAGE_ENABLED @@ -269,9 +278,11 @@ class AP_BoardConfig { // direct attached radio AP_Radio _radio; #endif - + +#if AP_RTC_ENABLED // real-time-clock; private because access is via the singleton AP_RTC rtc; +#endif #if HAL_HAVE_BOARD_VOLTAGE AP_Float _vbus_min; diff --git a/libraries/AP_Button/AP_Button.cpp b/libraries/AP_Button/AP_Button.cpp index c9d59b32192bff..c21a947e22a748 100644 --- a/libraries/AP_Button/AP_Button.cpp +++ b/libraries/AP_Button/AP_Button.cpp @@ -212,6 +212,7 @@ void AP_Button::update(void) pwm_start_debounce_ms = now_ms; } +#if HAL_GCS_ENABLED if (last_debounce_ms != 0 && (AP_HAL::millis() - last_report_ms) > AP_BUTTON_REPORT_PERIOD_MS && (AP_HAL::millis64() - last_debounce_ms) < report_send_time*1000ULL) { @@ -221,6 +222,7 @@ void AP_Button::update(void) // send a report to GCS send_report(); } +#endif if (!aux_functions_initialised) { run_aux_functions(true); @@ -273,7 +275,7 @@ void AP_Button::run_aux_functions(bool force) #if AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED const char *str = rc_channel->string_for_aux_function(func); if (str != nullptr) { - gcs().send_text(MAV_SEVERITY_INFO, "Button %i: executing (%s %s)", i+1, str, rc_channel->string_for_aux_pos(pos)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Button %i: executing (%s %s)", i+1, str, rc_channel->string_for_aux_pos(pos)); } #endif rc_channel->run_aux_function(func, pos, RC_Channel::AuxFuncTriggerSource::BUTTON); @@ -338,6 +340,7 @@ void AP_Button::timer_update(void) } } +#if HAL_GCS_ENABLED /* send a BUTTON_CHANGE report to the GCS */ @@ -352,6 +355,7 @@ void AP_Button::send_report(void) const gcs().send_to_active_channels(MAVLINK_MSG_ID_BUTTON_CHANGE, (const char *)&packet); } +#endif /* setup the pins as input with pullup. We need pullup to give reliable diff --git a/libraries/AP_CANManager/AP_CAN.h b/libraries/AP_CANManager/AP_CAN.h index c241b777fc65b7..53e7ccb14fea94 100644 --- a/libraries/AP_CANManager/AP_CAN.h +++ b/libraries/AP_CANManager/AP_CAN.h @@ -27,5 +27,7 @@ class AP_CAN { Scripting = 10, Benewake = 11, Scripting2 = 12, + TOFSenseP = 13, + NanoRadar_NRA24 = 14, }; }; diff --git a/libraries/AP_CANManager/AP_CANDriver.cpp b/libraries/AP_CANManager/AP_CANDriver.cpp index a3e74f98cb025a..1f279c12a690de 100644 --- a/libraries/AP_CANManager/AP_CANDriver.cpp +++ b/libraries/AP_CANManager/AP_CANDriver.cpp @@ -30,7 +30,7 @@ const AP_Param::GroupInfo AP_CANManager::CANDriver_Params::var_info[] = { // @Param: PROTOCOL // @DisplayName: Enable use of specific protocol over virtual driver // @Description: Enabling this option starts selected protocol that will use this virtual driver - // @Values: 0:Disabled,1:DroneCAN,4:PiccoloCAN,6:EFI_NWPMU,7:USD1,8:KDECAN,10:Scripting,11:Benewake,12:Scripting2 + // @Values: 0:Disabled,1:DroneCAN,4:PiccoloCAN,6:EFI_NWPMU,7:USD1,8:KDECAN,10:Scripting,11:Benewake,12:Scripting2,13:TOFSenseP,14:NanoRadar_NRA24 // @User: Advanced // @RebootRequired: True AP_GROUPINFO("PROTOCOL", 1, AP_CANManager::CANDriver_Params, _driver_type, float(AP_CAN::Protocol::DroneCAN)), diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index 893f1189a2efed..78be64a97c66c9 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -120,13 +120,7 @@ void AP_CANManager::init() WITH_SEMAPHORE(_sem); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - if (AP::sitl() != nullptr) { - if (AP::sitl()->speedup > 1) { - log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "CAN is not supported under speedup."); - - return; - } - } else { + if (AP::sitl() == nullptr) { AP_HAL::panic("CANManager: SITL not initialised!"); } #endif @@ -381,7 +375,7 @@ void AP_CANManager::log_text(AP_CANManager::LogLevel loglevel, const char *tag, void AP_CANManager::log_retrieve(ExpandingString &str) const { if (_log_buf == nullptr) { - gcs().send_text(MAV_SEVERITY_ERROR, "Log buffer not available"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Log buffer not available"); return; } str.append(_log_buf, _log_pos); @@ -391,7 +385,7 @@ void AP_CANManager::log_retrieve(ExpandingString &str) const /* handle MAV_CMD_CAN_FORWARD mavlink long command */ -bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_command_long_t &packet, const mavlink_message_t &msg) +bool AP_CANManager::handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg) { WITH_SEMAPHORE(can_forward.sem); const int8_t bus = int8_t(packet.param1)-1; @@ -448,7 +442,7 @@ void AP_CANManager::handle_can_frame(const mavlink_message_t &msg) buffer_size /= 2; } if (frame_buffer == nullptr) { - // disard the frames + // discard the frames return; } } @@ -500,7 +494,7 @@ void AP_CANManager::process_frame_buffer(void) break; } const int16_t retcode = hal.can[frame.bus]->send(frame.frame, - AP_HAL::native_micros64() + timeout_us, + AP_HAL::micros64() + timeout_us, AP_HAL::CANIface::IsMAVCAN); if (retcode == 0) { // no space in the CAN output slots, try again later diff --git a/libraries/AP_CANManager/AP_CANManager.h b/libraries/AP_CANManager/AP_CANManager.h index a0086fce2b01c2..85d4aa31ed31f2 100644 --- a/libraries/AP_CANManager/AP_CANManager.h +++ b/libraries/AP_CANManager/AP_CANManager.h @@ -101,7 +101,7 @@ class AP_CANManager static const struct AP_Param::GroupInfo var_info[]; #if HAL_GCS_ENABLED - bool handle_can_forward(mavlink_channel_t chan, const mavlink_command_long_t &packet, const mavlink_message_t &msg); + bool handle_can_forward(mavlink_channel_t chan, const mavlink_command_int_t &packet, const mavlink_message_t &msg); void handle_can_frame(const mavlink_message_t &msg); void handle_can_filter_modify(const mavlink_message_t &msg); #endif @@ -141,7 +141,6 @@ class AP_CANManager private: AP_Int8 _driver_type; - AP_CANDriver* _testcan; AP_CANDriver* _uavcan; AP_CANDriver* _piccolocan; }; diff --git a/libraries/AP_CANManager/AP_CANSensor.cpp b/libraries/AP_CANManager/AP_CANSensor.cpp index 1f60b115308493..881eb39ce93c8f 100644 --- a/libraries/AP_CANManager/AP_CANSensor.cpp +++ b/libraries/AP_CANManager/AP_CANSensor.cpp @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - generic CAN sensor class, for easy creation of CAN sensors using prioprietary protocols + generic CAN sensor class, for easy creation of CAN sensors using proprietary protocols */ #include @@ -137,12 +137,12 @@ bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_ bool read_select = false; bool write_select = true; - bool ret = _can_iface->select(read_select, write_select, &out_frame, AP_HAL::native_micros64() + timeout_us); + bool ret = _can_iface->select(read_select, write_select, &out_frame, AP_HAL::micros64() + timeout_us); if (!ret || !write_select) { return false; } - uint64_t deadline = AP_HAL::native_micros64() + 2000000; + uint64_t deadline = AP_HAL::micros64() + 2000000; return (_can_iface->send(out_frame, deadline, AP_HAL::CANIface::AbortOnError) == 1); } diff --git a/libraries/AP_CANManager/AP_SLCANIface.cpp b/libraries/AP_CANManager/AP_SLCANIface.cpp index c19e3c56d6ae4b..dcd04dcff12f1a 100644 --- a/libraries/AP_CANManager/AP_SLCANIface.cpp +++ b/libraries/AP_CANManager/AP_SLCANIface.cpp @@ -112,7 +112,7 @@ bool SLCAN::CANIface::push_Frame(AP_HAL::CANFrame &frame) AP_HAL::CANIface::CanRxItem frm; frm.frame = frame; frm.flags = 0; - frm.timestamp_us = AP_HAL::native_micros64(); + frm.timestamp_us = AP_HAL::micros64(); return add_to_rx_queue(frm); } @@ -532,10 +532,10 @@ void SLCAN::CANIface::update_slcan_port() } if (_prev_ser_port != _slcan_ser_port) { if (!_slcan_start_req) { - _slcan_start_req_time = AP_HAL::native_millis(); + _slcan_start_req_time = AP_HAL::millis(); _slcan_start_req = true; } - if (((AP_HAL::native_millis() - _slcan_start_req_time) < ((uint32_t)_slcan_start_delay*1000))) { + if (((AP_HAL::millis() - _slcan_start_req_time) < ((uint32_t)_slcan_start_delay*1000))) { return; } _port = AP::serialmanager().get_serial_by_id(_slcan_ser_port); @@ -546,12 +546,12 @@ void SLCAN::CANIface::update_slcan_port() _port->lock_port(_serial_lock_key, _serial_lock_key); _prev_ser_port = _slcan_ser_port; GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CANManager: Starting SLCAN Passthrough on Serial %d with CAN%d", _slcan_ser_port.get(), _iface_num); - _last_had_activity = AP_HAL::native_millis(); + _last_had_activity = AP_HAL::millis(); } if (_port == nullptr) { return; } - if (((AP_HAL::native_millis() - _last_had_activity) > ((uint32_t)_slcan_timeout*1000)) && + if (((AP_HAL::millis() - _last_had_activity) > ((uint32_t)_slcan_timeout*1000)) && (uint32_t)_slcan_timeout != 0) { _port->lock_port(0, 0); _port = nullptr; @@ -658,6 +658,9 @@ bool SLCAN::CANIface::select(bool &read, bool &write, const AP_HAL::CANFrame* co return ret; } + // ensure we own the UART. Locking is handled at the CAN interface level + _port->begin_locked(0, 0, 0, _serial_lock_key); + // if under passthrough, we only do send when can_iface also allows it if (_port->available_locked(_serial_lock_key) || rx_queue_.available()) { // allow for receiving messages over slcan @@ -690,7 +693,7 @@ int16_t SLCAN::CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadlin ) { return ret; } - reportFrame(frame, AP_HAL::native_micros64()); + reportFrame(frame, AP_HAL::micros64()); return ret; } @@ -705,14 +708,14 @@ int16_t SLCAN::CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& rx_time, if (ret > 0) { // we also pass this frame through to slcan iface, // and immediately return - reportFrame(out_frame, AP_HAL::native_micros64()); + reportFrame(out_frame, AP_HAL::micros64()); return ret; } else if (ret < 0) { return ret; } } - // We found nothing in HAL's CANIface recieve, so look in SLCANIface + // We found nothing in HAL's CANIface receive, so look in SLCANIface if (_port == nullptr) { return 0; } @@ -722,7 +725,7 @@ int16_t SLCAN::CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& rx_time, // flush bytes from port while (num_bytes--) { uint8_t b; - if (!_port->read_locked(&b, 1, _serial_lock_key)) { + if (_port->read_locked(&b, 1, _serial_lock_key) != 1) { break; } addByte(b); @@ -747,7 +750,7 @@ int16_t SLCAN::CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& rx_time, bool read = false; bool write = true; _can_iface->select(read, write, &out_frame, 0); // select without blocking - if (write && _can_iface->send(out_frame, AP_HAL::native_micros64() + 100000, out_flags) == 1) { + if (write && _can_iface->send(out_frame, AP_HAL::micros64() + 100000, out_flags) == 1) { rx_queue_.pop(); num_tries = 0; } else if (num_tries > 8) { diff --git a/libraries/AP_CANManager/README.md b/libraries/AP_CANManager/README.md index 67fd1352f1fc93..9ce85ac00b195d 100644 --- a/libraries/AP_CANManager/README.md +++ b/libraries/AP_CANManager/README.md @@ -2,38 +2,10 @@ **Testing under SITL** -https://github.com/linux-can/can-utils contains a nice set of utility to do CAN related testings on Linux system. I used Ubuntu for this development, for Ubuntu systems you can simply download this tool using `sudo apt-get install can-utils` +A wide range of DroneCAN peripherals are supported in the SITL +simulation system. The simplest way of starting a DroneCAN enabled +simulated vehicle is to use sim_vehicle.py. -Following are the common commands that can be used while testing or developing: -* Create Virtual CAN Interface: -``` -sudo modprobe vcan -sudo ip link add dev vcan0 type vcan -sudo ip link set up vcan0 -sudo ip link add dev vcan1 type vcan -sudo ip link set up vcan1 -``` -* Route one CANSocket to another -``` -sudo modprobe can-gw -sudo cangw -A -s vcan0 -d vcan1 -e -sudo cangw -A -s vcan1 -d vcan0 -e -``` -* Delete routes -``` -sudo cangw -D -s vcan0 -d vcan1 -e -sudo cangw -D -s vcan1 -d vcan0 -e -``` -* Route SLCAN to VCAN, this allows connecting CAN devices to SITL run via CAN Adapter like the one running in Ardupilot itself. -``` -sudo modprobe slcan -sudo slcan_attach -f -s8 -o /dev/ttyACM0 -sudo slcand ttyACM0 slcan0 -sudo ifconfig slcan0 up -sudo cangw -A -s vcan0 -d slcan0 -e -sudo cangw -A -s slcan0 -d vcan0 -e -``` -* Dump can messages: -``` -sudo candump vcan0 -``` +For a quadplane use: sim_vehicle.py with the option -f quadplane-can + +For a quadcopter use: sim_vehicle.py with the option -f quad-can diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index c48c1c52539d75..7be0cb8e83d58a 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -77,14 +77,100 @@ void AP_Camera::cam_mode_toggle() } // take a picture -void AP_Camera::take_picture() +bool AP_Camera::take_picture() { WITH_SEMAPHORE(_rsem); - if (primary == nullptr) { - return; + // call for each instance + bool success = false; + for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) { + if (_backends[i] != nullptr) { + success |= _backends[i]->take_picture(); + } + } + + // return true if at least once pic taken + return success; +} + +bool AP_Camera::take_picture(uint8_t instance) +{ + WITH_SEMAPHORE(_rsem); + + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + return backend->take_picture(); +} + +// take multiple pictures, time_interval between two consecutive pictures is in miliseconds +// if instance is not provided, all available cameras affected +// time_interval_ms must be positive +// total_num is number of pictures to be taken, -1 means capture forever +// returns true if at least one camera is successful +bool AP_Camera::take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num) +{ + WITH_SEMAPHORE(_rsem); + + // sanity check time interval + if (time_interval_ms == 0) { + return false; + } + + // call for all instances + bool success = false; + for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) { + if (_backends[i] != nullptr) { + _backends[i]->take_multiple_pictures(time_interval_ms, total_num); + success = true; + } } - primary->take_picture(); + + // return true if at least once backend was successful + return success; +} + +bool AP_Camera::take_multiple_pictures(uint8_t instance, uint32_t time_interval_ms, int16_t total_num) +{ + WITH_SEMAPHORE(_rsem); + + // sanity check time interval + if (time_interval_ms == 0) { + return false; + } + + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + backend->take_multiple_pictures(time_interval_ms, total_num); + return true; +} + +// stop capturing multiple image sequence +void AP_Camera::stop_capture() +{ + WITH_SEMAPHORE(_rsem); + + // call for each instance + for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) { + if (_backends[i] != nullptr) { + _backends[i]->stop_capture(); + } + } +} + +bool AP_Camera::stop_capture(uint8_t instance) +{ + WITH_SEMAPHORE(_rsem); + + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + backend->stop_capture(); + return true; } // start/stop recording video @@ -239,14 +325,51 @@ MAV_RESULT AP_Camera::handle_command_long(const mavlink_command_long_t &packet) } return MAV_RESULT_DENIED; case MAV_CMD_IMAGE_START_CAPTURE: - if (!is_zero(packet.param2) || !is_equal(packet.param3, 1.0f) || !is_zero(packet.param4)) { - // time interval is not supported - // multiple image capture is not supported - // capture sequence number is not supported + // param1 : camera id + // param2 : interval (in seconds) + // param3 : total num images + // sanity check instance + if (is_negative(packet.param1)) { return MAV_RESULT_UNSUPPORTED; } - take_picture(); - return MAV_RESULT_ACCEPTED; + // check if this is a single picture request (e.g. total images is 1 or interval and total images are zero) + if (is_equal(packet.param3, 1.0f) || + (is_zero(packet.param2) && is_zero(packet.param3))) { + if (is_zero(packet.param1)) { + // take pictures for every backend + return take_picture() ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; + } + // take picture for specified instance + return take_picture(packet.param1-1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; + } else if (is_zero(packet.param3)) { + // multiple picture request, take pictures forever + if (is_zero(packet.param1)) { + // take pictures for every backend + return take_multiple_pictures(packet.param2*1000, -1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; + } + return take_multiple_pictures(packet.param1-1, packet.param2*1000, -1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; + } else { + // take multiple pictures equal to the number specified in param3 + if (is_zero(packet.param1)) { + // take pictures for every backend + return take_multiple_pictures(packet.param2*1000, packet.param3) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; + } + return take_multiple_pictures(packet.param1-1, packet.param2*1000, packet.param3) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; + } + case MAV_CMD_IMAGE_STOP_CAPTURE: + // param1 : camera id + if (is_negative(packet.param1)) { + return MAV_RESULT_UNSUPPORTED; + } + if (is_zero(packet.param1)) { + // stop capture for every backend + stop_capture(); + return MAV_RESULT_ACCEPTED; + } + if (stop_capture(packet.param1-1)) { + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_UNSUPPORTED; case MAV_CMD_CAMERA_TRACK_POINT: if (set_tracking(TrackingType::TRK_POINT, Vector2f{packet.param1, packet.param2}, Vector2f{})) { return MAV_RESULT_ACCEPTED; @@ -418,20 +541,6 @@ void AP_Camera::update() } } -// take_picture - take a picture -void AP_Camera::take_picture(uint8_t instance) -{ - WITH_SEMAPHORE(_rsem); - - auto *backend = get_instance(instance); - if (backend == nullptr) { - return; - } - - // call backend - backend->take_picture(); -} - // start/stop recording video. returns true on success // start_recording should be true to start recording, false to stop recording bool AP_Camera::record_video(uint8_t instance, bool start_recording) @@ -529,6 +638,30 @@ bool AP_Camera::set_tracking(uint8_t instance, TrackingType tracking_type, const return backend->set_tracking(tracking_type, p1, p2); } +// set camera lens as a value from 0 to 5 +bool AP_Camera::set_lens(uint8_t lens) +{ + WITH_SEMAPHORE(_rsem); + + if (primary == nullptr) { + return false; + } + return primary->set_lens(lens); +} + +bool AP_Camera::set_lens(uint8_t instance, uint8_t lens) +{ + WITH_SEMAPHORE(_rsem); + + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + + // call instance + return backend->set_lens(lens); +} + #if AP_CAMERA_SCRIPTING_ENABLED // accessor to allow scripting backend to retrieve state // returns true on success and cam_state is filled in diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 04382c7de551ed..80221ac6434ba7 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -111,9 +111,22 @@ class AP_Camera { void cam_mode_toggle(); void cam_mode_toggle(uint8_t instance); - // take a picture - void take_picture(); - void take_picture(uint8_t instance); + // take a picture. If instance is not provided, all available cameras affected + // returns true if at least one camera took a picture + bool take_picture(); + bool take_picture(uint8_t instance); + + // take multiple pictures, time_interval between two consecutive pictures is in miliseconds + // if instance is not provided, all available cameras affected + // time_interval_ms must be positive + // total_num is number of pictures to be taken, -1 means capture forever + // returns true if at least one camera is successful + bool take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num); + bool take_multiple_pictures(uint8_t instance, uint32_t time_interval_ms, int16_t total_num); + + // stop capturing multiple image sequence + void stop_capture(); + bool stop_capture(uint8_t instance); // start/stop recording video // start_recording should be true to start recording, false to stop recording @@ -135,6 +148,10 @@ class AP_Camera { bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2); bool set_tracking(uint8_t instance, TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2); + // set camera lens as a value from 0 to 5 + bool set_lens(uint8_t lens); + bool set_lens(uint8_t instance, uint8_t lens); + // set if vehicle is in AUTO mode void set_is_auto_mode(bool enable) { _is_in_auto_mode = enable; } diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index 0dd3339b69f7f9..668053768169a9 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -3,6 +3,7 @@ #if AP_CAMERA_ENABLED #include #include +#include extern const AP_HAL::HAL& hal; @@ -32,6 +33,21 @@ void AP_Camera_Backend::update() // check feedback pin check_feedback(); + // time based triggering + // if time and distance triggering both are enabled then we only do time based triggering + if (time_interval_settings.num_remaining != 0) { + uint32_t delta_ms = AP_HAL::millis() - last_picture_time_ms; + if (delta_ms > time_interval_settings.time_interval_ms) { + if (take_picture()) { + // decrease num_remaining except when its -1 i.e. capture forever + if (time_interval_settings.num_remaining > 0) { + time_interval_settings.num_remaining--; + } + } + } + return; + } + // implement trigger distance if (!is_positive(_params.trigg_dist)) { last_location.lat = 0; @@ -78,6 +94,32 @@ void AP_Camera_Backend::update() take_picture(); } +// get corresponding mount instance for the camera +uint8_t AP_Camera_Backend::get_mount_instance() const +{ + // instance 0 means default + if (_params.mount_instance.get() == 0) { + return _instance; + } + return _params.mount_instance.get() - 1; +} + +// get mavlink gimbal device id which is normally mount_instance+1 +uint8_t AP_Camera_Backend::get_gimbal_device_id() const +{ +#if HAL_MOUNT_ENABLED + const uint8_t mount_instance = get_mount_instance(); + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + if (mount->get_mount_type(mount_instance) != AP_Mount::Type::None) { + return (mount_instance + 1); + } + } +#endif + return 0; +} + + // take a picture. returns true on success bool AP_Camera_Backend::take_picture() { @@ -86,7 +128,7 @@ bool AP_Camera_Backend::take_picture() // check minimum time interval since last picture taken uint32_t now_ms = AP_HAL::millis(); - if (now_ms - last_photo_time_ms < (uint32_t)(_params.interval_min * 1000)) { + if (now_ms - last_picture_time_ms < (uint32_t)(_params.interval_min * 1000)) { trigger_pending = true; return false; } @@ -96,7 +138,7 @@ bool AP_Camera_Backend::take_picture() // trigger actually taking picture and update image count if (trigger_pic()) { image_index++; - last_photo_time_ms = now_ms; + last_picture_time_ms = now_ms; IGNORE_RETURN(AP::ahrs().get_location(last_location)); log_picture(); return true; @@ -105,6 +147,19 @@ bool AP_Camera_Backend::take_picture() return false; } +// take multiple pictures, time_interval between two consecutive pictures is in miliseconds +// total_num is number of pictures to be taken, -1 means capture forever +void AP_Camera_Backend::take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num) +{ + time_interval_settings = {time_interval_ms, total_num}; +} + +// stop capturing multiple image sequence +void AP_Camera_Backend::stop_capture() +{ + time_interval_settings = {0, 0}; +} + // handle camera control void AP_Camera_Backend::control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id) { @@ -174,7 +229,8 @@ void AP_Camera_Backend::send_camera_information(mavlink_channel_t chan) const 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] + cam_definition_uri, // cam_definition_uri char[140] + get_gimbal_device_id());// gimbal_device_id uint8_t } // send camera settings message to GCS @@ -268,7 +324,7 @@ void AP_Camera_Backend::prep_mavlink_msg_camera_feedback(uint64_t timestamp_us) camera_feedback.yaw_sensor = ahrs.yaw_sensor; camera_feedback.feedback_trigger_logged_count = feedback_trigger_logged_count; - gcs().send_message(MSG_CAMERA_FEEDBACK); + GCS_SEND_MESSAGE(MSG_CAMERA_FEEDBACK); } // log picture diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index f61a929196d851..5f8f8b1d78fb9c 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -56,6 +56,13 @@ class AP_Camera_Backend // take a picture. returns true on success bool take_picture(); + // take multiple pictures, time_interval between two consecutive pictures is in miliseconds + // total_num is number of pictures to be taken, -1 means capture forever + void take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num); + + // stop capturing multiple image sequence + void stop_capture(); + // entry point to actually take a picture. returns true on success virtual bool trigger_pic() = 0; @@ -75,6 +82,9 @@ class AP_Camera_Backend // p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom virtual bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) { return false; } + // set camera lens as a value from 0 to 5 + virtual bool set_lens(uint8_t lens) { return false; } + // handle MAVLink messages from the camera virtual void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) {} @@ -125,12 +135,24 @@ class AP_Camera_Backend uint32_t feedback_trigger_logged_count; // ID sequence number } camera_feedback; + // Picture settings + struct { + uint32_t time_interval_ms; // time interval (in miliseconds) between two consecutive pictures + int16_t num_remaining; // number of pictures still to be taken, -1 means take unlimited pictures + } time_interval_settings; + // Logging Function void log_picture(); void Write_Camera(uint64_t timestamp_us=0); void Write_Trigger(); void Write_CameraInfo(enum LogMessages msg, uint64_t timestamp_us=0); + // get corresponding mount instance for the camera + uint8_t get_mount_instance() const; + + // get mavlink gimbal device id which is normally mount_instance+1 + uint8_t get_gimbal_device_id() const; + // internal members uint8_t _instance; // this instance's number bool timer_installed; // true if feedback pin change detected using timer @@ -140,7 +162,7 @@ class AP_Camera_Backend uint32_t feedback_trigger_timestamp_us; // system time (in microseconds) that timer detected the feedback pin changed uint32_t feedback_trigger_logged_count; // number of times the feedback has been logged bool trigger_pending; // true if a call to take_pic() was delayed due to the minimum time interval time - uint32_t last_photo_time_ms; // system time that photo was last taken + uint32_t last_picture_time_ms; // system time that photo was last taken Location last_location; // Location that last picture was taken at (used for trigg_dist calculation) uint16_t image_index; // number of pictures taken since boot bool last_is_armed; // stores last arm/disarm state. true if it was armed lastly diff --git a/libraries/AP_Camera/AP_Camera_Logging.cpp b/libraries/AP_Camera/AP_Camera_Logging.cpp index f6a5e26541fe4c..903f42a8a8ab58 100644 --- a/libraries/AP_Camera/AP_Camera_Logging.cpp +++ b/libraries/AP_Camera/AP_Camera_Logging.cpp @@ -1,11 +1,12 @@ #include "AP_Camera_Backend.h" +#include #if AP_CAMERA_ENABLED #include #include -// Write a Camera packet +// Write a Camera packet. Also writes a Mount packet if available void AP_Camera_Backend::Write_CameraInfo(enum LogMessages msg, uint64_t timestamp_us) { // exit immediately if no logger @@ -41,9 +42,14 @@ void AP_Camera_Backend::Write_CameraInfo(enum LogMessages msg, uint64_t timestam altitude_gps = 0; } + // if timestamp is zero set to current system time + if (timestamp_us == 0) { + timestamp_us = AP_HAL::micros64(); + } + const struct log_Camera pkt{ LOG_PACKET_HEADER_INIT(static_cast(msg)), - time_us : timestamp_us ? timestamp_us : AP_HAL::micros64(), + time_us : timestamp_us, instance : _instance, image_number: image_index, gps_time : gps.time_week_ms(), @@ -58,6 +64,13 @@ void AP_Camera_Backend::Write_CameraInfo(enum LogMessages msg, uint64_t timestam yaw : (uint16_t)ahrs.yaw_sensor }; AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt)); + +#if HAL_MOUNT_ENABLED + auto *mount = AP_Mount::get_singleton(); + if (mount!= nullptr) { + mount->write_log(get_mount_instance(), timestamp_us); + } +#endif } // Write a Camera packet diff --git a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp index 37ed06a4b4893a..7a1caa214fbb9d 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp +++ b/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp @@ -176,7 +176,8 @@ void AP_Camera_MAVLinkCamV2::send_camera_information(mavlink_channel_t chan) con _cam_info.lens_id, // lens_id, uint8_t _cam_info.flags, // flags uint32_t (CAMERA_CAP_FLAGS) _cam_info.cam_definition_version, // cam_definition_version uint16_t - _cam_info.cam_definition_uri); // cam_definition_uri char[140] + _cam_info.cam_definition_uri, // cam_definition_uri char[140] + get_gimbal_device_id()); // gimbal_device_id uint8_t } // search for camera in GCS_MAVLink routing table diff --git a/libraries/AP_Camera/AP_Camera_Mount.cpp b/libraries/AP_Camera/AP_Camera_Mount.cpp index 7d2aafe4218ceb..e81327fb58201f 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.cpp +++ b/libraries/AP_Camera/AP_Camera_Mount.cpp @@ -10,8 +10,7 @@ bool AP_Camera_Mount::trigger_pic() { AP_Mount* mount = AP::mount(); if (mount != nullptr) { - mount->take_picture(0); - return true; + return mount->take_picture(get_mount_instance()); } return false; } @@ -22,7 +21,7 @@ bool AP_Camera_Mount::record_video(bool start_recording) { AP_Mount* mount = AP::mount(); if (mount != nullptr) { - return mount->record_video(0, start_recording); + return mount->record_video(get_mount_instance(), start_recording); } return false; } @@ -32,7 +31,7 @@ bool AP_Camera_Mount::set_zoom(ZoomType zoom_type, float zoom_value) { AP_Mount* mount = AP::mount(); if (mount != nullptr) { - return mount->set_zoom(0, zoom_type, zoom_value); + return mount->set_zoom(get_mount_instance(), zoom_type, zoom_value); } return false; } @@ -43,7 +42,7 @@ SetFocusResult AP_Camera_Mount::set_focus(FocusType focus_type, float focus_valu { AP_Mount* mount = AP::mount(); if (mount != nullptr) { - return mount->set_focus(0, focus_type, focus_value); + return mount->set_focus(get_mount_instance(), focus_type, focus_value); } return SetFocusResult::FAILED; } @@ -55,7 +54,18 @@ bool AP_Camera_Mount::set_tracking(TrackingType tracking_type, const Vector2f& p { AP_Mount* mount = AP::mount(); if (mount != nullptr) { - return mount->set_tracking(0, tracking_type, p1, p2); + return mount->set_tracking(get_mount_instance(), tracking_type, p1, p2); + } + return false; +} + + +// set camera lens as a value from 0 to 5 +bool AP_Camera_Mount::set_lens(uint8_t lens) +{ + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + return mount->set_lens(get_mount_instance(), lens); } return false; } @@ -65,7 +75,7 @@ void AP_Camera_Mount::send_camera_information(mavlink_channel_t chan) const { AP_Mount* mount = AP::mount(); if (mount != nullptr) { - return mount->send_camera_information(chan); + return mount->send_camera_information(get_mount_instance(), chan); } } @@ -74,7 +84,7 @@ void AP_Camera_Mount::send_camera_settings(mavlink_channel_t chan) const { AP_Mount* mount = AP::mount(); if (mount != nullptr) { - return mount->send_camera_settings(chan); + return mount->send_camera_settings(get_mount_instance(), chan); } } diff --git a/libraries/AP_Camera/AP_Camera_Mount.h b/libraries/AP_Camera/AP_Camera_Mount.h index 8cfb1f7016ac5c..fa53057295b8c2 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.h +++ b/libraries/AP_Camera/AP_Camera_Mount.h @@ -51,6 +51,9 @@ class AP_Camera_Mount : public AP_Camera_Backend // 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; + // set camera lens as a value from 0 to 5 + bool set_lens(uint8_t lens) override; + // send camera information message to GCS void send_camera_information(mavlink_channel_t chan) const override; diff --git a/libraries/AP_Camera/AP_Camera_Params.cpp b/libraries/AP_Camera/AP_Camera_Params.cpp index 8f64550bfd27ee..ee3f7796590ab7 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: 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), 5:MAVLink, 6:MAVLinkCamV2, 7:Scripting // @User: Standard AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Camera_Params, type, 0, AP_PARAM_FLAG_ENABLE), @@ -81,6 +81,12 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = { // @User: Standard AP_GROUPINFO("_OPTIONS", 10, AP_Camera_Params, options, 0), + // @Param: _MNT_INST + // @DisplayName: Camera Mount instance + // @Description: Mount instance camera is associated with. 0 means camera and mount have identical instance numbers e.g. camera1 and mount1 + // @User: Standard + AP_GROUPINFO("_MNT_INST", 11, AP_Camera_Params, mount_instance, 0), + AP_GROUPEND }; diff --git a/libraries/AP_Camera/AP_Camera_Params.h b/libraries/AP_Camera/AP_Camera_Params.h index 904252b69fe903..ca54550fe1ddbe 100644 --- a/libraries/AP_Camera/AP_Camera_Params.h +++ b/libraries/AP_Camera/AP_Camera_Params.h @@ -22,6 +22,7 @@ class AP_Camera_Params { AP_Int8 relay_on; // relay value to trigger camera AP_Float interval_min; // minimum time (in seconds) between shots required by camera AP_Int8 options; // whether to start recording when armed and stop when disarmed + AP_Int8 mount_instance; // mount instance to which camera is associated with // pin number for accurate camera feedback messages AP_Int8 feedback_pin; diff --git a/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp b/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp index 8041a5fb2c9ce7..06ecf6ee3ae268 100644 --- a/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp +++ b/libraries/AP_Camera/AP_Camera_SoloGimbal.cpp @@ -6,7 +6,7 @@ // Toggle the shutter on the GoPro // This is so ArduPilot can toggle the shutter directly, either for mission/GCS commands, or when the -// Solo's gimbal is installed on a vehicle other than a Solo. The usual GoPro controls thorugh the +// Solo's gimbal is installed on a vehicle other than a Solo. The usual GoPro controls through the // Solo app and Solo controller do not use this, as it is done offboard on the companion computer. // entry point to actually take a picture. returns true on success bool AP_Camera_SoloGimbal::trigger_pic() diff --git a/libraries/AP_Camera/AP_Camera_config.h b/libraries/AP_Camera/AP_Camera_config.h index c07645112ae270..565c344f31e808 100644 --- a/libraries/AP_Camera/AP_Camera_config.h +++ b/libraries/AP_Camera/AP_Camera_config.h @@ -3,6 +3,7 @@ #include #include #include +#include #ifndef AP_CAMERA_ENABLED #define AP_CAMERA_ENABLED 1 @@ -13,7 +14,7 @@ #endif #ifndef AP_CAMERA_MAVLINK_ENABLED -#define AP_CAMERA_MAVLINK_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED +#define AP_CAMERA_MAVLINK_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED #endif #ifndef AP_CAMERA_MAVLINKCAMV2_ENABLED diff --git a/libraries/AP_Camera/AP_RunCam.cpp b/libraries/AP_Camera/AP_RunCam.cpp index b278d4cc7cddc7..86e7dee57c6af8 100644 --- a/libraries/AP_Camera/AP_RunCam.cpp +++ b/libraries/AP_Camera/AP_RunCam.cpp @@ -29,11 +29,12 @@ #include #include #include +#include const AP_Param::GroupInfo AP_RunCam::var_info[] = { // @Param: TYPE // @DisplayName: RunCam device type - // @Description: RunCam deviee type used to determine OSD menu structure and shutter options. + // @Description: RunCam device type used to determine OSD menu structure and shutter options. // @Values: 0:Disabled, 1:RunCam Split Micro/RunCam with UART, 2:RunCam Split, 3:RunCam Split4 4k, 4:RunCam Hybrid/RunCam Thumb Pro, 5:Runcam 2 4k AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::Disabled), AP_PARAM_FLAG_ENABLE), @@ -263,7 +264,7 @@ void AP_RunCam::update_osd() { bool use_armed_state_machine = hal.util->get_soft_armed(); #if OSD_ENABLED - // prevent runcam stick gestures interferring with osd stick gestures + // prevent runcam stick gestures interfering with osd stick gestures if (!use_armed_state_machine) { const AP_OSD* osd = AP::osd(); if (osd != nullptr) { @@ -579,7 +580,7 @@ void AP_RunCam::handle_2_key_simulation_process(Event ev) case Event::IN_MENU_EXIT: // if we are in a sub-menu this will move us out, if we are in the root menu this will - // exit causing the state machine to get out of sync. the OSD menu hierachy is consistently + // exit causing the state machine to get out of sync. the OSD menu hierarchy is consistently // 2 deep so we can count and be reasonably confident of where we are. // the only exception is if someone hits save and exit on the root menu - then we are lost. if (_in_menu > 0) { @@ -957,11 +958,11 @@ void AP_RunCam::parse_device_info(const Request& request) } if (_features > 0) { _state = State::INITIALIZED; - gcs().send_text(MAV_SEVERITY_INFO, "RunCam initialized, features 0x%04X, %d-key OSD\n", _features.get(), + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "RunCam initialized, features 0x%04X, %d-key OSD\n", _features.get(), has_5_key_OSD() ? 5 : has_2_key_OSD() ? 2 : 0); } else { // nothing as as nothing does - gcs().send_text(MAV_SEVERITY_WARNING, "RunCam device not found\n"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "RunCam device not found\n"); } debug("RunCam: initialized state: video: %d, osd: %d, cam: %d\n", int(_video_recording), int(_osd_option), int(_cam_control_option)); } diff --git a/libraries/AP_Common/AP_Common.cpp b/libraries/AP_Common/AP_Common.cpp index 19c403c353bf0d..19f2002ac41214 100644 --- a/libraries/AP_Common/AP_Common.cpp +++ b/libraries/AP_Common/AP_Common.cpp @@ -22,6 +22,9 @@ extern const AP_HAL::HAL& hal; +/* assert that const vals are float, not double. so 100.0 means 100.0f */ +static_assert(sizeof(1e6) == sizeof(float), "Compilation needs to use single-precision constants"); + /* Return true if value is between lower and upper bound inclusive. False otherwise. diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index fb5225caaaa1c6..f466e99db23353 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -33,6 +33,7 @@ Location::Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, AltFr set_alt_cm(alt_in_cm, frame); } +#if AP_AHRS_ENABLED Location::Location(const Vector3f &ekf_offset_neu, AltFrame frame) { zero(); @@ -48,22 +49,7 @@ Location::Location(const Vector3f &ekf_offset_neu, AltFrame frame) offset(ekf_offset_neu.x * 0.01, ekf_offset_neu.y * 0.01); } } - -Location::Location(const Vector3d &ekf_offset_neu, AltFrame frame) -{ - zero(); - - // store alt and alt frame - set_alt_cm(ekf_offset_neu.z, frame); - - // calculate lat, lon - Location ekf_origin; - if (AP::ahrs().get_origin(ekf_origin)) { - lat = ekf_origin.lat; - lng = ekf_origin.lng; - offset(ekf_offset_neu.x * 0.01, ekf_offset_neu.y * 0.01); - } -} +#endif // AP_AHRS_ENABLED void Location::set_alt_cm(int32_t alt_cm, AltFrame frame) { @@ -157,12 +143,17 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const alt_abs = alt; break; case AltFrame::ABOVE_HOME: +#if AP_AHRS_ENABLED if (!AP::ahrs().home_is_set()) { return false; } alt_abs = alt + AP::ahrs().get_home().alt; +#else + return false; +#endif // AP_AHRS_ENABLED break; case AltFrame::ABOVE_ORIGIN: +#if AP_AHRS_ENABLED { // fail if we cannot get ekf origin Location ekf_origin; @@ -172,6 +163,9 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const alt_abs = alt + ekf_origin.alt; } break; +#else + return false; +#endif // AP_AHRS_ENABLED case AltFrame::ABOVE_TERRAIN: alt_abs = alt + alt_terr_cm; break; @@ -183,12 +177,17 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const ret_alt_cm = alt_abs; return true; case AltFrame::ABOVE_HOME: +#if AP_AHRS_ENABLED if (!AP::ahrs().home_is_set()) { return false; } ret_alt_cm = alt_abs - AP::ahrs().get_home().alt; +#else + return false; +#endif // AP_AHRS_ENABLED return true; case AltFrame::ABOVE_ORIGIN: +#if AP_AHRS_ENABLED { // fail if we cannot get ekf origin Location ekf_origin; @@ -198,6 +197,9 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const ret_alt_cm = alt_abs - ekf_origin.alt; return true; } +#else + return false; +#endif // AP_AHRS_ENABLED case AltFrame::ABOVE_TERRAIN: ret_alt_cm = alt_abs - alt_terr_cm; return true; @@ -205,6 +207,7 @@ bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const return false; // LCOV_EXCL_LINE - not reachable } +#if AP_AHRS_ENABLED bool Location::get_vector_xy_from_origin_NE(Vector2f &vec_ne) const { Location ekf_origin; @@ -232,6 +235,7 @@ bool Location::get_vector_from_origin_NEU(Vector3f &vec_neu) const return true; } +#endif // AP_AHRS_ENABLED // return horizontal distance in meters between two locations ftype Location::get_distance(const Location &loc2) const @@ -306,6 +310,14 @@ void Location::offset(ftype ofs_north, ftype ofs_east) offset_latlng(lat, lng, ofs_north, ofs_east); } +// extrapolate latitude/longitude given distances (in meters) north +// and east. Note that this is metres, *even for the altitude*. +void Location::offset(const Vector3p &ofs_ned) +{ + offset_latlng(lat, lng, ofs_ned.x, ofs_ned.y); + alt += -ofs_ned.z * 100; // m -> cm +} + /* * extrapolate latitude/longitude given bearing and distance * Note that this function is accurate to about 1mm at a distance of @@ -473,7 +485,7 @@ int32_t Location::diff_longitude(int32_t lon1, int32_t lon2) } /* - limit lattitude to -90e7 to 90e7 + limit latitude to -90e7 to 90e7 */ int32_t Location::limit_lattitude(int32_t lat) { diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index 122bead689b6c5..134a27e590af36 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -79,6 +79,9 @@ class Location // extrapolate latitude/longitude given distances (in meters) north and east static void offset_latlng(int32_t &lat, int32_t &lng, ftype ofs_north, ftype ofs_east); void offset(ftype ofs_north, ftype ofs_east); + // extrapolate latitude/longitude given distances (in meters) north + // and east. Note that this is metres, *even for the altitude*. + void offset(const Vector3p &ofs_ned); // extrapolate latitude/longitude given bearing and distance void offset_bearing(ftype bearing_deg, ftype distance); @@ -148,7 +151,7 @@ class Location // wrap longitude at -180e7 to 180e7 static int32_t wrap_longitude(int64_t lon); - // limit lattitude to -90e7 to 90e7 + // limit latitude to -90e7 to 90e7 static int32_t limit_lattitude(int32_t lat); // get lon1-lon2, wrapping at -180e7 to 180e7 diff --git a/libraries/AP_Common/tests/test_location.cpp b/libraries/AP_Common/tests/test_location.cpp index fa29927a567054..d545c2c754df14 100644 --- a/libraries/AP_Common/tests/test_location.cpp +++ b/libraries/AP_Common/tests/test_location.cpp @@ -63,7 +63,7 @@ TEST(Location, LatLngWrapping) int32_t expected_lat; int32_t expected_lng; } tests[] { - {519634000, 1797560000, Vector2f{0, 100000}, 519634000, -1787860775} + {519634000, 1797560000, Vector2f{0, 100000}, 519634000, -1787860777} }; for (auto &test : tests) { @@ -98,7 +98,7 @@ TEST(Location, LocOffsetDouble) -353632620, 1491652373, Vector2d{4682795.4576701336, 5953662.7673837934}, Vector2d{4682797.1904749088, 5953664.1586009059}, - Vector2d{1.7365739867091179,1.2050807}, + Vector2d{1.7365739,1.4261966}, }; for (auto &test : tests) { @@ -113,6 +113,19 @@ TEST(Location, LocOffsetDouble) } } +TEST(Location, LocOffset3DDouble) +{ + Location loc { + -353632620, 1491652373, 60000, Location::AltFrame::ABSOLUTE + }; + // this is ned, so our latitude should change, and our new + // location should be above the original: + loc.offset(Vector3d{1000, 0, -10}); + EXPECT_EQ(loc.lat, -353542788); + EXPECT_EQ(loc.lng, 1491652373); + EXPECT_EQ(loc.alt, 61000); +} + TEST(Location, Tests) { Location test_location; @@ -282,8 +295,10 @@ TEST(Location, Distance) EXPECT_VECTOR2F_EQ(Vector3f(0, 0, 0), test_home.get_distance_NED(test_home)); EXPECT_VECTOR2F_EQ(Vector3f(-11.131885, 0, 0), test_home.get_distance_NED(test_home2)); Location test_loc = test_home; - test_loc.offset(-11.131885, 0); + test_loc.offset(-11.131886, 0); EXPECT_TRUE(test_loc.same_latlon_as(test_home2)); + test_loc = test_home; + test_loc.offset(-11.131885, 0); test_loc.offset_bearing(0, 11.131885); EXPECT_TRUE(test_loc.same_latlon_as(test_home)); @@ -356,7 +371,7 @@ TEST(Location, Line) } /* - check if we obey basic euclidian geometry rules of position + check if we obey basic euclidean geometry rules of position addition/subtraction */ TEST(Location, OffsetError) diff --git a/libraries/AP_Common/tests/test_nmea_print.cpp b/libraries/AP_Common/tests/test_nmea_print.cpp index 139e55d6e8c28a..36e62134ef2409 100644 --- a/libraries/AP_Common/tests/test_nmea_print.cpp +++ b/libraries/AP_Common/tests/test_nmea_print.cpp @@ -30,7 +30,7 @@ static DummyUart test_uart; TEST(NMEA, Printf) { - // test not enought space + // test not enough space test_uart.set_txspace(2); EXPECT_FALSE(nmea_printf(&test_uart, "TEST")); // normal test diff --git a/libraries/AP_Common/tests/test_sorting.cpp b/libraries/AP_Common/tests/test_sorting.cpp index d44f3b14dce296..025a61294c88c6 100644 --- a/libraries/AP_Common/tests/test_sorting.cpp +++ b/libraries/AP_Common/tests/test_sorting.cpp @@ -10,6 +10,8 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX +typedef int (*compare_fn_t)(const void*, const void*); + static int comp16(const uint16_t *v1, const uint16_t *v2) { return int32_t(*v1) - int32_t(*v2); } @@ -32,7 +34,7 @@ TEST(Sorting, sort) a1[j] = a2[j] = unsigned(random()) % maxval; } insertion_sort_uint16(a1, n); - qsort(a2, n, sizeof(uint16_t), (__compar_fn_t)comp16); + qsort(a2, n, sizeof(uint16_t), (compare_fn_t)comp16); check_equal(a1, a2, n); } } diff --git a/libraries/AP_Common/tests/wscript b/libraries/AP_Common/tests/wscript index 067612ac36691a..555f58b53a4b0f 100644 --- a/libraries/AP_Common/tests/wscript +++ b/libraries/AP_Common/tests/wscript @@ -4,9 +4,5 @@ def build(bld): bld.ap_find_tests( use='ap', + DOUBLE_PRECISION_SOURCES = ['test_location.cpp'] ) - -# location test needs double precision -def configure(cfg): - cfg.env.DOUBLE_PRECISION_SOURCES['AP_Common'] = ['tests/test_location.cpp'] - diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 010b62428b6951..cab4a834d61a56 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -1176,12 +1176,10 @@ void Compass::_probe_external_i2c_compasses(void) // IST8310 on external and internal bus if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV5 && AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV6) { - enum Rotation default_rotation; + enum Rotation default_rotation = AP_COMPASS_IST8310_DEFAULT_ROTATION; if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_AEROFC) { default_rotation = ROTATION_PITCH_180_YAW_90; - } else { - default_rotation = ROTATION_PITCH_180; } // probe all 4 possible addresses const uint8_t ist8310_addr[] = { 0x0C, 0x0D, 0x0E, 0x0F }; diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index 9ccbea05820eff..fd37550b41d5eb 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -35,9 +35,6 @@ #endif #endif -#ifndef COMPASS_CAL_ENABLED -#define COMPASS_CAL_ENABLED 1 -#endif #ifndef COMPASS_MOT_ENABLED #define COMPASS_MOT_ENABLED 1 #endif @@ -196,7 +193,7 @@ friend class AP_Compass_Backend; /* handle an incoming MAG_CAL command */ - MAV_RESULT handle_mag_cal_command(const mavlink_command_long_t &packet); + MAV_RESULT handle_mag_cal_command(const mavlink_command_int_t &packet); bool send_mag_cal_progress(const class GCS_MAVLINK& link); bool send_mag_cal_report(const class GCS_MAVLINK& link); diff --git a/libraries/AP_Compass/AP_Compass_Backend.cpp b/libraries/AP_Compass/AP_Compass_Backend.cpp index bbca45ddb3a9e3..c0a7bf973eeaa1 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.cpp +++ b/libraries/AP_Compass/AP_Compass_Backend.cpp @@ -89,7 +89,7 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i) } #if AP_COMPASS_DIAGONALS_ENABLED - // apply eliptical correction + // apply elliptical correction if (!diagonals.is_zero()) { Matrix3f mat( diagonals.x, offdiagonals.x, offdiagonals.y, @@ -123,7 +123,7 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i) } /* - we apply the motor offsets after we apply the eliptical + we apply the motor offsets after we apply the elliptical correction. This is needed to match the way that the motor compensation values are calculated, as they are calculated based on final field outputs, not on the raw outputs @@ -251,7 +251,7 @@ void AP_Compass_Backend::set_rotation(uint8_t instance, enum Rotation rotation) static constexpr float FILTER_KOEF = 0.1f; /* Check that the compass value is valid by using a mean filter. If - * the value is further than filtrer_range from mean value, it is + * the value is further than filter_range from mean value, it is * rejected. */ bool AP_Compass_Backend::field_ok(const Vector3f &field) diff --git a/libraries/AP_Compass/AP_Compass_Backend.h b/libraries/AP_Compass/AP_Compass_Backend.h index 0faae415006f32..779d63f385ec17 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.h +++ b/libraries/AP_Compass/AP_Compass_Backend.h @@ -92,7 +92,7 @@ class AP_Compass_Backend * 2. publish_raw_field - this provides an uncorrected point-sample for * calibration libraries * 3. correct_field - this corrects the measurement in-place for hard iron, - * soft iron, motor interference, and non-orthagonality errors + * soft iron, motor interference, and non-orthogonality errors * 4. publish_filtered_field - legacy filtered magnetic field * * All those functions expect the mag field to be in milligauss. diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index b226e505fa23ac..ed8f338e549be9 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -57,7 +57,7 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay) #if COMPASS_MAX_INSTANCES > 1 if (_priority_did_list[prio] != _priority_did_stored_list[prio]) { - gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal requires reboot after priority change"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal requires reboot after priority change"); return false; } #endif @@ -65,14 +65,14 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay) if (_calibrator[prio] == nullptr) { _calibrator[prio] = new CompassCalibrator(); if (_calibrator[prio] == nullptr) { - gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal object not initialised"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal object not initialised"); return false; } } if (option_set(Option::CAL_REQUIRE_GPS)) { if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) { - gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal requires GPS lock"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Compass cal requires GPS lock"); return false; } } @@ -98,7 +98,7 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay) if (!_cal_thread_started) { _cal_requires_reboot = true; if (!hal.scheduler->thread_create(FUNCTOR_BIND(this, &Compass::_update_calibration_trampoline, void), "compasscal", 2048, AP_HAL::Scheduler::PRIORITY_IO, 0)) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "CompassCalibrator: Cannot start compass thread."); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "CompassCalibrator: Cannot start compass thread."); return false; } _cal_thread_started = true; @@ -240,6 +240,7 @@ bool Compass::_accept_calibration_mask(uint8_t mask) return success; } +#if HAL_GCS_ENABLED bool Compass::send_mag_cal_progress(const GCS_MAVLINK& link) { const mavlink_channel_t chan = link.get_chan(); @@ -329,6 +330,7 @@ bool Compass::send_mag_cal_report(const GCS_MAVLINK& link) } return true; } +#endif bool Compass::is_calibrating() const { @@ -371,7 +373,7 @@ uint8_t Compass::_get_cal_mask() /* handle an incoming MAG_CAL command */ -MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet) +MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_int_t &packet) { MAV_RESULT result = MAV_RESULT_FAILED; @@ -379,7 +381,7 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet) case MAV_CMD_DO_START_MAG_CAL: { result = MAV_RESULT_ACCEPTED; if (hal.util->get_soft_armed()) { - gcs().send_text(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration"); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration"); result = MAV_RESULT_FAILED; break; } @@ -392,7 +394,7 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet) bool retry = !is_zero(packet.param2); bool autosave = !is_zero(packet.param3); float delay = packet.param4; - bool autoreboot = !is_zero(packet.param5); + bool autoreboot = packet.x != 0; if (mag_mask == 0) { // 0 means all _reset_compass_id(); @@ -449,6 +451,9 @@ MAV_RESULT Compass::handle_mag_cal_command(const mavlink_command_long_t &packet) return result; } +#endif // COMPASS_CAL_ENABLED + +#if AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED /* get mag field with the effects of offsets, diagonals and off-diagonals removed @@ -459,8 +464,8 @@ bool Compass::get_uncorrected_field(uint8_t instance, Vector3f &field) const field = get_field(instance); #if AP_COMPASS_DIAGONALS_ENABLED - // form eliptical correction matrix and invert it. This is - // needed to remove the effects of the eliptical correction + // form elliptical correction matrix and invert it. This is + // needed to remove the effects of the elliptical correction // when calculating new offsets const Vector3f &diagonals = get_diagonals(instance); if (!diagonals.is_zero()) { @@ -508,7 +513,7 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask, // get AHRS position. If unavailable then try GPS location if (!AP::ahrs().get_location(loc)) { if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) { - gcs().send_text(MAV_SEVERITY_ERROR, "Mag: no position available"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag: no position available"); return MAV_RESULT_FAILED; } loc = AP::gps().location(); @@ -522,7 +527,7 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask, float declination; float inclination; if (!AP_Declination::get_mag_field_ef(lat_deg, lon_deg, intensity, declination, inclination)) { - gcs().send_text(MAV_SEVERITY_ERROR, "Mag: WMM table error"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag: WMM table error"); return MAV_RESULT_FAILED; } @@ -547,13 +552,13 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask, continue; } if (!healthy(i)) { - gcs().send_text(MAV_SEVERITY_ERROR, "Mag[%u]: unhealthy\n", i); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag[%u]: unhealthy\n", i); return MAV_RESULT_FAILED; } Vector3f measurement; if (!get_uncorrected_field(i, measurement)) { - gcs().send_text(MAV_SEVERITY_ERROR, "Mag[%u]: bad uncorrected field", i); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mag[%u]: bad uncorrected field", i); return MAV_RESULT_FAILED; } @@ -570,5 +575,4 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask, return MAV_RESULT_ACCEPTED; } - -#endif // COMPASS_CAL_ENABLED +#endif // AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp index fb35e62ccbad55..8563dd480bf9bd 100644 --- a/libraries/AP_Compass/AP_Compass_DroneCAN.cpp +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.cpp @@ -31,11 +31,8 @@ extern const AP_HAL::HAL& hal; AP_Compass_DroneCAN::DetectedModules AP_Compass_DroneCAN::_detected_modules[]; HAL_Semaphore AP_Compass_DroneCAN::_sem_registry; -AP_Compass_DroneCAN::AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid) - : _ap_dronecan(ap_dronecan) - , _node_id(node_id) - , _sensor_id(sensor_id) - , _devid(devid) +AP_Compass_DroneCAN::AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint32_t devid) : + _devid(devid) { } @@ -59,7 +56,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].node_id, _detected_modules[index].sensor_id, _detected_modules[index].devid); + driver = new AP_Compass_DroneCAN(_detected_modules[index].ap_dronecan, _detected_modules[index].devid); if (driver) { if (!driver->init()) { delete driver; @@ -96,7 +93,7 @@ AP_Compass_Backend* AP_Compass_DroneCAN::probe(uint8_t index) bool AP_Compass_DroneCAN::init() { - // Adding 1 is necessary to allow backward compatibilty, where this field was set as 1 by default + // Adding 1 is necessary to allow backward compatibility, where this field was set as 1 by default if (!register_compass(_devid, _instance)) { return false; } @@ -123,7 +120,7 @@ AP_Compass_DroneCAN* AP_Compass_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_d } bool already_detected = false; - // Check if there's an empty spot for possible registeration + // Check if there's an empty spot for possible registration for (uint8_t i = 0; i < COMPASS_MAX_BACKEND; i++) { if (_detected_modules[i].ap_dronecan == ap_dronecan && _detected_modules[i].node_id == node_id && diff --git a/libraries/AP_Compass/AP_Compass_DroneCAN.h b/libraries/AP_Compass/AP_Compass_DroneCAN.h index 61f677454ed680..f72d799579b8a8 100644 --- a/libraries/AP_Compass/AP_Compass_DroneCAN.h +++ b/libraries/AP_Compass/AP_Compass_DroneCAN.h @@ -10,7 +10,7 @@ class AP_Compass_DroneCAN : public AP_Compass_Backend { public: - AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t sensor_id, uint32_t devid); + AP_Compass_DroneCAN(AP_DroneCAN* ap_dronecan, uint32_t devid); void read(void) override; @@ -30,9 +30,6 @@ class AP_Compass_DroneCAN : public AP_Compass_Backend { uint8_t _instance; - AP_DroneCAN* _ap_dronecan; - uint8_t _node_id; - uint8_t _sensor_id; uint32_t _devid; // Module Detection Registry diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index eb304ac9b6a5d2..a9c3d4b10c1e67 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -38,7 +38,7 @@ extern const AP_HAL::HAL& hal; /* - * Defaul address: 0x1E + * Default address: 0x1E */ #define HMC5843_REG_CONFIG_A 0x00 diff --git a/libraries/AP_Compass/AP_Compass_IST8310.h b/libraries/AP_Compass/AP_Compass_IST8310.h index abc01e0df8891f..96d061a9c2d334 100644 --- a/libraries/AP_Compass/AP_Compass_IST8310.h +++ b/libraries/AP_Compass/AP_Compass_IST8310.h @@ -31,6 +31,10 @@ #define HAL_COMPASS_IST8310_I2C_ADDR 0x0E #endif +#ifndef AP_COMPASS_IST8310_DEFAULT_ROTATION +#define AP_COMPASS_IST8310_DEFAULT_ROTATION ROTATION_PITCH_180 +#endif + class AP_Compass_IST8310 : public AP_Compass_Backend { public: diff --git a/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp b/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp index 92cf47d4421089..d671f3deb5b796 100644 --- a/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp +++ b/libraries/AP_Compass/AP_Compass_MMC5xx3.cpp @@ -70,7 +70,7 @@ AP_Compass_MMC5XX3::AP_Compass_MMC5XX3(AP_HAL::OwnPtr _dev, bool AP_Compass_MMC5XX3::init() { - // take i2c bus sempahore + // take i2c bus semaphore WITH_SEMAPHORE(dev->get_semaphore()); dev->set_retries(10); diff --git a/libraries/AP_Compass/AP_Compass_SITL.cpp b/libraries/AP_Compass/AP_Compass_SITL.cpp index fc0f745287b79c..24687214931081 100644 --- a/libraries/AP_Compass/AP_Compass_SITL.cpp +++ b/libraries/AP_Compass/AP_Compass_SITL.cpp @@ -51,7 +51,7 @@ AP_Compass_SITL::AP_Compass_SITL() /* - create correction matrix for diagnonals and off-diagonals + create correction matrix for diagonals and off-diagonals */ void AP_Compass_SITL::_setup_eliptical_correcion(uint8_t i) { diff --git a/libraries/AP_Compass/AP_Compass_config.h b/libraries/AP_Compass/AP_Compass_config.h index 3fb16fe0d3837d..6bb8153b58389a 100644 --- a/libraries/AP_Compass/AP_Compass_config.h +++ b/libraries/AP_Compass/AP_Compass_config.h @@ -3,6 +3,8 @@ #include #include #include +#include +#include #ifndef AP_COMPASS_ENABLED #define AP_COMPASS_ENABLED 1 @@ -12,6 +14,17 @@ #define AP_COMPASS_DIAGONALS_ENABLED 1 #endif +#ifndef COMPASS_CAL_ENABLED +#define COMPASS_CAL_ENABLED AP_COMPASS_ENABLED && AP_AHRS_DCM_ENABLED +#endif + +#ifndef AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED +#define AP_COMPASS_CALIBRATION_FIXED_YAW_ENABLED AP_GPS_ENABLED +#endif + +#define COMPASS_MAX_SCALE_FACTOR 1.5 +#define COMPASS_MIN_SCALE_FACTOR (1.0/COMPASS_MAX_SCALE_FACTOR) + // Backend support #ifndef AP_COMPASS_BACKEND_DEFAULT_ENABLED #define AP_COMPASS_BACKEND_DEFAULT_ENABLED AP_COMPASS_ENABLED diff --git a/libraries/AP_Compass/CompassCalibrator.cpp b/libraries/AP_Compass/CompassCalibrator.cpp index 6b77cd9e70a24e..57a374987c5718 100644 --- a/libraries/AP_Compass/CompassCalibrator.cpp +++ b/libraries/AP_Compass/CompassCalibrator.cpp @@ -57,6 +57,10 @@ * http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm */ +#include "AP_Compass_config.h" + +#if COMPASS_CAL_ENABLED + #include "AP_Compass.h" #include "CompassCalibrator.h" #include @@ -1153,3 +1157,5 @@ bool CompassCalibrator::right_angle_rotation(Rotation r) const return false; } } + +#endif // COMPASS_CAL_ENABLED diff --git a/libraries/AP_Compass/CompassCalibrator.h b/libraries/AP_Compass/CompassCalibrator.h index 38437f2942da17..3b58159f346ac8 100644 --- a/libraries/AP_Compass/CompassCalibrator.h +++ b/libraries/AP_Compass/CompassCalibrator.h @@ -1,14 +1,15 @@ #pragma once +#include "AP_Compass_config.h" + +#if COMPASS_CAL_ENABLED + #include #define COMPASS_CAL_NUM_SPHERE_PARAMS 4 #define COMPASS_CAL_NUM_ELLIPSOID_PARAMS 9 #define COMPASS_CAL_NUM_SAMPLES 300 // number of samples required before fitting begins -#define COMPASS_MAX_SCALE_FACTOR 1.5 -#define COMPASS_MIN_SCALE_FACTOR (1.0/COMPASS_MAX_SCALE_FACTOR) - class CompassCalibrator { public: CompassCalibrator(); @@ -240,7 +241,7 @@ class CompassCalibrator { bool _is_external; // true if compass is external (provided by caller) bool _check_orientation; // true if orientation should be automatically checked bool _fix_orientation; // true if orientation should be fixed if necessary - bool _always_45_deg; // true if orentation should considder 45deg with equal tolerance + bool _always_45_deg; // true if orientation should consider 45deg with equal tolerance float _orientation_confidence; // measure of confidence in automatic orientation detection CompassSample _last_sample; @@ -255,3 +256,5 @@ class CompassCalibrator { // Semaphore for intermediate structure for point sample collection HAL_Semaphore sample_sem; }; + +#endif // COMPASS_CAL_ENABLED diff --git a/libraries/AP_Compass/Compass_learn.cpp b/libraries/AP_Compass/Compass_learn.cpp index 4ccda4f3be3b43..fe57f712e41936 100644 --- a/libraries/AP_Compass/Compass_learn.cpp +++ b/libraries/AP_Compass/Compass_learn.cpp @@ -15,7 +15,7 @@ extern const AP_HAL::HAL &hal; CompassLearn::CompassLearn(Compass &_compass) : compass(_compass) { - gcs().send_text(MAV_SEVERITY_INFO, "CompassLearn: Initialised"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CompassLearn: Initialised"); } // accuracy threshold applied for GSF yaw estimate @@ -64,7 +64,7 @@ void CompassLearn::update(void) if (result == MAV_RESULT_ACCEPTED) { AP_Notify::flags.compass_cal_running = false; compass.set_learn_type(Compass::LEARN_NONE, true); - gcs().send_text(MAV_SEVERITY_INFO, "CompassLearn: Finished"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "CompassLearn: Finished"); } } diff --git a/libraries/AP_DAL/AP_DAL.cpp b/libraries/AP_DAL/AP_DAL.cpp index 8942a6e46d170a..0e4f309fad0b86 100644 --- a/libraries/AP_DAL/AP_DAL.cpp +++ b/libraries/AP_DAL/AP_DAL.cpp @@ -377,7 +377,7 @@ void AP_DAL::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeSta } -// log wheel odomotry data +// log wheel odometry data void AP_DAL::writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius) { end_frame(); @@ -478,22 +478,22 @@ void AP_DAL::handle_message(const log_REVH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) } /* - handle wheel odomotry data + handle wheel odometry data */ void AP_DAL::handle_message(const log_RWOH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) { _RWOH = msg; - // note that EKF2 does not support wheel odomotry + // note that EKF2 does not support wheel odometry ekf3.writeWheelOdom(msg.delAng, msg.delTime, msg.timeStamp_ms, msg.posOffset, msg.radius); } /* - handle body frame odomotry + handle body frame odometry */ void AP_DAL::handle_message(const log_RBOH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) { _RBOH = msg; - // note that EKF2 does not support body frame odomotry + // note that EKF2 does not support body frame odometry ekf3.writeBodyFrameOdom(msg.quality, msg.delPos, msg.delAng, msg.delTime, msg.timeStamp_ms, msg.delay_ms, msg.posOffset); } @@ -503,7 +503,7 @@ void AP_DAL::handle_message(const log_RBOH &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) void AP_DAL::handle_message(const log_RSLL &msg, NavEKF2 &ekf2, NavEKF3 &ekf3) { _RSLL = msg; - // note that EKF2 does not support body frame odomotry + // note that EKF2 does not support body frame odometry const Location loc {msg.lat, msg.lng, 0, Location::AltFrame::ABSOLUTE }; ekf3.setLatLng(loc, msg.posAccSD, msg.timestamp_ms); } diff --git a/libraries/AP_DAL/AP_DAL.h b/libraries/AP_DAL/AP_DAL.h index ddf643bcf6e33b..671499b547baa2 100644 --- a/libraries/AP_DAL/AP_DAL.h +++ b/libraries/AP_DAL/AP_DAL.h @@ -215,7 +215,7 @@ class AP_DAL { void writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint16_t delay_ms, uint32_t resetTime_ms); void writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeStamp_ms, uint16_t delay_ms); - // log wheel odomotry data + // log wheel odometry data void writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius); void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, uint16_t delay_ms, const Vector3f &posOffset); diff --git a/libraries/AP_DAL/AP_DAL_RangeFinder.cpp b/libraries/AP_DAL/AP_DAL_RangeFinder.cpp index 8da66e1e25bc41..d7cee48bfa70dc 100644 --- a/libraries/AP_DAL/AP_DAL_RangeFinder.cpp +++ b/libraries/AP_DAL/AP_DAL_RangeFinder.cpp @@ -6,6 +6,7 @@ #include "AP_DAL.h" #include #include +#include AP_DAL_RangeFinder::AP_DAL_RangeFinder() { diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index a931a782bb47f6..4f962574f7a0e7 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -9,18 +9,35 @@ #include #include #include +#include +#include +#include +#if AP_EXTERNAL_CONTROL_ENABLED +#include "AP_DDS_ExternalControl.h" +#endif +#include "AP_DDS_Frames.h" #include "AP_DDS_Client.h" +#include "AP_DDS_Topic_Table.h" +#include "AP_DDS_Service_Table.h" +#include "AP_DDS_External_Odom.h" +// 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_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 char WGS_84_FRAME_ID[] = "WGS-84"; -// https://www.ros.org/reps/rep-0105.html#base-link -static char BASE_LINK_FRAME_ID[] = "base_link"; + +// 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. +sensor_msgs_msg_Joy AP_DDS_Client::rx_joy_topic {}; +tf2_msgs_msg_TFMessage AP_DDS_Client::rx_dynamic_transforms_topic {}; +geometry_msgs_msg_TwistStamped AP_DDS_Client::rx_velocity_control_topic {}; + const AP_Param::GroupInfo AP_DDS_Client::var_info[] { @@ -30,7 +47,7 @@ const AP_Param::GroupInfo AP_DDS_Client::var_info[] { // @Values: 0:Disabled,1:Enabled // @RebootRequired: True // @User: Advanced - AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_DDS_Client, enabled, 0, AP_PARAM_FLAG_ENABLE), + AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_DDS_Client, enabled, ENABLED_BY_DEFAULT, AP_PARAM_FLAG_ENABLE), #if AP_DDS_UDP_ENABLED // @Param: _UDP_PORT @@ -40,13 +57,12 @@ const AP_Param::GroupInfo AP_DDS_Client::var_info[] { // @RebootRequired: True // @User: Standard AP_GROUPINFO("_PORT", 2, AP_DDS_Client, udp.port, 2019), + #endif AP_GROUPEND }; -#include "AP_DDS_Topic_Table.h" - void AP_DDS_Client::update_topic(builtin_interfaces_msg_Time& msg) { uint64_t utc_usec; @@ -284,7 +300,7 @@ void AP_DDS_Client::update_topic(geometry_msgs_msg_PoseStamped& msg) // Z - Up // https://www.ros.org/reps/rep-0103.html#axis-orientation // As a consequence, to follow ROS REP 103, it is necessary to switch X and Y, - // as well as invert Z (NED to ENU convertion) as well as a 90 degree rotation in the Z axis + // as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis // for x to point forward Quaternion orientation; if (ahrs.get_quaternion(orientation)) { @@ -361,7 +377,7 @@ void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg) // Z - Up // https://www.ros.org/reps/rep-0103.html#axis-orientation // As a consequence, to follow ROS REP 103, it is necessary to switch X and Y, - // as well as invert Z (NED to ENU convertion) as well as a 90 degree rotation in the Z axis + // as well as invert Z (NED to ENU conversion) as well as a 90 degree rotation in the Z axis // for x to point forward Quaternion orientation; if (ahrs.get_quaternion(orientation)) { @@ -402,37 +418,164 @@ bool AP_DDS_Client::start(void) } // read function triggered at every subscription callback -void AP_DDS_Client::on_topic (uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length, void* args) +void AP_DDS_Client::on_topic_trampoline(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length, + void* args) +{ + AP_DDS_Client *dds = (AP_DDS_Client *)args; + dds->on_topic(uxr_session, object_id, request_id, stream_id, ub, length); +} + +void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length) { - (void) uxr_session; (void) object_id; (void) request_id; (void) stream_id; (void) length; /* TEMPLATE for reading to the subscribed topics 1) Store the read contents into the ucdr buffer 2) Deserialize the said contents into the topic instance */ - + (void) uxr_session; + (void) request_id; + (void) stream_id; + (void) length; switch (object_id.id) { - case topics[to_underlying(TopicIndex::JOY_SUB)].dr_id.id: - sensor_msgs_msg_Joy topic; - const bool success = sensor_msgs_msg_Joy_deserialize_topic(ub, &topic); + case topics[to_underlying(TopicIndex::JOY_SUB)].dr_id.id: { + const bool success = sensor_msgs_msg_Joy_deserialize_topic(ub, &rx_joy_topic); if (success == false) { break; } - uint32_t* count_ptr = (uint32_t*) args; - (*count_ptr)++; - if (topic.axes_size >= 4) { + if (rx_joy_topic.axes_size >= 4) { GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Received sensor_msgs/Joy: %f, %f, %f, %f", - topic.axes[0], topic.axes[1], topic.axes[2], topic.axes[3]); + 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,"Received sensor_msgs/Joy: Insufficient axes size "); } break; } + 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) { + break; + } + + if (rx_dynamic_transforms_topic.transforms_size > 0) { +#if AP_DDS_VISUALODOM_ENABLED + AP_DDS_External_Odom::handle_external_odom(rx_dynamic_transforms_topic); +#endif // AP_DDS_VISUALODOM_ENABLED + + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Received tf2_msgs/TFMessage: Insufficient size "); + } + break; + } + 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. + } +#endif // AP_EXTERNAL_CONTROL_ENABLED + break; + } + } } +/* + callback on request completion + */ +void AP_DDS_Client::on_request_trampoline(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length, void* args) +{ + AP_DDS_Client *dds = (AP_DDS_Client *)args; + dds->on_request(uxr_session, object_id, request_id, sample_id, ub, length); +} + +void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length) +{ + (void) request_id; + (void) length; + switch (object_id.id) { + case services[to_underlying(ServiceIndex::ARMING_MOTORS)].rep_id: { + bool arm; + bool result; + const bool deserialize_success = ucdr_deserialize_bool(ub,&arm); + if (deserialize_success == false) { + break; + } + + if (arm) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Request for arming received"); + result = AP::arming().arm(AP_Arming::Method::DDS); + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Request for disarming received"); + result = AP::arming().disarm(AP_Arming::Method::DDS); + } + + const uxrObjectId replier_id = { + .id = services[to_underlying(ServiceIndex::ARMING_MOTORS)].rep_id, + .type = UXR_REPLIER_ID + }; + + //Todo : Fix the size-handling of services with the help of the functions autogenerated via Micro-XRCE-DDS Gen + uint8_t reply_buffer[8] {}; + ucdrBuffer reply_ub; + + ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer)); + const bool serialize_success = ucdr_serialize_bool(&reply_ub,result); + if (serialize_success == false) { + break; + } + + uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub)); + if (result) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"DDS Client: Request for Arming/Disarming : SUCCESS"); + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"DDS Client: Request for Arming/Disarming : FAIL"); + } + break; + } + case services[to_underlying(ServiceIndex::MODE_SWITCH)].rep_id: { + uint8_t mode; + const bool deserialize_success = ucdr_deserialize_uint8_t(ub,&mode); + if (deserialize_success == false) { + break; + } + bool status = AP::vehicle()->set_mode(mode, ModeReason::DDS_COMMAND); + uint8_t curr_mode = AP::vehicle()->get_mode(); + + const uxrObjectId replier_id = { + .id = services[to_underlying(ServiceIndex::MODE_SWITCH)].rep_id, + .type = UXR_REPLIER_ID + }; + + //Todo : Fix the size-handling of services with the help of the functions autogenerated via Micro-XRCE-DDS Gen + uint8_t reply_buffer[8] {}; + ucdrBuffer reply_ub; + + ucdr_init_buffer(&reply_ub, reply_buffer, sizeof(reply_buffer)); + bool serialize_success = true; + serialize_success &= ucdr_serialize_bool(&reply_ub, status); + serialize_success &= ucdr_serialize_uint8_t(&reply_ub, curr_mode); + if (serialize_success == false || reply_ub.error) { + break; + } + + uxr_buffer_reply(uxr_session, reliable_out, replier_id, sample_id, reply_buffer, ucdr_buffer_length(&reply_ub)); + if (status) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"DDS Client: Request for Mode Switch : SUCCESS"); + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"DDS Client: Request for Mode Switch : FAIL"); + } + break; + } + } +} + /* main loop for DDS thread */ @@ -444,7 +587,7 @@ void AP_DDS_Client::main_loop(void) } GCS_SEND_TEXT(MAV_SEVERITY_INFO,"DDS Client: Initialization passed"); - populate_static_transforms(static_transforms_topic); + populate_static_transforms(tx_static_transforms_topic); write_static_transforms(); while (true) { @@ -472,7 +615,10 @@ bool AP_DDS_Client::init() } // Register topic callbacks - uxr_set_topic_callback(&session, AP_DDS_Client::on_topic, &count); + uxr_set_topic_callback(&session, AP_DDS_Client::on_topic_trampoline, this); + + // ROS-2 Service : Register service request callbacks + uxr_set_request_callback(&session, AP_DDS_Client::on_request_trampoline, this); while (!uxr_create_session(&session)) { GCS_SEND_TEXT(MAV_SEVERITY_INFO,"DDS Client: Initialization waiting..."); @@ -524,7 +670,7 @@ bool AP_DDS_Client::create() return false; } - for (size_t i = 0 ; i < ARRAY_SIZE(topics); i++) { + for (uint16_t i = 0 ; i < ARRAY_SIZE(topics); i++) { // Topic const uxrObjectId topic_id = { .id = topics[i].topic_id, @@ -536,7 +682,7 @@ bool AP_DDS_Client::create() // Status requests constexpr uint8_t nRequests = 3; uint16_t requests[nRequests]; - constexpr uint16_t requestTimeoutMs = (uint8_t) nRequests * maxTimeMsPerRequestMs; + constexpr uint16_t requestTimeoutMs = nRequests * maxTimeMsPerRequestMs; uint8_t status[nRequests]; if (strlen(topics[i].dw_profile_label) > 0) { @@ -558,14 +704,14 @@ bool AP_DDS_Client::create() requests[2] = dwriter_req_id; if (!uxr_run_session_until_all_status(&session, requestTimeoutMs, requests, status, nRequests)) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Topic/Pub/Writer session request failure for index 'TODO'"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Topic/Pub/Writer session request failure for index '%u'",i); for (uint8_t s = 0 ; s < nRequests; s++) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Status '%d' result '%u'", s, status[s]); } // TODO add a failure log message sharing the status results return false; } else { - GCS_SEND_TEXT(MAV_SEVERITY_INFO,"XRCE Client: Topic/Pub/Writer session pass for index 'TOOO'"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"XRCE Client: Topic/Pub/Writer session pass for index '%u'",i); } } else if (strlen(topics[i].dr_profile_label) > 0) { // Subscriber @@ -586,18 +732,51 @@ bool AP_DDS_Client::create() requests[2] = dreader_req_id; if (!uxr_run_session_until_all_status(&session, requestTimeoutMs, requests, status, nRequests)) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Topic/Sub/Reader session request failure for index '%d'",(int)i); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Topic/Sub/Reader session request failure for index '%u'",i); for (uint8_t s = 0 ; s < nRequests; s++) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Status '%d' result '%u'", s, status[s]); } // TODO add a failure log message sharing the status results return false; } else { - GCS_SEND_TEXT(MAV_SEVERITY_INFO,"XRCE Client: Topic/Sub/Reader session pass for index '%d'",(int)i); + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"XRCE Client: Topic/Sub/Reader session pass for index '%u'",i); uxr_buffer_request_data(&session, reliable_out, topics[i].dr_id, reliable_in, &delivery_control); } } } + + // ROS-2 Service : else case for service requests + + for (uint16_t i = 0; i < ARRAY_SIZE(services); i++) { + + constexpr uint16_t requestTimeoutMs = maxTimeMsPerRequestMs; + + if (strlen(services[i].rep_profile_label) > 0) { + 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); + + uint16_t request = replier_req_id; + uint8_t status; + + if (!uxr_run_session_until_all_status(&session, requestTimeoutMs, &request, &status, 1)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Service/Replier session request failure for index '%u'",i); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR,"XRCE Client: Status result '%u'", status); + // TODO add a failure log message sharing the status results + return false; + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"XRCE Client: Service/Replier session pass for index '%u'",i); + uxr_buffer_request_data(&session, reliable_out, rep_id, reliable_in, &delivery_control); + } + + } else if (strlen(services[i].req_profile_label) > 0) { + // TODO : Add Similar Code for Requester Profile + } + } + return true; } @@ -636,9 +815,9 @@ void AP_DDS_Client::write_static_transforms() WITH_SEMAPHORE(csem); if (connected) { ucdrBuffer ub {}; - const uint32_t topic_size = tf2_msgs_msg_TFMessage_size_of_topic(&static_transforms_topic, 0); + const uint32_t topic_size = tf2_msgs_msg_TFMessage_size_of_topic(&tx_static_transforms_topic, 0); uxr_prepare_output_stream(&session,reliable_out,topics[2].dw_id,&ub,topic_size); - const bool success = tf2_msgs_msg_TFMessage_serialize_topic(&ub, &static_transforms_topic); + const bool success = tf2_msgs_msg_TFMessage_serialize_topic(&ub, &tx_static_transforms_topic); if (!success) { // TODO sometimes serialization fails on bootup. Determine why. // AP_HAL::panic("FATAL: DDS_Client failed to serialize\n"); @@ -675,14 +854,14 @@ void AP_DDS_Client::write_local_pose_topic() } } -void AP_DDS_Client::write_local_velocity_topic() +void AP_DDS_Client::write_tx_local_velocity_topic() { WITH_SEMAPHORE(csem); if (connected) { ucdrBuffer ub {}; - const uint32_t topic_size = geometry_msgs_msg_TwistStamped_size_of_topic(&local_velocity_topic, 0); + const uint32_t topic_size = geometry_msgs_msg_TwistStamped_size_of_topic(&tx_local_velocity_topic, 0); uxr_prepare_output_stream(&session,reliable_out,topics[5].dw_id,&ub,topic_size); - const bool success = geometry_msgs_msg_TwistStamped_serialize_topic(&ub, &local_velocity_topic); + const bool success = geometry_msgs_msg_TwistStamped_serialize_topic(&ub, &tx_local_velocity_topic); if (!success) { // TODO sometimes serialization fails on bootup. Determine why. // AP_HAL::panic("FATAL: DDS_Client failed to serialize\n"); @@ -750,9 +929,9 @@ void AP_DDS_Client::update() } if (cur_time_ms - last_local_velocity_time_ms > DELAY_LOCAL_VELOCITY_TOPIC_MS) { - update_topic(local_velocity_topic); + update_topic(tx_local_velocity_topic); last_local_velocity_time_ms = cur_time_ms; - write_local_velocity_topic(); + write_tx_local_velocity_topic(); } if (cur_time_ms - last_geo_pose_time_ms > DELAY_GEO_POSE_TOPIC_MS) { @@ -787,7 +966,7 @@ int clock_gettime(clockid_t clockid, struct timespec *ts) ts->tv_nsec = (utc_usec % 1000000ULL) * 1000UL; return 0; } -#endif // CONFIG_HAL_BOARD +#endif // CONFIG_HAL_BOARD != HAL_BOARD_SITL #endif // AP_DDS_ENABLED diff --git a/libraries/AP_DDS/AP_DDS_Client.h b/libraries/AP_DDS/AP_DDS_Client.h index 084546c270de6c..de6a7e54acba80 100644 --- a/libraries/AP_DDS/AP_DDS_Client.h +++ b/libraries/AP_DDS/AP_DDS_Client.h @@ -23,14 +23,12 @@ #include "fcntl.h" #include +#include "AP_DDS_config.h" #define DDS_MTU 512 #define DDS_STREAM_HISTORY 8 #define DDS_BUFFER_SIZE DDS_MTU * DDS_STREAM_HISTORY -// UDP only on SITL for now -#define AP_DDS_UDP_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) - #if AP_DDS_UDP_ENABLED #include #endif @@ -54,16 +52,23 @@ class AP_DDS_Client uxrStreamId reliable_in; uxrStreamId reliable_out; - // Topic + // Outgoing Sensor and AHRS data builtin_interfaces_msg_Time time_topic; - sensor_msgs_msg_NavSatFix nav_sat_fix_topic; - tf2_msgs_msg_TFMessage static_transforms_topic; - sensor_msgs_msg_BatteryState battery_state_topic; - sensor_msgs_msg_Joy joy_topic; - geometry_msgs_msg_PoseStamped local_pose_topic; - geometry_msgs_msg_TwistStamped local_velocity_topic; geographic_msgs_msg_GeoPoseStamped geo_pose_topic; + geometry_msgs_msg_PoseStamped local_pose_topic; + geometry_msgs_msg_TwistStamped tx_local_velocity_topic; + sensor_msgs_msg_BatteryState battery_state_topic; + sensor_msgs_msg_NavSatFix nav_sat_fix_topic; rosgraph_msgs_msg_Clock clock_topic; + // incoming joystick data + static sensor_msgs_msg_Joy rx_joy_topic; + // incoming REP147 velocity control + static geometry_msgs_msg_TwistStamped rx_velocity_control_topic; + // outgoing transforms + tf2_msgs_msg_TFMessage tx_static_transforms_topic; + tf2_msgs_msg_TFMessage tx_dynamic_transforms_topic; + // incoming transforms + static tf2_msgs_msg_TFMessage rx_dynamic_transforms_topic; HAL_Semaphore csem; @@ -80,10 +85,12 @@ class AP_DDS_Client static void update_topic(rosgraph_msgs_msg_Clock& msg); // subscription callback function - static void on_topic(uxrSession* session, uxrObjectId object_id, uint16_t request_id, uxrStreamId stream_id, struct ucdrBuffer* ub, uint16_t length, void* args); + 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); - // count of subscribed samples - uint32_t count; + // service replier callback function + static void on_request_trampoline(uxrSession* session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length, void* args); + void on_request(uxrSession* session, uxrObjectId object_id, uint16_t request_id, SampleIdentity* sample_id, ucdrBuffer* ub, uint16_t length); // delivery control parameters uxrDeliveryControl delivery_control { @@ -164,7 +171,7 @@ class AP_DDS_Client //! @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_local_velocity_topic(); + 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 clock and publish to the IO stream(s) @@ -188,7 +195,21 @@ class AP_DDS_Client }; static const struct Topic_table topics[]; + //! @brief Convenience grouping for a single "channel" of services + struct Service_table { + //! @brief Request ID for the service + const uint8_t req_id; + + //! @brief Reply ID for the service + const uint8_t rep_id; + //! @brief Profile Label for the service requester + const char* req_profile_label; + + //! @brief Profile Label for the service replier + const char* rep_profile_label; + }; + static const struct Service_table services[]; }; #endif // AP_DDS_ENABLED diff --git a/libraries/AP_DDS/AP_DDS_ExternalControl.cpp b/libraries/AP_DDS/AP_DDS_ExternalControl.cpp new file mode 100644 index 00000000000000..a72536d6ffde84 --- /dev/null +++ b/libraries/AP_DDS/AP_DDS_ExternalControl.cpp @@ -0,0 +1,44 @@ +#if AP_DDS_ENABLED + +#include "AP_DDS_ExternalControl.h" +#include "AP_DDS_Frames.h" +#include + +#include + +bool AP_DDS_External_Control::handle_velocity_control(geometry_msgs_msg_TwistStamped& cmd_vel) +{ + auto *external_control = AP::externalcontrol(); + if (external_control == nullptr) { + return false; + } + + if (strcmp(cmd_vel.header.frame_id, BASE_LINK_FRAME_ID) == 0) { + // Convert commands from body frame (x-forward, y-left, z-up) to NED. + Vector3f linear_velocity; + Vector3f linear_velocity_base_link { + float(cmd_vel.twist.linear.x), + float(cmd_vel.twist.linear.y), + float(-cmd_vel.twist.linear.z) }; + const float yaw_rate = -cmd_vel.twist.angular.z; + + auto &ahrs = AP::ahrs(); + linear_velocity = ahrs.body_to_earth(linear_velocity_base_link); + return external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate); + } + + else if (strcmp(cmd_vel.header.frame_id, MAP_FRAME) == 0) { + // Convert commands from ENU to NED frame + Vector3f linear_velocity { + float(cmd_vel.twist.linear.y), + float(cmd_vel.twist.linear.x), + float(-cmd_vel.twist.linear.z) }; + const float yaw_rate = -cmd_vel.twist.angular.z; + return external_control->set_linear_velocity_and_yaw_rate(linear_velocity, yaw_rate); + } + + return false; +} + + +#endif // AP_DDS_ENABLED \ No newline at end of file diff --git a/libraries/AP_DDS/AP_DDS_ExternalControl.h b/libraries/AP_DDS/AP_DDS_ExternalControl.h new file mode 100644 index 00000000000000..dbffafdd81ad1c --- /dev/null +++ b/libraries/AP_DDS/AP_DDS_ExternalControl.h @@ -0,0 +1,11 @@ +#pragma once + +#if AP_DDS_ENABLED +#include "geometry_msgs/msg/TwistStamped.h" + +class AP_DDS_External_Control +{ +public: + static bool handle_velocity_control(geometry_msgs_msg_TwistStamped& cmd_vel); +}; +#endif // AP_DDS_ENABLED diff --git a/libraries/AP_DDS/AP_DDS_External_Odom.cpp b/libraries/AP_DDS/AP_DDS_External_Odom.cpp new file mode 100644 index 00000000000000..8d8563e5e866c3 --- /dev/null +++ b/libraries/AP_DDS/AP_DDS_External_Odom.cpp @@ -0,0 +1,76 @@ + + +#include "AP_DDS_External_Odom.h" +#include "AP_DDS_Type_Conversions.h" + +#if AP_DDS_VISUALODOM_ENABLED + +#include +#include + +void AP_DDS_External_Odom::handle_external_odom(const tf2_msgs_msg_TFMessage& msg) +{ + auto *visual_odom = AP::visualodom(); + if (visual_odom == nullptr) { + return; + } + + for (size_t i = 0; i < msg.transforms_size; i++) { + const auto& ros_transform_stamped = msg.transforms[i]; + if (!is_odometry_frame(ros_transform_stamped)) { + continue; + } + const uint64_t remote_time_us {AP_DDS_Type_Conversions::time_u64_micros(ros_transform_stamped.header.stamp)}; + + Vector3f ap_position; + Quaternion ap_rotation; + + convert_transform(ros_transform_stamped.transform, ap_position, ap_rotation); + // Although ROS convention states quaternions in ROS messages should be normalized, it's not guaranteed. + // Before propagating a potentially inaccurate quaternion to the rest of AP, normalize it here. + // TODO what if the quaternion is NaN? + ap_rotation.normalize(); + + // No error is available in TF, trust the data as-is + const float posErr {0.0}; + const float angErr {0.0}; + // The odom to base_link transform used is locally consistent per ROS REP-105. + // https://www.ros.org/reps/rep-0105.html#id16 + // Thus, there will not be any resets. + const uint8_t reset_counter {0}; + // TODO implement jitter correction similar to GCS_MAVLINK::correct_offboard_timestamp_usec_to_ms(remote_time_us, sizeof(msg)); + const uint32_t time_ms {static_cast(remote_time_us * 1E-3)}; + visual_odom->handle_pose_estimate(remote_time_us, time_ms, ap_position.x, ap_position.y, ap_position.z, ap_rotation, posErr, angErr, reset_counter); + + } +} + +bool AP_DDS_External_Odom::is_odometry_frame(const geometry_msgs_msg_TransformStamped& msg) +{ + char odom_parent[] = "odom"; + char odom_child[] = "base_link"; + // Assume the frame ID's are null terminated. + return (strcmp(msg.header.frame_id, odom_parent) == 0) && + (strcmp(msg.child_frame_id, odom_child) == 0); +} + +void AP_DDS_External_Odom::convert_transform(const geometry_msgs_msg_Transform& ros_transform, Vector3f& translation, Quaternion& rotation) +{ + // convert from x-forward, y-left, z-up to NED + // https://github.com/mavlink/mavros/issues/49#issuecomment-51614130 + translation = { + static_cast(ros_transform.translation.x), + static_cast(-ros_transform.translation.y), + static_cast(-ros_transform.translation.z) + }; + + // In AP, q1 is the quaternion's scalar component. + // In ROS, w is the quaternion's scalar component. + // https://docs.ros.org/en/humble/Tutorials/Intermediate/Tf2/Quaternion-Fundamentals.html#components-of-a-quaternion + rotation.q1 = ros_transform.rotation.w; + rotation.q2 = ros_transform.rotation.x; + rotation.q3 = -ros_transform.rotation.y; + rotation.q4 = -ros_transform.rotation.z; +} + +#endif // AP_DDS_VISUALODOM_ENABLED diff --git a/libraries/AP_DDS/AP_DDS_External_Odom.h b/libraries/AP_DDS/AP_DDS_External_Odom.h new file mode 100644 index 00000000000000..2cba26a16d327b --- /dev/null +++ b/libraries/AP_DDS/AP_DDS_External_Odom.h @@ -0,0 +1,33 @@ +// Class for handling external localization data. +// For historical reasons, it's called odometry to match AP_VisualOdom. + +#pragma once + +#include "AP_DDS_config.h" +#if AP_DDS_VISUALODOM_ENABLED + +#include "geometry_msgs/msg/TransformStamped.h" +#include "tf2_msgs/msg/TFMessage.h" +#include "AP_Math/vector3.h" +#include "AP_Math/quaternion.h" + +class AP_DDS_External_Odom +{ +public: + + // Handler for external position localization + static void handle_external_odom(const tf2_msgs_msg_TFMessage& msg); + + // Checks the child and parent frames match a set needed for external odom. + // Since multiple different transforms can be sent, this validates the specific transform is + // for odometry. + static bool is_odometry_frame(const geometry_msgs_msg_TransformStamped& msg); + + // Helper to convert from ROS transform to AP datatypes + // ros_transform is in ENU + // translation is in NED + static void convert_transform(const geometry_msgs_msg_Transform& ros_transform, Vector3f& translation, Quaternion& rotation); + +}; + +#endif // AP_DDS_VISUALODOM_ENABLED diff --git a/libraries/AP_DDS/AP_DDS_Frames.h b/libraries/AP_DDS/AP_DDS_Frames.h new file mode 100644 index 00000000000000..0bdaf354ec116f --- /dev/null +++ b/libraries/AP_DDS/AP_DDS_Frames.h @@ -0,0 +1,7 @@ +#pragma once + +static constexpr char WGS_84_FRAME_ID[] = "WGS-84"; +// https://www.ros.org/reps/rep-0105.html#base-link +static constexpr char BASE_LINK_FRAME_ID[] = "base_link"; +// https://www.ros.org/reps/rep-0105.html#map +static constexpr char MAP_FRAME[] = "map"; diff --git a/libraries/AP_DDS/AP_DDS_Service_Table.h b/libraries/AP_DDS/AP_DDS_Service_Table.h new file mode 100644 index 00000000000000..50611276a5539e --- /dev/null +++ b/libraries/AP_DDS/AP_DDS_Service_Table.h @@ -0,0 +1,27 @@ +#include "uxr/client/client.h" + +enum class ServiceIndex: uint8_t { + ARMING_MOTORS, + MODE_SWITCH +}; + +static inline constexpr uint8_t to_underlying(const ServiceIndex index) +{ + static_assert(sizeof(index) == sizeof(uint8_t)); + return static_cast(index); +} + +constexpr struct AP_DDS_Client::Service_table AP_DDS_Client::services[] = { + { + .req_id = to_underlying(ServiceIndex::ARMING_MOTORS), + .rep_id = to_underlying(ServiceIndex::ARMING_MOTORS), + .req_profile_label = "", + .rep_profile_label = "arm_motors__replier", + }, + { + .req_id = to_underlying(ServiceIndex::MODE_SWITCH), + .rep_id = to_underlying(ServiceIndex::MODE_SWITCH), + .req_profile_label = "", + .rep_profile_label = "mode_switch__replier", + }, +}; diff --git a/libraries/AP_DDS/AP_DDS_Topic_Table.h b/libraries/AP_DDS/AP_DDS_Topic_Table.h index 376bf9dfc1f7b0..8ce9507d08005d 100644 --- a/libraries/AP_DDS/AP_DDS_Topic_Table.h +++ b/libraries/AP_DDS/AP_DDS_Topic_Table.h @@ -20,6 +20,8 @@ enum class TopicIndex: uint8_t { GEOPOSE_PUB, CLOCK_PUB, JOY_SUB, + DYNAMIC_TRANSFORMS_SUB, + VELOCITY_CONTROL_SUB, }; static inline constexpr uint8_t to_underlying(const TopicIndex index) @@ -120,4 +122,24 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = { .dw_profile_label = "", .dr_profile_label = "joy__dr", }, + { + .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_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", + }, }; diff --git a/libraries/AP_DDS/AP_DDS_Type_Conversions.cpp b/libraries/AP_DDS/AP_DDS_Type_Conversions.cpp new file mode 100644 index 00000000000000..2aa4caf543f89b --- /dev/null +++ b/libraries/AP_DDS/AP_DDS_Type_Conversions.cpp @@ -0,0 +1,13 @@ +#include "AP_DDS_Type_Conversions.h" +#if AP_DDS_ENABLED + +#include "builtin_interfaces/msg/Time.h" + + +uint64_t AP_DDS_Type_Conversions::time_u64_micros(const builtin_interfaces_msg_Time& ros_time) +{ + return (uint64_t(ros_time.sec) * 1000000ULL) + (ros_time.nanosec / 1000ULL); +} + + +#endif // AP_DDS_ENABLED diff --git a/libraries/AP_DDS/AP_DDS_Type_Conversions.h b/libraries/AP_DDS/AP_DDS_Type_Conversions.h new file mode 100644 index 00000000000000..71b2e3182de299 --- /dev/null +++ b/libraries/AP_DDS/AP_DDS_Type_Conversions.h @@ -0,0 +1,17 @@ +// Class for handling type conversions for DDS. + +#pragma once + +#if AP_DDS_ENABLED + +#include "builtin_interfaces/msg/Time.h" + +class AP_DDS_Type_Conversions +{ +public: + + // Convert ROS time to a uint64_t [μS] + static uint64_t time_u64_micros(const builtin_interfaces_msg_Time& ros_time); +}; + +#endif // AP_DDS_ENABLED diff --git a/libraries/AP_DDS/AP_DDS_config.h b/libraries/AP_DDS/AP_DDS_config.h new file mode 100644 index 00000000000000..febd1a75423bec --- /dev/null +++ b/libraries/AP_DDS/AP_DDS_config.h @@ -0,0 +1,17 @@ +#pragma once + +#include + +#ifndef AP_DDS_ENABLED +#define AP_DDS_ENABLED 1 +#endif + +// UDP only on SITL for now +#ifndef AP_DDS_UDP_ENABLED +#define AP_DDS_UDP_ENABLED AP_DDS_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif + +#include +#ifndef AP_DDS_VISUALODOM_ENABLED +#define AP_DDS_VISUALODOM_ENABLED HAL_VISUALODOM_ENABLED && AP_DDS_ENABLED +#endif diff --git a/libraries/AP_DDS/Idl/ardupilot_msgs/srv/ArmMotors.idl b/libraries/AP_DDS/Idl/ardupilot_msgs/srv/ArmMotors.idl new file mode 100644 index 00000000000000..b4a8c877a991f0 --- /dev/null +++ b/libraries/AP_DDS/Idl/ardupilot_msgs/srv/ArmMotors.idl @@ -0,0 +1,20 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from ardupilot_msgs/srv/ArmMotors.srv +// generated code does not contain a copyright notice + + +module ardupilot_msgs { + module srv { + struct ArmMotors_Request { + @verbatim (language="comment", text= + "This service requests the vehicle to arm or disarm its motors." "\n" + "Set true to arm motors, false to disarm motors.") + boolean arm; + }; + @verbatim (language="comment", text= + "True if arming/disarming request for motors was successful , false otherwise. ") + struct ArmMotors_Response { + boolean result; + }; + }; +}; diff --git a/libraries/AP_DDS/Idl/ardupilot_msgs/srv/ModeSwitch.idl b/libraries/AP_DDS/Idl/ardupilot_msgs/srv/ModeSwitch.idl new file mode 100644 index 00000000000000..8c1eb7397d46b5 --- /dev/null +++ b/libraries/AP_DDS/Idl/ardupilot_msgs/srv/ModeSwitch.idl @@ -0,0 +1,26 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from ardupilot_msgs/srv/ModeSwitch.srv +// generated code does not contain a copyright notice + + +module ardupilot_msgs { + module srv { + struct ModeSwitch_Request { + @verbatim (language="comment", text= + "This service requests the vehicle to switch its drive/flight mode" "\n" + "mode : Set the value to the drive/flight mode to be used" "\n" + "Copter : https://mavlink.io/en/messages/ardupilotmega.html#COPTER_MODE" "\n" + "Rover : https://mavlink.io/en/messages/ardupilotmega.html#ROVER_MODE" "\n" + "Plane : https://mavlink.io/en/messages/ardupilotmega.html#PLANE_MODE") + uint8 mode; + }; + @verbatim (language="comment", text= + "status : True if the request for mode switch was successful, False otherwise" "\n" + "curr_mode : Returns the code for the current drive/flight mode , after the processing the request") + struct ModeSwitch_Response { + boolean status; + + uint8 curr_mode; + }; + }; +}; diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index f785c70f704176..3e893985992760 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -2,7 +2,7 @@ ## Architecture -Ardupilot contains the DDS Client library, which can run as SITL. Then, the DDS application runs a ROS2 node, an EProsima Integration Service, and the MicroXRCE Agent. The two systems communicate can communicate over serial or UDP. +Ardupilot contains the DDS Client library, which can run as SITL. Then, the DDS application runs a ROS 2 node, an eProsima Integration Service, and the MicroXRCE Agent. The two systems communicate over serial or UDP. ```mermaid --- @@ -18,7 +18,7 @@ graph LR end subgraph DDS Application - ros[ROS2 Node] <--> agent[Micro ROS Agent] + ros[ROS 2 Node] <--> agent[Micro ROS Agent] agent <-->port1[udp:2019] end @@ -41,7 +41,7 @@ graph LR end subgraph DDS Application - ros[ROS2 Node] <--> agent[Micro ROS Agent] + ros[ROS 2 Node] <--> agent[Micro ROS Agent] agent <--> port2[devUSB2] end @@ -84,7 +84,7 @@ While DDS support in Ardupilot is mostly through git submodules, another tool ne ``` > :warning: **If you have installed FastDDS or FastDDSGen globally on your system**: -eProsima's libraries and the packaging system in Ardupilot are not determistic in this scenario. +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) @@ -104,25 +104,28 @@ sudo apt-get install socat Set up your [SITL](https://ardupilot.org/dev/docs/setting-up-sitl-on-linux.html). Run the simulator with the following command. If using UDP, the only parameter you need to set it `DDS_ENABLE`. -| Name | Description | -| - | - | -| DDS_ENABLE | Set to 1 to enable DDS | -| SERIAL1_BAUD | The serial baud rate for DDS | -| SERIAL1_PROTOCOL | Set this to 45 to use DDS on the serial port | -```bash +| Name | Description | Default | +| - | - | - | +| 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 sim_vehicle.py -w -v ArduPlane --console -DG --enable-dds -# Enable DDS (both for UDP or Serial) -param set DDS_ENABLE 1 - -# Only for Serial +# Only set this for Serial, which means 115200 baud param set SERIAL1_BAUD 115 # See libraries/AP_SerialManager/AP_SerialManager.h AP_SerialManager SerialProtocol_DDS_XRCE param set SERIAL1_PROTOCOL 45 ``` -Because `DDS_ENABLE` requires a reboot, stop the simulator with ctrl+C and proceed to the next section. + +DDS is currently enabled by default, if it's part of the build. To disable it, run the following and reboot the simulator. +``` +param set DDS_ENABLE 0 +REBOOT +``` + ## Setup ROS 2 and micro-ROS Follow the steps to use the microROS Agent @@ -132,11 +135,11 @@ Follow the steps to use the microROS Agent - https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html - Install geographic_msgs - ```bash + ```console sudo apt install ros-humble-geographic-msgs ``` -- Install and run the microROS agent (as descibed here). Make sure to use the `humble` branch. +- Install and run the microROS agent (as described here). Make sure to use the `humble` branch. - Follow [the instructions](https://micro.ros.org/docs/tutorials/core/first_application_linux/) for the following: - Do "Installing ROS 2 and the micro-ROS build system" @@ -148,11 +151,11 @@ Follow the steps to use the microROS Agent Until this [PR](https://github.com/micro-ROS/micro-ROS.github.io/pull/401) is merged, ignore the notes about `foxy`. It works on `humble`. -## Using the ROS2 CLI to Read Ardupilot Data +## Using the ROS 2 CLI to Read Ardupilot Data After your setups are complete, do the following: -- Source the ros2 installation - ```bash +- Source the ROS 2 installation + ```console source /opt/ros/humble/setup.bash ``` @@ -161,77 +164,130 @@ Next, follow the associated section for your chosen transport, and finally you c ### UDP (recommended for SITL) - Run the microROS agent - ```bash + ```console cd ardupilot/libraries/AP_DDS ros2 run micro_ros_agent micro_ros_agent udp4 -p 2019 -r dds_xrce_profile.xml ``` - Run SITL (remember to kill any terminals running ardupilot SITL beforehand) - ```bash + ```console sim_vehicle.py -v ArduPlane -DG --console --enable-dds ``` ### Serial - Start a virtual serial port with socat. Take note of the two `/dev/pts/*` ports. If yours are different, substitute as needed. - ```bash + ```console socat -d -d pty,raw,echo=0 pty,raw,echo=0 >>> 2023/02/21 05:26:06 socat[334] N PTY is /dev/pts/1 >>> 2023/02/21 05:26:06 socat[334] N PTY is /dev/pts/2 >>> 2023/02/21 05:26:06 socat[334] N starting data transfer loop with FDs [5,5] and [7,7] ``` - Run the microROS agent - ```bash + ```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 ``` - Run SITL (remember to kill any terminals running ardupilot SITL beforehand) - ```bash + ```console # assuming we are using /dev/pts/1 for Ardupilot SITL sim_vehicle.py -v ArduPlane -DG --console --enable-dds -A "--uartC=uart:/dev/pts/1" ``` ## Use ROS 2 CLI -- You should be able to see the agent here and view the data output. - ```bash - $ ros2 node list - /Ardupilot_DDS_XRCE_Client - - $ ros2 topic list -v - Published topics: - * /ap/battery/battery0 [sensor_msgs/msg/BatteryState] 1 publisher - * /ap/clock [rosgraph_msgs/msg/Clock] 1 publisher - * /ap/geopose/filtered [geographic_msgs/msg/GeoPoseStamped] 1 publisher - * /ap/navsat/navsat0 [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 - * /ap/twist/filtered [geometry_msgs/msg/TwistStamped] 1 publisher - * /parameter_events [rcl_interfaces/msg/ParameterEvent] 1 publisher - * /rosout [rcl_interfaces/msg/Log] 1 publisher - - Subscribed topics: - * /ap/joy [sensor_msgs/msg/Joy] 1 subscriber - - $ ros2 topic hz /ap/time - average rate: 50.115 - min: 0.012s max: 0.024s std dev: 0.00328s window: 52 - - $ ros2 topic echo /ap/time - sec: 1678668735 - nanosec: 729410000 - --- - ``` +You should be able to see the agent here and view the data output. - The static transforms for enabled sensors are also published, and can be recieved like so: - ```console - ros2 topic echo /ap/tf_static --qos-depth 1 --qos-history keep_last --qos-reliability reliable --qos-durability transient_local --once - ``` - In order to consume the transforms, it's highly recommended to [create and run a transform broadcaster in ROS 2](https://docs.ros.org/en/humble/Concepts/About-Tf2.html#tutorials). +```bash +$ ros2 node list +/ardupilot_dds +``` +```bash +$ ros2 topic list -v +Published topics: + * /ap/battery/battery0 [sensor_msgs/msg/BatteryState] 1 publisher + * /ap/clock [rosgraph_msgs/msg/Clock] 1 publisher + * /ap/geopose/filtered [geographic_msgs/msg/GeoPoseStamped] 1 publisher + * /ap/navsat/navsat0 [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 + * /ap/twist/filtered [geometry_msgs/msg/TwistStamped] 1 publisher + * /parameter_events [rcl_interfaces/msg/ParameterEvent] 1 publisher + * /rosout [rcl_interfaces/msg/Log] 1 publisher + +Subscribed topics: + * /ap/cmd_vel [geometry_msgs/msg/TwistStamped] 1 subscriber + * /ap/joy [sensor_msgs/msg/Joy] 1 subscriber + * /tf [tf2_msgs/msg/TFMessage] 1 subscriber +``` + +```bash +$ ros2 topic hz /ap/time +average rate: 50.115 + min: 0.012s max: 0.024s std dev: 0.00328s window: 52 +``` + +```bash +$ ros2 topic echo /ap/time +sec: 1678668735 +nanosec: 729410000 +``` + +```bash +$ ros2 service list +/ap/arm_motors +/ap/mode_switch +--- +``` + +The static transforms for enabled sensors are also published, and can be received like so: + +```bash +ros2 topic echo /ap/tf_static --qos-depth 1 --qos-history keep_last --qos-reliability reliable --qos-durability transient_local --once +``` + +In order to consume the transforms, it's highly recommended to [create and run a transform broadcaster in ROS 2](https://docs.ros.org/en/humble/Concepts/About-Tf2.html#tutorials). + +## Using ROS 2 services + +The `AP_DDS` libraary 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 +the request / reply topics from DDS to ROS 2, but this is no longer required. + +List the available services: + +```bash +$ ros2 service list -t +/ap/arm_motors [ardupilot_msgs/srv/ArmMotors] +/ap/mode_switch [ardupilot_msgs/srv/ModeSwitch] +``` + +Call the arm motors service: + +```bash +$ ros2 service call /ap/arm_motors ardupilot_msgs/srv/ArmMotors "{arm: True}" +requester: making request: ardupilot_msgs.srv.ArmMotors_Request(arm=True) + +response: +ardupilot_msgs.srv.ArmMotors_Response(result=True) +``` + +Call the mode switch service: + +```bash +$ ros2 service call /ap/mode_switch ardupilot_msgs/srv/ModeSwitch "{mode: 4}" +requester: making request: ardupilot_msgs.srv.ModeSwitch_Request(mode=4) + +response: +ardupilot_msgs.srv.ModeSwitch_Response(status=True, curr_mode=4) +``` + +## Contributing to `AP_DDS` library -## Contributing to AP_DDS library ### Adding DDS messages to Ardupilot Unlike the use of ROS 2 `.msg` files, since Ardupilot supports native DDS, the message files follow [OMG IDL DDS v4.2](https://www.omg.org/spec/IDL/4.2/PDF). @@ -239,25 +295,77 @@ This package is intended to work with any `.idl` file complying with those exten Over time, these restrictions will ideally go away. -To get a new IDL file from ROS2, follow this process: -```console +To get a new IDL file from ROS 2, follow this process: + +```bash cd ardupilot source /opt/ros/humble/setup.bash + # Find the IDL file find /opt/ros/$ROS_DISTRO -type f -wholename \*builtin_interfaces/msg/Time.idl + # Create the directory in the source tree if it doesn't exist similar to the one found in the ros directory mkdir -p libraries/AP_DDS/Idl/builtin_interfaces/msg/ + # Copy the IDL cp /opt/ros/humble/share/builtin_interfaces/msg/Time.idl libraries/AP_DDS/Idl/builtin_interfaces/msg/ + # Build the code again with the `--enable-dds` flag as described above ``` +### Rules for adding topics and services to `dds_xrce_profile.xml` + +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`. + +#### 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: + +| ROS 2 | DDS | +| --- | --- | +| `rosgraph_msgs::msg::Clock` | `rosgraph_msgs::msg::dds_::Clock_` | +| `sensor_msgs::msg::NavSatFix` | `sensor_msgs::msg::dds_::NavSatFix_` | +| `ardupilot_msgs::srv::ArmMotors_Request` | `ardupilot_msgs::srv::dds_::ArmMotors_Request_` | +| `ardupilot_msgs::srv::ArmMotors_Response` | `ardupilot_msgs::srv::dds_::ArmMotors_Response_` | + +Note that a service interface always requires a Request / Response pair. + +#### ROS 2 topic and service names + +The ROS 2 design article: [Topic and Service name mapping to DDS](https://design.ros2.org/articles/topic_and_service_names.html) describes the mapping of ROS 2 topic and service +names to DDS. Each ROS 2 subsytem is provided a prefix when mapped to DDS. +The request / response pair for services require an additional suffix. + +| ROS 2 subsystem | DDS Prefix | DDS Suffix | +| --- | --- | --- | +| topics | rt/ | | +| service request | rq/ | Request | +| service response | rr/ | Reply | +| service | rs/ | | +| parameter | rp/ | | +| action | ra/ | | + +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/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. + ### 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). -```console +```bash ./Tools/CodeStyle/ardupilot-astyle.sh libraries/AP_DDS/*.h libraries/AP_DDS/*.cpp ``` @@ -266,7 +374,7 @@ This will run the tools automatically when you commit. If there are changes, jus 1. Install [pre-commit](https://pre-commit.com/#installation) python package. 1. Install ArduPilot's hooks in the root of the repo, then commit like normal - ```console + ```bash cd ardupilot pre-commit install git commit diff --git a/libraries/AP_DDS/dds_xrce_profile.xml b/libraries/AP_DDS/dds_xrce_profile.xml index 5cf78c37c6eedc..c97e6d9d11af0c 100644 --- a/libraries/AP_DDS/dds_xrce_profile.xml +++ b/libraries/AP_DDS/dds_xrce_profile.xml @@ -2,7 +2,7 @@ - Ardupilot_DDS_XRCE_Client + ardupilot_dds @@ -238,4 +238,42 @@ sensor_msgs::msg::dds_::Joy_ + + rt/tf + tf2_msgs::msg::dds_::TFMessage_ + + KEEP_LAST + 5 + + + + + NO_KEY + rt/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 + diff --git a/libraries/AP_DDS/tests/test_ap_dds_external_odom.cpp b/libraries/AP_DDS/tests/test_ap_dds_external_odom.cpp new file mode 100644 index 00000000000000..804d891e161806 --- /dev/null +++ b/libraries/AP_DDS/tests/test_ap_dds_external_odom.cpp @@ -0,0 +1,38 @@ +#include + +#include +#include "geometry_msgs/msg/TransformStamped.h" +#include + +const AP_HAL::HAL &hal = AP_HAL::get_HAL(); + +TEST(AP_DDS_EXTERNAL_ODOM, test_is_odometry_success) +{ + geometry_msgs_msg_TransformStamped msg {}; + + strncpy(msg.header.frame_id, "odom", strlen("odom") + 1); + strncpy(msg.child_frame_id, "base_link", strlen("base_link") + 1); + ASSERT_TRUE(AP_DDS_External_Odom::is_odometry_frame(msg)); + + strncpy(msg.header.frame_id, "invalid", strlen("invalid") + 1); + strncpy(msg.child_frame_id, "base_link", strlen("base_link") + 1); + ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg)); + + strncpy(msg.header.frame_id, "odom", strlen("odom") + 1); + strncpy(msg.child_frame_id, "invalid", strlen("invalid") + 1); + ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg)); + + strncpy(msg.header.frame_id, "odom_with_invalid_extra", strlen("odom_with_invalid_extra") + 1); + strncpy(msg.child_frame_id, "base_link", strlen("base_link") + 1); + ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg)); + + strncpy(msg.header.frame_id, "odom", strlen("odom") + 1); + strncpy(msg.child_frame_id, "base_link_with_invalid_extra", strlen("base_link_with_invalid_extra") + 1); + ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg)); + + strncpy(msg.header.frame_id, "x", strlen("x") + 1); + strncpy(msg.child_frame_id, "base_link", strlen("base_link") + 1); + ASSERT_FALSE(AP_DDS_External_Odom::is_odometry_frame(msg)); +} + +AP_GTEST_MAIN() diff --git a/libraries/AP_DDS/tests/test_ap_dds_type_conversions.cpp b/libraries/AP_DDS/tests/test_ap_dds_type_conversions.cpp new file mode 100644 index 00000000000000..f0b89f207d25f3 --- /dev/null +++ b/libraries/AP_DDS/tests/test_ap_dds_type_conversions.cpp @@ -0,0 +1,28 @@ +#include + +#include +#include "builtin_interfaces/msg/Time.h" +#include + + +const AP_HAL::HAL &hal = AP_HAL::get_HAL(); + +TEST(AP_DDS_TYPE_CONVERSIONS, test_time_u64_micros) +{ + builtin_interfaces_msg_Time ros_time {}; + ASSERT_EQ(AP_DDS_Type_Conversions::time_u64_micros(ros_time), 0UL); + + ros_time.sec = 5; + ASSERT_EQ(AP_DDS_Type_Conversions::time_u64_micros(ros_time), uint64_t(5E6)); + + ros_time.nanosec = 1000; + const uint64_t expected5 = uint64_t(5E6) + 1; + ASSERT_EQ(AP_DDS_Type_Conversions::time_u64_micros(ros_time), expected5); + + ros_time.sec = 7 * 24 * 60 * 60; // 1 week of runtime + ros_time.nanosec = 1000; + const uint64_t expected_long_runtime = uint64_t(ros_time.sec) * 1000000 + 1; + ASSERT_EQ(AP_DDS_Type_Conversions::time_u64_micros(ros_time), expected_long_runtime); +} + +AP_GTEST_MAIN() diff --git a/libraries/AP_DDS/tests/wscript b/libraries/AP_DDS/tests/wscript new file mode 100644 index 00000000000000..5f82c39f837b47 --- /dev/null +++ b/libraries/AP_DDS/tests/wscript @@ -0,0 +1,10 @@ +#!/usr/bin/env python3 + +def build(bld): + if not bld.env.ENABLE_DDS: + return + + bld.ap_find_tests( + use='ap', + DOUBLE_PRECISION_SOURCES = ['test_ap_dds_external_odom.cpp'] + ) diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index 57b2d7f234683d..540120564d8075 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.cpp +++ b/libraries/AP_DroneCAN/AP_Canard_iface.cpp @@ -90,7 +90,7 @@ bool CanardInterface::broadcast(const Canard::Transfer &bcast_transfer) { #if CANARD_ENABLE_CANFD .canfd = bcast_transfer.canfd, #endif - .deadline_usec = AP_HAL::native_micros64() + (bcast_transfer.timeout_ms * 1000), + .deadline_usec = AP_HAL::micros64() + (bcast_transfer.timeout_ms * 1000), #if CANARD_MULTI_IFACE .iface_mask = uint8_t((1<canard, txf, AP_HAL::native_micros64()); + canardHandleRxFrame(&canard_ifaces[0]->canard, txf, AP_HAL::micros64()); } canardPopTxQueue(&test_iface.canard); } @@ -242,7 +242,7 @@ void CanardInterface::processTx(bool raw_commands_only = false) { // top of the queue, so wait for the next loop break; } - if ((txf->iface_mask & (1U<deadline_usec)) { + if ((txf->iface_mask & (1U<deadline_usec)) { // try sending to interfaces, clearing the mask if we succeed if (ifaces[iface]->send(txmsg, txf->deadline_usec, 0) > 0) { txf->iface_mask &= ~(1U<delay_microseconds(1000); } #else - const uint64_t deadline = AP_HAL::native_micros64() + duration_ms*1000; + const uint64_t deadline = AP_HAL::micros64() + duration_ms*1000; while (true) { processRx(); processTx(); { WITH_SEMAPHORE(_sem_rx); WITH_SEMAPHORE(_sem_tx); - canardCleanupStaleTransfers(&canard, AP_HAL::native_micros64()); + canardCleanupStaleTransfers(&canard, AP_HAL::micros64()); } - uint64_t now = AP_HAL::native_micros64(); + uint64_t now = AP_HAL::micros64(); if (now < deadline) { _event_handle.wait(MIN(UINT16_MAX - 2U, deadline - now)); hal.scheduler->delay_microseconds(50); diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index d3921e42571625..c980c413cc03e8 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -34,6 +34,7 @@ #include #include #include +#include #include #include #include @@ -71,6 +72,8 @@ extern const AP_HAL::HAL& hal; #define AP_DRONECAN_VOLZ_FEEDBACK_ENABLED 0 #endif +#define AP_DRONECAN_GETSET_TIMEOUT_MS 100 // timeout waiting for response from node after 0.1 sec + #define debug_dronecan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "DroneCAN", fmt, ##args); } while (0) // Translation of all messages from DroneCAN structures into AP structures is done @@ -127,7 +130,7 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { // @Param: ESC_OF // @DisplayName: ESC Output channels offset - // @Description: Offset for ESC numbering in DroneCAN ESC RawCommand messages. This allows for more efficient packing of ESC command messages. If your ESCs are on servo functions 5 to 8 and you set this parameter to 4 then the ESC RawCommand will be sent with the first 4 slots filled. This can be used for more efficint usage of CAN bandwidth + // @Description: Offset for ESC numbering in DroneCAN ESC RawCommand messages. This allows for more efficient packing of ESC command messages. If your ESCs are on servo functions 5 to 8 and you set this parameter to 4 then the ESC RawCommand will be sent with the first 4 slots filled. This can be used for more efficient usage of CAN bandwidth // @Range: 0 18 // @User: Advanced AP_GROUPINFO("ESC_OF", 7, AP_DroneCAN, _esc_offset, 0), @@ -138,6 +141,13 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { // @Range: 1024 16384 // @User: Advanced AP_GROUPINFO("POOL", 8, AP_DroneCAN, _pool_size, DRONECAN_NODE_POOL_SIZE), + + // @Param: ESC_RV + // @DisplayName: Bitmask for output channels for reversible ESCs over DroneCAN. + // @Description: Bitmask with one set for each output channel that uses a reversible ESC over DroneCAN. Reversible ESCs use both positive and negative values in RawCommands, with positive commanding the forward direction and negative commanding the reverse direction. + // @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32 + // @User: Advanced + AP_GROUPINFO("ESC_RV", 9, AP_DroneCAN, _esc_rv, 0), AP_GROUPEND }; @@ -149,7 +159,7 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { AP_DroneCAN::AP_DroneCAN(const int driver_index) : _driver_index(driver_index), canard_iface(driver_index), -_dna_server(*this) +_dna_server(*this, canard_iface, driver_index) { AP_Param::setup_object_defaults(this, var_info); @@ -230,7 +240,9 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) } // Roundup all subscribers from supported drivers +#if AP_GPS_DRONECAN_ENABLED AP_GPS_DroneCAN::subscribe_msgs(this); +#endif #if AP_COMPASS_DRONECAN_ENABLED AP_Compass_DroneCAN::subscribe_msgs(this); #endif @@ -247,6 +259,9 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) #if AP_RANGEFINDER_DRONECAN_ENABLED AP_RangeFinder_DroneCAN::subscribe_msgs(this); #endif +#if AP_RCPROTOCOL_DRONECAN_ENABLED + AP_RCProtocol_DroneCAN::subscribe_msgs(this); +#endif #if AP_EFI_DRONECAN_ENABLED AP_EFI_DroneCAN::subscribe_msgs(this); #endif @@ -269,9 +284,11 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) esc_hobbywing_raw.set_timeout_ms(2); esc_hobbywing_raw.set_priority(CANARD_TRANSFER_PRIORITY_HIGH); #endif - + +#if AP_DRONECAN_HIMARK_SERVO_SUPPORT himark_out.set_timeout_ms(2); himark_out.set_priority(CANARD_TRANSFER_PRIORITY_HIGH); +#endif rgb_led.set_timeout_ms(20); rgb_led.set_priority(CANARD_TRANSFER_PRIORITY_LOW); @@ -368,12 +385,13 @@ void AP_DroneCAN::loop(void) safety_state_send(); notify_state_send(); + check_parameter_callback_timeout(); send_parameter_request(); send_parameter_save_request(); send_node_status(); _dna_server.verify_nodes(); -#if AP_DRONECAN_SEND_GPS +#if AP_DRONECAN_SEND_GPS && AP_GPS_DRONECAN_ENABLED if (option_is_set(AP_DroneCAN::Options::SEND_GNSS) && !AP_GPS_DroneCAN::instance_exists(this)) { // send if enabled and this interface/driver is not used by the AP_GPS driver gnss_send_fix(); @@ -386,13 +404,16 @@ void AP_DroneCAN::loop(void) #endif if (_SRV_armed_mask != 0) { // we have active servos - uint32_t now = AP_HAL::native_micros(); + uint32_t now = AP_HAL::micros(); const uint32_t servo_period_us = 1000000UL / unsigned(_servo_rate_hz.get()); if (now - _SRV_last_send_us >= servo_period_us) { _SRV_last_send_us = now; +#if AP_DRONECAN_HIMARK_SERVO_SUPPORT if (option_is_set(Options::USE_HIMARK_SERVO)) { SRV_send_himark(); - } else { + } else +#endif + { SRV_send_actuator(); } for (uint8_t i = 0; i < DRONECAN_SRV_NUMBER; i++) { @@ -480,7 +501,7 @@ void AP_DroneCAN::handle_hobbywing_StatusMsg2(const CanardRxTransfer& transfer, void AP_DroneCAN::send_node_status(void) { - const uint32_t now = AP_HAL::native_millis(); + const uint32_t now = AP_HAL::millis(); if (now - _node_status_last_send_ms < 1000) { return; } @@ -528,11 +549,25 @@ void AP_DroneCAN::send_node_status(void) void AP_DroneCAN::handle_node_info_request(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoRequest& req) { node_info_rsp.status = node_status_msg; - node_info_rsp.status.uptime_sec = AP_HAL::native_millis() / 1000; + node_info_rsp.status.uptime_sec = AP_HAL::millis() / 1000; node_info_server.respond(transfer, node_info_rsp); } +int16_t AP_DroneCAN::scale_esc_output(uint8_t idx){ + static const int16_t cmd_max = ((1<<13)-1); + float scaled = 0; + + //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)); + } 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); + } + + return static_cast(scaled); +} ///// SRV output ///// @@ -592,6 +627,7 @@ void AP_DroneCAN::SRV_send_actuator(void) } while (repeat_send); } +#if AP_DRONECAN_HIMARK_SERVO_SUPPORT /* Himark servo output. This uses com.himark.servo.ServoCmd packets */ @@ -623,10 +659,10 @@ void AP_DroneCAN::SRV_send_himark(void) himark_out.broadcast(msg); } +#endif // AP_DRONECAN_HIMARK_SERVO_SUPPORT void AP_DroneCAN::SRV_send_esc(void) { - static const int cmd_max = ((1<<13)-1); uavcan_equipment_esc_RawCommand esc_msg; uint8_t active_esc_num = 0, max_esc_num = 0; @@ -651,12 +687,7 @@ void AP_DroneCAN::SRV_send_esc(void) for (uint8_t i = esc_offset; i < max_esc_num && k < 20; i++) { if ((((uint32_t) 1) << i) & _ESC_armed_mask) { - // TODO: ESC negative scaling for reverse thrust and reverse rotation - float scaled = cmd_max * (hal.rcout->scale_esc_to_unity(_SRV_conf[i].pulse) + 1.0) / 2.0; - - scaled = constrain_float(scaled, 0, cmd_max); - - esc_msg.cmd.data[k] = static_cast(scaled); + esc_msg.cmd.data[k] = scale_esc_output(i); } else { esc_msg.cmd.data[k] = static_cast(0); } @@ -685,7 +716,6 @@ void AP_DroneCAN::SRV_send_esc(void) */ void AP_DroneCAN::SRV_send_esc_hobbywing(void) { - static const int cmd_max = ((1<<13)-1); com_hobbywing_esc_RawCommand esc_msg; uint8_t active_esc_num = 0, max_esc_num = 0; @@ -710,12 +740,7 @@ void AP_DroneCAN::SRV_send_esc_hobbywing(void) for (uint8_t i = esc_offset; i < max_esc_num && k < 20; i++) { if ((((uint32_t) 1) << i) & _ESC_armed_mask) { - // TODO: ESC negative scaling for reverse thrust and reverse rotation - float scaled = cmd_max * (hal.rcout->scale_esc_to_unity(_SRV_conf[i].pulse) + 1.0) / 2.0; - - scaled = constrain_float(scaled, 0, cmd_max); - - esc_msg.command.data[k] = static_cast(scaled); + esc_msg.command.data[k] = scale_esc_output(i); } else { esc_msg.command.data[k] = static_cast(0); } @@ -781,7 +806,7 @@ void AP_DroneCAN::SRV_push_servos() // notify state send void AP_DroneCAN::notify_state_send() { - uint32_t now = AP_HAL::native_millis(); + uint32_t now = AP_HAL::millis(); if (_notify_state_hz == 0 || (now - _last_notify_state_ms) < uint32_t(1000 / _notify_state_hz)) { return; @@ -876,7 +901,7 @@ void AP_DroneCAN::notify_state_send() } msg.aux_data.len = 2; notify_state.broadcast(msg); - _last_notify_state_ms = AP_HAL::native_millis(); + _last_notify_state_ms = AP_HAL::millis(); } #if AP_DRONECAN_SEND_GPS @@ -898,7 +923,7 @@ void AP_DroneCAN::gnss_send_fix() const Location &loc = gps.location(); const Vector3f &vel = gps.velocity(); - pkt.timestamp.usec = AP_HAL::native_micros64(); + pkt.timestamp.usec = AP_HAL::micros64(); pkt.gnss_timestamp.usec = gps.time_epoch_usec(); if (pkt.gnss_timestamp.usec == 0) { pkt.gnss_time_standard = UAVCAN_EQUIPMENT_GNSS_FIX2_GNSS_TIME_STANDARD_NONE; @@ -966,7 +991,7 @@ void AP_DroneCAN::gnss_send_fix() - const uint32_t now_ms = AP_HAL::native_millis(); + const uint32_t now_ms = AP_HAL::millis(); if (now_ms - _gnss.last_send_status_ms >= 1000) { _gnss.last_send_status_ms = now_ms; @@ -1031,7 +1056,7 @@ void AP_DroneCAN::gnss_send_yaw() // SafetyState send void AP_DroneCAN::safety_state_send() { - uint32_t now = AP_HAL::native_millis(); + uint32_t now = AP_HAL::millis(); if (now - _last_safety_state_ms < 500) { // update at 2Hz return; @@ -1154,7 +1179,7 @@ void AP_DroneCAN::handle_traffic_report(const CanardRxTransfer& transfer, const pkt.flags |= ADSB_FLAGS_BARO_VALID; } - vehicle.last_update_ms = AP_HAL::native_millis() - (vehicle.info.tslc * 1000); + vehicle.last_update_ms = AP_HAL::millis() - (vehicle.info.tslc * 1000); adsb->handle_adsb_vehicle(vehicle); #endif } @@ -1165,7 +1190,7 @@ void AP_DroneCAN::handle_traffic_report(const CanardRxTransfer& transfer, const void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg) { // log as CSRV message - AP::logger().Write_ServoStatus(AP_HAL::native_micros64(), + AP::logger().Write_ServoStatus(AP_HAL::micros64(), msg.actuator_id, msg.position, msg.force, @@ -1174,13 +1199,14 @@ void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const 0, 0, 0, 0, 0, 0); } +#if AP_DRONECAN_HIMARK_SERVO_SUPPORT /* handle himark ServoInfo message */ void AP_DroneCAN::handle_himark_servoinfo(const CanardRxTransfer& transfer, const com_himark_servo_ServoInfo &msg) { // log as CSRV message - AP::logger().Write_ServoStatus(AP_HAL::native_micros64(), + AP::logger().Write_ServoStatus(AP_HAL::micros64(), msg.servo_id, msg.pos_sensor*0.01, 0, @@ -1193,6 +1219,7 @@ void AP_DroneCAN::handle_himark_servoinfo(const CanardRxTransfer& transfer, cons msg.pcb_temp*0.2-40, msg.error_status); } +#endif // AP_DRONECAN_HIMARK_SERVO_SUPPORT #if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer, const com_volz_servo_ActuatorStatus& msg) @@ -1203,7 +1230,7 @@ void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer, "s#dAv%O", "F-00000", "QBfffBh", - AP_HAL::native_micros64(), + AP_HAL::micros64(), msg.actuator_id, ToDeg(msg.actual_position), msg.current * 0.025f, @@ -1264,6 +1291,31 @@ void AP_DroneCAN::handle_debug(const CanardRxTransfer& transfer, const uavcan_pr #endif } +/* + check for parameter get/set response timeout +*/ +void AP_DroneCAN::check_parameter_callback_timeout() +{ + WITH_SEMAPHORE(_param_sem); + + // return immediately if not waiting for get/set parameter response + if (param_request_sent_ms == 0) { + return; + } + + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - param_request_sent_ms > AP_DRONECAN_GETSET_TIMEOUT_MS) { + param_request_sent_ms = 0; + param_int_cb = nullptr; + param_float_cb = nullptr; + param_string_cb = nullptr; + } +} + +/* + send any queued request to get/set parameter + called from loop +*/ void AP_DroneCAN::send_parameter_request() { WITH_SEMAPHORE(_param_sem); @@ -1274,12 +1326,17 @@ void AP_DroneCAN::send_parameter_request() param_request_sent = true; } +/* + set named float parameter on node +*/ bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, float value, ParamGetSetFloatCb *cb) { WITH_SEMAPHORE(_param_sem); + + // fail if waiting for any previous get/set request if (param_int_cb != nullptr || - param_float_cb != nullptr) { - //busy + param_float_cb != nullptr || + param_string_cb != nullptr) { return false; } param_getset_req.index = 0; @@ -1288,16 +1345,22 @@ bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, float param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE; param_float_cb = cb; param_request_sent = false; + param_request_sent_ms = AP_HAL::millis(); param_request_node_id = node_id; return true; } +/* + set named integer parameter on node +*/ bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, int32_t value, ParamGetSetIntCb *cb) { WITH_SEMAPHORE(_param_sem); + + // fail if waiting for any previous get/set request if (param_int_cb != nullptr || - param_float_cb != nullptr) { - //busy + param_float_cb != nullptr || + param_string_cb != nullptr) { return false; } param_getset_req.index = 0; @@ -1306,16 +1369,46 @@ bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, int32 param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; param_int_cb = cb; param_request_sent = false; + param_request_sent_ms = AP_HAL::millis(); + param_request_node_id = node_id; + return true; +} + +/* + set named string parameter on node +*/ +bool AP_DroneCAN::set_parameter_on_node(uint8_t node_id, const char *name, const string &value, ParamGetSetStringCb *cb) +{ + WITH_SEMAPHORE(_param_sem); + + // fail if waiting for any previous get/set request + if (param_int_cb != nullptr || + param_float_cb != nullptr || + param_string_cb != nullptr) { + return false; + } + param_getset_req.index = 0; + param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data)-1); + memcpy(¶m_getset_req.value.string_value, (const void*)&value, sizeof(value)); + param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE; + param_string_cb = cb; + param_request_sent = false; + param_request_sent_ms = AP_HAL::millis(); param_request_node_id = node_id; return true; } +/* + get named float parameter on node +*/ bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetFloatCb *cb) { WITH_SEMAPHORE(_param_sem); + + // fail if waiting for any previous get/set request if (param_int_cb != nullptr || - param_float_cb != nullptr) { - //busy + param_float_cb != nullptr || + param_string_cb != nullptr) { return false; } param_getset_req.index = 0; @@ -1323,16 +1416,22 @@ bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, Param param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY; param_float_cb = cb; param_request_sent = false; + param_request_sent_ms = AP_HAL::millis(); param_request_node_id = node_id; return true; } +/* + get named integer parameter on node +*/ bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetIntCb *cb) { WITH_SEMAPHORE(_param_sem); + + // fail if waiting for any previous get/set request if (param_int_cb != nullptr || - param_float_cb != nullptr) { - //busy + param_float_cb != nullptr || + param_string_cb != nullptr) { return false; } param_getset_req.index = 0; @@ -1340,6 +1439,30 @@ bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, Param param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY; param_int_cb = cb; param_request_sent = false; + param_request_sent_ms = AP_HAL::millis(); + param_request_node_id = node_id; + return true; +} + +/* + get named string parameter on node +*/ +bool AP_DroneCAN::get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetStringCb *cb) +{ + WITH_SEMAPHORE(_param_sem); + + // fail if waiting for any previous get/set request + if (param_int_cb != nullptr || + param_float_cb != nullptr || + param_string_cb != nullptr) { + return false; + } + param_getset_req.index = 0; + param_getset_req.name.len = strncpy_noterm((char*)param_getset_req.name.data, name, sizeof(param_getset_req.name.data)); + param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY; + param_string_cb = cb; + param_request_sent = false; + param_request_sent_ms = AP_HAL::millis(); param_request_node_id = node_id; return true; } @@ -1348,7 +1471,8 @@ void AP_DroneCAN::handle_param_get_set_response(const CanardRxTransfer& transfer { WITH_SEMAPHORE(_param_sem); if (!param_int_cb && - !param_float_cb) { + !param_float_cb && + !param_string_cb) { return; } if ((rsp.value.union_tag == UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) && param_int_cb) { @@ -1360,6 +1484,7 @@ void AP_DroneCAN::handle_param_get_set_response(const CanardRxTransfer& transfer param_getset_req.value.integer_value = val; param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; param_request_sent = false; + param_request_sent_ms = AP_HAL::millis(); param_request_node_id = transfer.source_node_id; return; } @@ -1372,15 +1497,32 @@ void AP_DroneCAN::handle_param_get_set_response(const CanardRxTransfer& transfer param_getset_req.value.real_value = val; param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE; param_request_sent = false; + param_request_sent_ms = AP_HAL::millis(); + param_request_node_id = transfer.source_node_id; + return; + } + } else if ((rsp.value.union_tag == UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE) && param_string_cb) { + string val; + memcpy(&val, &rsp.value.string_value, sizeof(val)); + if ((*param_string_cb)(this, transfer.source_node_id, (const char*)rsp.name.data, val)) { + // we want the parameter to be set with val + param_getset_req.index = 0; + memcpy(param_getset_req.name.data, rsp.name.data, rsp.name.len); + memcpy(¶m_getset_req.value.string_value, &val, sizeof(val)); + param_getset_req.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE; + param_request_sent = false; + param_request_sent_ms = AP_HAL::millis(); param_request_node_id = transfer.source_node_id; return; } } + + param_request_sent_ms = 0; param_int_cb = nullptr; param_float_cb = nullptr; + param_string_cb = nullptr; } - void AP_DroneCAN::send_parameter_save_request() { WITH_SEMAPHORE(_param_save_sem); diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.h b/libraries/AP_DroneCAN/AP_DroneCAN.h index 6c267fc579873d..81abfbdda44303 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN.h @@ -54,6 +54,10 @@ #define AP_DRONECAN_HOBBYWING_ESC_SUPPORT (BOARD_FLASH_SIZE>1024) #endif +#ifndef AP_DRONECAN_HIMARK_SERVO_SUPPORT +#define AP_DRONECAN_HIMARK_SERVO_SUPPORT (BOARD_FLASH_SIZE>1024) +#endif + // fwd-declare callback classes class AP_DroneCAN_DNA_Server; @@ -74,8 +78,12 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { uint8_t get_driver_index() const { return _driver_index; } + // define string with length structure + struct string { uint8_t len; uint8_t data[128]; }; + FUNCTOR_TYPEDEF(ParamGetSetIntCb, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); FUNCTOR_TYPEDEF(ParamGetSetFloatCb, bool, AP_DroneCAN*, const uint8_t, const char*, float &); + FUNCTOR_TYPEDEF(ParamGetSetStringCb, bool, AP_DroneCAN*, const uint8_t, const char*, string &); FUNCTOR_TYPEDEF(ParamSaveCb, void, AP_DroneCAN*, const uint8_t, bool); void send_node_status(); @@ -95,11 +103,15 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { // THIS IS NOT A THREAD SAFE API! void send_reboot_request(uint8_t node_id); - // set param value + // get or set param value + // returns true on success, false on failure + // failures occur when waiting on node to respond to previous get or set request bool set_parameter_on_node(uint8_t node_id, const char *name, float value, ParamGetSetFloatCb *cb); bool set_parameter_on_node(uint8_t node_id, const char *name, int32_t value, ParamGetSetIntCb *cb); + bool set_parameter_on_node(uint8_t node_id, const char *name, const string &value, ParamGetSetStringCb *cb); bool get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetFloatCb *cb); bool get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetIntCb *cb); + bool get_parameter_on_node(uint8_t node_id, const char *name, ParamGetSetStringCb *cb); // Save parameters bool save_parameters_on_node(uint8_t node_id, ParamSaveCb *cb); @@ -143,7 +155,12 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { ///// SRV output ///// void SRV_send_actuator(); void SRV_send_esc(); +#if AP_DRONECAN_HIMARK_SERVO_SUPPORT void SRV_send_himark(); +#endif + + //scale servo output appropriately before sending + int16_t scale_esc_output(uint8_t idx); // SafetyState void safety_state_send(); @@ -151,27 +168,32 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { // send notify vehicle state void notify_state_send(); - // send parameter get/set request + // check for parameter get/set response timeout + void check_parameter_callback_timeout(); + + // send queued parameter get/set request. called from loop void send_parameter_request(); - // send parameter save request + // send queued parameter save request. called from loop void send_parameter_save_request(); // periodic logging void logging(); - // set parameter on a node - ParamGetSetIntCb *param_int_cb; - ParamGetSetFloatCb *param_float_cb; - bool param_request_sent = true; - HAL_Semaphore _param_sem; - uint8_t param_request_node_id; + // get parameter on a node + ParamGetSetIntCb *param_int_cb; // latest get param request callback function (for integers) + ParamGetSetFloatCb *param_float_cb; // latest get param request callback function (for floats) + ParamGetSetStringCb *param_string_cb; // latest get param request callback function (for strings) + bool param_request_sent = true; // true after a param request has been sent, false when queued to be sent + uint32_t param_request_sent_ms; // system time that get param request was sent + HAL_Semaphore _param_sem; // semaphore protecting this block of variables + uint8_t param_request_node_id; // node id of most recent get param request // save parameters on a node - ParamSaveCb *save_param_cb; - bool param_save_request_sent = true; - HAL_Semaphore _param_save_sem; - uint8_t param_save_request_node_id; + ParamSaveCb *save_param_cb; // latest save param request callback function + bool param_save_request_sent = true; // true after a save param request has been sent, false when queued to be sent + HAL_Semaphore _param_save_sem; // semaphore protecting this block of variables + uint8_t param_save_request_node_id; // node id of most recent save param request // UAVCAN parameters AP_Int8 _dronecan_node; @@ -182,6 +204,7 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { AP_Int16 _options; AP_Int16 _notify_state_hz; AP_Int16 _pool_size; + AP_Int32 _esc_rv; uint32_t *mem_pool; @@ -243,7 +266,10 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { Canard::Publisher safety_state{canard_iface}; Canard::Publisher arming_status{canard_iface}; Canard::Publisher notify_state{canard_iface}; + +#if AP_DRONECAN_HIMARK_SERVO_SUPPORT Canard::Publisher himark_out{canard_iface}; +#endif #if AP_DRONECAN_SEND_GPS Canard::Publisher gnss_fix2{canard_iface}; @@ -314,6 +340,10 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { void handle_hobbywing_StatusMsg1(const CanardRxTransfer& transfer, const com_hobbywing_esc_StatusMsg1& msg); void handle_hobbywing_StatusMsg2(const CanardRxTransfer& transfer, const com_hobbywing_esc_StatusMsg2& msg); #endif // AP_DRONECAN_HOBBYWING_ESC_SUPPORT + +#if AP_DRONECAN_HIMARK_SERVO_SUPPORT + void handle_himark_servoinfo(const CanardRxTransfer& transfer, const com_himark_servo_ServoInfo &msg); +#endif // incoming button handling void handle_button(const CanardRxTransfer& transfer, const ardupilot_indication_Button& msg); @@ -321,7 +351,6 @@ 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); - void handle_himark_servoinfo(const CanardRxTransfer& transfer, const com_himark_servo_ServoInfo &msg); 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); diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp index d20a728bd007e8..02b5ed7453647a 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp @@ -36,12 +36,12 @@ extern const AP_HAL::HAL& hal; #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) : +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(ap_dronecan.canard_iface), + _canard_iface(canard_iface), storage(StorageManager::StorageCANDNA), - allocation_sub(allocation_cb, _ap_dronecan.get_driver_index()), - node_status_sub(node_status_cb, _ap_dronecan.get_driver_index()), + allocation_sub(allocation_cb, driver_index), + node_status_sub(node_status_cb, driver_index), node_info_client(_canard_iface, node_info_cb) {} diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h index 4dba03b5e3dee4..ee58191e803c3d 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.h @@ -104,7 +104,7 @@ class AP_DroneCAN_DNA_Server Canard::Client node_info_client; public: - AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan); + AP_DroneCAN_DNA_Server(AP_DroneCAN &ap_dronecan, CanardInterface &canard_iface, uint8_t driver_index); // Do not allow copies diff --git a/libraries/AP_EFI/AP_EFI_Serial_MS.cpp b/libraries/AP_EFI/AP_EFI_Serial_MS.cpp index 29a6000377c834..4c87783b1d0e7e 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_MS.cpp +++ b/libraries/AP_EFI/AP_EFI_Serial_MS.cpp @@ -43,12 +43,15 @@ void AP_EFI_Serial_MS::update() const uint32_t expected_bytes = 2 + (RT_LAST_OFFSET - RT_FIRST_OFFSET) + 4; if (port->available() >= expected_bytes && read_incoming_realtime_data()) { - last_response_ms = now; copy_to_frontend(); } - if (now - last_response_ms > 100) { + const uint32_t last_request_delta = (now - last_request_ms); + const uint32_t available = port->available(); + if (((last_request_delta > 150) && (available > 0)) || // nothing in our input buffer 150 ms after request + ((last_request_delta > 90) && (available == 0))) { // we requested something over 90 ms ago, but didn't get any data port->discard_input(); + last_request_ms = now; // Request an update from the realtime table (7). // The data we need start at offset 6 and ends at 129 send_request(7, RT_FIRST_OFFSET, RT_LAST_OFFSET); @@ -59,7 +62,7 @@ bool AP_EFI_Serial_MS::read_incoming_realtime_data() { // Data is parsed directly from the buffer, otherwise we would need to allocate // several hundred bytes for the entire realtime data table or request every - // value individiually + // value individually uint16_t message_length = 0; // reset checksum before reading new data diff --git a/libraries/AP_EFI/AP_EFI_Serial_MS.h b/libraries/AP_EFI/AP_EFI_Serial_MS.h index 533d2dab93df3c..89dd018bf0cf98 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_MS.h +++ b/libraries/AP_EFI/AP_EFI_Serial_MS.h @@ -46,7 +46,7 @@ class AP_EFI_Serial_MS: public AP_EFI_Backend { uint8_t step; uint8_t response_flag; uint16_t message_counter; - uint32_t last_response_ms; + uint32_t last_request_ms; // confirmed that last command was ok bool last_command_confirmed; diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index dcc46fdca12796..9945d16ce45784 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -86,7 +86,7 @@ uint8_t AP_ESC_Telem::get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) con float rpm; if (get_rpm(i, rpm)) { freqs[valid_escs++] = rpm * (1.0f / 60.0f); - } else if (_rpm_data[i].last_update_us > 0) { + } else if (was_rpm_data_ever_reported(_rpm_data[i])) { // if we have ever received data on an ESC, mark it as valid but with no data // this prevents large frequency shifts when ESCs disappear freqs[valid_escs++] = 0.0f; @@ -103,12 +103,12 @@ uint32_t AP_ESC_Telem::get_active_esc_mask() const { const uint32_t now = AP_HAL::millis(); uint32_t now_us = AP_HAL::micros(); for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { - if (now - _telem_data[i].last_update_ms >= ESC_TELEM_DATA_TIMEOUT_MS - && now_us - _rpm_data[i].last_update_us >= ESC_RPM_DATA_TIMEOUT_US) { + 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].last_update_ms == 0 && _rpm_data[i].last_update_us == 0) { - // have never seen telem from this ESC + if (now - _telem_data[i].last_update_ms >= ESC_TELEM_DATA_TIMEOUT_MS + && !rpm_data_within_timeout(_rpm_data[i], now_us, ESC_RPM_DATA_TIMEOUT_US)) { continue; } ret |= (1U << i); @@ -131,7 +131,7 @@ bool AP_ESC_Telem::are_motors_running(uint32_t servo_channel_mask, float min_rpm if (BIT_IS_SET(servo_channel_mask, i)) { const volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[i]; // we choose a relatively strict measure of health so that failsafe actions can rely on the results - if (now < rpmdata.last_update_us || now - rpmdata.last_update_us > ESC_RPM_CHECK_TIMEOUT_US) { + if (!rpm_data_within_timeout(rpmdata, now, ESC_RPM_CHECK_TIMEOUT_US)) { return false; } if (rpmdata.rpm < min_rpm) { @@ -151,7 +151,7 @@ bool AP_ESC_Telem::is_telemetry_active(uint32_t servo_channel_mask) const for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { if (BIT_IS_SET(servo_channel_mask, i)) { // no data received - if (get_last_telem_data_ms(i) == 0 && _rpm_data[i].last_update_us == 0) { + if (get_last_telem_data_ms(i) == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) { return false; } } @@ -173,8 +173,7 @@ bool AP_ESC_Telem::get_rpm(uint8_t esc_index, float& rpm) const } const uint32_t now = AP_HAL::micros(); - if (rpmdata.last_update_us > 0 && (now >= rpmdata.last_update_us) - && (now - rpmdata.last_update_us < ESC_RPM_DATA_TIMEOUT_US)) { + if (rpm_data_within_timeout(rpmdata, now, ESC_RPM_DATA_TIMEOUT_US)) { const float slew = MIN(1.0f, (now - rpmdata.last_update_us) * rpmdata.update_rate_hz * (1.0f / 1e6f)); rpm = (rpmdata.prev_rpm + (rpmdata.rpm - rpmdata.prev_rpm) * slew); @@ -200,7 +199,7 @@ bool AP_ESC_Telem::get_raw_rpm(uint8_t esc_index, float& rpm) const const uint32_t now = AP_HAL::micros(); - if (now < rpmdata.last_update_us || now - rpmdata.last_update_us > ESC_RPM_DATA_TIMEOUT_US) { + if (!rpm_data_within_timeout(rpmdata, now, ESC_RPM_DATA_TIMEOUT_US)) { return false; } @@ -305,8 +304,8 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) return; } - uint32_t now = AP_HAL::millis(); - uint32_t now_us = AP_HAL::micros(); + const uint32_t now = AP_HAL::millis(); + 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); @@ -326,7 +325,7 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) const uint8_t esc_id = (i * 4 + j) + esc_offset; if (esc_id < ESC_TELEM_MAX_ESCS && (now - _telem_data[esc_id].last_update_ms <= ESC_TELEM_DATA_TIMEOUT_MS || - now_us - _rpm_data[esc_id].last_update_us <= ESC_RPM_DATA_TIMEOUT_US)) { + rpm_data_within_timeout(_rpm_data[esc_id], now_us, ESC_RPM_DATA_TIMEOUT_US))) { all_stale = false; break; } @@ -469,17 +468,16 @@ void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const float new_rpm, cons _have_data = true; - const uint32_t now = AP_HAL::micros(); + const uint32_t now = MAX(1U ,AP_HAL::micros()); // don't allow a value of 0 in, as we use this as a flag in places volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[esc_index]; const auto last_update_us = rpmdata.last_update_us; rpmdata.prev_rpm = rpmdata.rpm; rpmdata.rpm = new_rpm; - if (now > last_update_us) { // cope with wrapping - rpmdata.update_rate_hz = 1.0e6f / (now - last_update_us); - } + rpmdata.update_rate_hz = 1.0e6f / constrain_uint32((now - last_update_us), 100, 1000000U*10U); // limit the update rate 0.1Hz to 10KHz rpmdata.last_update_us = now; rpmdata.error_rate = error_rate; + rpmdata.data_valid = true; #ifdef ESC_TELEM_DEBUG hal.console->printf("RPM: rate=%.1fhz, rpm=%f)\n", rpmdata.update_rate_hz, new_rpm); @@ -490,10 +488,11 @@ void AP_ESC_Telem::update() { AP_Logger *logger = AP_Logger::get_singleton(); - // Push received telemetry data into the logging system - if (logger && logger->logging_enabled()) { + const uint32_t now_us = AP_HAL::micros(); - for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { + for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { + // Push received telemetry data into the logging system + if (logger && logger->logging_enabled()) { if (_telem_data[i].last_update_ms != _last_telem_log_ms[i] || _rpm_data[i].last_update_us != _last_rpm_log_us[i]) { @@ -529,9 +528,32 @@ void AP_ESC_Telem::update() _last_rpm_log_us[i] = _rpm_data[i].last_update_us; } } + + if ((now_us - _rpm_data[i].last_update_us) > ESC_RPM_DATA_TIMEOUT_US) { + _rpm_data[i].data_valid = false; + } } } +bool AP_ESC_Telem::rpm_data_within_timeout (const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const uint32_t timeout_us) +{ + // easy case, has the time window been crossed so it's invalid + if ((now_us - instance.last_update_us) > timeout_us) { + return false; + } + // we never got a valid data, to it's invalid + if (instance.last_update_us == 0) { + return false; + } + // check if things generally expired on us, this is done to handle time wrapping + return instance.data_valid; +} + +bool AP_ESC_Telem::was_rpm_data_ever_reported (const volatile AP_ESC_Telem_Backend::RpmData &instance) +{ + return instance.last_update_us > 0; +} + #if AP_SCRIPTING_ENABLED /* set RPM scale factor from script diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.h b/libraries/AP_ESC_Telem/AP_ESC_Telem.h index fa834b29d1969e..503ef43299dfce 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.h @@ -87,7 +87,7 @@ class AP_ESC_Telem { // send telemetry data to mavlink void send_esc_telemetry_mavlink(uint8_t mav_chan); - // udpate at 10Hz to log telemetry + // update at 10Hz to log telemetry void update(); // is rpm telemetry configured for the provided channel mask @@ -97,6 +97,9 @@ class AP_ESC_Telem { // can also be called from scripting void update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate); + // callback to update the data in the frontend, should be called by the driver when new data is available + void update_telem_data(const uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, const uint16_t data_mask); + #if AP_SCRIPTING_ENABLED /* set RPM scale factor from script @@ -106,8 +109,9 @@ class AP_ESC_Telem { private: - // callback to update the data in the frontend, should be called by the driver when new data is available - void update_telem_data(const uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, const uint16_t data_mask); + // helper that validates RPM data + 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); // rpm data volatile AP_ESC_Telem_Backend::RpmData _rpm_data[ESC_TELEM_MAX_ESCS]; diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h index 1ee76c7e3e73ac..e40c09b64a3c9e 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h @@ -25,8 +25,9 @@ class AP_ESC_Telem_Backend { float rpm; // rpm float prev_rpm; // previous rpm float error_rate; // error rate in percent - uint32_t last_update_us; // last update time, determines whether active + uint32_t last_update_us; // last update time, greater then 0 means we've gotten data at some point float update_rate_hz; + bool data_valid; // if this isn't set to true, then the ESC data should be ignored }; enum TelemetryType { diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp index 220c899823c6e6..25f84fb285c69a 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_SITL.cpp @@ -44,22 +44,30 @@ void AP_ESC_Telem_SITL::update() return; } uint32_t mask = sitl->state.motor_mask; + + /* + mask out motors we should not be providing telemetry for. On + AP_Periph SIM_CAN_SRV_MSK are the outputs we will provide + telemetry for, on the main firmware it is the ones we don't + provide telemetry for + */ +#if defined(HAL_BUILD_AP_PERIPH) + mask &= uint32_t(sitl->can_servo_mask); +#else + mask &= ~uint32_t(sitl->can_servo_mask); +#endif uint8_t bit; + while ((bit = __builtin_ffs(mask)) != 0) { uint8_t motor = bit-1; mask &= ~(1U<throttle)) { - if (!is_zero(sitl->esc_rpm_armed) && hal.util->get_soft_armed()) { - update_rpm(motor, sitl->esc_rpm_armed); - } - } else { - update_rpm(motor, sitl->state.rpm[motor]); - } + const float min_rpm = hal.util->get_soft_armed()? sitl->esc_rpm_armed : 0; + update_rpm(motor, MAX(min_rpm, sitl->state.rpm[motor])); // some fake values so that is_telemetry_active() returns true TelemetryData t { - .temperature_cdeg = 32, + .temperature_cdeg = 3200, .voltage = 16.8f, .current = 0.8f, .consumption_mah = 1.0f, diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp index d0beac4a9ad6de..c1769fe2a00a8e 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - suppport for serial connected AHRS systems + support for serial connected AHRS systems */ #include "AP_ExternalAHRS_config.h" @@ -23,7 +23,7 @@ #include "AP_ExternalAHRS.h" #include "AP_ExternalAHRS_backend.h" #include "AP_ExternalAHRS_VectorNav.h" -#include "AP_ExternalAHRS_LORD.h" +#include "AP_ExternalAHRS_MicroStrain5.h" #include @@ -53,7 +53,7 @@ const AP_Param::GroupInfo AP_ExternalAHRS::var_info[] = { // @Param: _TYPE // @DisplayName: AHRS type // @Description: Type of AHRS device - // @Values: 0:None,1:VectorNav,2:LORD + // @Values: 0:None,1:VectorNav,2:MicroStrain // @User: Standard AP_GROUPINFO_FLAGS("_TYPE", 1, AP_ExternalAHRS, devtype, HAL_EXTERNAL_AHRS_DEFAULT, AP_PARAM_FLAG_ENABLE), @@ -92,21 +92,20 @@ void AP_ExternalAHRS::init(void) switch (DevType(devtype)) { case DevType::None: // nothing to do - break; + return; #if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED case DevType::VecNav: backend = new AP_ExternalAHRS_VectorNav(this, state); - break; + return; #endif -#if AP_EXTERNAL_AHRS_LORD_ENABLED - case DevType::LORD: - backend = new AP_ExternalAHRS_LORD(this, state); - break; - default: +#if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED + case DevType::MicroStrain5: + backend = new AP_ExternalAHRS_MicroStrain5(this, state); + return; #endif - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unsupported ExternalAHRS type %u", unsigned(devtype)); - break; } + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unsupported ExternalAHRS type %u", unsigned(devtype)); } bool AP_ExternalAHRS::enabled() const @@ -193,7 +192,12 @@ bool AP_ExternalAHRS::get_speed_down(float &speedD) bool AP_ExternalAHRS::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const { - return backend && backend->pre_arm_check(failure_msg, failure_msg_len); + if (backend == nullptr) { + hal.util->snprintf(failure_msg, failure_msg_len, "ExternalAHRS: Invalid backend"); + return false; + } + + return backend->pre_arm_check(failure_msg, failure_msg_len); } /* diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h index 5e69f54bb9da0d..89e2331cb86188 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - suppport for serial connected AHRS systems + support for serial connected AHRS systems */ #pragma once @@ -46,8 +46,8 @@ class AP_ExternalAHRS { #if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED VecNav = 1, #endif -#if AP_EXTERNAL_AHRS_LORD_ENABLED - LORD = 2, +#if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED + MicroStrain5 = 2, #endif }; diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp new file mode 100644 index 00000000000000..abdc63250ec587 --- /dev/null +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp @@ -0,0 +1,318 @@ +/* + 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 . + */ +/* + support for MicroStrain CX5/GX5-45 serially connected AHRS Systems + */ + +#define ALLOW_DOUBLE_MATH_FUNCTIONS + +#include "AP_ExternalAHRS_config.h" + +#if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED + +#include "AP_ExternalAHRS_MicroStrain5.h" +#include "AP_Compass/AP_Compass_config.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +extern const AP_HAL::HAL &hal; + +AP_ExternalAHRS_MicroStrain5::AP_ExternalAHRS_MicroStrain5(AP_ExternalAHRS *_frontend, + AP_ExternalAHRS::state_t &_state): AP_ExternalAHRS_backend(_frontend, _state) +{ + auto &sm = AP::serialmanager(); + uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0); + + baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0); + port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0); + + if (!uart) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "ExternalAHRS no UART"); + return; + } + + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_MicroStrain5::update_thread, void), "AHRS", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) { + AP_BoardConfig::allocation_error("Failed to allocate ExternalAHRS update thread"); + } + + hal.scheduler->delay(5000); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MicroStrain ExternalAHRS initialised"); +} + +void AP_ExternalAHRS_MicroStrain5::update_thread(void) +{ + if (!port_open) { + port_open = true; + uart->begin(baudrate); + } + + while (true) { + build_packet(); + hal.scheduler->delay_microseconds(100); + } +} + + + +// Builds packets by looking at each individual byte, once a full packet has been read in it checks the checksum then handles the packet. +void AP_ExternalAHRS_MicroStrain5::build_packet() +{ + if (uart == nullptr) { + return; + } + + WITH_SEMAPHORE(sem); + uint32_t nbytes = MIN(uart->available(), 2048u); + while (nbytes--> 0) { + uint8_t b; + if (!uart->read(b)) { + break; + } + DescriptorSet descriptor; + if (handle_byte(b, descriptor)) { + switch (descriptor) { + case DescriptorSet::IMUData: + post_imu(); + break; + case DescriptorSet::GNSSData: + break; + case DescriptorSet::EstimationData: + post_filter(); + break; + case DescriptorSet::BaseCommand: + case DescriptorSet::DMCommand: + case DescriptorSet::SystemCommand: + break; + } + } + } +} + + + +// Posts data from an imu packet to `state` and `handle_external` methods +void AP_ExternalAHRS_MicroStrain5::post_imu() const +{ + { + WITH_SEMAPHORE(state.sem); + state.accel = imu_data.accel; + state.gyro = imu_data.gyro; + + state.quat = imu_data.quat; + state.have_quaternion = true; + } + + { + AP_ExternalAHRS::ins_data_message_t ins { + accel: imu_data.accel, + gyro: imu_data.gyro, + temperature: -300 + }; + AP::ins().handle_external(ins); + } + +#if AP_COMPASS_EXTERNALAHRS_ENABLED + { + AP_ExternalAHRS::mag_data_message_t mag { + field: imu_data.mag + }; + AP::compass().handle_external(mag); + } +#endif + +#if AP_BARO_EXTERNALAHRS_ENABLED + { + const AP_ExternalAHRS::baro_data_message_t baro { + instance: 0, + pressure_pa: imu_data.pressure, + // setting temp to 25 effectively disables barometer temperature calibrations - these are already performed by MicroStrain + temperature: 25, + }; + AP::baro().handle_external(baro); + } +#endif +} + +void AP_ExternalAHRS_MicroStrain5::post_filter() const +{ + { + WITH_SEMAPHORE(state.sem); + state.velocity = Vector3f{filter_data.ned_velocity_north, filter_data.ned_velocity_east, filter_data.ned_velocity_down}; + state.have_velocity = true; + + state.location = Location{filter_data.lat, filter_data.lon, gnss_data.msl_altitude, Location::AltFrame::ABSOLUTE}; + state.have_location = true; + } + + AP_ExternalAHRS::gps_data_message_t gps { + gps_week: filter_data.week, + ms_tow: filter_data.tow_ms, + fix_type: (uint8_t) gnss_data.fix_type, + satellites_in_view: gnss_data.satellites, + + horizontal_pos_accuracy: gnss_data.horizontal_position_accuracy, + vertical_pos_accuracy: gnss_data.vertical_position_accuracy, + horizontal_vel_accuracy: gnss_data.speed_accuracy, + + hdop: gnss_data.hdop, + vdop: gnss_data.vdop, + + longitude: filter_data.lon, + latitude: filter_data.lat, + msl_altitude: gnss_data.msl_altitude, + + ned_vel_north: filter_data.ned_velocity_north, + ned_vel_east: filter_data.ned_velocity_east, + ned_vel_down: filter_data.ned_velocity_down, + }; + + if (gps.fix_type >= 3 && !state.have_origin) { + WITH_SEMAPHORE(state.sem); + state.origin = Location{int32_t(filter_data.lat), + int32_t(filter_data.lon), + int32_t(gnss_data.msl_altitude), + Location::AltFrame::ABSOLUTE}; + state.have_origin = true; + } + + uint8_t instance; + if (AP::gps().get_first_external_instance(instance)) { + AP::gps().handle_external(gps, instance); + } +} + +int8_t AP_ExternalAHRS_MicroStrain5::get_port(void) const +{ + if (!uart) { + return -1; + } + return port_num; +}; + +// Get model/type name +const char* AP_ExternalAHRS_MicroStrain5::get_name() const +{ + return "MicroStrain5"; +} + +bool AP_ExternalAHRS_MicroStrain5::healthy(void) const +{ + uint32_t now = AP_HAL::millis(); + return (now - last_ins_pkt < 40 && now - last_gps_pkt < 500 && now - last_filter_pkt < 500); +} + +bool AP_ExternalAHRS_MicroStrain5::initialised(void) const +{ + return last_ins_pkt != 0 && last_gps_pkt != 0 && last_filter_pkt != 0; +} + +bool AP_ExternalAHRS_MicroStrain5::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const +{ + if (!healthy()) { + hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain unhealthy"); + return false; + } + if (gnss_data.fix_type < 3) { + hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain no GPS lock"); + return false; + } + if (filter_status.state != 0x02) { + hal.util->snprintf(failure_msg, failure_msg_len, "MicroStrain filter not running"); + return false; + } + + return true; +} + +void AP_ExternalAHRS_MicroStrain5::get_filter_status(nav_filter_status &status) const +{ + memset(&status, 0, sizeof(status)); + if (last_ins_pkt != 0 && last_gps_pkt != 0) { + status.flags.initalized = 1; + } + if (healthy() && last_ins_pkt != 0) { + status.flags.attitude = 1; + status.flags.vert_vel = 1; + status.flags.vert_pos = 1; + + if (gnss_data.fix_type >= 3) { + status.flags.horiz_vel = 1; + status.flags.horiz_pos_rel = 1; + status.flags.horiz_pos_abs = 1; + status.flags.pred_horiz_pos_rel = 1; + status.flags.pred_horiz_pos_abs = 1; + status.flags.using_gps = 1; + } + } +} + +void AP_ExternalAHRS_MicroStrain5::send_status_report(GCS_MAVLINK &link) 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.speed_accuracy/vel_gate, gnss_data.horizontal_position_accuracy/pos_gate, gnss_data.vertical_position_accuracy/hgt_gate, + mag_var, 0, 0); + +} + + +#endif // AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h new file mode 100644 index 00000000000000..e6b2b9e6bdcb17 --- /dev/null +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.h @@ -0,0 +1,73 @@ +/* + 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 . + */ +/* + support for MicroStrain CX5/GX5-45 serially connected AHRS Systems + */ + +#pragma once + +#include "AP_ExternalAHRS_config.h" + +#if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED + +#include "AP_ExternalAHRS_backend.h" +#include +#include +#include "MicroStrain_common.h" + +class AP_ExternalAHRS_MicroStrain5: public AP_ExternalAHRS_backend, public AP_MicroStrain +{ +public: + + AP_ExternalAHRS_MicroStrain5(AP_ExternalAHRS *frontend, AP_ExternalAHRS::state_t &state); + + // get serial port number, -1 for not enabled + int8_t get_port(void) const override; + + // Get model/type name + const char* get_name() const override; + + // accessors for AP_AHRS + bool healthy(void) const override; + 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; + + // check for new data + void update() override { + build_packet(); + }; + +private: + + uint32_t baudrate; + int8_t port_num; + bool port_open = false; + + + + void build_packet(); + + void post_imu() const; + void post_gnss() const; + void post_filter() const; + + void update_thread(); + + AP_HAL::UARTDriver *uart; + HAL_Semaphore sem; + +}; + +#endif // AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp index 2e6c2b8fab29fb..b7c0bf4bff18cb 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - suppport for serial connected AHRS systems + support for serial connected AHRS systems */ #define ALLOW_DOUBLE_MATH_FUNCTIONS @@ -31,6 +31,7 @@ #include #include #include +#include #include #include #include @@ -282,8 +283,8 @@ bool AP_ExternalAHRS_VectorNav::check_uart() return true; } -// Send command to read given register number and wait for responce -// Only run from thread! This blocks until a responce is received +// Send command to read given register number and wait for response +// Only run from thread! This blocks until a response is received #define READ_REQUEST_RETRY_MS 500 void AP_ExternalAHRS_VectorNav::wait_register_responce(const uint8_t register_num) { @@ -581,8 +582,10 @@ void AP_ExternalAHRS_VectorNav::process_packet2(const uint8_t *b) Location::AltFrame::ABSOLUTE}; state.have_origin = true; } - - AP::gps().handle_external(gps); + uint8_t instance; + if (AP::gps().get_first_external_instance(instance)) { + AP::gps().handle_external(gps, instance); + } } /* diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h index 183184bf24248f..3ce1fe7f5e2d5d 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.h @@ -13,7 +13,7 @@ along with this program. If not, see . */ /* - suppport for serial connected AHRS systems + support for serial connected AHRS systems */ #pragma once diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h index 0e167aad7604f6..ef9ef52158833b 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h @@ -10,8 +10,12 @@ #define AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED HAL_EXTERNAL_AHRS_ENABLED #endif -#ifndef AP_EXTERNAL_AHRS_LORD_ENABLED -#define AP_EXTERNAL_AHRS_LORD_ENABLED AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED +#ifndef AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED +#define AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_MICROSTRAIN_ENABLED +#define AP_MICROSTRAIN_ENABLED AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED #endif #ifndef AP_EXTERNAL_AHRS_VECTORNAV_ENABLED diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.cpp b/libraries/AP_ExternalAHRS/MicroStrain_common.cpp similarity index 50% rename from libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.cpp rename to libraries/AP_ExternalAHRS/MicroStrain_common.cpp index d43f74eb251384..d5b723cb125c6a 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.cpp +++ b/libraries/AP_ExternalAHRS/MicroStrain_common.cpp @@ -11,35 +11,17 @@ along with this program. If not, see . */ /* - suppport for LORD Microstrain CX5/GX5-45 serially connected AHRS Systems + support for MicroStrain CX5/GX5-45 serially connected AHRS Systems */ #define ALLOW_DOUBLE_MATH_FUNCTIONS #include "AP_ExternalAHRS_config.h" -#if AP_EXTERNAL_AHRS_LORD_ENABLED +#if AP_MICROSTRAIN_ENABLED -#include "AP_ExternalAHRS_LORD.h" -#include -#include -#include +#include "MicroStrain_common.h" #include -#include -#include -#include -#include -#include - - -enum class DescriptorSet { - BaseCommand = 0x01, - DMCommand = 0x0C, - SystemCommand = 0x7F, - IMUData = 0x80, - GNSSData = 0x81, - EstimationData = 0x82 -}; enum class INSPacketField { ACCEL = 0x04, @@ -72,55 +54,9 @@ enum class FilterPacketField { NED_VELOCITY = 0x02 }; -extern const AP_HAL::HAL &hal; - -AP_ExternalAHRS_LORD::AP_ExternalAHRS_LORD(AP_ExternalAHRS *_frontend, - AP_ExternalAHRS::state_t &_state): AP_ExternalAHRS_backend(_frontend, _state) -{ - auto &sm = AP::serialmanager(); - uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0); - - baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0); - port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0); - - if (!uart) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ExternalAHRS no UART"); - return; - } - - if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_LORD::update_thread, void), "AHRS", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) { - AP_BoardConfig::allocation_error("Failed to allocate ExternalAHRS update thread"); - } - - hal.scheduler->delay(5000); - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "LORD ExternalAHRS initialised"); -} - -void AP_ExternalAHRS_LORD::update_thread(void) -{ - if (!port_open) { - port_open = true; - uart->begin(baudrate); - } - - while (true) { - build_packet(); - hal.scheduler->delay_microseconds(100); - } -} - -// Builds packets by looking at each individual byte, once a full packet has been read in it checks the checksum then handles the packet. -void AP_ExternalAHRS_LORD::build_packet() +bool AP_MicroStrain::handle_byte(const uint8_t b, DescriptorSet& descriptor) { - WITH_SEMAPHORE(sem); - uint32_t nbytes = MIN(uart->available(), 2048u); - while (nbytes--> 0) { - uint8_t b; - if (!uart->read(b)) { - break; - } - - switch (message_in.state) { + switch (message_in.state) { case ParseState::WaitingFor_SyncOne: if (b == SYNC_ONE) { message_in.packet.header[0] = b; @@ -158,16 +94,16 @@ void AP_ExternalAHRS_LORD::build_packet() message_in.index = 0; if (valid_packet(message_in.packet)) { - handle_packet(message_in.packet); + descriptor = handle_packet(message_in.packet); + return true; } } break; } - } + return false; } -// returns true if the fletcher checksum for the packet is valid, else false. -bool AP_ExternalAHRS_LORD::valid_packet(const LORD_Packet & packet) const +bool AP_MicroStrain::valid_packet(const MicroStrain_Packet & packet) { uint8_t checksum_one = 0; uint8_t checksum_two = 0; @@ -185,30 +121,29 @@ bool AP_ExternalAHRS_LORD::valid_packet(const LORD_Packet & packet) const return packet.checksum[0] == checksum_one && packet.checksum[1] == checksum_two; } -// Calls the correct functions based on the packet descriptor of the packet -void AP_ExternalAHRS_LORD::handle_packet(const LORD_Packet& packet) +AP_MicroStrain::DescriptorSet AP_MicroStrain::handle_packet(const MicroStrain_Packet& packet) { - switch ((DescriptorSet) packet.header[2]) { + const DescriptorSet descriptor = DescriptorSet(packet.header[2]); + switch (descriptor) { case DescriptorSet::IMUData: handle_imu(packet); - post_imu(); break; case DescriptorSet::GNSSData: handle_gnss(packet); break; case DescriptorSet::EstimationData: handle_filter(packet); - post_filter(); break; case DescriptorSet::BaseCommand: case DescriptorSet::DMCommand: case DescriptorSet::SystemCommand: break; } + return descriptor; } -// Collects data from an imu packet into `imu_data` -void AP_ExternalAHRS_LORD::handle_imu(const LORD_Packet& packet) + +void AP_MicroStrain::handle_imu(const MicroStrain_Packet& packet) { last_ins_pkt = AP_HAL::millis(); @@ -244,51 +179,8 @@ void AP_ExternalAHRS_LORD::handle_imu(const LORD_Packet& packet) } } -// Posts data from an imu packet to `state` and `handle_external` methods -void AP_ExternalAHRS_LORD::post_imu() const -{ - { - WITH_SEMAPHORE(state.sem); - state.accel = imu_data.accel; - state.gyro = imu_data.gyro; - - state.quat = imu_data.quat; - state.have_quaternion = true; - } - - { - AP_ExternalAHRS::ins_data_message_t ins { - accel: imu_data.accel, - gyro: imu_data.gyro, - temperature: -300 - }; - AP::ins().handle_external(ins); - } - -#if AP_COMPASS_EXTERNALAHRS_ENABLED - { - AP_ExternalAHRS::mag_data_message_t mag { - field: imu_data.mag - }; - AP::compass().handle_external(mag); - } -#endif - -#if AP_BARO_EXTERNALAHRS_ENABLED - { - const AP_ExternalAHRS::baro_data_message_t baro { - instance: 0, - pressure_pa: imu_data.pressure, - // setting temp to 25 effectively disables barometer temperature calibrations - these are already performed by lord - temperature: 25, - }; - AP::baro().handle_external(baro); - } -#endif -} -// Collects data from a gnss packet into `gnss_data` -void AP_ExternalAHRS_LORD::handle_gnss(const LORD_Packet &packet) +void AP_MicroStrain::handle_gnss(const MicroStrain_Packet &packet) { last_gps_pkt = AP_HAL::millis(); @@ -354,7 +246,7 @@ void AP_ExternalAHRS_LORD::handle_gnss(const LORD_Packet &packet) } } -void AP_ExternalAHRS_LORD::handle_filter(const LORD_Packet &packet) +void AP_MicroStrain::handle_filter(const MicroStrain_Packet &packet) { last_filter_pkt = AP_HAL::millis(); @@ -392,168 +284,7 @@ void AP_ExternalAHRS_LORD::handle_filter(const LORD_Packet &packet) } } -void AP_ExternalAHRS_LORD::post_filter() const -{ - { - WITH_SEMAPHORE(state.sem); - state.velocity = Vector3f{filter_data.ned_velocity_north, filter_data.ned_velocity_east, filter_data.ned_velocity_down}; - state.have_velocity = true; - - state.location = Location{filter_data.lat, filter_data.lon, gnss_data.msl_altitude, Location::AltFrame::ABSOLUTE}; - state.have_location = true; - } - - AP_ExternalAHRS::gps_data_message_t gps { - gps_week: filter_data.week, - ms_tow: filter_data.tow_ms, - fix_type: (uint8_t) gnss_data.fix_type, - satellites_in_view: gnss_data.satellites, - - horizontal_pos_accuracy: gnss_data.horizontal_position_accuracy, - vertical_pos_accuracy: gnss_data.vertical_position_accuracy, - horizontal_vel_accuracy: gnss_data.speed_accuracy, - - hdop: gnss_data.hdop, - vdop: gnss_data.vdop, - - longitude: filter_data.lon, - latitude: filter_data.lat, - msl_altitude: gnss_data.msl_altitude, - - ned_vel_north: filter_data.ned_velocity_north, - ned_vel_east: filter_data.ned_velocity_east, - ned_vel_down: filter_data.ned_velocity_down, - }; - - if (gps.fix_type >= 3 && !state.have_origin) { - WITH_SEMAPHORE(state.sem); - state.origin = Location{int32_t(filter_data.lat), - int32_t(filter_data.lon), - int32_t(gnss_data.msl_altitude), - Location::AltFrame::ABSOLUTE}; - state.have_origin = true; - } - - AP::gps().handle_external(gps); -} - -int8_t AP_ExternalAHRS_LORD::get_port(void) const -{ - if (!uart) { - return -1; - } - return port_num; -}; - -// Get model/type name -const char* AP_ExternalAHRS_LORD::get_name() const -{ - return "LORD"; -} - -bool AP_ExternalAHRS_LORD::healthy(void) const -{ - uint32_t now = AP_HAL::millis(); - return (now - last_ins_pkt < 40 && now - last_gps_pkt < 500 && now - last_filter_pkt < 500); -} - -bool AP_ExternalAHRS_LORD::initialised(void) const -{ - return last_ins_pkt != 0 && last_gps_pkt != 0 && last_filter_pkt != 0; -} - -bool AP_ExternalAHRS_LORD::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const -{ - if (!healthy()) { - hal.util->snprintf(failure_msg, failure_msg_len, "LORD unhealthy"); - return false; - } - if (gnss_data.fix_type < 3) { - hal.util->snprintf(failure_msg, failure_msg_len, "LORD no GPS lock"); - return false; - } - if (filter_status.state != 0x02) { - hal.util->snprintf(failure_msg, failure_msg_len, "LORD filter not running"); - return false; - } - - return true; -} - -void AP_ExternalAHRS_LORD::get_filter_status(nav_filter_status &status) const -{ - memset(&status, 0, sizeof(status)); - if (last_ins_pkt != 0 && last_gps_pkt != 0) { - status.flags.initalized = 1; - } - if (healthy() && last_ins_pkt != 0) { - status.flags.attitude = 1; - status.flags.vert_vel = 1; - status.flags.vert_pos = 1; - - if (gnss_data.fix_type >= 3) { - status.flags.horiz_vel = 1; - status.flags.horiz_pos_rel = 1; - status.flags.horiz_pos_abs = 1; - status.flags.pred_horiz_pos_rel = 1; - status.flags.pred_horiz_pos_abs = 1; - status.flags.using_gps = 1; - } - } -} - -void AP_ExternalAHRS_LORD::send_status_report(GCS_MAVLINK &link) 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.speed_accuracy/vel_gate, gnss_data.horizontal_position_accuracy/pos_gate, gnss_data.vertical_position_accuracy/hgt_gate, - mag_var, 0, 0); - -} - -Vector3f AP_ExternalAHRS_LORD::populate_vector3f(const uint8_t *data, uint8_t offset) const +Vector3f AP_MicroStrain::populate_vector3f(const uint8_t *data, uint8_t offset) { return Vector3f { be32tofloat_ptr(data, offset), @@ -562,7 +293,7 @@ Vector3f AP_ExternalAHRS_LORD::populate_vector3f(const uint8_t *data, uint8_t of }; } -Quaternion AP_ExternalAHRS_LORD::populate_quaternion(const uint8_t *data, uint8_t offset) const +Quaternion AP_MicroStrain::populate_quaternion(const uint8_t *data, uint8_t offset) { return Quaternion { be32tofloat_ptr(data, offset), @@ -572,4 +303,5 @@ Quaternion AP_ExternalAHRS_LORD::populate_quaternion(const uint8_t *data, uint8_ }; } -#endif // AP_EXTERNAL_AHRS_LORD_ENABLE + +#endif // AP_MICROSTRAIN_ENABLED \ No newline at end of file diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.h b/libraries/AP_ExternalAHRS/MicroStrain_common.h similarity index 58% rename from libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.h rename to libraries/AP_ExternalAHRS/MicroStrain_common.h index 38fab6ebbb8d8c..37158d7c70dfa4 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_LORD.h +++ b/libraries/AP_ExternalAHRS/MicroStrain_common.h @@ -11,43 +11,25 @@ along with this program. If not, see . */ /* - suppport for serial connected AHRS systems + support for MicroStrain MIP parsing */ #pragma once #include "AP_ExternalAHRS_config.h" -#if AP_EXTERNAL_AHRS_LORD_ENABLED +#if AP_MICROSTRAIN_ENABLED -#include "AP_ExternalAHRS_backend.h" #include +#include +#include -class AP_ExternalAHRS_LORD: public AP_ExternalAHRS_backend +class AP_MicroStrain { public: - AP_ExternalAHRS_LORD(AP_ExternalAHRS *frontend, AP_ExternalAHRS::state_t &state); - // get serial port number, -1 for not enabled - int8_t get_port(void) const override; - - // Get model/type name - const char* get_name() const override; - - // accessors for AP_AHRS - bool healthy(void) const override; - 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; - - // check for new data - void update() override { - build_packet(); - }; - -private: +protected: enum class ParseState { WaitingFor_SyncOne, @@ -58,32 +40,16 @@ class AP_ExternalAHRS_LORD: public AP_ExternalAHRS_backend WaitingFor_Checksum }; - void update_thread(); - - AP_HAL::UARTDriver *uart; - HAL_Semaphore sem; - - uint32_t baudrate; - int8_t port_num; - bool port_open = false; - - const uint8_t SYNC_ONE = 0x75; - const uint8_t SYNC_TWO = 0x65; - - uint32_t last_ins_pkt; - uint32_t last_gps_pkt; - uint32_t last_filter_pkt; - - // A LORD packet can be a maximum of 261 bytes - struct LORD_Packet { + // A MicroStrain packet can be a maximum of 261 bytes + struct MicroStrain_Packet { uint8_t header[4]; uint8_t payload[255]; uint8_t checksum[2]; }; struct { - LORD_Packet packet; - ParseState state; + MicroStrain_Packet packet; + AP_MicroStrain::ParseState state; uint8_t index; } message_in; @@ -133,19 +99,36 @@ class AP_ExternalAHRS_LORD: public AP_ExternalAHRS_backend float speed_accuracy; } filter_data; - void build_packet(); - bool valid_packet(const LORD_Packet &packet) const; - void handle_packet(const LORD_Packet &packet); - void handle_imu(const LORD_Packet &packet); - void handle_gnss(const LORD_Packet &packet); - void handle_filter(const LORD_Packet &packet); - void post_imu() const; - void post_gnss() const; - void post_filter() const; + enum class DescriptorSet { + BaseCommand = 0x01, + DMCommand = 0x0C, + SystemCommand = 0x7F, + IMUData = 0x80, + GNSSData = 0x81, + EstimationData = 0x82 + }; - Vector3f populate_vector3f(const uint8_t* data, uint8_t offset) const; - Quaternion populate_quaternion(const uint8_t* data, uint8_t offset) const; + const uint8_t SYNC_ONE = 0x75; + const uint8_t SYNC_TWO = 0x65; + + uint32_t last_ins_pkt; + uint32_t last_gps_pkt; + uint32_t last_filter_pkt; + // Handle a single byte. + // If the byte matches a descriptor, it returns true and that type should be handled. + bool handle_byte(const uint8_t b, DescriptorSet& descriptor); + // Returns true if the fletcher checksum for the packet is valid, else false. + static bool valid_packet(const MicroStrain_Packet &packet); + // Calls the correct functions based on the packet descriptor of the packet + DescriptorSet handle_packet(const MicroStrain_Packet &packet); + // Collects data from an imu packet into `imu_data` + void handle_imu(const MicroStrain_Packet &packet); + // Collects data from a gnss packet into `gnss_data` + void handle_gnss(const MicroStrain_Packet &packet); + void handle_filter(const MicroStrain_Packet &packet); + static Vector3f populate_vector3f(const uint8_t* data, uint8_t offset); + static Quaternion populate_quaternion(const uint8_t* data, uint8_t offset); }; -#endif // AP_EXTERNAL_AHRS_LORD_ENABLED +#endif // AP_MICROSTRAIN_ENABLED diff --git a/libraries/AP_ExternalControl/AP_ExternalControl.cpp b/libraries/AP_ExternalControl/AP_ExternalControl.cpp new file mode 100644 index 00000000000000..e0e92f0a299113 --- /dev/null +++ b/libraries/AP_ExternalControl/AP_ExternalControl.cpp @@ -0,0 +1,24 @@ +#include "AP_ExternalControl.h" + +#if AP_EXTERNAL_CONTROL_ENABLED + +// singleton instance +AP_ExternalControl *AP_ExternalControl::singleton; + +AP_ExternalControl::AP_ExternalControl() +{ + singleton = this; +} + + +namespace AP +{ + +AP_ExternalControl *externalcontrol() +{ + return AP_ExternalControl::get_singleton(); +} + +}; + +#endif // AP_EXTERNAL_CONTROL_ENABLED diff --git a/libraries/AP_ExternalControl/AP_ExternalControl.h b/libraries/AP_ExternalControl/AP_ExternalControl.h new file mode 100644 index 00000000000000..7c3d7b7e35728a --- /dev/null +++ b/libraries/AP_ExternalControl/AP_ExternalControl.h @@ -0,0 +1,43 @@ +/* + external control library for MAVLink, DDS and scripting + */ + +#pragma once + +#include "AP_ExternalControl_config.h" + +#if AP_EXTERNAL_CONTROL_ENABLED + +#include + +class AP_ExternalControl +{ +public: + + AP_ExternalControl(); + /* + Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw. + Velocity is in earth frame, NED [m/s]. + Yaw is in earth frame, NED [rad/s]. + */ + virtual bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) + { + return false; + } + + static AP_ExternalControl *get_singleton(void) + { + return singleton; + } + +private: + static AP_ExternalControl *singleton; +}; + + +namespace AP +{ +AP_ExternalControl *externalcontrol(); +}; + +#endif // AP_EXTERNAL_CONTROL_ENABLED diff --git a/libraries/AP_ExternalControl/AP_ExternalControl_config.h b/libraries/AP_ExternalControl/AP_ExternalControl_config.h new file mode 100644 index 00000000000000..1192bac86717cd --- /dev/null +++ b/libraries/AP_ExternalControl/AP_ExternalControl_config.h @@ -0,0 +1,10 @@ +#pragma once + +#include +#include + +#ifndef AP_EXTERNAL_CONTROL_ENABLED +#define AP_EXTERNAL_CONTROL_ENABLED 1 +#endif + + diff --git a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp index 329402001bdf5f..af59ca8110a180 100644 --- a/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp +++ b/libraries/AP_FETtecOneWire/AP_FETtecOneWire.cpp @@ -154,7 +154,7 @@ void AP_FETtecOneWire::init() } _invalid_mask = false; // mask is good - gcs().send_text(MAV_SEVERITY_INFO, "FETtec: allocated %u motors", _esc_count); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "FETtec: allocated %u motors", _esc_count); // We expect to be able to send a fast-throttle command in each loop. // 8 bits - OneWire Header diff --git a/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp index f728b3362c392c..59cbd357624114 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp @@ -879,7 +879,7 @@ bool AP_Filesystem_FATFS::format(void) #if FF_USE_MKFS WITH_SEMAPHORE(sem); hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Filesystem_FATFS::format_handler, void)); - // the format is handled asyncronously, we inform user of success + // the format is handled asynchronously, we inform user of success // via a text message. format_status can be polled for progress format_status = FormatStatus::PENDING; return true; diff --git a/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp b/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp index f2219e6d7b9ff4..28f296e44647ee 100644 --- a/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp +++ b/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp @@ -56,7 +56,7 @@ static UNUSED_FUNCTION void test_page_program() hal.console->printf("Failed to allocate data for read"); } - // fill program data with its own adress + // fill program data with its own address for (uint32_t i = 0; i < jedec_dev.get_page_size(); i++) { data[i] = i; } diff --git a/libraries/AP_FlashStorage/AP_FlashStorage.cpp b/libraries/AP_FlashStorage/AP_FlashStorage.cpp index a8f99670d6d336..b53960f44bb6d9 100644 --- a/libraries/AP_FlashStorage/AP_FlashStorage.cpp +++ b/libraries/AP_FlashStorage/AP_FlashStorage.cpp @@ -152,7 +152,7 @@ bool AP_FlashStorage::switch_full_sector(void) } // protected_switch_full_sector is protected by switch_full_sector to -// avoid an infinite recursion problem; switch_full_sectory calls +// avoid an infinite recursion problem; switch_full_sector calls // write() which can call switch_full_sector. This has been seen in // practice, and while it might be caused by corruption... corruption // happens. diff --git a/libraries/AP_FlashStorage/AP_FlashStorage.h b/libraries/AP_FlashStorage/AP_FlashStorage.h index b4cb1afd71a890..0f9b6fe3b776e8 100644 --- a/libraries/AP_FlashStorage/AP_FlashStorage.h +++ b/libraries/AP_FlashStorage/AP_FlashStorage.h @@ -236,7 +236,7 @@ class AP_FlashStorage { bool switch_sectors(void) WARN_IF_UNUSED; // _switch_full_sector is protected by switch_full_sector to avoid - // an infinite recursion problem; switch_full_sectory calls + // an infinite recursion problem; switch_full_sector calls // write() which can call switch_full_sector. This has been seen // in practice. bool protected_switch_full_sector(void) WARN_IF_UNUSED; diff --git a/libraries/AP_Follow/AP_Follow.cpp b/libraries/AP_Follow/AP_Follow.cpp index 15196278be72e2..bb7dedc03aae7b 100644 --- a/libraries/AP_Follow/AP_Follow.cpp +++ b/libraries/AP_Follow/AP_Follow.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_Follow_config.h" + +#if AP_FOLLOW_ENABLED + #include #include "AP_Follow.h" #include @@ -26,7 +30,7 @@ extern const AP_HAL::HAL& hal; #define AP_FOLLOW_TIMEOUT_MS 3000 // position estimate timeout after 1 second -#define AP_FOLLOW_SYSID_TIMEOUT_MS 10000 // forget sysid we are following if we haave not heard from them in 10 seconds +#define AP_FOLLOW_SYSID_TIMEOUT_MS 10000 // forget sysid we are following if we have not heard from them in 10 seconds #define AP_FOLLOW_OFFSET_TYPE_NED 0 // offsets are in north-east-down frame #define AP_FOLLOW_OFFSET_TYPE_RELATIVE 1 // offsets are relative to lead vehicle's heading @@ -534,3 +538,5 @@ AP_Follow &follow() } } + +#endif diff --git a/libraries/AP_Follow/AP_Follow.h b/libraries/AP_Follow/AP_Follow.h index 78f413c98d8d1c..5918215352a7ca 100644 --- a/libraries/AP_Follow/AP_Follow.h +++ b/libraries/AP_Follow/AP_Follow.h @@ -13,6 +13,9 @@ along with this program. If not, see . */ #pragma once +#include "AP_Follow_config.h" + +#if AP_FOLLOW_ENABLED #include #include @@ -160,3 +163,5 @@ class AP_Follow namespace AP { AP_Follow &follow(); }; + +#endif diff --git a/libraries/AP_Follow/AP_Follow_config.h b/libraries/AP_Follow/AP_Follow_config.h new file mode 100644 index 00000000000000..f5aa2dae54d465 --- /dev/null +++ b/libraries/AP_Follow/AP_Follow_config.h @@ -0,0 +1,5 @@ +#pragma once + +#ifndef AP_FOLLOW_ENABLED +#define AP_FOLLOW_ENABLED 1 +#endif diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_D.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_D.cpp index 45d4edbbb76c24..90047effd583bc 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_D.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_D.cpp @@ -71,8 +71,8 @@ void AP_Frsky_D::send(void) send_uint16(DATA_ID_GPS_COURS_BP, (uint16_t)((_ahrs.yaw_sensor / 100) % 360)); // send heading in degree based on AHRS and not GPS calc_gps_position(); if (AP::gps().status() >= 3) { - send_uint16(DATA_ID_GPS_LAT_BP, _SPort_data.latdddmm); // send gps lattitude degree and minute integer part - send_uint16(DATA_ID_GPS_LAT_AP, _SPort_data.latmmmm); // send gps lattitude minutes decimal part + send_uint16(DATA_ID_GPS_LAT_BP, _SPort_data.latdddmm); // send gps latitude degree and minute integer part + send_uint16(DATA_ID_GPS_LAT_AP, _SPort_data.latmmmm); // send gps latitude minutes decimal part send_uint16(DATA_ID_GPS_LAT_NS, _SPort_data.lat_ns); // send gps North / South information send_uint16(DATA_ID_GPS_LONG_BP, _SPort_data.londddmm); // send gps longitude degree and minute integer part send_uint16(DATA_ID_GPS_LONG_AP, _SPort_data.lonmmmm); // send gps longitude minutes decimal part diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp index 75daa6c4c2e4c7..623ad0184f748e 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_MAVliteMsgHandler.cpp @@ -54,8 +54,10 @@ MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command(const mavlink_command_long case MAV_CMD_DO_SET_MODE: return handle_command_do_set_mode(mav_command_long); //case MAV_CMD_DO_SET_HOME: +#if AP_FENCE_ENABLED case MAV_CMD_DO_FENCE_ENABLE: return handle_command_do_fence_enable(mav_command_long); +#endif case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: return handle_command_preflight_reboot(mav_command_long); //case MAV_CMD_DO_START_MAG_CAL: @@ -127,9 +129,9 @@ MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_preflight_calibration_baro return MAV_RESULT_DENIED; } // 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 AP_Airspeed *airspeed = AP_Airspeed::get_singleton(); @@ -141,9 +143,9 @@ MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_preflight_calibration_baro return MAV_RESULT_ACCEPTED; } +#if AP_FENCE_ENABLED MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_do_fence_enable(const mavlink_command_long_t &mav_command_long) { -#if AP_FENCE_ENABLED AC_Fence *fence = AP::fence(); if (fence == nullptr) { return MAV_RESULT_UNSUPPORTED; @@ -159,10 +161,8 @@ MAV_RESULT AP_Frsky_MAVliteMsgHandler::handle_command_do_fence_enable(const mavl default: return MAV_RESULT_FAILED; } -#else - return MAV_RESULT_UNSUPPORTED; -#endif // AP_FENCE_ENABLED } +#endif // AP_FENCE_ENABLED /* * Handle the PARAM_REQUEST_READ mavlite message @@ -177,7 +177,7 @@ void AP_Frsky_MAVliteMsgHandler::handle_param_request_read(const AP_Frsky_MAVlit } // find existing param if (!AP_Param::get(param_name,param_value)) { - gcs().send_text(MAV_SEVERITY_WARNING, "Param read failed (%s)", param_name); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Param read failed (%s)", param_name); return; } AP_Frsky_MAVlite_Message txmsg; @@ -223,13 +223,13 @@ void AP_Frsky_MAVliteMsgHandler::handle_param_set(const AP_Frsky_MAVlite_Message } } if ((parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) || vp->is_read_only()) { - gcs().send_text(MAV_SEVERITY_WARNING, "Param write denied (%s)", param_name); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Param write denied (%s)", param_name); } else if (!AP_Param::set_and_save_by_name(param_name, param_value)) { - gcs().send_text(MAV_SEVERITY_WARNING, "Param write failed (%s)", param_name); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Param write failed (%s)", param_name); } // let's read back the last value, either the readonly one or the updated one if (!AP_Param::get(param_name,param_value)) { - gcs().send_text(MAV_SEVERITY_WARNING, "Param read failed (%s)", param_name); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Param read failed (%s)", param_name); return; } AP_Frsky_MAVlite_Message txmsg; diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_MAVlite_SPortToMAVlite.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_MAVlite_SPortToMAVlite.cpp index 26b8b5b2af9732..601c7e98d021f3 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_MAVlite_SPortToMAVlite.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_MAVlite_SPortToMAVlite.cpp @@ -20,7 +20,7 @@ void AP_Frsky_MAVlite_SPortToMAVlite::update_checksum(const uint8_t c) } /* - Parses sport packets and if successfull fills the rxmsg mavlite struct + Parses sport packets and if successful fills the rxmsg mavlite struct */ bool AP_Frsky_MAVlite_SPortToMAVlite::process(AP_Frsky_MAVlite_Message &rxmsg, const AP_Frsky_SPort::sport_packet_t &packet) { diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 62ec572a26ba75..a085c021f283cc 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -12,6 +12,10 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ +#include "AP_GPS_config.h" + +#if AP_GPS_ENABLED + #include "AP_GPS.h" #include @@ -49,6 +53,7 @@ #include #include +#include "AP_GPS_FixType.h" #define GPS_RTK_INJECT_TO_ALL 127 #ifndef GPS_MAX_RATE_MS @@ -107,6 +112,16 @@ static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT == (uint32_t static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED == (uint32_t)GPS_FIX_TYPE_RTK_FIXED, "FIX_RTK_FIXED incorrect"); #endif +// ensure that our own enum-class status is equivalent to the +// ArduPilot-scoped AP_GPS_FixType enumeration: +static_assert((uint32_t)AP_GPS::GPS_Status::NO_GPS == (uint8_t)AP_GPS_FixType::NO_GPS, "NO_GPS incorrect"); +static_assert((uint32_t)AP_GPS::GPS_Status::NO_FIX == (uint8_t)AP_GPS_FixType::NONE, "NO_FIX incorrect"); +static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_2D == (uint8_t)AP_GPS_FixType::FIX_2D, "FIX_2D incorrect"); +static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D == (uint8_t)AP_GPS_FixType::FIX_3D, "FIX_3D incorrect"); +static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS == (uint8_t)AP_GPS_FixType::DGPS, "FIX_DGPS incorrect"); +static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT == (uint8_t)AP_GPS_FixType::RTK_FLOAT, "FIX_RTK_FLOAT incorrect"); +static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED == (uint8_t)AP_GPS_FixType::RTK_FIXED, "FIX_RTK_FIXED incorrect"); + AP_GPS *AP_GPS::_singleton; // table of user settable parameters @@ -334,7 +349,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { // @Param: _DRV_OPTIONS // @DisplayName: driver options // @Description: Additional backend specific options - // @Bitmask: 0:Use UART2 for moving baseline on ublox,1:Use base station for GPS yaw on SBF,2:Use baudrate 115200,3:Use dedicated CAN port b/w GPSes for moving baseline,4:Use ellipsoid height instead of AMSL for uBlox driver + // @Bitmask: 0:Use UART2 for moving baseline on ublox,1:Use base station for GPS yaw on SBF,2:Use baudrate 115200,3:Use dedicated CAN port b/w GPSes for moving baseline,4:Use ellipsoid height instead of AMSL // @User: Advanced AP_GROUPINFO("_DRV_OPTIONS", 22, AP_GPS, _driver_options, 0), @@ -470,8 +485,10 @@ void AP_GPS::init(const AP_SerialManager& serial_manager) } _last_instance_swap_ms = 0; +#if defined(GPS_BLENDED_INSTANCE) // Initialise class variables used to do GPS blending _omega_lpf = 1.0f / constrain_float(_blend_tc, 5.0f, 30.0f); +#endif // prep the state instance fields for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) { @@ -491,11 +508,12 @@ void AP_GPS::init(const AP_SerialManager& serial_manager) // GPS solution is treated as an additional sensor. uint8_t AP_GPS::num_sensors(void) const { - if (!_output_is_blended) { - return num_instances; - } else { +#if defined(GPS_BLENDED_INSTANCE) + if (_output_is_blended) { return num_instances+1; } +#endif + return num_instances; } bool AP_GPS::speed_accuracy(uint8_t instance, float &sacc) const @@ -725,7 +743,7 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) case GPS_TYPE_UAVCAN: case GPS_TYPE_UAVCAN_RTK_BASE: case GPS_TYPE_UAVCAN_RTK_ROVER: -#if HAL_ENABLE_DRONECAN_DRIVERS +#if AP_GPS_DRONECAN_ENABLED dstate->auto_detected_baud = false; // specified, not detected return AP_GPS_DroneCAN::probe(*this, state[instance]); #endif @@ -1037,17 +1055,17 @@ void AP_GPS::update_instance(uint8_t instance) if (data_should_be_logged && should_log()) { Write_GPS(instance); } +#else + (void)data_should_be_logged; #endif -#ifndef HAL_BUILD_AP_PERIPH +#if AP_RTC_ENABLED if (state[instance].status >= GPS_OK_FIX_3D) { const uint64_t now = time_epoch_usec(instance); if (now != 0) { AP::rtc().set_utc_usec(now, AP_RTC::SOURCE_GPS); } } -#else - (void)data_should_be_logged; #endif } @@ -1146,8 +1164,18 @@ void AP_GPS::update(void) void AP_GPS::update_primary(void) { #if defined(GPS_BLENDED_INSTANCE) - // if blending is requested, attempt to calculate weighting for each GPS - if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::BLEND) { + /* + if blending is requested, attempt to calculate weighting for + each GPS + we do not do blending if using moving baseline yaw as the rover is + significant lagged and gives no more information on position or + velocity + */ + const bool using_moving_base = (_type[0] == GPS_TYPE_UAVCAN_RTK_BASE || + _type[0] == GPS_TYPE_UBLOX_RTK_BASE || + _type[1] == GPS_TYPE_UAVCAN_RTK_BASE || + _type[1] == GPS_TYPE_UBLOX_RTK_BASE); + if ((GPSAutoSwitch)_auto_switch.get() == GPSAutoSwitch::BLEND && !using_moving_base) { _output_is_blended = calc_blend_weights(); // adjust blend health counter if (!_output_is_blended) { @@ -1291,6 +1319,7 @@ void AP_GPS::update_primary(void) } #endif // GPS_MAX_RECEIVERS > 1 +#if HAL_GCS_ENABLED void AP_GPS::handle_gps_inject(const mavlink_message_t &msg) { mavlink_gps_inject_data_t packet; @@ -1328,6 +1357,7 @@ void AP_GPS::handle_msg(const mavlink_message_t &msg) } } } +#endif #if HAL_MSP_GPS_ENABLED void AP_GPS::handle_msp(const MSP::msp_gps_data_message_t &pkt) @@ -1341,13 +1371,23 @@ void AP_GPS::handle_msp(const MSP::msp_gps_data_message_t &pkt) #endif // HAL_MSP_GPS_ENABLED #if HAL_EXTERNAL_AHRS_ENABLED -void AP_GPS::handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt) + +bool AP_GPS::get_first_external_instance(uint8_t& instance) const { for (uint8_t i=0; ihandle_external(pkt); + instance = i; + return true; } } + return false; +} + +void AP_GPS::handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt, const uint8_t instance) +{ + if (_type[instance] == GPS_TYPE_EXTERNAL_AHRS && drivers[instance] != nullptr) { + drivers[instance]->handle_external(pkt); + } } #endif // HAL_EXTERNAL_AHRS_ENABLED @@ -1442,7 +1482,7 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan) ground_speed(0)*100, // cm/s ground_course(0)*100, // 1/100 degrees, num_sats(0), - height_elipsoid_mm, // Elipsoid height in mm + height_elipsoid_mm, // Ellipsoid height in mm hacc * 1000, // one-sigma standard deviation in mm vacc * 1000, // one-sigma standard deviation in mm sacc * 1000, // one-sigma standard deviation in mm/s @@ -1485,7 +1525,7 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) state[1].rtk_num_sats, state[1].rtk_age_ms, gps_yaw_cdeg(1), - height_elipsoid_mm, // Elipsoid height in mm + height_elipsoid_mm, // Ellipsoid height in mm hacc * 1000, // one-sigma standard deviation in mm vacc * 1000, // one-sigma standard deviation in mm sacc * 1000, // one-sigma standard deviation in mm/s @@ -1493,6 +1533,7 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) } #endif // GPS_MAX_RECEIVERS +#if HAL_GCS_ENABLED void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst) { if (inst >= GPS_MAX_RECEIVERS) { @@ -1502,6 +1543,7 @@ void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan, uint8_t inst) drivers[inst]->send_mavlink_gps_rtk(chan); } } +#endif bool AP_GPS::first_unconfigured_gps(uint8_t &instance) const { @@ -1542,11 +1584,13 @@ bool AP_GPS::all_consistent(float &distance) const return (distance < 50); } +#if defined(GPS_BLENDED_INSTANCE) // 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); } +#endif /* re-assemble fragmented RTCM data @@ -1659,7 +1703,7 @@ void AP_GPS::Write_AP_Logger_Log_Startup_messages() */ bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const { - // always enusre a lag is provided + // always ensure a lag is provided lag_sec = 0.1f; if (instance >= GPS_MAX_INSTANCES) { @@ -2104,21 +2148,21 @@ bool AP_GPS::is_healthy(uint8_t instance) const return false; } -#ifdef HAL_BUILD_AP_PERIPH +#ifndef HAL_BUILD_AP_PERIPH /* on AP_Periph handling of timing is done by the flight controller receiving the DroneCAN messages */ - return drivers[instance] != nullptr && drivers[instance]->is_healthy(); -#else /* allow two lost frames before declaring the GPS unhealthy, but - require the average frame rate to be close to 5Hz. We allow for - a bit higher average for a rover due to the packet loss that - happens with the RTCMv3 data + require the average frame rate to be close to 5Hz. + + We allow for a rate of 3Hz average for a moving baseline rover + due to the packet loss that happens with the RTCMv3 data and the + fact that the rate of yaw data is not critical */ const uint8_t delay_threshold = 2; - const float delay_avg_max = ((_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) || (_type[instance] == GPS_TYPE_UAVCAN_RTK_ROVER))?245:215; + const float delay_avg_max = ((_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) || (_type[instance] == GPS_TYPE_UAVCAN_RTK_ROVER))?333:215; const GPS_timing &t = timing[instance]; bool delay_ok = (t.delayed_count < delay_threshold) && t.average_delta_ms < delay_avg_max && @@ -2126,6 +2170,7 @@ bool AP_GPS::is_healthy(uint8_t instance) const if (!delay_ok) { return false; } +#endif // HAL_BUILD_AP_PERIPH #if defined(GPS_BLENDED_INSTANCE) if (instance == GPS_BLENDED_INSTANCE) { @@ -2135,7 +2180,6 @@ bool AP_GPS::is_healthy(uint8_t instance) const return drivers[instance] != nullptr && drivers[instance]->is_healthy(); -#endif // HAL_BUILD_AP_PERIPH } bool AP_GPS::prepare_for_arming(void) { @@ -2150,7 +2194,7 @@ bool AP_GPS::prepare_for_arming(void) { bool AP_GPS::backends_healthy(char failure_msg[], uint16_t failure_msg_len) { for (uint8_t i = 0; i < GPS_MAX_RECEIVERS; i++) { -#if HAL_ENABLE_DRONECAN_DRIVERS +#if AP_GPS_DRONECAN_ENABLED if (_type[i] == GPS_TYPE_UAVCAN || _type[i] == GPS_TYPE_UAVCAN_RTK_BASE || _type[i] == GPS_TYPE_UAVCAN_RTK_ROVER) { @@ -2313,3 +2357,5 @@ AP_GPS &gps() } }; + +#endif // AP_GPS_ENABLED diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index ed66955ae5d83c..a097e25138ee29 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_GPS_config.h" + +#if AP_GPS_ENABLED + #include #include #include @@ -59,10 +63,6 @@ #define GPS_MOVING_BASELINE GPS_MAX_RECEIVERS>1 #endif -#ifndef HAL_MSP_GPS_ENABLED -#define HAL_MSP_GPS_ENABLED HAL_MSP_SENSORS_ENABLED -#endif - #if GPS_MOVING_BASELINE #include "MovingBase.h" #endif // GPS_MOVING_BASELINE @@ -249,7 +249,11 @@ class AP_GPS void handle_msp(const MSP::msp_gps_data_message_t &pkt); #endif #if HAL_EXTERNAL_AHRS_ENABLED - void handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt); + // Retrieve the first instance ID that is configured as type GPS_TYPE_EXTERNAL_AHRS. + // Can be used by external AHRS systems that only report one GPS to get the instance ID. + // Returns true if an instance was found, false otherwise. + bool get_first_external_instance(uint8_t& instance) const WARN_IF_UNUSED; + void handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt, const uint8_t instance); #endif // Accessor functions @@ -730,6 +734,7 @@ class AP_GPS void inject_data(const uint8_t *data, uint16_t len); void inject_data(uint8_t instance, const uint8_t *data, uint16_t len); +#if defined(GPS_BLENDED_INSTANCE) // GPS blending and switching Vector3f _blended_antenna_offset; // blended antenna offset float _blended_lag_sec; // blended receiver lag in seconds @@ -743,6 +748,7 @@ class AP_GPS // calculate the blended state void calc_blended_state(void); +#endif bool should_log() const; @@ -785,3 +791,5 @@ class AP_GPS namespace AP { AP_GPS &gps(); }; + +#endif // AP_GPS_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp index b3d361f80b5612..2471d3958019f4 100644 --- a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp @@ -16,9 +16,12 @@ // // UAVCAN GPS driver // +#include "AP_GPS_config.h" + +#if AP_GPS_DRONECAN_ENABLED + #include -#if HAL_ENABLE_DRONECAN_DRIVERS #include "AP_GPS_DroneCAN.h" #include @@ -52,7 +55,7 @@ extern const AP_HAL::HAL& hal; #define LOG_TAG "GPS" #if CONFIG_HAL_BOARD == HAL_BOARD_SITL -#define NATIVE_TIME_OFFSET (AP_HAL::micros64() - AP_HAL::native_micros64()) +#define NATIVE_TIME_OFFSET (AP_HAL::micros64() - AP_HAL::micros64()) #else #define NATIVE_TIME_OFFSET 0 #endif @@ -318,7 +321,7 @@ AP_GPS_DroneCAN* AP_GPS_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, */ void AP_GPS_DroneCAN::handle_velocity(const float vx, const float vy, const float vz) { - if (!isnanf(vx)) { + if (!isnan(vx)) { const Vector3f vel(vx, vy, vz); interim_state.velocity = vel; velocity_to_speed_course(interim_state); @@ -380,29 +383,30 @@ void AP_GPS_DroneCAN::handle_fix2_msg(const uavcan_equipment_gnss_Fix2& msg, uin Location loc = { }; loc.lat = msg.latitude_deg_1e8 / 10; loc.lng = msg.longitude_deg_1e8 / 10; - loc.alt = msg.height_msl_mm / 10; + const int32_t alt_amsl_cm = msg.height_msl_mm / 10; interim_state.have_undulation = true; interim_state.undulation = (msg.height_msl_mm - msg.height_ellipsoid_mm) * 0.001; interim_state.location = loc; + set_alt_amsl_cm(interim_state, alt_amsl_cm); handle_velocity(msg.ned_velocity[0], msg.ned_velocity[1], msg.ned_velocity[2]); if (msg.covariance.len == 6) { - if (!isnanf(msg.covariance.data[0])) { + if (!isnan(msg.covariance.data[0])) { interim_state.horizontal_accuracy = sqrtf(msg.covariance.data[0]); interim_state.have_horizontal_accuracy = true; } else { interim_state.have_horizontal_accuracy = false; } - if (!isnanf(msg.covariance.data[2])) { + if (!isnan(msg.covariance.data[2])) { interim_state.vertical_accuracy = sqrtf(msg.covariance.data[2]); interim_state.have_vertical_accuracy = true; } else { interim_state.have_vertical_accuracy = false; } - if (!isnanf(msg.covariance.data[3]) && - !isnanf(msg.covariance.data[4]) && - !isnanf(msg.covariance.data[5])) { + if (!isnan(msg.covariance.data[3]) && + !isnan(msg.covariance.data[4]) && + !isnan(msg.covariance.data[5])) { interim_state.speed_accuracy = sqrtf((msg.covariance.data[3] + msg.covariance.data[4] + msg.covariance.data[5])/3); interim_state.have_speed_accuracy = true; } else { @@ -476,12 +480,12 @@ void AP_GPS_DroneCAN::handle_aux_msg(const uavcan_equipment_gnss_Auxiliary& msg) { WITH_SEMAPHORE(sem); - if (!isnanf(msg.hdop)) { + if (!isnan(msg.hdop)) { seen_aux = true; interim_state.hdop = msg.hdop * 100.0; } - if (!isnanf(msg.vdop)) { + if (!isnan(msg.vdop)) { seen_aux = true; interim_state.vdop = msg.vdop * 100.0; } @@ -768,7 +772,7 @@ void AP_GPS_DroneCAN::send_rtcm(void) } WITH_SEMAPHORE(sem); - const uint32_t now = AP_HAL::native_millis(); + const uint32_t now = AP_HAL::millis(); if (now - _rtcm_stream.last_send_ms < 20) { // don't send more than 50 per second return; @@ -796,7 +800,7 @@ void AP_GPS_DroneCAN::inject_data(const uint8_t *data, uint16_t len) { // we only handle this if we are the first DroneCAN GPS or we are // using a different uavcan instance than the first GPS, as we - // send the data as broadcast on all DroneCAN devive ports and we + // send the data as broadcast on all DroneCAN device ports and we // don't want to send duplicates const uint32_t now_ms = AP_HAL::millis(); if (_detected_module == 0 || @@ -891,4 +895,4 @@ bool AP_GPS_DroneCAN::instance_exists(const AP_DroneCAN* ap_dronecan) } #endif // AP_DRONECAN_SEND_GPS -#endif // HAL_ENABLE_DRONECAN_DRIVERS +#endif // AP_GPS_DRONECAN_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.h b/libraries/AP_GPS/AP_GPS_DroneCAN.h index 9d77a8d6eba978..10f6d71954a3ca 100644 --- a/libraries/AP_GPS/AP_GPS_DroneCAN.h +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.h @@ -18,9 +18,12 @@ // #pragma once +#include "AP_GPS_config.h" + +#if AP_GPS_DRONECAN_ENABLED + #include #include -#if HAL_ENABLE_DRONECAN_DRIVERS #include "AP_GPS.h" #include "GPS_Backend.h" #include "RTCM3_Parser.h" @@ -147,4 +150,5 @@ class AP_GPS_DroneCAN : public AP_GPS_Backend { ByteBuffer *buf; } _rtcm_stream; }; -#endif + +#endif // AP_GPS_DRONECAN_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_ERB.cpp b/libraries/AP_GPS/AP_GPS_ERB.cpp index 3326ac60405d34..1dde8997f2d85d 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.cpp +++ b/libraries/AP_GPS/AP_GPS_ERB.cpp @@ -150,9 +150,9 @@ AP_GPS_ERB::_parse_gps(void) _last_pos_time = _buffer.pos.time; state.location.lng = (int32_t)(_buffer.pos.longitude * (double)1e7); state.location.lat = (int32_t)(_buffer.pos.latitude * (double)1e7); - state.location.alt = (int32_t)(_buffer.pos.altitude_msl * 100); state.have_undulation = true; state.undulation = _buffer.pos.altitude_msl - _buffer.pos.altitude_ellipsoid; + set_alt_amsl_cm(state, _buffer.pos.altitude_msl * 100); state.status = next_fix; _new_position = true; state.horizontal_accuracy = _buffer.pos.horizontal_accuracy * 1.0e-3f; diff --git a/libraries/AP_GPS/AP_GPS_ERB.h b/libraries/AP_GPS/AP_GPS_ERB.h index 8fb6f7ed0e3988..6e99fbe8e73d9d 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.h +++ b/libraries/AP_GPS/AP_GPS_ERB.h @@ -34,7 +34,9 @@ class AP_GPS_ERB : public AP_GPS_Backend AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } +#if HAL_GCS_ENABLED bool supports_mavlink_gps_rtk_message() const override { return true; } +#endif static bool _detect(struct ERB_detect_state &state, uint8_t data); diff --git a/libraries/AP_GPS/AP_GPS_FixType.h b/libraries/AP_GPS/AP_GPS_FixType.h new file mode 100644 index 00000000000000..e3254551d3bd25 --- /dev/null +++ b/libraries/AP_GPS/AP_GPS_FixType.h @@ -0,0 +1,18 @@ +#pragma once + +// a AP_GPS-library-independent enumeration which lists the commonly +// accepted set of GPS Fix Types which GPSs report. This header can +// be used even if AP_GPS is not compiled in. + +// this is not enum-class as many places in the code want to check for +// "a fix at least this good" using "<". + +enum AP_GPS_FixType { + NO_GPS = 0, ///< No GPS connected/detected + NONE = 1, ///< Receiving valid GPS messages but no lock + FIX_2D = 2, ///< Receiving valid messages and 2D lock + FIX_3D = 3, ///< Receiving valid messages and 3D lock + DGPS = 4, ///< Receiving valid messages and 3D lock with differential improvements + RTK_FLOAT = 5, ///< Receiving valid messages and 3D RTK Float + RTK_FIXED = 6, ///< Receiving valid messages and 3D RTK Fixed +}; diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index dab26c3494ab1c..248e38ef139201 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -23,6 +23,7 @@ #include "AP_GPS.h" #include "AP_GPS_GSOF.h" #include +#include #if AP_GPS_GSOF_ENABLED @@ -224,29 +225,17 @@ AP_GPS_GSOF::SwapFloat(const uint8_t* src, const uint32_t pos) const uint32_t AP_GPS_GSOF::SwapUint32(const uint8_t* src, const uint32_t pos) const { - union { - uint32_t u; - char bytes[sizeof(uint32_t)]; - } uint32u; - uint32u.bytes[0] = src[pos + 3]; - uint32u.bytes[1] = src[pos + 2]; - uint32u.bytes[2] = src[pos + 1]; - uint32u.bytes[3] = src[pos + 0]; - - return uint32u.u; + 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 { - union { - uint16_t u; - char bytes[sizeof(uint16_t)]; - } uint16u; - uint16u.bytes[0] = src[pos + 1]; - uint16u.bytes[1] = src[pos + 0]; - - return uint16u.u; + uint16_t u; + memcpy(&u, &src[pos], sizeof(u)); + return be16toh(u); } bool diff --git a/libraries/AP_GPS/AP_GPS_MAV.cpp b/libraries/AP_GPS/AP_GPS_MAV.cpp index c195d96254c4f0..d5c3f4925ea888 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.cpp +++ b/libraries/AP_GPS/AP_GPS_MAV.cpp @@ -16,11 +16,14 @@ // // MAVLINK GPS driver // -#include "AP_GPS_MAV.h" -#include + +#include "AP_GPS_config.h" #if AP_GPS_MAV_ENABLED +#include "AP_GPS_MAV.h" +#include + // Reading does nothing in this class; we simply return whether or not // the latest reading has been consumed. By calling this function we assume // the caller is consuming the new data; diff --git a/libraries/AP_GPS/AP_GPS_MAV.h b/libraries/AP_GPS/AP_GPS_MAV.h index f0c3872d79caad..5128949a9c740b 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.h +++ b/libraries/AP_GPS/AP_GPS_MAV.h @@ -19,16 +19,15 @@ // #pragma once +#include "AP_GPS_config.h" + +#if AP_GPS_MAV_ENABLED + #include #include "AP_GPS.h" #include "GPS_Backend.h" -#ifndef AP_GPS_MAV_ENABLED - #define AP_GPS_MAV_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED -#endif - -#if AP_GPS_MAV_ENABLED class AP_GPS_MAV : public AP_GPS_Backend { public: @@ -47,4 +46,5 @@ class AP_GPS_MAV : public AP_GPS_Backend { uint32_t first_week; JitterCorrection jitter{2000}; }; -#endif + +#endif // AP_GPS_MAV_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index f9b6a0285984d6..1712f6754bcc57 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -329,7 +329,7 @@ bool AP_GPS_NMEA::_term_complete() case _GPS_SENTENCE_GGA: _last_GGA_ms = now; if (_last_KSXT_pos_ms == 0 && _last_AGRICA_ms == 0) { - state.location.alt = _new_altitude; + set_alt_amsl_cm(state, _new_altitude); state.location.lat = _new_latitude; state.location.lng = _new_longitude; } @@ -426,7 +426,7 @@ bool AP_GPS_NMEA::_term_complete() } state.location.lat = _ksxt.fields[2]*1.0e7; state.location.lng = _ksxt.fields[1]*1.0e7; - state.location.alt = _ksxt.fields[3]*1.0e2; + set_alt_amsl_cm(state, _ksxt.fields[3]*1.0e2); _last_KSXT_pos_ms = now; if (_ksxt.fields[9] >= 1) { // we have 3D fix @@ -458,8 +458,9 @@ bool AP_GPS_NMEA::_term_complete() _last_3D_velocity_ms = now; state.location.lat = ag.lat*1.0e7; state.location.lng = ag.lng*1.0e7; - state.location.alt = ag.alt*1.0e2; state.undulation = -ag.undulation; + state.have_undulation = true; + set_alt_amsl_cm(state, ag.alt*1.0e2); state.velocity = ag.vel_NED; velocity_to_speed_course(state); state.speed_accuracy = ag.vel_stddev.length(); @@ -469,7 +470,6 @@ bool AP_GPS_NMEA::_term_complete() state.have_speed_accuracy = true; state.have_horizontal_accuracy = true; state.have_vertical_accuracy = true; - state.have_undulation = true; check_new_itow(ag.itow, _sentence_length); break; } @@ -629,7 +629,7 @@ bool AP_GPS_NMEA::_term_complete() // case _GPS_SENTENCE_RMC + 7: // Speed (GPRMC) case _GPS_SENTENCE_VTG + 5: // Speed (VTG) - _new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximiates * 0.514 + _new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximates * 0.514 break; case _GPS_SENTENCE_HDT + 1: // Course (HDT) _new_gps_yaw = _parse_decimal_100(_term); diff --git a/libraries/AP_GPS/AP_GPS_NOVA.cpp b/libraries/AP_GPS/AP_GPS_NOVA.cpp index 86780bdd6b79de..bea9bfd675f424 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.cpp +++ b/libraries/AP_GPS/AP_GPS_NOVA.cpp @@ -86,8 +86,11 @@ AP_GPS_NOVA::read(void) } bool ret = false; - while (port->available() > 0) { - uint8_t temp = port->read(); + for (uint16_t i=0; i<8192; i++) { + uint8_t temp; + if (!port->read(temp)) { + break; + } #if AP_GPS_DEBUG_LOGGING_ENABLED log_data(&temp, 1); #endif @@ -205,9 +208,9 @@ AP_GPS_NOVA::process_message(void) state.location.lat = (int32_t) (bestposu.lat * (double)1e7); state.location.lng = (int32_t) (bestposu.lng * (double)1e7); - state.location.alt = (int32_t) (bestposu.hgt * 100); state.have_undulation = true; state.undulation = bestposu.undulation; + set_alt_amsl_cm(state, bestposu.hgt * 100); state.num_sats = bestposu.svsused; diff --git a/libraries/AP_GPS/AP_GPS_SBF.cpp b/libraries/AP_GPS/AP_GPS_SBF.cpp index 5119786f27c19b..3b1d8d70095c96 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.cpp +++ b/libraries/AP_GPS/AP_GPS_SBF.cpp @@ -415,9 +415,9 @@ 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.location.alt = (int32_t)(((float)temp.Height - temp.Undulation) * 1e2f); state.have_undulation = true; state.undulation = -temp.Undulation; + set_alt_amsl_cm(state, ((float)temp.Height - temp.Undulation) * 1e2f); } if (temp.NrSV != 255) { diff --git a/libraries/AP_GPS/AP_GPS_SBF.h b/libraries/AP_GPS/AP_GPS_SBF.h index ac4944a9ccb8a5..2d8d47baafc500 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.h +++ b/libraries/AP_GPS/AP_GPS_SBF.h @@ -45,7 +45,9 @@ class AP_GPS_SBF : public AP_GPS_Backend void broadcast_configuration_failure_reason(void) const override; +#if HAL_GCS_ENABLED bool supports_mavlink_gps_rtk_message(void) const override { return true; }; +#endif // get the velocity lag, returns true if the driver is confident in the returned value bool get_lag(float &lag_sec) const override { lag_sec = 0.08f; return true; } ; diff --git a/libraries/AP_GPS/AP_GPS_SBP.h b/libraries/AP_GPS/AP_GPS_SBP.h index 6ebeb1892d6570..a5535889312013 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.h +++ b/libraries/AP_GPS/AP_GPS_SBP.h @@ -32,7 +32,9 @@ class AP_GPS_SBP : public AP_GPS_Backend AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } +#if HAL_GCS_ENABLED bool supports_mavlink_gps_rtk_message() const override { return true; } +#endif // Methods bool read() override; diff --git a/libraries/AP_GPS/AP_GPS_SIRF.cpp b/libraries/AP_GPS/AP_GPS_SIRF.cpp index d758003c3ff70e..da37a94affe8d0 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.cpp +++ b/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -18,10 +18,14 @@ // Code by Michael Smith. // +#include "AP_GPS_config.h" + +#if AP_GPS_SIRF_ENABLED + #include "AP_GPS_SIRF.h" +#include #include -#if AP_GPS_SIRF_ENABLED // Initialisation messages // // Turn off all messages except for 0x29. @@ -177,13 +181,15 @@ AP_GPS_SIRF::_parse_gps(void) }else{ state.status = AP_GPS::GPS_OK_FIX_2D; } - state.location.lat = swap_int32(_buffer.nav.latitude); - state.location.lng = swap_int32(_buffer.nav.longitude); - state.location.alt = swap_int32(_buffer.nav.altitude_msl); + state.location.lat = int32_t(be32toh(_buffer.nav.latitude)); + state.location.lng = int32_t(be32toh(_buffer.nav.longitude)); + const int32_t alt_amsl = int32_t(be32toh(_buffer.nav.altitude_msl)); + const int32_t alt_ellipsoid = int32_t(be32toh(_buffer.nav.altitude_ellipsoid)); + state.undulation = (alt_amsl - alt_ellipsoid)*0.01; state.have_undulation = true; - state.undulation = (state.location.alt - swap_int32(_buffer.nav.altitude_ellipsoid))*0.01; - state.ground_speed = swap_int32(_buffer.nav.ground_speed)*0.01f; - state.ground_course = wrap_360(swap_int16(_buffer.nav.ground_course)*0.01f); + set_alt_amsl_cm(state, alt_amsl); + state.ground_speed = int32_t(be32toh(_buffer.nav.ground_speed))*0.01f; + state.ground_course = wrap_360(int16_t(be16toh(_buffer.nav.ground_course)*0.01f)); state.num_sats = _buffer.nav.satellites; fill_3d_velocity(); return true; @@ -248,4 +254,5 @@ bool AP_GPS_SIRF::_detect(struct SIRF_detect_state &state, uint8_t data) } return false; } -#endif + +#endif // AP_GPS_SIRF_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index cf3cdd6d30131c..343587c68e55e5 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -594,11 +594,10 @@ AP_GPS_UBLOX::read(void) for (uint16_t i = 0; i < numc; i++) { // Process bytes received // read the next byte - const int16_t rdata = port->read(); - if (rdata < 0) { + uint8_t data; + if (!port->read(data)) { break; } - const uint8_t data = rdata; #if AP_GPS_DEBUG_LOGGING_ENABLED log_data(&data, 1); #endif @@ -1103,7 +1102,7 @@ AP_GPS_UBLOX::_parse_gps(void) } if(GNSS_GALILEO ==_buffer.gnss.configBlock[i].gnssId) { _buffer.gnss.configBlock[i].resTrkCh = (_buffer.gnss.numTrkChHw - 3) / (gnssCount * 2); - _buffer.gnss.configBlock[i].maxTrkCh = 8; //Per the M8 receiver description UBX-13003221 - R16, 4.1.1.3 it is not recommended to set the number of galileo channels higher then eigh + _buffer.gnss.configBlock[i].maxTrkCh = 8; //Per the M8 receiver description UBX-13003221 - R16, 4.1.1.3 it is not recommended to set the number of galileo channels higher then eight } } _buffer.gnss.configBlock[i].flags = _buffer.gnss.configBlock[i].flags | 0x00000001; @@ -1368,13 +1367,9 @@ AP_GPS_UBLOX::_parse_gps(void) _last_pos_time = _buffer.posllh.itow; state.location.lng = _buffer.posllh.longitude; state.location.lat = _buffer.posllh.latitude; - if (option_set(AP_GPS::HeightEllipsoid)) { - state.location.alt = _buffer.posllh.altitude_ellipsoid / 10; - } else { - state.location.alt = _buffer.posllh.altitude_msl / 10; - } state.have_undulation = true; state.undulation = (_buffer.posllh.altitude_msl - _buffer.posllh.altitude_ellipsoid) * 0.001; + set_alt_amsl_cm(state, _buffer.posllh.altitude_msl / 10); state.status = next_fix; _new_position = true; @@ -1532,13 +1527,9 @@ AP_GPS_UBLOX::_parse_gps(void) _last_pos_time = _buffer.pvt.itow; state.location.lng = _buffer.pvt.lon; state.location.lat = _buffer.pvt.lat; - if (option_set(AP_GPS::HeightEllipsoid)) { - state.location.alt = _buffer.pvt.h_ellipsoid / 10; - } else { - state.location.alt = _buffer.pvt.h_msl / 10; - } state.have_undulation = true; state.undulation = (_buffer.pvt.h_msl - _buffer.pvt.h_ellipsoid) * 0.001; + set_alt_amsl_cm(state, _buffer.pvt.h_msl / 10); switch (_buffer.pvt.fix_type) { case 0: diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index eea8967af94e65..68afe623b4880c 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -20,11 +20,13 @@ // UBlox Lea6H protocol: http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf #pragma once -#include "AP_GPS.h" -#include "GPS_Backend.h" +#include "AP_GPS_config.h" #if AP_GPS_UBLOX_ENABLED +#include "AP_GPS.h" +#include "GPS_Backend.h" + #include /* diff --git a/libraries/AP_GPS/AP_GPS_config.h b/libraries/AP_GPS/AP_GPS_config.h index ef5bde2f5dffda..954a1f3bcf1649 100644 --- a/libraries/AP_GPS/AP_GPS_config.h +++ b/libraries/AP_GPS/AP_GPS_config.h @@ -1,6 +1,7 @@ #pragma once #include +#include #ifndef AP_GPS_ENABLED #define AP_GPS_ENABLED 1 @@ -10,6 +11,10 @@ #define AP_GPS_BACKEND_DEFAULT_ENABLED AP_GPS_ENABLED #endif +#ifndef AP_GPS_DRONECAN_ENABLED +#define AP_GPS_DRONECAN_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS +#endif + #ifndef AP_GPS_ERB_ENABLED #define AP_GPS_ERB_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED #endif @@ -18,6 +23,14 @@ #define AP_GPS_GSOF_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED #endif +#ifndef AP_GPS_MAV_ENABLED + #define AP_GPS_MAV_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED +#endif + +#ifndef HAL_MSP_GPS_ENABLED +#define HAL_MSP_GPS_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED && HAL_MSP_SENSORS_ENABLED +#endif + #ifndef AP_GPS_NMEA_ENABLED #define AP_GPS_NMEA_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED #endif @@ -47,5 +60,5 @@ #endif #ifndef AP_GPS_UBLOX_ENABLED - #define AP_GPS_UBLOX_ENABLED 1 + #define AP_GPS_UBLOX_ENABLED AP_GPS_BACKEND_DEFAULT_ENABLED #endif diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index 3b442cffc86757..095bb27366d7a4 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_GPS_config.h" + +#if AP_GPS_ENABLED + #include "AP_GPS.h" #include "GPS_Backend.h" #include @@ -46,37 +50,6 @@ AP_GPS_Backend::AP_GPS_Backend(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL:: state.have_vertical_accuracy = false; } -int32_t AP_GPS_Backend::swap_int32(int32_t v) const -{ - const uint8_t *b = (const uint8_t *)&v; - union { - int32_t v; - uint8_t b[4]; - } u; - - u.b[0] = b[3]; - u.b[1] = b[2]; - u.b[2] = b[1]; - u.b[3] = b[0]; - - return u.v; -} - -int16_t AP_GPS_Backend::swap_int16(int16_t v) const -{ - const uint8_t *b = (const uint8_t *)&v; - union { - int16_t v; - uint8_t b[2]; - } u; - - u.b[0] = b[1]; - u.b[1] = b[0]; - - return u.v; -} - - /** fill in time_week_ms and time_week from BCD date and time components assumes MTK19 millisecond form of bcd_time @@ -197,9 +170,9 @@ bool AP_GPS_Backend::should_log() const } +#if HAL_GCS_ENABLED void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan) { -#if HAL_GCS_ENABLED const uint8_t instance = state.instance; // send status switch (instance) { @@ -236,8 +209,8 @@ void AP_GPS_Backend::send_mavlink_gps_rtk(mavlink_channel_t chan) state.rtk_iar_num_hypotheses); break; } -#endif } +#endif /* @@ -377,14 +350,14 @@ bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state, const float min_dist = MIN(offset_dist, reported_distance); if (offset_dist < minimum_antenna_seperation) { - // offsets have to be sufficently large to get a meaningful angle off of them + // offsets have to be sufficiently large to get a meaningful angle off of them Debug("Insufficent antenna offset (%f, %f, %f)", (double)offset.x, (double)offset.y, (double)offset.z); goto bad_yaw; } if (reported_distance < minimum_antenna_seperation) { - // if the reported distance is less then the minimum seperation it's not sufficently robust - Debug("Reported baseline distance (%f) was less then the minimum antenna seperation (%f)", + // if the reported distance is less then the minimum separation it's not sufficiently robust + Debug("Reported baseline distance (%f) was less then the minimum antenna separation (%f)", (double)reported_distance, (double)minimum_antenna_seperation); goto bad_yaw; } @@ -468,6 +441,21 @@ bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state, } #endif // GPS_MOVING_BASELINE +/* + set altitude in location structure, honouring the driver option for + MSL vs ellipsoid height + */ +void AP_GPS_Backend::set_alt_amsl_cm(AP_GPS::GPS_State &_state, int32_t alt_amsl_cm) +{ + if (option_set(AP_GPS::HeightEllipsoid) && _state.have_undulation) { + // user has asked ArduPilot to use ellipsoid height in the + // canonical height for mission and navigation + _state.location.alt = alt_amsl_cm - _state.undulation*100; + } else { + _state.location.alt = alt_amsl_cm; + } +} + #if AP_GPS_DEBUG_LOGGING_ENABLED /* @@ -540,3 +528,5 @@ void AP_GPS_Backend::logging_start(void) logging_loop(); } #endif // AP_GPS_DEBUG_LOGGING_ENABLED + +#endif // AP_GPS_ENABLED diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h index ce1fac0d62eca1..f69125f145147a 100644 --- a/libraries/AP_GPS/GPS_Backend.h +++ b/libraries/AP_GPS/GPS_Backend.h @@ -18,7 +18,12 @@ */ #pragma once +#include "AP_GPS_config.h" + +#if AP_GPS_ENABLED + #include +#include #include #include "AP_GPS.h" #include "AP_GPS_config.h" @@ -55,13 +60,15 @@ class AP_GPS_Backend virtual void inject_data(const uint8_t *data, uint16_t len); +#if HAL_GCS_ENABLED //MAVLink methods virtual bool supports_mavlink_gps_rtk_message() const { return false; } virtual void send_mavlink_gps_rtk(mavlink_channel_t chan); + virtual void handle_msg(const mavlink_message_t &msg) { return ; } +#endif virtual void broadcast_configuration_failure_reason(void) const { return ; } - virtual void handle_msg(const mavlink_message_t &msg) { return ; } #if HAL_MSP_GPS_ENABLED virtual void handle_msp(const MSP::msp_gps_data_message_t &pkt) { return; } #endif @@ -108,10 +115,6 @@ class AP_GPS_Backend uint32_t _last_itow_ms; bool _have_itow; - // common utility functions - int32_t swap_int32(int32_t v) const; - int16_t swap_int16(int16_t v) const; - /* fill in 3D velocity from 2D components */ @@ -157,6 +160,9 @@ class AP_GPS_Backend void log_data(const uint8_t *data, uint16_t length); #endif + // set alt in location, honouring GPS driver option for ellipsoid height + void set_alt_amsl_cm(AP_GPS::GPS_State &_state, int32_t alt_amsl_cm); + private: // itow from previous message uint64_t _pseudo_itow; @@ -178,3 +184,5 @@ class AP_GPS_Backend #endif }; + +#endif // AP_GPS_ENABLED diff --git a/libraries/AP_Generator/AP_Generator.cpp b/libraries/AP_Generator/AP_Generator.cpp index f531c05ec7c981..d5cfca045d2d79 100644 --- a/libraries/AP_Generator/AP_Generator.cpp +++ b/libraries/AP_Generator/AP_Generator.cpp @@ -36,7 +36,7 @@ const AP_Param::GroupInfo AP_Generator::var_info[] = { // @Param: OPTIONS // @DisplayName: Generator Options // @Description: Bitmask of options for generators - // @Bitmask: 0:Supress Maintenance-Required Warnings + // @Bitmask: 0:Suppress Maintenance-Required Warnings // @User: Standard AP_GROUPINFO("OPTIONS", 2, AP_Generator, _options, 0), @@ -65,13 +65,13 @@ void AP_Generator::init() // Not using a generator return; -#if AP_GENERATOR_IE650_800_ENABLED +#if AP_GENERATOR_IE_650_800_ENABLED case Type::IE_650_800: _driver_ptr = new AP_Generator_IE_650_800(*this); break; #endif -#if AP_GENERATOR_IE2400_ENABLED +#if AP_GENERATOR_IE_2400_ENABLED case Type::IE_2400: _driver_ptr = new AP_Generator_IE_2400(*this); break; @@ -91,7 +91,7 @@ void AP_Generator::init() void AP_Generator::update() { - // Return immediatly if not enabled. Don't support run-time disabling of generator + // Return immediately if not enabled. Don't support run-time disabling of generator if (_driver_ptr == nullptr) { return; } @@ -124,7 +124,7 @@ bool AP_Generator::pre_arm_check(char* failmsg, uint8_t failmsg_len) const return true; } // Don't allow arming if we have disabled the generator since boot - strncpy(failmsg, "Generator disabled, reboot reqired", failmsg_len); + strncpy(failmsg, "Generator disabled, reboot required", failmsg_len); return false; } if (_driver_ptr == nullptr) { diff --git a/libraries/AP_Generator/AP_Generator.h b/libraries/AP_Generator/AP_Generator.h index d0a11a597a3d58..be36d09e200916 100644 --- a/libraries/AP_Generator/AP_Generator.h +++ b/libraries/AP_Generator/AP_Generator.h @@ -82,10 +82,10 @@ class AP_Generator enum class Type { GEN_DISABLED = 0, -#if AP_GENERATOR_IE650_800_ENABLED +#if AP_GENERATOR_IE_650_800_ENABLED IE_650_800 = 1, #endif -#if AP_GENERATOR_IE2400_ENABLED +#if AP_GENERATOR_IE_2400_ENABLED IE_2400 = 2, #endif #if AP_GENERATOR_RICHENPOWER_ENABLED diff --git a/libraries/AP_Generator/AP_Generator_Backend.cpp b/libraries/AP_Generator/AP_Generator_Backend.cpp index 99de2363366e9f..6a74ee53e2c245 100644 --- a/libraries/AP_Generator/AP_Generator_Backend.cpp +++ b/libraries/AP_Generator/AP_Generator_Backend.cpp @@ -16,7 +16,7 @@ #if HAL_GENERATOR_ENABLED -// Base class consructor +// Base class constructor AP_Generator_Backend::AP_Generator_Backend(AP_Generator& frontend) : _frontend(frontend) { diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.cpp b/libraries/AP_Generator/AP_Generator_IE_2400.cpp index b56c3f3935d7f4..d297261d5ff4fa 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_2400.cpp @@ -15,7 +15,7 @@ #include "AP_Generator_IE_2400.h" -#if AP_GENERATOR_IE2400_ENABLED +#if AP_GENERATOR_IE_2400_ENABLED #include @@ -182,6 +182,7 @@ bool AP_Generator_IE_2400::check_for_err_code(char* msg_txt, uint8_t msg_len) co return true; } +#if HAL_LOGGING_ENABLED // log generator status to the onboard log void AP_Generator_IE_2400::log_write() { @@ -203,4 +204,6 @@ void AP_Generator_IE_2400::log_write() _err_code ); } -#endif // AP_GENERATOR_IE2400_ENABLED +#endif // HAL_LOGGING_ENABLED + +#endif // AP_GENERATOR_IE_2400_ENABLED diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.h b/libraries/AP_Generator/AP_Generator_IE_2400.h index 178e0d69fc5439..65acfa8ef95028 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.h +++ b/libraries/AP_Generator/AP_Generator_IE_2400.h @@ -2,7 +2,7 @@ #include "AP_Generator_IE_FuelCell.h" -#if AP_GENERATOR_IE2400_ENABLED +#if AP_GENERATOR_IE_2400_ENABLED class AP_Generator_IE_2400 : public AP_Generator_IE_FuelCell { @@ -32,7 +32,9 @@ class AP_Generator_IE_2400 : public AP_Generator_IE_FuelCell // Check for error codes that are deemed severe and would be cause to trigger a battery monitor low failsafe action bool is_low_error(const uint32_t err_in) const; +#if HAL_LOGGING_ENABLED void log_write(void) override; +#endif // IE 2.4kW failsafes enum class ErrorCode { @@ -53,5 +55,5 @@ class AP_Generator_IE_2400 : public AP_Generator_IE_FuelCell uint16_t _spm_pwr; // Stack Power Module (SPM) power draw (Watts) }; -#endif // AP_GENERATOR_IE2400_ENABLED +#endif // AP_GENERATOR_IE_2400_ENABLED diff --git a/libraries/AP_Generator/AP_Generator_IE_650_800.cpp b/libraries/AP_Generator/AP_Generator_IE_650_800.cpp index 2a208a8d59249d..8c5b770e1511f1 100644 --- a/libraries/AP_Generator/AP_Generator_IE_650_800.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_650_800.cpp @@ -15,7 +15,7 @@ #include "AP_Generator_IE_650_800.h" -#if AP_GENERATOR_IE650_800_ENABLED +#if AP_GENERATOR_IE_650_800_ENABLED extern const AP_HAL::HAL& hal; @@ -28,7 +28,7 @@ void AP_Generator_IE_650_800::init() // This unit does not have current but this needs to be true to make use of consumed_mah in BattMonitor _frontend._has_current = true; _frontend._has_consumed_energy = true; - _frontend._has_fuel_remaining = false; + _frontend._has_fuel_remaining = true; } // Update fuel cell, expected to be called at 20hz @@ -122,5 +122,5 @@ AP_BattMonitor::Failsafe AP_Generator_IE_650_800::update_failsafes() const return AP_BattMonitor::Failsafe::None; } -#endif // AP_GENERATOR_IE650_800_ENABLED +#endif // AP_GENERATOR_IE_650_800_ENABLED diff --git a/libraries/AP_Generator/AP_Generator_IE_650_800.h b/libraries/AP_Generator/AP_Generator_IE_650_800.h index 545e3e244aa162..94e4c50a2519a0 100644 --- a/libraries/AP_Generator/AP_Generator_IE_650_800.h +++ b/libraries/AP_Generator/AP_Generator_IE_650_800.h @@ -2,7 +2,7 @@ #include "AP_Generator_IE_FuelCell.h" -#if AP_GENERATOR_IE650_800_ENABLED +#if AP_GENERATOR_IE_650_800_ENABLED class AP_Generator_IE_650_800 : public AP_Generator_IE_FuelCell { @@ -46,7 +46,7 @@ class AP_Generator_IE_650_800 : public AP_Generator_IE_FuelCell static const uint32_t ERROR_START_UNDER_PRESS = (1U << 19); // (0x80000), Tank pressure < 6 barg static const uint32_t ERROR_TANK_UNDER_PRESS = (1U << 18); // (0x40000), Tank pressure < 5 barg static const uint32_t ERROR_TANK_LOW_PRESS = (1U << 17); // (0x20000), Tank pressure < 15 barg - static const uint32_t ERROR_SAFETY_FLAG = (1U << 16); // (0x10000), Fuel cell's internal saftey flags not set true + static const uint32_t ERROR_SAFETY_FLAG = (1U << 16); // (0x10000), Fuel cell's internal safety flags not set true static const uint32_t ERROR_DENY_START1 = (1U << 15); // (0x8000), Stack 1 denied start static const uint32_t ERROR_DENY_START2 = (1U << 14); // (0x4000), Stack 2 denied start static const uint32_t ERROR_STACK_UT1 = (1U << 13); // (0x2000), Stack 1 under temperature (<5 degC) @@ -74,7 +74,7 @@ class AP_Generator_IE_650_800 : public AP_Generator_IE_FuelCell | ERROR_START_TIMEOUT // (0x200000), Fuel cell's internal State == start for > 30 s | ERROR_START_UNDER_PRESS // (0x80000), Tank pressure < 6 barg | ERROR_TANK_UNDER_PRESS // (0x40000), Tank pressure < 5 barg - | ERROR_SAFETY_FLAG // (0x10000), Fuel cell's internal saftey flags not set true + | ERROR_SAFETY_FLAG // (0x10000), Fuel cell's internal safety flags not set true | ERROR_DENY_START1 // (0x8000), Stack 1 denied start | ERROR_DENY_START2 // (0x4000), Stack 2 denied start | ERROR_BAT_UV_DENY // (0x400), Battery under voltage (21.6 V) and master denied @@ -95,4 +95,4 @@ class AP_Generator_IE_650_800 : public AP_Generator_IE_FuelCell | ERROR_BAT_UT; // (0x8), Battery undertemperature (<-15 degC) }; -#endif // AP_GENERATOR_IE650_800_ENABLED +#endif // AP_GENERATOR_IE_650_800_ENABLED diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp index 901a5836386dae..b66d59b8ddcd49 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp @@ -26,7 +26,7 @@ void AP_Generator_IE_FuelCell::init() _uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Generator, 0); if (_uart == nullptr) { - gcs().send_text(MAV_SEVERITY_INFO, "Generator: No serial port found"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Generator: No serial port found"); return; } _uart->begin(AP::serialmanager().find_baudrate(AP_SerialManager::SerialProtocol_Generator, 0)); @@ -67,7 +67,9 @@ void AP_Generator_IE_FuelCell::update() update_frontend(); +#if HAL_LOGGING_ENABLED log_write(); +#endif } // Add a single character to the buffer and attempt to decode @@ -151,7 +153,7 @@ void AP_Generator_IE_FuelCell::check_status(const uint32_t now) if (!healthy() && (!_health_warn_last_ms || (now - _health_warn_last_ms >= 20000))) { // Don't spam GCS with unhealthy message _health_warn_last_ms = now; - gcs().send_text(MAV_SEVERITY_ALERT, "Generator: Not healthy"); + GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "Generator: Not healthy"); } else if (healthy()) { _health_warn_last_ms = 0; @@ -161,7 +163,7 @@ void AP_Generator_IE_FuelCell::check_status(const uint32_t now) if (_state != _last_state) { for (const struct Lookup_State entry : lookup_state) { if (_state == entry.option) { - gcs().send_text(MAV_SEVERITY_INFO, "Generator: %s", entry.msg_txt); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Generator: %s", entry.msg_txt); break; } } @@ -171,7 +173,7 @@ void AP_Generator_IE_FuelCell::check_status(const uint32_t now) // Check error codes char msg_txt[32]; if (check_for_err_code_if_changed(msg_txt, sizeof(msg_txt))) { - gcs().send_text(MAV_SEVERITY_ALERT, "%s", msg_txt); + GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "%s", msg_txt); } } diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h index 682d71f350f172..84395f1125c917 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h @@ -4,6 +4,8 @@ #if AP_GENERATOR_IE_ENABLED +#include + class AP_Generator_IE_FuelCell : public AP_Generator_Backend { @@ -81,13 +83,15 @@ class AP_Generator_IE_FuelCell : public AP_Generator_Backend // Assigns the unit specific measurements once a valid sentence is obtained virtual void assign_measurements(const uint32_t now) = 0; +#if HAL_LOGGING_ENABLED virtual void log_write(void) {} +#endif // Add a single character to the buffer and attempt to decode. // Returns true if a complete sentence was successfully decoded or if the buffer is full. bool decode(char c); - // Unit specific decoding to process characters recieved and build sentence + // Unit specific decoding to process characters received and build sentence virtual void decode_latest_term(void) = 0; // Check if we should notify on any change of fuel cell state diff --git a/libraries/AP_Generator/AP_Generator_RichenPower.cpp b/libraries/AP_Generator/AP_Generator_RichenPower.cpp index 129cbc2e5b0379..530f8192b371d5 100644 --- a/libraries/AP_Generator/AP_Generator_RichenPower.cpp +++ b/libraries/AP_Generator/AP_Generator_RichenPower.cpp @@ -190,7 +190,7 @@ bool AP_Generator_RichenPower::generator_ok_to_run() const constexpr float AP_Generator_RichenPower::heat_required_for_run() { // assume that heat is proportional to RPM. Return a number - // proportial to RPM. Reduce it to account for the cooling some%/s + // proportional to RPM. Reduce it to account for the cooling some%/s // cooling return (45 * IDLE_RPM) * heat_environment_loss_30s; } @@ -235,7 +235,9 @@ void AP_Generator_RichenPower::update(void) update_frontend_readings(); +#if HAL_LOGGING_ENABLED Log_Write(); +#endif } // update_runstate updates the servo output we use to control the @@ -308,6 +310,7 @@ void AP_Generator_RichenPower::update_runstate() } } +#if HAL_LOGGING_ENABLED // log generator status to the onboard log void AP_Generator_RichenPower::Log_Write() { @@ -336,6 +339,7 @@ void AP_Generator_RichenPower::Log_Write() last_reading.mode ); } +#endif // generator prearm checks; notably, if we never see a generator we do // not run the checks. Generators are attached/detached at will, and diff --git a/libraries/AP_Generator/AP_Generator_RichenPower.h b/libraries/AP_Generator/AP_Generator_RichenPower.h index 790f2f7ff3ad71..c5999c0ed61bc4 100644 --- a/libraries/AP_Generator/AP_Generator_RichenPower.h +++ b/libraries/AP_Generator/AP_Generator_RichenPower.h @@ -5,6 +5,7 @@ #if AP_GENERATOR_RICHENPOWER_ENABLED +#include #include #include #include @@ -93,9 +94,11 @@ class AP_Generator_RichenPower : public AP_Generator_Backend Mode mode; }; +#if HAL_LOGGING_ENABLED // method and state to write and entry to the onboard log: void Log_Write(); uint32_t last_logged_reading_ms; +#endif struct Reading last_reading; uint32_t last_reading_ms; diff --git a/libraries/AP_Generator/AP_Generator_config.h b/libraries/AP_Generator/AP_Generator_config.h index 7dbe5fc99b5569..83d096cfa09edc 100644 --- a/libraries/AP_Generator/AP_Generator_config.h +++ b/libraries/AP_Generator/AP_Generator_config.h @@ -14,12 +14,12 @@ #define AP_GENERATOR_IE_ENABLED AP_GENERATOR_BACKEND_DEFAULT_ENABLED #endif -#ifndef AP_GENERATOR_IE2400_ENABLED -#define AP_GENERATOR_IE2400_ENABLED AP_GENERATOR_IE_ENABLED +#ifndef AP_GENERATOR_IE_2400_ENABLED +#define AP_GENERATOR_IE_2400_ENABLED AP_GENERATOR_IE_ENABLED #endif -#ifndef AP_GENERATOR_IE650_800_ENABLED -#define AP_GENERATOR_IE650_800_ENABLED AP_GENERATOR_IE_ENABLED +#ifndef AP_GENERATOR_IE_650_800_ENABLED +#define AP_GENERATOR_IE_650_800_ENABLED AP_GENERATOR_IE_ENABLED #endif #ifndef AP_GENERATOR_RICHENPOWER_ENABLED diff --git a/libraries/AP_Gripper/AP_Gripper.h b/libraries/AP_Gripper/AP_Gripper.h index 29a7c24c447f29..3d412a191a1096 100644 --- a/libraries/AP_Gripper/AP_Gripper.h +++ b/libraries/AP_Gripper/AP_Gripper.h @@ -75,7 +75,7 @@ class AP_Gripper { AP_Int16 grab_pwm; // PWM value sent to Gripper to initiate grabbing the cargo AP_Int16 release_pwm; // PWM value sent to Gripper to release the cargo AP_Int16 neutral_pwm; // PWM value sent to gripper when not grabbing or releasing - AP_Int8 regrab_interval; // Time in seconds that EPM gripper will regrab the cargo to ensure grip has not weakend + AP_Int8 regrab_interval; // Time in seconds that EPM gripper will regrab the cargo to ensure grip has not weakened AP_Float autoclose_time; // Automatic close time (in seconds) AP_Int16 uavcan_hardpoint_id; diff --git a/libraries/AP_Gripper/AP_Gripper_Backend.h b/libraries/AP_Gripper/AP_Gripper_Backend.h index 1607289130a902..1508e0ab1bdeb5 100644 --- a/libraries/AP_Gripper/AP_Gripper_Backend.h +++ b/libraries/AP_Gripper/AP_Gripper_Backend.h @@ -45,7 +45,7 @@ class AP_Gripper_Backend { // grabbed - returns true if currently in grabbed position virtual bool grabbed() const = 0; - // type-specific intiailisations: + // type-specific initialisations: virtual void init_gripper() = 0; // type-specific periodic updates: diff --git a/libraries/AP_Gripper/AP_Gripper_EPM.cpp b/libraries/AP_Gripper/AP_Gripper_EPM.cpp index 5b55219c3a24e4..5762597f50f010 100644 --- a/libraries/AP_Gripper/AP_Gripper_EPM.cpp +++ b/libraries/AP_Gripper/AP_Gripper_EPM.cpp @@ -65,7 +65,7 @@ void AP_Gripper_EPM::grab() // move the servo output to the grab position SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm); } - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbing"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load grabbing"); AP::logger().Write_Event(LogEvent::GRIPPER_GRAB); } @@ -89,7 +89,7 @@ void AP_Gripper_EPM::release() // move the servo to the release position SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm); } - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load releasing"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load releasing"); AP::logger().Write_Event(LogEvent::GRIPPER_RELEASE); } diff --git a/libraries/AP_Gripper/AP_Gripper_Servo.cpp b/libraries/AP_Gripper/AP_Gripper_Servo.cpp index 43f08895a860f3..0ef9957da0fec9 100644 --- a/libraries/AP_Gripper/AP_Gripper_Servo.cpp +++ b/libraries/AP_Gripper/AP_Gripper_Servo.cpp @@ -29,7 +29,7 @@ void AP_Gripper_Servo::grab() // check if we are already grabbed if (config.state == AP_Gripper::STATE_GRABBED) { // inform user that we are already grabbed - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbed"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load grabbed"); return; } @@ -39,7 +39,7 @@ void AP_Gripper_Servo::grab() // move the servo to the grab position SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm); _last_grab_or_release = AP_HAL::millis(); - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbing"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load grabbing"); AP::logger().Write_Event(LogEvent::GRIPPER_GRAB); } @@ -54,7 +54,7 @@ void AP_Gripper_Servo::release() // check if we are already released if (config.state == AP_Gripper::STATE_RELEASED) { // inform user that we are already released - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load released"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load released"); return; } @@ -64,7 +64,7 @@ void AP_Gripper_Servo::release() // move the servo to the release position SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm); _last_grab_or_release = AP_HAL::millis(); - gcs().send_text(MAV_SEVERITY_INFO, "Gripper load releasing"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load releasing"); AP::logger().Write_Event(LogEvent::GRIPPER_RELEASE); } diff --git a/libraries/AP_Gripper/AP_Gripper_Servo.h b/libraries/AP_Gripper/AP_Gripper_Servo.h index 3c72effc090d3b..e51b729d0b1a9a 100644 --- a/libraries/AP_Gripper/AP_Gripper_Servo.h +++ b/libraries/AP_Gripper/AP_Gripper_Servo.h @@ -44,7 +44,7 @@ class AP_Gripper_Servo : public AP_Gripper_Backend { protected: - // type-specific intiailisations: + // type-specific initializations: void init_gripper() override; // type-specific periodic updates: diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.cpp b/libraries/AP_GyroFFT/AP_GyroFFT.cpp index 9b510a4034b60f..886baa3749c370 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.cpp +++ b/libraries/AP_GyroFFT/AP_GyroFFT.cpp @@ -273,7 +273,7 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz) // check for harmonics across all harmonic notch filters // note that we only allow one harmonic notch filter linked to the FFT code - uint8_t harmonics = 0; + uint32_t harmonics = 0; uint8_t num_notches = 0; for (auto ¬ch : _ins->harmonic_notches) { if (notch.params.enabled()) { @@ -362,8 +362,8 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz) } } -// sample the gyros either by using a gyro window sampled at the gyro rate or making invdividual samples -// called from fast_loop thread - this function does not take out a sempahore to avoid waiting on the FFT thread +// sample the gyros either by using a gyro window sampled at the gyro rate or making individual samples +// called from fast_loop thread - this function does not take out a semaphore to avoid waiting on the FFT thread void AP_GyroFFT::sample_gyros() { if (!analysis_enabled()) { diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.h b/libraries/AP_GyroFFT/AP_GyroFFT.h index c422372970ef2e..19b501b7193580 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.h +++ b/libraries/AP_GyroFFT/AP_GyroFFT.h @@ -190,7 +190,7 @@ class AP_GyroFFT float update_tl_noise_center_bandwidth_hz(FrequencyPeak peak, uint8_t axis, float value) { return (_thread_state._center_bandwidth_hz_filtered[peak][axis] = _center_bandwidth_filter[peak].apply(axis, value)); } - // write single log mesages + // write single log messages void log_noise_peak(uint8_t id, FrequencyPeak peak) const; // calculate the peak noise frequency void calculate_noise(bool calibrating, const EngineConfig& config); diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 38958a5f5e86b3..027b8f4a07bd12 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -1,5 +1,5 @@ /** - * C preprocesor enumeration of the boards supported by the AP_HAL. + * C preprocessor enumeration of the boards supported by the AP_HAL. * This list exists so HAL_BOARD == HAL_BOARD_xxx preprocessor blocks * can be used to exclude HAL boards from the build when appropriate. * It's not an elegant solution but we can improve it in future. @@ -169,6 +169,10 @@ #define HAL_WITH_IO_MCU 0 #endif +#ifndef HAL_WITH_IO_MCU_DSHOT +#define HAL_WITH_IO_MCU_DSHOT 0 +#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 @@ -283,6 +287,22 @@ #define HAL_DSHOT_ALARM_ENABLED 0 #endif +#ifndef HAL_DSHOT_ENABLED +#define HAL_DSHOT_ENABLED 1 +#endif + +#ifndef HAL_SERIALLED_ENABLED +#define HAL_SERIALLED_ENABLED HAL_DSHOT_ENABLED +#endif + +#ifndef HAL_SERIAL_ESC_COMM_ENABLED +#ifdef DISABLE_SERIAL_ESC_COMM +#define HAL_SERIAL_ESC_COMM_ENABLED 0 +#else +#define HAL_SERIAL_ESC_COMM_ENABLED 1 +#endif +#endif + #ifndef HAL_HNF_MAX_FILTERS // On an F7 The difference in CPU load between 1 notch and 24 notches is about 2% // The difference in CPU load between 1Khz backend and 2Khz backend is about 10% @@ -298,7 +318,8 @@ #else // Enough for a notch per motor on an octa quad using two IMUs and one harmonic // plus one static notch with one harmonic -#define HAL_HNF_MAX_FILTERS 18 +// Or triple-notch per motor on one IMU with one harmonic +#define HAL_HNF_MAX_FILTERS 24 #endif #endif // HAL_HNF_MAX_FILTERS @@ -311,6 +332,7 @@ #ifndef HAL_USE_QUADSPI #define HAL_USE_QUADSPI 0 #endif + #ifndef HAL_USE_OCTOSPI #define HAL_USE_OCTOSPI 0 #endif @@ -332,13 +354,6 @@ #endif -// sanity checks for the configuration. This can't test everything as -// the libraries can do their own definitions - but we can catch some -// things: -#if HAL_MINIMIZE_FEATURES && BOARD_FLASH_SIZE > 1024 -#error "2MB board with minimize features?!" -#endif - #ifndef HAL_ENABLE_SENDING_STATS #define HAL_ENABLE_SENDING_STATS BOARD_FLASH_SIZE >= 256 #endif diff --git a/libraries/AP_HAL/AP_HAL_Namespace.h b/libraries/AP_HAL/AP_HAL_Namespace.h index 35a8124d615ee2..b3e84314ed9ef0 100644 --- a/libraries/AP_HAL/AP_HAL_Namespace.h +++ b/libraries/AP_HAL/AP_HAL_Namespace.h @@ -51,7 +51,7 @@ namespace AP_HAL { /* Typdefs for function pointers (Procedure, Member Procedure) For member functions we use the FastDelegate delegates class - which allows us to encapculate a member function as a type + which allows us to encapsulate a member function as a type */ typedef void(*Proc)(void); FUNCTOR_TYPEDEF(MemberProc, void); diff --git a/libraries/AP_HAL/CANIface.cpp b/libraries/AP_HAL/CANIface.cpp index 1bc85bc969f740..7bd1a8ebbda471 100644 --- a/libraries/AP_HAL/CANIface.cpp +++ b/libraries/AP_HAL/CANIface.cpp @@ -77,7 +77,7 @@ int16_t AP_HAL::CANIface::send(const CANFrame& frame, uint64_t tx_deadline, CanI } else { CanRxItem rx_item; rx_item.frame = frame; - rx_item.timestamp_us = AP_HAL::native_micros64(); + rx_item.timestamp_us = AP_HAL::micros64(); rx_item.flags = AP_HAL::CANIface::IsMAVCAN; add_to_rx_queue(rx_item); } diff --git a/libraries/AP_HAL/CANIface.h b/libraries/AP_HAL/CANIface.h index cd17c42b91cc1f..06b4f7dffbf848 100644 --- a/libraries/AP_HAL/CANIface.h +++ b/libraries/AP_HAL/CANIface.h @@ -179,7 +179,7 @@ class AP_HAL::CANIface // fill read select with true if a frame is available in Rx buffer // fill write select with true if space is available in Tx buffer // Also waits for Rx or Tx event depending on read_select and write_select values - // passed to the method until timeout. Returns true if the Rx/Tx even occured + // passed to the method until timeout. Returns true if the Rx/Tx even occurred // while waiting, false if timedout virtual bool select(bool &read_select, bool &write_select, const CANFrame* const pending_tx, uint64_t timeout) @@ -192,11 +192,11 @@ class AP_HAL::CANIface return true; } - // Put frame in queue to be sent, return negative if error occured, 0 if no space, and 1 if successful + // Put frame in queue to be sent, return negative if error occurred, 0 if no space, and 1 if successful // must be called on child class virtual int16_t send(const CANFrame& frame, uint64_t tx_deadline, CanIOFlags flags); - // Non blocking receive frame that pops the frames received inside the buffer, return negative if error occured, + // Non blocking receive frame that pops the frames received inside the buffer, return negative if error occurred, // 0 if no frame available, 1 if successful // must be called on child class virtual int16_t receive(CANFrame& out_frame, uint64_t& out_ts_monotonic, CanIOFlags& out_flags); @@ -231,6 +231,7 @@ class AP_HAL::CANIface uint32_t rx_overflow; uint32_t rx_errors; uint32_t num_busoff_err; + uint64_t last_transmit_us; } bus_stats_t; #if !defined(HAL_BOOTLOADER_BUILD) diff --git a/libraries/AP_HAL/Device.cpp b/libraries/AP_HAL/Device.cpp index beedb242212b34..8f80bf4bff9fa8 100644 --- a/libraries/AP_HAL/Device.cpp +++ b/libraries/AP_HAL/Device.cpp @@ -30,7 +30,7 @@ Periodically (say at 50Hz) you should then call check_next_register(). If that returns false then the sensor has had a corrupted register value. Marking the sensor as unhealthy is - approriate. The bad value will be corrected + appropiate. The bad value will be corrected */ /* diff --git a/libraries/AP_HAL/GPIO.h b/libraries/AP_HAL/GPIO.h index 5dbd7530149645..f32a1eb250ede4 100644 --- a/libraries/AP_HAL/GPIO.h +++ b/libraries/AP_HAL/GPIO.h @@ -82,7 +82,7 @@ class AP_HAL::GPIO { // ret indicates the functor must return void // pin is the pin which has triggered the interrupt // state is the new state of the pin - // timestamp is the time in microseconds the interrupt occured + // timestamp is the time in microseconds the interrupt occurred FUNCTOR_TYPEDEF(irq_handler_fn_t, void, uint8_t, bool, uint32_t); virtual bool attach_interrupt(uint8_t pin, irq_handler_fn_t fn, diff --git a/libraries/AP_HAL/RCOutput.cpp b/libraries/AP_HAL/RCOutput.cpp index 825bcef2aedb4b..c998f5c1566899 100644 --- a/libraries/AP_HAL/RCOutput.cpp +++ b/libraries/AP_HAL/RCOutput.cpp @@ -30,6 +30,7 @@ const char* AP_HAL::RCOutput::get_output_mode_string(enum output_mode out_mode) case MODE_PWM_DSHOT1200: return "DS1200"; case MODE_NEOPIXEL: + case MODE_NEOPIXELRGB: return "NeoP"; case MODE_PROFILED: return "ProfiLED"; @@ -76,7 +77,7 @@ bool AP_HAL::RCOutput::is_dshot_protocol(const enum output_mode mode) /* * calculate the prescaler required to achieve the desire bitrate */ -uint32_t AP_HAL::RCOutput::calculate_bitrate_prescaler(uint32_t timer_clock, uint32_t target_frequency, bool is_dshot) +uint32_t AP_HAL::RCOutput::calculate_bitrate_prescaler(uint32_t timer_clock, uint32_t target_frequency, bool at_least_freq) { if (target_frequency > timer_clock) { // we can't achieve the desired frequency @@ -85,32 +86,21 @@ uint32_t AP_HAL::RCOutput::calculate_bitrate_prescaler(uint32_t timer_clock, uin uint32_t prescaler; - if (is_dshot) { - // original prescaler calculation from betaflight. bi-dir dshot is incredibly sensitive to the bitrate + if (at_least_freq) { // choose a frequency of at least the target, needed by BLHeli_S + prescaler = uint32_t(floorf((float) timer_clock / target_frequency + 0.01f) - 1); + } else { // original prescaler calculation from betaflight, chooses closest + // bi-dir dshot is incredibly sensitive to the bitrate prescaler = uint32_t(lrintf((float) timer_clock / target_frequency + 0.01f) - 1); - } else { - // adjust frequency to give an allowed value given the clock, erring on the high side - prescaler = timer_clock / target_frequency; - while ((timer_clock / prescaler) < target_frequency && prescaler > 1) { - prescaler--; - } - // prescaler is divisor - 1 - prescaler--; - } - - if (!is_dshot) { - const uint32_t freq = timer_clock / (prescaler + 1); - // find the closest value - const float delta = fabsf(float(freq) - target_frequency); - if (freq > target_frequency - && delta > fabsf(float(timer_clock / (prescaler+2)) - target_frequency)) { - prescaler++; - } else if (prescaler > 0 && freq < target_frequency - && delta > fabsf(float(timer_clock / (prescaler)) - target_frequency)) { - prescaler--; - } } return prescaler; } +/* + returns the pwm value scaled to [-1;1] regrading to set_esc_scaling ranges range without constraints. +*/ +float AP_HAL::RCOutput::scale_esc_to_unity(uint16_t pwm) const +{ + return 2.0 * ((float) pwm - _esc_pwm_min) / (_esc_pwm_max - _esc_pwm_min) - 1.0; +} + diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index dae1b69444d54b..366b13963a481d 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -139,17 +139,15 @@ class AP_HAL::RCOutput { microseconds, and represent minimum and maximum PWM values which will be used to convert channel writes into a percentage */ - virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) {} + void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) { + _esc_pwm_min = min_pwm; + _esc_pwm_max = max_pwm; + } - /* - return ESC scaling value from set_esc_scaling() - */ - virtual bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm) { return false; } - /* returns the pwm value scaled to [-1;1] regrading to set_esc_scaling ranges range without constraints. */ - virtual float scale_esc_to_unity(uint16_t pwm) { return 0; } + float scale_esc_to_unity(uint16_t pwm) const; /* return the erpm and error rate for a channel if available @@ -217,6 +215,7 @@ class AP_HAL::RCOutput { MODE_PWM_DSHOT1200, MODE_NEOPIXEL, // same as MODE_PWM_DSHOT at 800kHz but it's an LED MODE_PROFILED, // same as MODE_PWM_DSHOT using separate clock and data + MODE_NEOPIXELRGB, // same as MODE_NEOPIXEL but RGB ordering }; // true when the output mode is of type dshot // static to allow use in the ChibiOS thread stuff @@ -225,6 +224,7 @@ class AP_HAL::RCOutput { static bool is_led_protocol(const enum output_mode mode) { switch (mode) { case MODE_NEOPIXEL: + case MODE_NEOPIXELRGB: case MODE_PROFILED: return true; default: @@ -274,6 +274,12 @@ class AP_HAL::RCOutput { virtual void set_output_mode(uint32_t mask, enum output_mode mode) {} + virtual enum output_mode get_output_mode(uint32_t& mask) { + mask = 0; + return MODE_PWM_NORMAL; + } + + /* * get output mode banner to inform user of how outputs are configured */ @@ -311,6 +317,12 @@ class AP_HAL::RCOutput { */ virtual void set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz) {} + /* + Set the dshot period in us, only for use by the IOMCU + */ + virtual void set_dshot_period(uint32_t period_us, uint8_t dshot_rate) {} + virtual uint32_t get_dshot_period_us() const { return 0; } + /* Set the dshot ESC type */ @@ -320,7 +332,7 @@ class AP_HAL::RCOutput { const static uint32_t ALL_CHANNELS = 255; /* - Send a dshot command, if command timout is 0 then 10 commands are sent + Send a dshot command, if command timeout is 0 then 10 commands are sent chan is the servo channel to send the command to */ virtual void send_dshot_command(uint8_t command, uint8_t chan = ALL_CHANNELS, uint32_t command_timeout_ms = 0, uint16_t repeat_count = 10, bool priority = false) {} @@ -341,7 +353,7 @@ class AP_HAL::RCOutput { and led number. A led number of -1 means all LEDs. LED 0 is the first LED */ virtual void set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) {} - + /* trigger send of serial led */ @@ -362,7 +374,7 @@ class AP_HAL::RCOutput { /* * calculate the prescaler required to achieve the desire bitrate */ - static uint32_t calculate_bitrate_prescaler(uint32_t timer_clock, uint32_t target_frequency, bool is_dshot); + static uint32_t calculate_bitrate_prescaler(uint32_t timer_clock, uint32_t target_frequency, bool at_least_freq = false); /* * bit width values for different protocols @@ -372,7 +384,7 @@ class AP_HAL::RCOutput { * Options are (ticks, percentage): * 20/7/14, 35/70 * 11/4/8, 36/72 - * 8/3/6, 37/75 + * 8/3/6, 37/75 <-- this is the preferred duty cycle and has some support on the interwebs */ // bitwidths: 8/3/6 == 37%/75% static constexpr uint32_t DSHOT_BIT_WIDTH_TICKS_DEFAULT = 8; @@ -403,4 +415,7 @@ class AP_HAL::RCOutput { // helper functions for implementation of get_output_mode_banner 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; }; diff --git a/libraries/AP_HAL/SIMState.cpp b/libraries/AP_HAL/SIMState.cpp index 3a76e7d6f8f4ec..776e56ef7402d8 100644 --- a/libraries/AP_HAL/SIMState.cpp +++ b/libraries/AP_HAL/SIMState.cpp @@ -197,12 +197,6 @@ void SIMState::fdm_input_local(void) if (frsky_d != nullptr) { frsky_d->update(); } - // if (frsky_sport != nullptr) { - // frsky_sport->update(); - // } - // if (frsky_sportpassthrough != nullptr) { - // frsky_sportpassthrough->update(); - // } #if AP_SIM_CRSF_ENABLED if (crsf != nullptr) { @@ -232,8 +226,8 @@ void SIMState::fdm_input_local(void) vectornav->update(); } - if (lord != nullptr) { - lord->update(); + if (microstrain5 != nullptr) { + microstrain5->update(); } #if HAL_SIM_AIS_ENABLED @@ -267,7 +261,6 @@ void SIMState::_simulator_servos(struct sitl_input &input) { // output at chosen framerate uint32_t now = AP_HAL::micros(); - // last_update_usec = now; // find the barometer object if it exists const auto *_barometer = AP_Baro::get_singleton(); diff --git a/libraries/AP_HAL/SIMState.h b/libraries/AP_HAL/SIMState.h index 86ab3ce0b8015f..b86c0282d45434 100644 --- a/libraries/AP_HAL/SIMState.h +++ b/libraries/AP_HAL/SIMState.h @@ -29,7 +29,7 @@ #include #include #include -#include +#include #include #include @@ -190,8 +190,8 @@ class AP_HAL::SIMState { // simulated VectorNav system: SITL::VectorNav *vectornav; - // simulated LORD Microstrain system - SITL::LORD *lord; + // simulated MicroStrain Series 5 system + SITL::MicroStrain5 *microstrain5; #if HAL_SIM_JSON_MASTER_ENABLED // Ride along instances via JSON SITL backend diff --git a/libraries/AP_HAL/WSPIDevice.h b/libraries/AP_HAL/WSPIDevice.h index 08c93f4bfe4856..1b4c3a294c5f7e 100644 --- a/libraries/AP_HAL/WSPIDevice.h +++ b/libraries/AP_HAL/WSPIDevice.h @@ -143,7 +143,7 @@ class WSPIDevice : public Device virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override = 0; - // Set command header for upcomming transfer call(s) + // Set command header for upcoming transfer call(s) virtual void set_cmd_header(const CommandHeader& cmd_hdr) override = 0; virtual bool is_busy() = 0; diff --git a/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp b/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp index 33689a8fdd2e63..1a177b13bb55b0 100644 --- a/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp +++ b/libraries/AP_HAL/examples/AnalogIn/AnalogIn.cpp @@ -22,7 +22,7 @@ void loop(); //declaration of the loop() function const AP_HAL::HAL& hal = AP_HAL::get_HAL(); //create a reference to AP_HAL::HAL object to get access to hardware specific functions. For more info see -AP_HAL::AnalogSource* chan; //delare a pointer to AnalogSource object. AnalogSource class can be found in : AP_HAL->AnalogIn.h +AP_HAL::AnalogSource* chan; //declare a pointer to AnalogSource object. AnalogSource class can be found in : AP_HAL->AnalogIn.h // the setup function runs once when the board powers up void setup(void) { diff --git a/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp b/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp index ff6e57cb652044..ca8dd7b0b086cc 100644 --- a/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp +++ b/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp @@ -28,12 +28,12 @@ void drive(uint16_t hz_speed); class Menu_Commands { public: /* Menu commands to drive a SERVO type with - * repective PWM output freq defined by SERVO_HZ + * respective PWM output freq defined by SERVO_HZ */ int8_t menu_servo(uint8_t argc, const Menu::arg *argv); /* Menu commands to drive a ESC type with - * repective PWM output freq defined by ESC_HZ + * respective PWM output freq defined by ESC_HZ */ int8_t menu_esc(uint8_t argc, const Menu::arg *argv); }; @@ -45,7 +45,7 @@ Menu_Commands commands; static uint16_t pwm = 1500; static int8_t delta = 1; -/* Function to drive a RC output TYPE especified */ +/* Function to drive a RC output TYPE specified */ void drive(uint16_t hz_speed) { hal.rcout->set_freq(0xFF, hz_speed); diff --git a/libraries/AP_HAL/examples/Storage/Storage.cpp b/libraries/AP_HAL/examples/Storage/Storage.cpp index 171c423de5b39d..e39fd83b1af27b 100644 --- a/libraries/AP_HAL/examples/Storage/Storage.cpp +++ b/libraries/AP_HAL/examples/Storage/Storage.cpp @@ -20,7 +20,7 @@ void setup(void) st->init(); /* - Calculate XOR of the full conent of memory + Calculate XOR of the full content of memory Do it by block of 8 bytes */ unsigned char buff[8], XOR_res = 0; @@ -35,7 +35,7 @@ void setup(void) /* print XORed result */ - hal.console->printf("XORed ememory: %u\r\n", (unsigned) XOR_res); + hal.console->printf("XORed memory: %u\r\n", (unsigned) XOR_res); } // In main loop do nothing diff --git a/libraries/AP_HAL/system.h b/libraries/AP_HAL/system.h index c93a7f9f0b9026..c3ba107a75cee8 100644 --- a/libraries/AP_HAL/system.h +++ b/libraries/AP_HAL/system.h @@ -19,12 +19,6 @@ uint16_t millis16(); uint64_t micros64(); uint64_t millis64(); -uint32_t native_micros(); -uint32_t native_millis(); -uint16_t native_millis16(); -uint64_t native_micros64(); -uint64_t native_millis64(); - void dump_stack_trace(); void dump_core_file(); diff --git a/libraries/AP_HAL/tests/test_prescaler.cpp b/libraries/AP_HAL/tests/test_prescaler.cpp index 85d08bd3705774..119791640a50bd 100644 --- a/libraries/AP_HAL/tests/test_prescaler.cpp +++ b/libraries/AP_HAL/tests/test_prescaler.cpp @@ -6,6 +6,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); enum Type { DSHOT, + DSHOT_S, NEOPIXEL, NONE }; @@ -21,26 +22,29 @@ class PrescalerParameterizedTestFixture :public ::testing::TestWithParam 50000000 ? 0.03f : 0.05f; - ::printf("Clock: %uMHz, Target: %uKHz, Rate: %uKHz, prescaler: %u, error: %.1f%%, Dshot: %i\n", - clock/1000000, target_rate/1000, (clock/(prescaler+1))/1000, prescaler, rate_delta * 100.f, is_dshot); + // with low prescaler values accuracy is compromised + const float expected_delta = prescaler == 2 ? 0.3 : prescaler >= 12 ? 0.03f : 0.09f; + ::printf("Clock: %uMHz, Target: %uKHz, Rate: %uKHz, prescaler: %u, error: %.1f%%, at-least: %i\n", + clock/1000000, target_rate/1000, (clock/(prescaler+1))/1000, prescaler, rate_delta * 100.f, at_least_freq); // assert the output of expected results EXPECT_EQ(test_results[test_index].clock, clock); EXPECT_EQ(test_results[test_index].target, target_rate); EXPECT_EQ(test_results[test_index].rate, clock/(prescaler+1)); EXPECT_EQ(test_results[test_index].prescaler, prescaler); - EXPECT_EQ(test_results[test_index].type, is_dshot?DSHOT:NONE); + EXPECT_TRUE(at_least_freq ? test_results[test_index].type == DSHOT_S : + (test_results[test_index].type == DSHOT || test_results[test_index].type == NONE)); test_index++; EXPECT_TRUE(rate_delta < expected_delta); - if (is_dshot) { + if (test_results[test_index].type == DSHOT) { EXPECT_TRUE(fabs(clock/(prescaler+1.0f)-target_rate) < fabsf(clock/(prescaler+2.0f)-target_rate)); EXPECT_TRUE(fabs(clock/(float(prescaler))-target_rate) > fabsf(clock/(prescaler+1.0f)-target_rate)); + } else if(test_results[test_index].type == DSHOT_S) { + EXPECT_TRUE(fabs(clock/float(prescaler)) > target_rate); } } @@ -71,19 +75,19 @@ class PrescalerParameterizedTestFixture :public ::testing::TestWithParam 8) { return -1; } + PERF_STATS(stats.tx_requests); /* * Normally we should perform the same check as in @ref canAcceptNewTxFrame(), because @@ -323,7 +324,7 @@ int16_t CANIface::send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline, } else if ((can_->TSR & bxcan::TSR_TME2) == bxcan::TSR_TME2) { txmailbox = 2; } else { - PERF_STATS(stats.tx_rejected); + PERF_STATS(stats.tx_overflow); return 0; // No transmission for you. } @@ -496,6 +497,9 @@ void CANIface::handleTxMailboxInterrupt(uint8_t mailbox_index, bool txok, const if (txok && !txi.pushed) { txi.pushed = true; PERF_STATS(stats.tx_success); +#if !defined(HAL_BOOTLOADER_BUILD) + stats.last_transmit_us = timestamp_us; +#endif } } diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 0e2f647a377610..533733c10831de 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -14,15 +14,26 @@ * * Code by Andrew Tridgell and Siddharth Bharat Purohit * Bi-directional dshot based on Betaflight, code by Andy Piper and Siddharth Bharat Purohit + * + * There really is no dshot reference. For information try these resources: + * https://blck.mn/2016/11/dshot-the-new-kid-on-the-block/ + * https://www.swallenhardware.io/battlebots/2019/4/20/a-developers-guide-to-dshot-escs */ #include + +#if defined(IOMCU_FW) && HAL_DSHOT_ENABLED +// need to give the little guy as much help as possible +#pragma GCC optimize("O2") +#endif + #include "RCOutput.h" #include #include #include #include "GPIO.h" #include "Util.h" +#include "Scheduler.h" #include "hwdef/common/stm32_util.h" #include "hwdef/common/watchdog.h" #include @@ -61,7 +72,9 @@ extern AP_IOMCU iomcu; #define TELEM_IC_SAMPLE 16 struct RCOutput::pwm_group RCOutput::pwm_group_list[] = { HAL_PWM_GROUPS }; +#if HAL_SERIAL_ESC_COMM_ENABLED struct RCOutput::irq_state RCOutput::irq; +#endif const uint8_t RCOutput::NUM_GROUPS = ARRAY_SIZE(RCOutput::pwm_group_list); // event mask for triggering a PWM send @@ -97,7 +110,7 @@ void RCOutput::init() group.dshot_event_mask = EVENT_MASK(i); for (uint8_t j = 0; j < 4; j++ ) { -#if !APM_BUILD_TYPE(APM_BUILD_iofirmware) +#if !defined(IOMCU_FW) uint8_t chan = group.chan[j]; if (SRV_Channels::is_GPIO(chan+chan_offset)) { group.chan[j] = CHAN_DISABLED; @@ -153,6 +166,7 @@ void RCOutput::init() _initialised = true; } +#if HAL_SERIALLED_ENABLED // start the led thread bool RCOutput::start_led_thread(void) { @@ -198,10 +212,12 @@ void RCOutput::led_thread() led_timer_tick(LED_OUTPUT_PERIOD_US + AP_HAL::micros64()); } } +#endif // HAL_SERIAL_ENABLED /* - thread for handling RCOutput send + thread for handling RCOutput send on FMU */ +#if !defined(IOMCU_FW) void RCOutput::rcout_thread() { uint64_t last_thread_run_us = 0; // last time we did a 1kHz run of rcout @@ -240,7 +256,7 @@ void RCOutput::rcout_thread() // main thread requested a new dshot send or we timed out - if we are not running // as a multiple of loop rate then ignore EVT_PWM_SEND events to preserve periodicity - if (!serial_group && have_pwm_event) { + if (!in_soft_serial() && have_pwm_event) { dshot_send_groups(time_out_us); // now unlock everything @@ -257,14 +273,15 @@ void RCOutput::rcout_thread() static bool output_masks = true; if (AP_HAL::millis() > 5000 && output_masks) { output_masks = false; - hal.console->printf("bdmask 0x%x, en_mask 0x%lx, 3dmask 0x%x:\n", _bdshot.mask, en_mask, _reversible_mask); + hal.console->printf("bdmask 0x%lx, en_mask 0x%lx, 3dmask 0x%lx:\n", _bdshot.mask, en_mask, _reversible_mask); for (auto &group : pwm_group_list) { - hal.console->printf(" timer %u: ch_mask 0x%x, en_mask 0x%x\n", group.timer_id, group.ch_mask, group.en_mask); + hal.console->printf(" timer %u: ch_mask 0x%lx, en_mask 0x%lx\n", group.timer_id, group.ch_mask, group.en_mask); } } #endif } } +#endif __RAMFUNC__ void RCOutput::dshot_update_tick(virtual_timer_t* vt, void* p) { @@ -500,6 +517,11 @@ void RCOutput::set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz) if (loop_rate_hz <= 100 || dshot_rate == 0) { _dshot_period_us = 1000UL; _dshot_rate = 0; +#if HAL_WITH_IO_MCU + if (AP_BoardConfig::io_dshot()) { + iomcu.set_dshot_period(1000UL, 0); + } +#endif return; } // if there are non-dshot channels then do likewise @@ -509,6 +531,13 @@ void RCOutput::set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz) group.current_mode == MODE_PWM_BRUSHED) { _dshot_period_us = 1000UL; _dshot_rate = 0; +#if HAL_WITH_IO_MCU + // this is not strictly neccessary since the iomcu could run at a different rate, + // but there is only one parameter to control this + if (AP_BoardConfig::io_dshot()) { + iomcu.set_dshot_period(1000UL, 0); + } +#endif return; } } @@ -528,9 +557,14 @@ void RCOutput::set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz) drate = _dshot_rate * loop_rate_hz; } _dshot_period_us = 1000000UL / drate; +#if HAL_WITH_IO_MCU + if (AP_BoardConfig::io_dshot()) { + iomcu.set_dshot_period(_dshot_period_us, _dshot_rate); + } +#endif } -#ifndef DISABLE_DSHOT +#if HAL_DSHOT_ENABLED /* Set/get the dshot esc_type */ @@ -551,7 +585,7 @@ void RCOutput::set_dshot_esc_type(DshotEscType dshot_esc_type) break; } } -#endif +#endif // #if HAL_DSHOT_ENABLED /* find pwm_group and index in group given a channel number @@ -622,6 +656,12 @@ uint16_t RCOutput::get_freq(uint8_t chan) void RCOutput::enable_ch(uint8_t chan) { +#if HAL_WITH_IO_MCU + if (chan < chan_offset && AP_BoardConfig::io_enabled()) { + iomcu.enable_ch(chan); + return; + } +#endif uint8_t i; pwm_group *grp = find_chan(chan, i); if (grp) { @@ -632,6 +672,12 @@ void RCOutput::enable_ch(uint8_t chan) void RCOutput::disable_ch(uint8_t chan) { +#if HAL_WITH_IO_MCU + if (chan < chan_offset && AP_BoardConfig::io_enabled()) { + iomcu.disable_ch(chan); + return; + } +#endif uint8_t i; pwm_group *grp = find_chan(chan, i); if (grp) { @@ -659,13 +705,7 @@ void RCOutput::write(uint8_t chan, uint16_t period_us) #if HAL_WITH_IO_MCU // handle IO MCU channels if (AP_BoardConfig::io_enabled()) { - uint16_t io_period_us = period_us; - if ((iomcu_mode == MODE_PWM_ONESHOT125) && ((1U<safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED; for (auto &group : pwm_group_list) { - if (serial_group) { + if (in_soft_serial()) { continue; } if (!group.pwm_started) { @@ -745,15 +785,16 @@ void RCOutput::push_local(void) uint32_t width = (group.pwm_cfg.frequency/1000000U) * period_us; pwmEnableChannel(group.pwm_drv, j, width); } -#ifndef DISABLE_DSHOT +#if HAL_DSHOT_ENABLED else if (is_dshot_protocol(group.current_mode) || is_led_protocol(group.current_mode)) { // set period_us to time for pulse output, to enable very fast rates period_us = group.dshot_pulse_time_us; } -#endif //#ifndef DISABLE_DSHOT +#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 @@ -786,12 +827,7 @@ uint16_t RCOutput::read(uint8_t chan) } #if HAL_WITH_IO_MCU if (chan < chan_offset) { - uint16_t period_us = iomcu.read_channel(chan); - if ((iomcu_mode == MODE_PWM_ONESHOT125) && ((1U<lock(); +#endif if (!group.dma_buffer || buffer_length != group.dma_buffer_len) { if (group.dma_buffer) { hal.util->free_type(group.dma_buffer, group.dma_buffer_len, AP_HAL::Util::MEM_DMA_SAFE); group.dma_buffer_len = 0; } - group.dma_buffer = (uint32_t *)hal.util->malloc_type(buffer_length, AP_HAL::Util::MEM_DMA_SAFE); + group.dma_buffer = (dmar_uint_t *)hal.util->malloc_type(buffer_length, AP_HAL::Util::MEM_DMA_SAFE); if (!group.dma_buffer) { +#if AP_HAL_SHARED_DMA_ENABLED group.dma_handle->unlock(); +#endif print_group_setup_error(group, "failed to allocate DMA buffer"); return false; } @@ -927,26 +976,32 @@ bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_ pwmStop(group.pwm_drv); group.pwm_started = false; } - const uint32_t target_frequency = bitrate * bit_width; - const uint32_t prescaler = calculate_bitrate_prescaler(group.pwm_drv->clock, target_frequency, is_dshot); - if (prescaler > 0x8000) { + const uint32_t prescaler = calculate_bitrate_prescaler(group.pwm_drv->clock, target_frequency, at_least_freq); + if (prescaler == 0 || prescaler > 0x8000) { +#if AP_HAL_SHARED_DMA_ENABLED group.dma_handle->unlock(); +#endif print_group_setup_error(group, "failed to match clock speed"); return false; } - const uint32_t freq = group.pwm_drv->clock / prescaler; + const uint32_t freq = group.pwm_drv->clock / (prescaler + 1); + // PSC is calculated by ChibiOS as (pwm_drv.clock / pwm_cfg.frequency) - 1; group.pwm_cfg.frequency = freq; - group.pwm_cfg.period = bit_width; group.pwm_cfg.dier = TIM_DIER_UDE; group.pwm_cfg.cr2 = 0; group.bit_width_mul = (freq + (target_frequency/2)) / target_frequency; - - //hal.console->printf("CLOCK=%u BW=%u FREQ=%u BR=%u MUL=%u PRE=%u\n", unsigned(group.pwm_drv->clock), unsigned(bit_width), unsigned(group.pwm_cfg.frequency), - // unsigned(bitrate), unsigned(group.bit_width_mul), unsigned(prescaler)); - + // ARR is calculated by ChibiOS as pwm_cfg.period -1 + group.pwm_cfg.period = bit_width * group.bit_width_mul; +#if 0 + hal.console->printf("CLOCK=%u BW=%u FREQ=%u BR=%u MUL=%u PRE=%u\n", unsigned(group.pwm_drv->clock), unsigned(bit_width), unsigned(group.pwm_cfg.frequency), + unsigned(bitrate), unsigned(group.bit_width_mul), unsigned(prescaler)); + static char clock_setup[64]; + hal.util->snprintf(clock_setup, 64, "CLOCK=%u BW=%u FREQ=%u BR=%u MUL=%u PRE=%u\n", unsigned(group.pwm_drv->clock), unsigned(bit_width), unsigned(group.pwm_cfg.frequency), + unsigned(bitrate), unsigned(group.bit_width_mul), unsigned(prescaler)); +#endif for (uint8_t j=0; j<4; j++) { pwmmode_t mode = group.pwm_cfg.channels[j].mode; if (mode != PWM_OUTPUT_DISABLED) { @@ -967,11 +1022,13 @@ bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_ } } +#if AP_HAL_SHARED_DMA_ENABLED group.dma_handle->unlock(); +#endif return true; #else return false; -#endif //#ifndef DISABLE_DSHOT +#endif // HAL_DSHOT_ENABLED } /* @@ -984,9 +1041,9 @@ void RCOutput::set_group_mode(pwm_group &group) pwmStop(group.pwm_drv); group.pwm_started = false; } - +#ifdef HAL_WITH_BIDIR_DSHOT memset(group.bdshot.erpm, 0, 4*sizeof(uint16_t)); - +#endif switch (group.current_mode) { case MODE_PWM_BRUSHED: // force zero output initially @@ -1000,7 +1057,9 @@ void RCOutput::set_group_mode(pwm_group &group) break; case MODE_NEOPIXEL: + case MODE_NEOPIXELRGB: case MODE_PROFILED: +#if HAL_SERIALLED_ENABLED { uint8_t bits_per_pixel = 24; bool active_high = true; @@ -1032,16 +1091,24 @@ void RCOutput::set_group_mode(pwm_group &group) } break; } +#endif case MODE_PWM_DSHOT150 ... MODE_PWM_DSHOT1200: { +#if HAL_DSHOT_ENABLED const uint32_t rate = protocol_bitrate(group.current_mode); bool active_high = is_bidir_dshot_enabled() ? false : true; + bool at_least_freq = false; // calculate min time between pulses const uint32_t pulse_send_time_us = 1000000UL * dshot_bit_length / rate; + // BLHeli_S (and BlueJay) appears to always want the frequency above the target + if (_dshot_esc_type == DSHOT_ESC_BLHELI_S || _dshot_esc_type == DSHOT_ESC_BLHELI_EDT_S) { + at_least_freq = true; + } + // configure timer driver for DMAR at requested rate if (!setup_group_DMA(group, rate, DSHOT_BIT_WIDTH_TICKS, active_high, - MAX(DSHOT_BUFFER_LENGTH, GCR_TELEMETRY_BUFFER_LEN), pulse_send_time_us, true)) { + MAX(DSHOT_BUFFER_LENGTH, GCR_TELEMETRY_BUFFER_LEN), pulse_send_time_us, at_least_freq)) { group.current_mode = MODE_PWM_NORMAL; break; } @@ -1050,6 +1117,7 @@ void RCOutput::set_group_mode(pwm_group &group) // to all intents and purposes the pulse time of send and receive are the same group.dshot_pulse_time_us = pulse_send_time_us + pulse_send_time_us + 30; } +#endif break; } @@ -1110,24 +1178,51 @@ void RCOutput::set_output_mode(uint32_t mask, const enum output_mode mode) } #if HAL_WITH_IO_MCU if ((mode == MODE_PWM_ONESHOT || - mode == MODE_PWM_ONESHOT125) && + mode == MODE_PWM_ONESHOT125 || + mode == MODE_PWM_BRUSHED || + (mode >= MODE_PWM_DSHOT150 && mode <= MODE_PWM_DSHOT600)) && (mask & ((1U<> chan_offset); } /* @@ -1147,8 +1242,14 @@ bool RCOutput::get_output_mode_banner(char banner_msg[], uint8_t banner_msg_len) #if HAL_WITH_IO_MCU // fill in ch_mode array for IOMCU channels if (AP_BoardConfig::io_enabled()) { + uint8_t iomcu_mask; + const output_mode iomcu_mode = iomcu.get_output_mode(iomcu_mask); for (uint8_t i = 0; i < chan_offset; i++ ) { - ch_mode[i] = iomcu_mode; + if (iomcu_mask & 1U< 0) && (iomcu_mode != MODE_PWM_NONE); } @@ -1252,7 +1353,7 @@ void RCOutput::trigger_groups(void) osalSysLock(); for (auto &group : pwm_group_list) { - if (irq.waiter) { + if (soft_serial_waiting()) { // doing serial output, don't send pulses continue; } @@ -1266,9 +1367,9 @@ void RCOutput::trigger_groups(void) } } osalSysUnlock(); -#ifndef HAL_NO_RCOUT_THREAD +#if !defined(HAL_NO_RCOUT_THREAD) || HAL_DSHOT_ENABLED // trigger a PWM send - if (!serial_group && hal.scheduler->in_main_thread()) { + if (!in_soft_serial() && hal.scheduler->in_main_thread() && rcout_thread_ctx) { chEvtSignal(rcout_thread_ctx, EVT_PWM_SEND); } #endif @@ -1287,7 +1388,7 @@ void RCOutput::trigger_groups(void) */ void RCOutput::timer_tick(uint64_t time_out_us) { - if (serial_group) { + if (in_soft_serial()) { return; } @@ -1309,7 +1410,7 @@ void RCOutput::timer_tick(uint64_t time_out_us) */ void RCOutput::led_timer_tick(uint64_t time_out_us) { - if (serial_group) { + if (in_soft_serial()) { return; } @@ -1325,11 +1426,75 @@ void RCOutput::led_timer_tick(uint64_t time_out_us) } } +#if defined(IOMCU_FW) && HAL_DSHOT_ENABLED +THD_WORKING_AREA(dshot_thread_wa, 64); +void RCOutput::timer_tick() +{ + if (dshot_timer_setup) { + return; + } + + bool dshot_enabled = false; + for (uint8_t i = 0; i < NUM_GROUPS; i++ ) { + pwm_group &group = pwm_group_list[i]; + if (is_dshot_protocol(group.current_mode)) { + dshot_enabled = true; + break; + } + } + if (!dshot_timer_setup && dshot_enabled) { + chThdCreateStatic(dshot_thread_wa, sizeof(dshot_thread_wa), + APM_RCOUT_PRIORITY, &RCOutput::dshot_send_trampoline, this); + dshot_timer_setup = true; + } +} + +void RCOutput::dshot_send_trampoline(void *p) +{ + RCOutput *rcout = (RCOutput *)p; + rcout->rcout_thread(); +} + +/* + thread for handling RCOutput send on IOMCU + */ +void RCOutput::rcout_thread() { + // don't start outputting until fully configured + while (!hal.scheduler->is_system_initialized()) { + hal.scheduler->delay_microseconds(1000); + } + + rcout_thread_ctx = chThdGetSelfX(); + + while (true) { + chEvtWaitOne(EVT_PWM_SEND | EVT_PWM_SYNTHETIC_SEND); + + // this is when the cycle is supposed to start + if (_dshot_cycle == 0) { + // register a timer for the next tick if push() will not be providing it + if (_dshot_rate != 1) { + chVTSet(&_dshot_rate_timer, chTimeUS2I(_dshot_period_us), dshot_update_tick, this); + } + } + + // main thread requested a new dshot send or we timed out - if we are not running + // as a multiple of loop rate then ignore EVT_PWM_SEND events to preserve periodicity + dshot_send_groups(0); +#if AP_HAL_SHARED_DMA_ENABLED + dshot_collect_dma_locks(0); +#endif + if (_dshot_rate > 0) { + _dshot_cycle = (_dshot_cycle + 1) % _dshot_rate; + } + } +} +#endif // IOMCU_FW && DISABLE_DSHOT + // send dshot for all groups that support it void RCOutput::dshot_send_groups(uint64_t time_out_us) { -#ifndef DISABLE_DSHOT - if (serial_group) { +#if HAL_DSHOT_ENABLED + if (in_soft_serial()) { return; } @@ -1354,7 +1519,7 @@ void RCOutput::dshot_send_groups(uint64_t time_out_us) if (command_sent) { _dshot_current_command.cycle--; } -#endif //#ifndef DISABLE_DSHOT +#endif // HAL_DSHOT_ENABLED } __RAMFUNC__ void RCOutput::dshot_send_next_group(void* p) @@ -1369,12 +1534,18 @@ __RAMFUNC__ void RCOutput::dshot_send_next_group(void* p) /* allocate DMA channel */ +#if AP_HAL_SHARED_DMA_ENABLED void RCOutput::dma_allocate(Shared_DMA *ctx) { for (auto &group : pwm_group_list) { if (group.dma_handle == ctx && group.dma == nullptr) { chSysLock(); group.dma = dmaStreamAllocI(group.dma_up_stream_id, 10, dma_up_irq_callback, &group); +#if defined(IOMCU_FW) + if (group.pwm_started) { + pwmStart(group.pwm_drv, &group.pwm_cfg); + } +#endif chSysUnlock(); #if STM32_DMA_SUPPORTS_DMAMUX if (group.dma) { @@ -1393,12 +1564,20 @@ void RCOutput::dma_deallocate(Shared_DMA *ctx) for (auto &group : pwm_group_list) { if (group.dma_handle == ctx && group.dma != nullptr) { chSysLock(); +#if defined(IOMCU_FW) + // leaving the peripheral running on IOMCU plays havoc with the UART that is + // also sharing this channel + if (group.pwm_started) { + pwmStop(group.pwm_drv); + } +#endif dmaStreamFreeI(group.dma); group.dma = nullptr; chSysUnlock(); } } } +#endif // AP_HAL_SHARED_DMA_ENABLED /* create a DSHOT 16 bit packet. Based on prepareDshotPacket from betaflight @@ -1432,11 +1611,15 @@ uint16_t RCOutput::create_dshot_packet(const uint16_t value, bool telem_request, /* fill in a DMA buffer for dshot + the buffer format is (stride is always 4 for 4 channels): + [ch0b0][ch1b0][ch2b0][ch3b0][ch0b1][ch1b1][ch2b1][ch3b1]...[ch0bN][ch1bN][ch2bN][ch3bN] + where N = dshot_bit_length - 1 + each value is a number of beats for the DMA engine to send in burst via DMAR to the 4 CCR registers */ -void RCOutput::fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul) +void RCOutput::fill_DMA_buffer_dshot(dmar_uint_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul) { - const uint32_t DSHOT_MOTOR_BIT_0 = DSHOT_BIT_0_TICKS * clockmul; - const uint32_t DSHOT_MOTOR_BIT_1 = DSHOT_BIT_1_TICKS * clockmul; + const dmar_uint_t DSHOT_MOTOR_BIT_0 = DSHOT_BIT_0_TICKS * clockmul; + const dmar_uint_t DSHOT_MOTOR_BIT_1 = DSHOT_BIT_1_TICKS * clockmul; uint16_t i = 0; for (; i < dshot_pre; i++) { buffer[i * stride] = 0; @@ -1457,23 +1640,25 @@ void RCOutput::fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t */ void RCOutput::dshot_send(pwm_group &group, uint64_t time_out_us) { -#ifndef DISABLE_DSHOT - if (irq.waiter || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE)) { +#if HAL_DSHOT_ENABLED + if (soft_serial_waiting() || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE)) { // doing serial output or DMAR input, don't send DShot pulses return; } +#if AP_HAL_SHARED_DMA_ENABLED // first make sure we have the DMA channel before anything else osalDbgAssert(!group.dma_handle->is_locked(), "DMA handle is already locked"); group.dma_handle->lock(); - +#endif // if we are sharing UP channels then it might have taken a long time to get here, // if there's not enough time to actually send a pulse then cancel - - if (AP_HAL::micros64() + group.dshot_pulse_time_us > time_out_us) { +#if AP_HAL_SHARED_DMA_ENABLED + if (time_out_us > 0 && AP_HAL::micros64() + group.dshot_pulse_time_us > time_out_us) { group.dma_handle->unlock(); return; } +#endif // only the timer thread releases the locks group.dshot_waiter = rcout_thread_ctx; @@ -1524,8 +1709,9 @@ void RCOutput::dshot_send(pwm_group &group, uint64_t time_out_us) } #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++) { @@ -1569,15 +1755,21 @@ void RCOutput::dshot_send(pwm_group &group, uint64_t time_out_us) if (value != 0) { value += DSHOT_ZERO_THROTTLE; } - +#if !defined(IOMCU_FW) if (!armed) { // when disarmed we always send a zero value value = 0; } - +#endif // according to sskaug requesting telemetry while trying to arm may interfere with the good frame calc bool request_telemetry = telem_request_mask & chan_mask; - uint16_t packet = create_dshot_packet(value, request_telemetry, group.bdshot.enabled); + uint16_t packet = create_dshot_packet(value, request_telemetry, +#ifdef HAL_WITH_BIDIR_DSHOT + group.bdshot.enabled +#else + false +#endif + ); if (request_telemetry) { telem_request_mask &= ~chan_mask; } @@ -1588,7 +1780,7 @@ void RCOutput::dshot_send(pwm_group &group, uint64_t time_out_us) chEvtGetAndClearEvents(group.dshot_event_mask); // start sending the pulses out send_pulses_DMAR(group, DSHOT_BUFFER_LENGTH); -#endif //#ifndef DISABLE_DSHOT +#endif // HAL_DSHOT_ENABLED } /* @@ -1596,14 +1788,15 @@ void RCOutput::dshot_send(pwm_group &group, uint64_t time_out_us) return true if send was successful called from led thread */ +#if HAL_SERIALLED_ENABLED bool RCOutput::serial_led_send(pwm_group &group) { if (!group.serial_led_pending || !is_led_protocol(group.current_mode)) { return true; } -#ifndef DISABLE_DSHOT - if (irq.waiter || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE)) { +#if HAL_DSHOT_ENABLED + if (soft_serial_waiting() || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE)) { // doing serial output or DMAR input, don't send DShot pulses return false; } @@ -1627,10 +1820,10 @@ bool RCOutput::serial_led_send(pwm_group &group) // start sending the pulses out send_pulses_DMAR(group, group.dma_buffer_len); -#endif //#ifndef DISABLE_DSHOT +#endif // HAL_DSHOT_ENABLED return true; } - +#endif // HAL_SERIALLED_ENABLED /* send a series of pulses for a group using DMAR. Pulses must have @@ -1639,7 +1832,7 @@ bool RCOutput::serial_led_send(pwm_group &group) */ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length) { -#ifndef DISABLE_DSHOT +#if HAL_DSHOT_ENABLED osalDbgAssert(group.dma && group.dma_buffer, "DMA structures are corrupt"); /* The DMA approach we are using is based on the DMAR method from @@ -1653,34 +1846,43 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length) datasheet. Many thanks to the betaflight developers for coming up with this great method. */ +#ifdef HAL_GPIO_LINE_GPIO54 TOGGLE_PIN_DEBUG(54); +#endif #if STM32_DMA_SUPPORTS_DMAMUX dmaSetRequestSource(group.dma, group.dma_up_channel); #endif dmaStreamSetPeripheral(group.dma, &(group.pwm_drv->tim->DMAR)); stm32_cacheBufferFlush(group.dma_buffer, buffer_length); dmaStreamSetMemory0(group.dma, group.dma_buffer); - dmaStreamSetTransactionSize(group.dma, buffer_length/sizeof(uint32_t)); + dmaStreamSetTransactionSize(group.dma, buffer_length / sizeof(dmar_uint_t)); #if STM32_DMA_ADVANCED dmaStreamSetFIFO(group.dma, STM32_DMA_FCR_DMDIS | STM32_DMA_FCR_FTH_FULL); #endif dmaStreamSetMode(group.dma, STM32_DMA_CR_CHSEL(group.dma_up_channel) | - STM32_DMA_CR_DIR_M2P | STM32_DMA_CR_PSIZE_WORD | STM32_DMA_CR_MSIZE_WORD | + STM32_DMA_CR_DIR_M2P | STM32_DMA_CR_PSIZE_WORD | +#if defined(IOMCU_FW) + STM32_DMA_CR_MSIZE_BYTE | +#else + STM32_DMA_CR_MSIZE_WORD | +#endif STM32_DMA_CR_MINC | STM32_DMA_CR_PL(3) | STM32_DMA_CR_TEIE | STM32_DMA_CR_TCIE); // setup for burst strided transfers into the timers 4 CCR registers const uint8_t ccr_ofs = offsetof(stm32_tim_t, CCR)/4; + // burst address (BA) of the CCR register, burst length (BL) of 4 (0b11) group.pwm_drv->tim->DCR = STM32_TIM_DCR_DBA(ccr_ofs) | STM32_TIM_DCR_DBL(3); group.dshot_state = DshotState::SEND_START; - +#ifdef HAL_GPIO_LINE_GPIO54 TOGGLE_PIN_DEBUG(54); +#endif dmaStreamEnable(group.dma); // record when the transaction was started group.last_dmar_send_us = AP_HAL::micros64(); -#endif //#ifndef DISABLE_DSHOT +#endif // HAL_DSHOT_ENABLED } /* @@ -1709,10 +1911,13 @@ __RAMFUNC__ void RCOutput::dma_up_irq_callback(void *p, uint32_t flags) pwm_group *group = (pwm_group *)p; chSysLockFromISR(); dmaStreamDisable(group->dma); - if (group->in_serial_dma && irq.waiter) { +#if HAL_SERIAL_ESC_COMM_ENABLED + if (group->in_serial_dma && soft_serial_waiting()) { // tell the waiting process we've done the DMA chEvtSignalI(irq.waiter, serial_event_mask); - } else { + } else +#endif + { // this prevents us ever having two dshot pulses too close together // dshot mandates a minimum pulse separation of 40us, WS2812 mandates 50us so we // pick the higher value @@ -1763,6 +1968,7 @@ void RCOutput::dma_cancel(pwm_group& group) While serial output is active normal output to the channel group is suspended. */ +#if HAL_SERIAL_ESC_COMM_ENABLED bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t chanmask) { // account for IOMCU channels @@ -1788,7 +1994,7 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t cha } if (!new_serial_group) { - if (serial_group) { + if (in_soft_serial()) { // shutdown old group serial_end(); } @@ -1831,10 +2037,10 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t cha /* fill in a DMA buffer for a serial byte, assuming 1 start bit and 1 stop bit */ -void RCOutput::fill_DMA_buffer_byte(uint32_t *buffer, uint8_t stride, uint8_t b, uint32_t bitval) +void RCOutput::fill_DMA_buffer_byte(dmar_uint_t *buffer, uint8_t stride, uint8_t b, uint32_t bitval) { - const uint32_t BIT_0 = bitval; - const uint32_t BIT_1 = 0; + const dmar_uint_t BIT_0 = bitval; + const dmar_uint_t BIT_1 = 0; // start bit buffer[0] = BIT_0; @@ -1877,8 +2083,8 @@ bool RCOutput::serial_write_byte(uint8_t b) */ bool RCOutput::serial_write_bytes(const uint8_t *bytes, uint16_t len) { -#ifndef DISABLE_DSHOT - if (!serial_group) { +#if HAL_DSHOT_ENABLED + if (!in_soft_serial()) { return false; } serial_group->dma_handle->lock(); @@ -2001,8 +2207,7 @@ bool RCOutput::serial_read_byte(uint8_t &b) */ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len) { -#ifndef DISABLE_SERIAL_ESC_COMM - if (serial_group == nullptr) { + if (!in_soft_serial()) { return 0; } pwm_group &group = *serial_group; @@ -2062,10 +2267,6 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len) palWriteLine(HAL_GPIO_LINE_GPIO54, 0); #endif return i; -#else - return false; -#endif //#ifndef DISABLE_SERIAL_ESC_COMM - } /* @@ -2073,8 +2274,7 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len) */ void RCOutput::serial_end(void) { -#ifndef DISABLE_SERIAL_ESC_COMM - if (serial_group) { + if (in_soft_serial()) { if (serial_thread == chThdGetSelfX()) { chThdSetPriority(serial_priority); serial_thread = nullptr; @@ -2087,8 +2287,8 @@ void RCOutput::serial_end(void) } } serial_group = nullptr; -#endif //#ifndef DISABLE_SERIAL_ESC_COMM } +#endif // HAL_SERIAL_ESC_COMM_ENABLED /* get safety switch state for Util.cpp @@ -2215,6 +2415,7 @@ uint32_t RCOutput::protocol_bitrate(const enum output_mode mode) case MODE_PWM_DSHOT1200: return 1200000; case MODE_NEOPIXEL: + case MODE_NEOPIXELRGB: return 800000; case MODE_PROFILED: return 1500000; // experiment winding this up 3000000 max from data sheet @@ -2228,6 +2429,7 @@ uint32_t RCOutput::protocol_bitrate(const enum output_mode mode) setup serial led output for a given channel number, with the given max number of LEDs in the chain. */ +#if HAL_SERIALLED_ENABLED bool RCOutput::set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode, uint32_t clock_mask) { if (!_initialised || num_leds == 0) { @@ -2253,9 +2455,11 @@ bool RCOutput::set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, ou } switch (mode) { - case MODE_NEOPIXEL: { + + case MODE_NEOPIXEL: + case MODE_NEOPIXELRGB: { grp->serial_nleds = MAX(num_leds, grp->serial_nleds); - grp->led_mode = MODE_NEOPIXEL; + grp->led_mode = mode; return true; } case MODE_PROFILED: { @@ -2280,8 +2484,6 @@ bool RCOutput::set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, ou } - - #pragma GCC push_options #pragma GCC optimize("O2") // Fill the group DMA buffer with data to be output @@ -2308,6 +2510,9 @@ void RCOutput::fill_DMA_buffer_serial_led(pwm_group& group) case MODE_NEOPIXEL: _set_neopixel_rgb_data(&group, j, i, led.red, led.green, led.blue); break; + case MODE_NEOPIXELRGB: + _set_neopixel_rgb_data(&group, j, i, led.green, led.red, led.blue); + break; case MODE_PROFILED: { if (i < group.serial_nleds - 2) { _set_profiled_rgb_data(&group, j, i, led.red, led.green, led.blue); @@ -2332,7 +2537,7 @@ void RCOutput::_set_neopixel_rgb_data(pwm_group *grp, uint8_t idx, uint8_t led, const uint8_t pad_start_bits = 1; const uint8_t neopixel_bit_length = 24; const uint8_t stride = 4; - uint32_t *buf = grp->dma_buffer + (led * neopixel_bit_length + pad_start_bits) * stride + idx; + dmar_uint_t *buf = grp->dma_buffer + (led * neopixel_bit_length + pad_start_bits) * stride + idx; uint32_t bits = (green<<16) | (red<<8) | blue; const uint32_t BIT_0 = NEOP_BIT_0_TICKS * grp->bit_width_mul; const uint32_t BIT_1 = NEOP_BIT_1_TICKS * grp->bit_width_mul; @@ -2351,7 +2556,7 @@ void RCOutput::_set_profiled_rgb_data(pwm_group *grp, uint8_t idx, uint8_t led, const uint8_t pad_start_bits = 1; const uint8_t bit_length = 25; const uint8_t stride = 4; - uint32_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx; + dmar_uint_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx; uint32_t bits = 0x1000000 | (blue<<16) | (red<<8) | green; const uint32_t BIT_1 = PROFI_BIT_1_TICKS * grp->bit_width_mul; for (uint16_t b=0; b < bit_length; b++) { @@ -2369,7 +2574,7 @@ void RCOutput::_set_profiled_blank_frame(pwm_group *grp, uint8_t idx, uint8_t le const uint8_t pad_start_bits = 1; const uint8_t bit_length = 25; const uint8_t stride = 4; - uint32_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx; + dmar_uint_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx; const uint32_t BIT_1 = PROFI_BIT_1_TICKS * grp->bit_width_mul; for (uint16_t b=0; b < bit_length; b++) { buf[b * stride] = BIT_1; @@ -2384,7 +2589,7 @@ void RCOutput::_set_profiled_clock(pwm_group *grp, uint8_t idx, uint8_t led) const uint8_t pad_start_bits = 1; const uint8_t bit_length = 25; const uint8_t stride = 4; - uint32_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx; + dmar_uint_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx; const uint32_t BIT_1 = PROFI_BIT_0_TICKS * grp->bit_width_mul; for (uint16_t b=0; b < bit_length; b++) { buf[b * stride] = BIT_1; @@ -2480,6 +2685,7 @@ void RCOutput::serial_led_set_single_rgb_data(pwm_group& group, uint8_t idx, uin switch (group.current_mode) { case MODE_PROFILED: case MODE_NEOPIXEL: + case MODE_NEOPIXELRGB: group.serial_led_data[idx][led].red = red; group.serial_led_data[idx][led].green = green; group.serial_led_data[idx][led].blue = blue; @@ -2520,6 +2726,7 @@ void RCOutput::serial_led_send(const uint16_t chan) serial_led_pending = true; } } +#endif // HAL_SERIALLED_ENABLED void RCOutput::timer_info(ExpandingString &str) { @@ -2528,9 +2735,12 @@ void RCOutput::timer_info(ExpandingString &str) for (auto &group : pwm_group_list) { uint32_t target_freq; +#if HAL_SERIAL_ESC_COMM_ENABLED if (&group == serial_group) { target_freq = 19200 * 10; - } else if (is_dshot_protocol(group.current_mode)) { + } else +#endif // HAL_SERIAL_ESC_COMM_ENABLED + if (is_dshot_protocol(group.current_mode)) { target_freq = protocol_bitrate(group.current_mode) * DSHOT_BIT_WIDTH_TICKS; } else { target_freq = protocol_bitrate(group.current_mode) * NEOP_BIT_WIDTH_TICKS; diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index c8a97bbf80a1c7..53630f626327c8 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -16,18 +16,19 @@ */ #pragma once +#include #include "AP_HAL_ChibiOS.h" #include #include #include "shared_dma.h" -#include "ch.h" -#include "hal.h" #if HAL_USE_PWM == TRUE -#if !STM32_DMA_ADVANCED && !defined(STM32G4) && !defined(STM32L4) -#define DISABLE_DSHOT +#if defined(IOMCU_FW) +typedef uint8_t dmar_uint_t; // save memory to allow dshot on IOMCU +#else +typedef uint32_t dmar_uint_t; #endif #define RCOU_DSHOT_TIMING_DEBUG 0 @@ -51,15 +52,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput void read(uint16_t* period_us, uint8_t len) override; uint16_t read_last_sent(uint8_t ch) override; void read_last_sent(uint16_t* period_us, uint8_t len) override; - void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override { - _esc_pwm_min = min_pwm; - _esc_pwm_max = max_pwm; - } - bool get_esc_scaling(uint16_t &min_pwm, uint16_t &max_pwm) override { - min_pwm = _esc_pwm_min; - max_pwm = _esc_pwm_max; - return true; - } + // surface dshot telemetry for use by the harmonic notch and status information #ifdef HAL_WITH_BIDIR_DSHOT uint16_t get_erpm(uint8_t chan) const override { return _bdshot.erpm[chan]; } @@ -68,6 +61,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput } #endif void set_output_mode(uint32_t mask, const enum output_mode mode) override; + enum output_mode get_output_mode(uint32_t& mask) override; bool get_output_mode_banner(char banner_msg[], uint8_t banner_msg_len) const override; /* @@ -75,10 +69,6 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput */ uint32_t get_disabled_channels(uint32_t digital_mask) override; - float scale_esc_to_unity(uint16_t pwm) override { - return 2.0 * ((float) pwm - _esc_pwm_min) / (_esc_pwm_max - _esc_pwm_min) - 1.0; - } - void cork(void) override; void push(void) override; @@ -109,12 +99,17 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput */ void led_timer_tick(uint64_t last_run_us); +#if defined(IOMCU_FW) && HAL_DSHOT_ENABLED + void timer_tick() override; + static void dshot_send_trampoline(void *p); +#endif /* setup for serial output to a set of ESCs, using the given baudrate. Assumes 1 start bit, 1 stop bit, LSB first and 8 databits. This is used for ESC configuration and firmware flashing */ +#if HAL_SERIAL_ESC_COMM_ENABLED bool setup_serial_output(uint32_t chan_mask, ByteBuffer *buffer, uint32_t baudrate); /* @@ -148,13 +143,14 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput serial_setup_output() */ void serial_end(void) override; +#endif /* enable telemetry request for a mask of channels. This is used with Dshot to get telemetry feedback The mask uses servo channel numbering */ - void set_telem_request_mask(uint32_t mask) override { telem_request_mask = (mask >> chan_offset); } + void set_telem_request_mask(uint32_t mask) override; #ifdef HAL_WITH_BIDIR_DSHOT /* @@ -172,7 +168,18 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput */ void set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz) override; -#ifndef DISABLE_DSHOT +#if defined(IOMCU_FW) + /* + Get/Set the dshot period in us, only for use by the IOMCU + */ + void set_dshot_period(uint32_t period_us, uint8_t dshot_rate) override { + _dshot_period_us = period_us; + _dshot_rate = dshot_rate; + } + uint32_t get_dshot_period_us() const override { return _dshot_period_us; } +#endif + +#if HAL_DSHOT_ENABLED /* Set/get the dshot esc_type */ @@ -196,7 +203,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput */ void set_safety_mask(uint32_t mask) { safety_mask = mask; } -#ifndef DISABLE_DSHOT +#if HAL_DSHOT_ENABLED /* * mark the channels in chanmask as reversible. This is needed for some ESC types (such as Dshot) * so that output scaling can be performed correctly. The chanmask passed is added (ORed) into any existing mask. @@ -210,7 +217,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput * The mask uses servo channel numbering */ void set_reversed_mask(uint32_t chanmask) override; - uint32_t get_reversed_mask() override { return _reversed_mask << chan_offset; } + uint32_t get_reversed_mask() override { return _reversed_mask; } /* mark escs as active for the purpose of sending dshot commands @@ -240,6 +247,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput setup serial LED output for a given channel number, with the given max number of LEDs in the chain. */ +#if HAL_SERIALLED_ENABLED bool set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode = MODE_PWM_NONE, uint32_t clock_mask = 0) override; /* @@ -252,7 +260,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput trigger send of serial LED data */ void serial_led_send(const uint16_t chan) override; - +#endif /* rcout thread */ @@ -285,7 +293,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput static const uint8_t dshot_pre = 1; static const uint8_t dshot_post = 2; static const uint16_t dshot_bit_length = 16 + dshot_pre + dshot_post; - static const uint16_t DSHOT_BUFFER_LENGTH = dshot_bit_length * 4 * sizeof(uint32_t); + static const uint16_t DSHOT_BUFFER_LENGTH = dshot_bit_length * 4 * sizeof(dmar_uint_t); static const uint16_t MIN_GCR_BIT_LEN = 7; static const uint16_t MAX_GCR_BIT_LEN = 22; static const uint16_t GCR_TELEMETRY_BIT_LEN = MAX_GCR_BIT_LEN; @@ -318,8 +326,10 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput // mask of channels that are enabled and active uint32_t en_mask; const stm32_dma_stream_t *dma; +#if AP_HAL_SHARED_DMA_ENABLED Shared_DMA *dma_handle; - uint32_t *dma_buffer; +#endif + dmar_uint_t *dma_buffer; uint16_t dma_buffer_len; bool pwm_started; uint32_t bit_width_mul; @@ -329,7 +339,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput uint64_t dshot_pulse_time_us; uint64_t dshot_pulse_send_time_us; virtual_timer_t dma_timeout; - +#if HAL_SERIALLED_ENABLED // serial LED support volatile uint8_t serial_nleds; uint8_t clock_mask; @@ -340,10 +350,11 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput // structure to hold serial LED data until it can be transferred // to the DMA buffer SerialLed* serial_led_data[4]; +#endif eventmask_t dshot_event_mask; thread_t* dshot_waiter; - +#if HAL_SERIAL_ESC_COMM_ENABLED // serial output struct { // expected time per bit @@ -355,14 +366,14 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput // thread waiting for byte to be written thread_t *waiter; } serial; +#endif // support for bi-directional dshot volatile DshotState dshot_state; - +#ifdef HAL_WITH_BIDIR_DSHOT struct { uint16_t erpm[4]; volatile bool enabled; -#ifdef HAL_WITH_BIDIR_DSHOT const stm32_dma_stream_t *ic_dma[4]; uint16_t dma_tx_size; // save tx value from last read Shared_DMA *ic_dma_handle[4]; @@ -375,11 +386,9 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput uint16_t telem_rate[4]; uint16_t telem_err_rate[4]; uint64_t last_print; // debug -#endif #endif } bdshot; -#ifdef HAL_WITH_BIDIR_DSHOT // do we have an input capture dma channel bool has_ic_dma() const { return bdshot.ic_dma_handle[bdshot.curr_telem_chan] != nullptr; @@ -402,7 +411,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput bool ic_enabled() const { return bdshot.enabled && has_ic(); } -#endif +#endif // HAL_WITH_BIDIR_DSHOT // are we safe to send another pulse? bool can_send_dshot_pulse() const { return is_dshot_protocol(current_mode) && AP_HAL::micros() - last_dmar_send_us > (dshot_pulse_time_us + 50); @@ -418,6 +427,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput */ thread_t *rcout_thread_ctx; +#if HAL_SERIALLED_ENABLED /* timer thread for use by led events */ @@ -428,7 +438,9 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput */ HAL_Semaphore led_thread_sem; bool led_thread_created; +#endif +#if HAL_SERIAL_ESC_COMM_ENABLED /* structure for IRQ handler for soft-serial input */ @@ -462,16 +474,30 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput bool timed_out; } irq; - // the group being used for serial output struct pwm_group *serial_group; thread_t *serial_thread; tprio_t serial_priority; +#endif // HAL_SERIAL_ESC_COMM_ENABLED + + static bool soft_serial_waiting() { +#if HAL_SERIAL_ESC_COMM_ENABLED + return irq.waiter != nullptr; +#else + return false; +#endif + } + + bool in_soft_serial() const { +#if HAL_SERIAL_ESC_COMM_ENABLED + return serial_group != nullptr; +#else + return false; +#endif + } static pwm_group pwm_group_list[]; static const uint8_t NUM_GROUPS; - uint16_t _esc_pwm_min; - uint16_t _esc_pwm_max; // offset of first local channel uint8_t chan_offset; @@ -516,7 +542,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput // virtual timer for post-push() pulses virtual_timer_t _dshot_rate_timer; -#ifndef DISABLE_DSHOT +#if HAL_DSHOT_ENABLED // dshot commands // RingBuffer to store outgoing request. struct DshotCommandPacket { @@ -537,7 +563,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput return (_dshot_current_command.chan == RCOutput::ALL_CHANNELS || (group.ch_mask & (1UL << _dshot_current_command.chan))) && _dshot_current_command.cycle > 0; } -#endif +#endif // HAL_DSHOT_ENABLED bool corked; // mask of channels that are running in high speed uint32_t fast_channel_mask; @@ -561,8 +587,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput // widest pulse for oneshot triggering uint16_t trigger_widest_pulse; - // iomcu output mode (pwm, oneshot or oneshot125) - enum output_mode iomcu_mode = MODE_PWM_NORMAL; + bool dshot_timer_setup; volatile bool _initialised; @@ -617,7 +642,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput void dma_allocate(Shared_DMA *ctx); void dma_deallocate(Shared_DMA *ctx); uint16_t create_dshot_packet(const uint16_t value, bool telem_request, bool bidir_telem); - void fill_DMA_buffer_dshot(uint32_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul); + void fill_DMA_buffer_dshot(dmar_uint_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul); void dshot_send_groups(uint64_t time_out_us); void dshot_send(pwm_group &group, uint64_t time_out_us); @@ -632,7 +657,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput bool mode_requires_dma(enum output_mode mode) const; bool setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_width, bool active_high, const uint16_t buffer_length, uint32_t pulse_time_us, - bool is_dshot); + bool at_least_freq); void send_pulses_DMAR(pwm_group &group, uint32_t buffer_length); void set_group_mode(pwm_group &group); static uint32_t protocol_bitrate(const enum output_mode mode); @@ -665,14 +690,14 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput void _set_profiled_rgb_data(pwm_group *grp, uint8_t idx, uint8_t led, uint8_t red, uint8_t green, uint8_t blue); void _set_profiled_clock(pwm_group *grp, uint8_t idx, uint8_t led); void _set_profiled_blank_frame(pwm_group *grp, uint8_t idx, uint8_t led); - +#if AP_HAL_SHARED_DMA_ENABLED // serial output support bool serial_write_byte(uint8_t b); bool serial_read_byte(uint8_t &b); - void fill_DMA_buffer_byte(uint32_t *buffer, uint8_t stride, uint8_t b , uint32_t bitval); + void fill_DMA_buffer_byte(dmar_uint_t *buffer, uint8_t stride, uint8_t b , uint32_t bitval); static void serial_bit_irq(void); static void serial_byte_timeout(virtual_timer_t* vt, void *ctx); - +#endif }; #if RCOU_DSHOT_TIMING_DEBUG diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp index 733a7e44b5889a..db368a9cbfbb1a 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp @@ -16,12 +16,18 @@ #include #include "RCOutput.h" #include +#include #include "hwdef/common/stm32_util.h" #include #include #if HAL_USE_PWM == TRUE -#ifndef DISABLE_DSHOT +#if HAL_DSHOT_ENABLED + +#if HAL_WITH_IO_MCU +#include +extern AP_IOMCU iomcu; +#endif using namespace ChibiOS; @@ -33,7 +39,7 @@ bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t cha return false; } - if (irq.waiter || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE)) { + if (soft_serial_waiting() || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE)) { // doing serial output or DMAR input, don't send DShot pulses return false; } @@ -42,9 +48,10 @@ bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t cha TOGGLE_PIN_DEBUG(81); #endif // first make sure we have the DMA channel before anything else - +#if AP_HAL_SHARED_DMA_ENABLED osalDbgAssert(!group.dma_handle->is_locked(), "DMA handle is already locked"); group.dma_handle->lock(); +#endif // only the timer thread releases the locks group.dshot_waiter = rcout_thread_ctx; @@ -101,8 +108,15 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman return; } // not an FMU channel - if (chan < chan_offset) { - return; + if (chan < chan_offset || chan == ALL_CHANNELS) { +#if HAL_WITH_IO_MCU + if (AP_BoardConfig::io_dshot()) { + iomcu.send_dshot_command(command, chan, command_timeout_ms, repeat_count, priority); + } +#endif + if (chan != ALL_CHANNELS) { + return; + } } DshotCommandPacket pkt; @@ -124,14 +138,14 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman // The chanmask passed is added (ORed) into any existing mask. // The mask uses servo channel numbering void RCOutput::set_reversed_mask(uint32_t chanmask) { - _reversed_mask |= (chanmask >> chan_offset); + _reversed_mask |= chanmask; } // Set the dshot outputs that should be reversible/3D // The chanmask passed is added (ORed) into any existing mask. // The mask uses servo channel numbering void RCOutput::set_reversible_mask(uint32_t chanmask) { - _reversible_mask |= (chanmask >> chan_offset); + _reversible_mask |= chanmask; } // Update the dshot outputs that should be reversible/3D at 1Hz @@ -150,10 +164,10 @@ void RCOutput::update_channel_masks() { case DSHOT_ESC_BLHELI_EDT: case DSHOT_ESC_BLHELI_EDT_S: if (_reversible_mask & (1U<wabase) < min_stack) { // use task priority for line number. This allows us to // identify the task fairly reliably +#if AP_INTERNALERROR_ENABLED AP::internalerror().error(AP_InternalError::error_t::stack_overflow, tp->realprio); +#endif } } } diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.h b/libraries/AP_HAL_ChibiOS/Scheduler.h index 736d1088d4e12b..415d8d4fa17d2e 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.h +++ b/libraries/AP_HAL_ChibiOS/Scheduler.h @@ -26,7 +26,6 @@ #define APM_MAIN_PRIORITY 180 #define APM_TIMER_PRIORITY 181 #define APM_RCOUT_PRIORITY 181 -#define APM_RCIN_PRIORITY 177 #define APM_LED_PRIORITY 60 #define APM_UART_PRIORITY 60 #define APM_UART_UNBUFFERED_PRIORITY 181 @@ -42,6 +41,10 @@ #define APM_MAIN_PRIORITY_BOOST 182 #endif +#ifndef APM_RCIN_PRIORITY +#define APM_RCIN_PRIORITY 177 +#endif + #ifndef APM_SPI_PRIORITY // SPI priority needs to be above main priority to ensure fast sampling of IMUs can keep up // with the data rate diff --git a/libraries/AP_HAL_ChibiOS/Storage.h b/libraries/AP_HAL_ChibiOS/Storage.h index beccd623b18a58..59266d19bb086c 100644 --- a/libraries/AP_HAL_ChibiOS/Storage.h +++ b/libraries/AP_HAL_ChibiOS/Storage.h @@ -79,7 +79,7 @@ class ChibiOS::Storage : public AP_HAL::Storage { bool _flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length); bool _flash_erase_sector(uint8_t sector); bool _flash_erase_ok(void); - uint8_t _flash_page; + uint16_t _flash_page; bool _flash_failed; uint32_t _last_re_init_ms; uint32_t _last_empty_ms; diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index f3efaeade6aaca..911688f643e151 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -231,6 +231,12 @@ static int hal_console_vprintf(const char *fmt, va_list arg) void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) { + if (b == 0 && txS == 0 && rxS == 0 && _tx_initialised && _rx_initialised) { + // just changing port owner + _uart_owner_thd = chThdGetSelfX(); + return; + } + thread_rx_init(); if (sdef.serial == nullptr) { diff --git a/libraries/AP_HAL_ChibiOS/Util.cpp b/libraries/AP_HAL_ChibiOS/Util.cpp index c49d882bfe7871..7d56981c5c4c39 100644 --- a/libraries/AP_HAL_ChibiOS/Util.cpp +++ b/libraries/AP_HAL_ChibiOS/Util.cpp @@ -27,6 +27,7 @@ #include "hwdef/common/flash.h" #include #include +#include #include "sdcard.h" #include "shared_dma.h" #if defined(HAL_PWM_ALARM) || HAL_DSHOT_ALARM_ENABLED || HAL_CANMANAGER_ENABLED || HAL_USE_PWM == TRUE @@ -137,7 +138,7 @@ void *Util::heap_realloc(void *heap, void *ptr, size_t old_size, size_t new_size void *new_mem = chHeapAlloc((memory_heap_t *)heap, new_size); if (new_mem != nullptr) { const size_t old_size2 = chHeapGetSize(ptr); -#ifdef HAL_DEBUG_BUILD +#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); } @@ -705,9 +706,7 @@ bool Util::get_random_vals(uint8_t* data, size_t size) { #if HAL_USE_HW_RNG && defined(RNG) size_t true_random_vals = stm32_rand_generate_nonblocking(data, size); - if (true_random_vals == size) { - return true; - } else { + if (true_random_vals != size) { if (!(true_random_vals % 2)) { data[true_random_vals] = (uint8_t)(get_random16() & 0xFF); true_random_vals++; @@ -718,10 +717,18 @@ bool Util::get_random_vals(uint8_t* data, size_t size) true_random_vals+=sizeof(uint16_t); } } - return true; #else - return false; + size_t true_random_vals = 0; + while(true_random_vals < size) { + uint16_t val = get_random16(); + memcpy(&data[true_random_vals], &val, sizeof(uint16_t)); + true_random_vals+=sizeof(uint16_t); + } + if (size % 2) { + data[size-1] = get_random16() & 0xFF; + } #endif + return true; } /** diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_Pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_Pinout.jpg new file mode 100644 index 00000000000000..c3e32454cb0e8b Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_Pinout.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_structure.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_structure.jpg new file mode 100644 index 00000000000000..303819d5527ade Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_structure.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4pilot_inshell.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4pilot_inshell.jpg new file mode 100644 index 00000000000000..5f2c55ae4c8dc3 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4pilot_inshell.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4pilot_size.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4pilot_size.jpg new file mode 100644 index 00000000000000..5235092346ec9f Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4pilot_size.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/README.md b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/README.md new file mode 100644 index 00000000000000..818b8926e62ee5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/README.md @@ -0,0 +1,97 @@ +# CM4PILOT Integrated Flight Controller + +The CM4PILOT is a low-cost and compact flight controller which integrated a Raspberry Pi CM4 in the cockpit. + +
+
+ + +## Features + + - Raspberry Pi CM4 + Ardupilot, Companion Computers in cockpit structure + - Small Footprint and Lightweight, 58mm X 50mm X 18mm,26g(without shell) + - Broadcom BCM2711, quad-core Cortex-A72 (ARM v8) 64-bit SoC @ 1.5GHz + - STM32F405 microcontroller + - IMU: BMI088 + - Mag: LIS3MDLTR + - Baro: BMP280 + - RTC: PCF85063 + - 2 2-lane MIPI CSI camera ports + - 2 microSD card slot port + - 1 power ports(Analog) + - 6 UARTs and USB ports for FMU + - 2 UARTs and 4 USB2.0 and 1 OTG for CM4 + - 1 I2C port + - 1 CAN port + - 1 SBUS input and 8 PWM output (all support DShot) + - External SPI port + - Buzzer on board + - RBG LED on board + - 128M flash on board for logging + +## UART Mapping + + - SERIAL0 -> USB(OTG1) + - SERIAL1 -> USART1(Telem1)(DMA capable) + - SERIAL2 -> USART3 (CM4)(DMA capable) + - SERIAL3 -> UART4 (GPS)(DMA capable) + - SERIAL4 -> UART6 (GPS2)(DMA capable) + - SERIAL5 -> USART2 (SBUS)(RC input, no DMA capable) + +## RC Input + +RC input is configured on the SBUS pin (UART2_RX). It supports all RC protocols except serial protocols + +## PWM Output + +The CM4PILOT supports up to 8 PWM outputs. All outputs support DShot (No BDshot). +The PWM is in 4 groups: + + - PWM 1~4 in group1 + - PWM 5,6 in group2 + - PWM 7,8 in group3 + - Buzzer on board in group4 + +## GPIOs + +All 8 PWM channels can be used for GPIO functions. +The pin numbers for these PWM channels in ArduPilot are shown below: + +| PWM Channels | Pin | PWM Channels | Pin | +| ------------ | ---- | ------------ | ---- | +| PWM1 | 50 | PWM8 | 57 | +| PWM2 | 51 | +| PWM3 | 52 | +| PWM4 | 53 | +| PWM5 | 54 | +| PWM6 | 55 | +| PWM7 | 56 | + +## Battery Monitoring + +The correct battery setting parameters are set by default and are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 11 + - BATT_CURR_PIN 12 + - BATT_VOLT_SCALE 10.1 + - BATT_CURR_SCALE 17.0 + +## Compass + +The CM4PILOT has one built-in compass LIS3MDLTR, you can also 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 “ACNS-CM4PILOT”. + +Initial firmware load can be done with DFU by plugging in USB with the +boot button pressed. Then you should load the "xxx_bl.hex" +firmware, using your favorite DFU loading tool. + +Subsequently, you can update the firmware with Mission Planner. + +## Pinout and Size + +
+
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef-bl.dat new file mode 100644 index 00000000000000..a0cc0566706aa2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef-bl.dat @@ -0,0 +1,42 @@ +# hw definition file for processing by chibios_pins.py +# for CM4pilot bootloader + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_ACNS_CM4PILOT + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +FLASH_SIZE_KB 1024 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 64 + +# order of UARTs +SERIAL_ORDER OTG1 USART1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +#PC13 VBUS INPUT OPENDRAIN + +PC14 LED_BOOTLOADER OUTPUT LOW GPIO(0) +PA13 LED_ACTIVITY OUTPUT LOW GPIO(1) # optional +define HAL_LED_ON 1 + +# Add CS pins to ensure they are high in bootloader +PA4 BMI088_A_CS CS +PC3 BMI088_G_CS CS +PB12 MAG_CS CS +PD2 SDCARD_CS CS +PA14 FLASH_CS CS +PC15 ESPI_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef.dat new file mode 100644 index 00000000000000..f4467ca87762b8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef.dat @@ -0,0 +1,199 @@ +# hw definition file for processing by chibios_pins.py +# CM4pilot, developed by Robin Luo luojinglinemail@gmail.com + +################################################# +### MCU CONFIGURATION ### +################################################# + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID AP_HW_ACNS_CM4PILOT + +# crystal frequency +OSCILLATOR_HZ 16000000 + +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 16384 +define HAL_STORAGE_SIZE 15360 +STORAGE_FLASH_PAGE 1 + +# enable FLASH/RAMTROM parameter storage +#define HAL_WITH_DATAFLASH 1 +# enable logging to dataflash +#define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# order of UARTs +SERIAL_ORDER OTG1 USART1 USART3 UART4 USART6 USART2 + +################################################# +### PIN DEFINITIONS ### +################################################# + +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 + +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 + +PB10 USART3_TX USART3 +PB11 USART3_RX USART3 + +# default to timer for RC input +PA3 TIM9_CH2 TIM9 RCININT PULLDOWN LOW + +# alternative using USART2 +PA2 USART2_TX USART2 NODMA +PA3 USART2_RX USART2 NODMA ALT(1) + + +# IMU SPI +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 BMI088_A_CS CS +PC3 BMI088_G_CS CS +PC4 BMI088_A_DRDY INPUT +PB2 BMI088_G_DRDY INPUT + +# SD CARD SPI +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PC12 SPI3_MOSI SPI3 +PD2 SDCARD_CS CS +PA14 FLASH_CS CS + +# MAG SPI +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 +PB12 MAG_CS CS +PC5 MAG_DRDY INPUT +PC15 ESPI_CS CS + +# I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +#define HAL_USE_I2C TRUE +#define STM32_I2C_USE_I2C1 TRUE +# I2C Buses +I2C_ORDER I2C1 +#define HAL_I2C_CLEAR_ON_TIMEOUT 0 + +# CAN +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +# CAN Buses +#CAN_ORDER 1 + +# reduce memory usage +define UAVCAN_NODE_POOL_SIZE 1024 + +PC0 RSSI_ADC_PIN ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1) + +PC14 LED_BLUE OUTPUT LOW GPIO(0) +PA13 LED_GREEN OUTPUT LOW GPIO(1) +#PC15 LED_RED OUTPUT LOW GPIO(2) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +#define HAL_GPIO_C_LED_PIN 2 + + +#pwm output +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) +PB5 TIM3_CH2 TIM3 PWM(2) GPIO(51) +PB4 TIM3_CH1 TIM3 PWM(3) GPIO(52) +PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) +PB3 TIM2_CH2 TIM2 PWM(5) GPIO(54) +PA15 TIM2_CH1 TIM2 PWM(6) GPIO(55) +PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56) +PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57) +#PWM output for buzzer +PA8 TIM1_CH1 TIM1 GPIO(77) LOW ALARM +#PA2 TIM2_CH3 TIM2 PWM(10) GPIO(59) + +PC13 VBUS INPUT OPENDRAIN + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +################################################# +### DEVICES ### +################################################# + +# BMI088 on SPI1 +SPIDEV bmi088_g SPI1 DEVID1 BMI088_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_a SPI1 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ + +# MAG on SPI2 +SPIDEV lis3mdl SPI2 DEVID3 MAG_CS MODE3 500*KHZ 500*KHZ + +# SD Card on SPI3 +SPIDEV sdcard SPI3 DEVID4 SDCARD_CS MODE3 400*KHZ 25*MHZ + +# Flash Card on SPI3 +SPIDEV dataflash SPI3 DEVID5 FLASH_CS MODE3 500*KHZ 25*MHZ + +# one IMU +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180_YAW_90 +#ROTATION_ROLL_180_YAW_270 + +# one baro, multiple possible choices for different board variants +BARO BMP280 I2C:0:0x76 + +# one mag +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 +define HAL_BATT_VOLT_PIN 12 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_VOLT_SCALE 10.1 +define HAL_BATT_CURR_SCALE 17.0 + +#analog rssi pin (also could be used as analog airspeed input) +# PC0 - ADC1_CH10 +define BOARD_RSSI_ANA_PIN 10 + +# 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 OSD_ENABLED 0 + +define STM32_PWM_USE_ADVANCED TRUE + + + +# --------------------- save flash ---------------------- +include ../include/minimize_features.inc +include ../include/minimal.inc + + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/F405AIO_bottom.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/F405AIO_bottom.jpg new file mode 100644 index 00000000000000..9477d07375c49c Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/F405AIO_bottom.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/F405AIO_top.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/F405AIO_top.jpg new file mode 100644 index 00000000000000..ee3e0e96d99e5f Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/F405AIO_top.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/README.md b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/README.md new file mode 100644 index 00000000000000..431bd94eedc994 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/README.md @@ -0,0 +1,85 @@ +# ACNS-F405AIO Integrated Flight Controller + +The ACNS-F405AIO is a low-cost compact flight controller for multi-rotor UAVs which integrated 4 BLheli_s ESCs on board. + +## Features + + - STM32F405RET microcontroller + - IMU: BMI160, ICM42688 + - Mag: LIS3MDLTR + - Baro: BMP280 + - 1 microSD card slot port + - 6 UARTs and USB ports + - 1 I2C port + - 1 CAN port + - 1 SBUS input and 8 PWM output (4 Internal ESCs,4 External PWM ports ) + - 1 External SPI port + - 1 RGB LED on board + - 128M flash on board + - 4 BLheli_s ESCs, 3-4s, 30A, The motor order matches the Arducotper X frame type config + - Small footprint and lightweight, 39mm X 39mm X 10mm, 9g(without shell) + +## UART Mapping + + - SERIAL0 -> USB (OTG1) + - SERIAL1 -> USART1(Telem1) (DMA) + - SERIAL2 -> USART3(Telem2) (DMA) + - SERIAL3 -> UART4(GPS) (DMA) + - SERIAL4 -> UART6(GPS2) (DMA) + - SERIAL5 -> USART2(SBUS) (RC input, NO DMA) + +## RC Input + +RC input is configured on the SBUS pin (UART2_RX). It supports all RC protocols except serial protocols + +## PWM Output + +The ACNS-F405AIO supports up to 8 PWM outputs. All outputs support DShot (No BDshot). +The PWM is in 3 groups: + + - PWM 1~4 in group1 (4 Motors) + - PWM 5,6 in group2 (External PWM) + - PWM 7,8 in group3 (External PWM) + +## GPIOs + +4 External PWM channels can be used for GPIO functions. +The pin numbers for these PWM channels in ArduPilot are shown below: + +| PWM Channels | Pin | +| ------------ | ---- | +| PWM5 | 54 | +| PWM6 | 55 | +| PWM7 | 56 | +| PWM8 | 57 | + +## Battery Monitoring + +The correct battery setting parameters are set by default and are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 11 + - BATT_CURR_PIN 12 + - BATT_VOLT_SCALE 9.2 + - BATT_CURR_SCALE 50.0 + +## Compass + +The ACNS-F405AIO has one built-in compass LIS3MDLTR, you can also 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 “ACNS-F405AIO”. + +Initial firmware load can be done with DFU by plugging in USB with the +boot button pressed. Then you should load the "xxx_bl.hex" +firmware, using your favorite DFU loading tool. + +Subsequently, you can update the firmware with Mission Planner. + +## Pinout
+ + + + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/hwdef-bl.dat new file mode 100644 index 00000000000000..c6c1b1529e1a37 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/hwdef-bl.dat @@ -0,0 +1,42 @@ +# hw definition file for processing by chibios_pins.py +# for F405AIO bootloader + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1116 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +FLASH_SIZE_KB 1024 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 64 + +# order of UARTs +SERIAL_ORDER OTG1 USART1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +#PC13 VBUS INPUT OPENDRAIN + +PC14 LED_BOOTLOADER OUTPUT LOW GPIO(0) +PA13 LED_ACTIVITY OUTPUT LOW GPIO(1) # optional +define HAL_LED_ON 1 + +# Add CS pins to ensure they are high in bootloader +PA4 GYRO1_CS CS +PC3 GYRO2_CS CS +PB12 MAG_CS CS +PD2 SDCARD_CS CS +PA14 FLASH_CS CS +PA8 ESPI_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/hwdef.dat new file mode 100644 index 00000000000000..3dc24cb1e55a1f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-F405AIO/hwdef.dat @@ -0,0 +1,202 @@ +# hw definition file for processing by chibios_pins.py +# F405AIO, developed by Robin Luo + +################################################# +### MCU CONFIGURATION ### +################################################# + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1116 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +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 16384 +define HAL_STORAGE_SIZE 15360 +STORAGE_FLASH_PAGE 1 + +# enable FLASH/RAMTROM parameter storage +#define HAL_WITH_DATAFLASH 1 +# enable logging to dataflash +#define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# order of UARTs +# | sr0| sr1 | sr2 | GPS | +SERIAL_ORDER OTG1 USART1 USART3 UART4 USART6 USART2 + +################################################# +### PIN DEFINITIONS ### +################################################# + +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 + +PA9 USART1_TX USART1 +PA10 USART1_RX USART1 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 + +PB10 USART3_TX USART3 +PB11 USART3_RX USART3 + +# default to timer for RC input +PA3 TIM9_CH2 TIM9 RCININT PULLDOWN LOW + +# alternative using USART2 +PA2 USART2_TX USART2 NODMA +PA3 USART2_RX USART2 NODMA ALT(1) + + +# IMU SPI +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 GYRO1_CS CS +PC3 GYRO2_CS CS +PC4 GYRO1_DRDY INPUT +PB2 GYRO2_DRDY INPUT + +# SD CARD SPI +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PC12 SPI3_MOSI SPI3 +PD2 SDCARD_CS CS +PA14 FLASH_CS CS + +# MAG SPI +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 +PB12 MAG_CS CS +PC5 MAG_DRDY INPUT +PA8 ESPI_CS CS + +# I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +#define HAL_USE_I2C TRUE +#define STM32_I2C_USE_I2C1 TRUE +# I2C Buses +I2C_ORDER I2C1 +#define HAL_I2C_CLEAR_ON_TIMEOUT 0 + +# CAN +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +# CAN Buses +#CAN_ORDER 1 + +# reduce memory usage +define UAVCAN_NODE_POOL_SIZE 1024 + +PC0 RSSI_ADC_PIN ADC1 SCALE(1) +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1) + +PC14 LED_BLUE OUTPUT LOW GPIO(0) +PA13 LED_GREEN OUTPUT LOW GPIO(1) +PC15 LED_RED OUTPUT LOW GPIO(2) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + + +#pwm output +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) +PB5 TIM3_CH2 TIM3 PWM(2) GPIO(51) +PB4 TIM3_CH1 TIM3 PWM(3) GPIO(52) +PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) +PB3 TIM2_CH2 TIM2 PWM(5) GPIO(54) +PA15 TIM2_CH1 TIM2 PWM(6) GPIO(55) +PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56) +PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57) +#PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) +#PA2 TIM2_CH3 TIM2 PWM(10) GPIO(59) + +PC13 VBUS INPUT OPENDRAIN + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + +################################################# +### DEVICES ### +################################################# + +# BMI160 on SPI1 +SPIDEV bmi160 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 4*MHZ +# ICM42688 on SPI1 +SPIDEV icm42688 SPI1 DEVID2 GYRO2_CS MODE3 1*MHZ 4*MHZ +# QMI8658 on SPI1 +#SPIDEV LSM6DSL SPI1 DEVID2 GYRO2_CS MODE3 1*MHZ 4*MHZ + +# MAG on SPI2 +SPIDEV lis3mdl SPI2 DEVID3 MAG_CS MODE3 500*KHZ 500*KHZ +#SPIDEV lis3mdl SPI2 DEVID6 MAG_CS MODE3 500*KHZ 500*KHZ + +# SD Card on SPI3 +SPIDEV sdcard SPI3 DEVID4 SDCARD_CS MODE3 400*KHZ 25*MHZ + +# Flash Card on SPI3 +SPIDEV dataflash SPI3 DEVID5 FLASH_CS MODE3 500*KHZ 25*MHZ + +# two IMU +IMU BMI160 SPI:bmi160 ROTATION_ROLL_180_YAW_270 +IMU Invensensev3 SPI:icm42688 ROTATION_NONE +#IMU LSM6DSL SPI:lsm6dsl ROTATION_ROLL_180 + +# one baro, multiple possible choices for different board variants +BARO BMP280 I2C:0:0x76 + +# one mag +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 +define HAL_BATT_VOLT_PIN 12 +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_VOLT_SCALE 9.2 +define HAL_BATT_CURR_SCALE 50.0 + +#analog rssi pin (also could be used as analog airspeed input) +# PC0 - ADC1_CH10 +define BOARD_RSSI_ANA_PIN 10 + +# 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 OSD_ENABLED 0 + +define STM32_PWM_USE_ADVANCED TRUE + + + +# --------------------- save flash ---------------------- +include ../include/minimize_features.inc +include ../include/minimal.inc + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef-bl.dat new file mode 100644 index 00000000000000..7525052dedf884 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef-bl.dat @@ -0,0 +1,41 @@ +# hw definition file ARACE SmartBat CAN node + +# MCU class and specific type +MCU CKS32F4xx CKS32F407xx + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# board ID for firmware load +APJ_BOARD_ID 1134 + +# CKS32F407 does not work in bootloader with normal optimisation +env OPTIMIZE -Og + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 64 +FLASH_SIZE_KB 1024 + +# --------------------------------------------- +PC12 LED_BOOTLOADER OUTPUT LOW # green +define HAL_LED_ON 0 + +# enable CAN support +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW HIGH + +CAN_ORDER 1 + +define HAL_USE_SERIAL FALSE + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 32 +define HAL_USE_EMPTY_IO TRUE + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef.dat new file mode 100644 index 00000000000000..c454eadbb4447e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef.dat @@ -0,0 +1,63 @@ +# hw definition file for ARACE SmartBat + +# MCU class and specific type +MCU CKS32F4xx CKS32F407xx + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# board ID for firmware load +APJ_BOARD_ID 1134 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +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 + +# activity LED +PC12 LED OUTPUT LOW # green +define HAL_LED_ON 0 + +# enable CAN support +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW HIGH + +CAN_ORDER 1 + +define HAL_DISABLE_LOOP_DELAY + +define HAL_NO_MONITOR_THREAD +define HAL_NO_LOGGING + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +SERIAL_ORDER USART1 + +# USART1 for debug +PA9 USART1_TX USART1 SPEED_HIGH +PA10 USART1_RX USART1 SPEED_HIGH + +# ADC inputs, scale 10 is used so voltages +# stay in 3.3v max range with 6S +PC0 CELL1 ADC1 SCALE(10) ANALOG(1) +PC1 CELL2 ADC1 SCALE(10) ANALOG(2) +PC2 CELL3 ADC1 SCALE(10) ANALOG(3) +PC3 CELL4 ADC1 SCALE(10) ANALOG(4) +PA0 CELL5 ADC1 SCALE(10) ANALOG(5) +PA1 CELL6 ADC1 SCALE(10) ANALOG(6) + +# setup as a battery balance plug monitor +define HAL_PERIPH_ENABLE_BATTERY_BALANCE +define AP_PERIPH_BATTERY_BALANCE_NUMCELLS_DEFAULT 6 +define AP_PERIPH_BATTERY_BALANCE_RATE_DEFAULT 2 +define AP_PERIPH_BATTERY_BALANCE_CELL1_PIN_DEFAULT 1 +define AP_PERIPH_BATTERY_BALANCE_ID_DEFAULT 0 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat index 02774a106336b1..b9f1429dd39fab 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat @@ -30,9 +30,6 @@ env OPTIMIZE -O2 # order of UARTs (and USB) SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2 -# default the 2nd interface to MAVLink2 -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 - # default to all pins low to avoid ESD issues DEFAULTGPIO OUTPUT LOW PULLDOWN @@ -82,22 +79,27 @@ PD9 USART3_RX USART3 # USART6 is for IOMCU PC6 USART6_TX USART6 PC7 USART6_RX USART6 -IOMCU_UART USART6 - -# uart6, RX only, RC input, if no IOMCU -# PC7 USART6_RX USART6 - -# ethernet (not implemented yet) -#PA1 ETH_REF_CLK -#PA2 ETH_MDIO -#PA7 ETH_CRS_DV -#PB11 ETH_TX_EN -#PC1 ETH_MDC -#PC4 ETH_RXD0 -#PC5 ETH_RXD1 -#PG12 ETH_TXD1 -#PG13 ETH_TXD0 -#PG15 ETH_POWER_EN + +# Uncomment this line for carriers boards with an IO MCU +# IOMCU_UART USART6 + +# Ethernet +PB11 ETH_RMII_TX_EN ETH1 +PG13 ETH_RMII_TXD0 ETH1 +PG12 ETH_RMII_TXD1 ETH1 +PC4 ETH_RMII_RXD0 ETH1 +PC5 ETH_RMII_RXD1 ETH1 +PA7 ETH_RMII_CRS_DV ETH1 +PA1 ETH_RMII_REF_CLK ETH1 +PC1 ETH_MDC ETH1 +PA2 ETH_MDIO ETH1 + +PG15 GPIO_ETH_ENABLE OUTPUT HIGH GPIO(113) +define HAL_GPIO_ETH_ENABLE 113 + +define BOARD_PHY_ID MII_LAN8742A_ID +define BOARD_PHY_RMII +define HAL_PERIPH_ENABLE_NETWORKING # ADC PA0 SCALED1_V3V3 ADC1 SCALE(2) @@ -141,10 +143,14 @@ 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 +#PB3 SPI6_SCK SPI6 +#PA6 SPI6_MISO SPI6 +#PG14 SPI6_MOSI SPI6 +#PI10 EXT1_CS CS +#PD11 DRDY_ADIS16507 INPUT GPIO(93) + +# use GPIO(93) for data ready on ADIS16507 +#define ADIS_DRDY_PIN 93 # PWM output pins PI0 TIM5_CH4 TIM5 PWM(1) GPIO(50) @@ -214,7 +220,6 @@ PI11 VDD_3V3_SENSORS1_EN OUTPUT HIGH PF4 VDD_3V3_SENSORS2_EN OUTPUT HIGH PE7 VDD_3V3_SENSORS3_EN OUTPUT HIGH PG8 VDD_3V3_SENSORS4_EN OUTPUT HIGH -PG15 ETH_PWR_EN OUTPUT LOW # disable power on ethernet # start peripheral power off, then enable after init # this prevents a problem with radios that use RTS for @@ -287,6 +292,7 @@ COMPASS BMM150 I2C:0:0x10 false ROTATION_NONE SPIDEV iim42652 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ SPIDEV icm42688 SPI2 DEVID1 IMU2_CS MODE3 2*MHZ 8*MHZ SPIDEV icm42688_ext SPI3 DEVID1 IMU3_CS MODE3 2*MHZ 8*MHZ +#SPIDEV adis16507 SPI6 DEVID1 EXT1_CS MODE3 1*MHZ 2*MHZ SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ @@ -294,6 +300,7 @@ SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ IMU Invensensev3 SPI:iim42652 ROTATION_ROLL_180_YAW_135 IMU Invensensev3 SPI:icm42688 ROTATION_YAW_45 IMU Invensensev3 SPI:icm42688_ext ROTATION_ROLL_180_YAW_270 +#IMU ADIS1647x SPI:adis16507 ROTATION_NONE ADIS_DRDY_PIN define HAL_DEFAULT_INS_FAST_SAMPLE 7 @@ -320,3 +327,6 @@ ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin # note that if firmware is build with --secure-bl then DFU is # disabled ENABLE_DFU_BOOT 1 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/ARK_CANNODE.JPG b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/ARK_CANNODE.JPG new file mode 100644 index 00000000000000..caf14d3eafd00c Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/ARK_CANNODE.JPG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/ARK_CANNODE2.JPG b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/ARK_CANNODE2.JPG new file mode 100644 index 00000000000000..6499c4898986e6 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/ARK_CANNODE2.JPG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef-bl.dat new file mode 100644 index 00000000000000..e46f2696da8804 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef-bl.dat @@ -0,0 +1,72 @@ +# hw definition file for processing by chibios_pins.py +# hardware repository: https://github.com/ARK-Electronics/ARK_CANNODE + +# MCU class and specific type +# note: the device is STM32F412CE, not all F412 pins are available +MCU STM32F4xx STM32F412Rx + +# board ID for firmware load +APJ_BOARD_ID 83 + +env AP_PERIPH 1 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +FLASH_RESERVE_START_KB 0 +# two sectors for bootloader, two for storage +FLASH_BOOTLOADER_LOAD_KB 64 + +# 1Mb flash +FLASH_SIZE_KB 1024 + +# order of UARTs +SERIAL_ORDER USART1 USART2 + +# USART1 GPS +PA15 USART1_TX USART1 +PB3 USART1_RX USART1 + +# USART2 in debug connector +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 + +# LEDs +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 HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +# use pixracer style 3-LED indicators +define HAL_HAVE_PIXRACER_LED + +# CAN bus +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PC14 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PC15 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW + +# pins for SWD debugging with a STlink or black-magic probe. +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CS and DRDY +PA4 IMU1_CS CS +PB12 EXT_CS CS +PB2 MPU_DRDY INPUT + +# store parameters in pages 2 and 3 +STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 8192 + +define CAN_APP_NODE_NAME "org.ardupilot.ARK_CANNODE" + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat new file mode 100644 index 00000000000000..a4cf80cd7c99d8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat @@ -0,0 +1,128 @@ +# hw definition file for processing by chibios_pins.py +# hardware repository: https://github.com/ARK-Electronics/ARK_CANNODE + +# MCU class and specific type +# note: the device is STM32F412CG, not all F412 pins are available +MCU STM32F4xx STM32F412Rx + +# board ID for firmware load +APJ_BOARD_ID 83 + +env AP_PERIPH 1 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +# bootloader starts firmware at 64k +FLASH_RESERVE_START_KB 64 + +# 1Mb flash +FLASH_SIZE_KB 1024 + +# order of I2C buses +I2C_ORDER I2C1 + +define HAL_I2C_INTERNAL_MASK 0 + +# order of UARTs +SERIAL_ORDER USART1 USART2 + +# pin definitions +# 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. +PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR +PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51) +PB10 TIM2_CH3 TIM2 PWM(3) GPIO(52) +PB4 TIM3_CH1 TIM3 PWM(4) GPIO(53) BIDIR +PB5 TIM3_CH2 TIM3 PWM(5) GPIO(54) +PB0 TIM3_CH3 TIM3 PWM(6) GPIO(55) +PB1 TIM3_CH4 TIM3 PWM(7) GPIO(56) BIDIR +PB7 TIM4_CH2 TIM4 PWM(8) GPIO(58) NODMA # DMA would be shared with I2C + +# USART1 GPS +PA15 USART1_TX USART1 +PB3 USART1_RX USART1 + +# USART2 in debug connector +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 + +# SPI bus for IMU +PB2 MPU_DRDY INPUT +PA4 IMU1_CS CS +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# LEDs +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 HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +# use pixracer style 3-LED indicators +define HAL_HAVE_PIXRACER_LED + +# CAN bus +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PC14 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PC15 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW + +# pins for SWD debugging with a STlink or black-magic probe. +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 FSYNC for ICM42688p +# PB8 TIM10_CH1 TIM10 + +# store parameters in pages 2 and 3 +STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 8192 + +# no ADC pins +define HAL_USE_ADC FALSE + +# External SPI2 +PB12 EXT_CS1 SPI2 +PC13 EXT_CS2 SPI2 +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +# I2C port +PB6 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# SPI device table - can't yet use IMU in AP_Periph +#SPIDEV icm42688 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ +#IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180 + +define HAL_USE_SPI TRUE + +define GPS_MAX_RECEIVERS 1 +define GPS_MAX_INSTANCES 1 +define HAL_COMPASS_MAX_SENSORS 1 +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_BARO +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY + +define CAN_APP_NODE_NAME "org.ardupilot.ARK_CANNODE" + +# enable ESC control +define HAL_SUPPORT_RCOUT_SERIAL 1 +define HAL_WITH_ESC_TELEM 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef-bl.dat index d69fd0e166ff34..156dcb3da435d7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef-bl.dat @@ -63,11 +63,6 @@ PA12 CAN1_TX CAN1 PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW -define HAL_USE_CAN TRUE -define STM32_CAN_USE_CAN1 TRUE - -define CAN_APP_NODE_NAME "org.ardupilot.ARK_GPS" - # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat index 764df2bcacd322..091463e4a05bdc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_GPS/hwdef.dat @@ -123,7 +123,6 @@ define HAL_PERIPH_ENABLE_NOTIFY # GPS on 2nd port define HAL_PERIPH_GPS_PORT_DEFAULT 1 -define CAN_APP_NODE_NAME "org.ardupilot.ARK_GPS" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef-bl.dat index 34e43e84795208..60b60d4c43b63a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef-bl.dat @@ -63,11 +63,6 @@ PA12 CAN1_TX CAN1 PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW -define HAL_USE_CAN TRUE -define STM32_CAN_USE_CAN1 TRUE - -define CAN_APP_NODE_NAME "org.ardupilot.ARK_RTK_GPS" - # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 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 a5677ff249d367..138ab20ea1f03e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat @@ -135,4 +135,3 @@ define HAL_PERIPH_ENABLE_RC_OUT # GPS on 2nd port define HAL_PERIPH_GPS_PORT_DEFAULT 1 -define CAN_APP_NODE_NAME "org.ardupilot.ARK_RTK_GPS" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed-DLVR/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed-DLVR/hwdef-bl.dat index 642299c17d69b0..3eba2b385c0b33 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed-DLVR/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed-DLVR/hwdef-bl.dat @@ -1,7 +1,5 @@ include ../f103-periph/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_DLVR_Airspeed" - # board ID for firmware load APJ_BOARD_ID 1104 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed-DLVR/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed-DLVR/hwdef.dat index 4665dd2f53a815..e5de5c06aa35aa 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed-DLVR/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed-DLVR/hwdef.dat @@ -3,8 +3,6 @@ include ../f103-periph/hwdef.inc # board ID for firmware load APJ_BOARD_ID 1104 -define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_DLVR_Airspeed" - define HAL_COMPASS_MAX_SENSORS 1 define HAL_AIRSPEED_BUS_DEFAULT 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef-bl.dat index eb5785215e95d1..f9287716155c48 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef-bl.dat @@ -1,7 +1,5 @@ include ../f103-periph/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_Airspeed" - # board ID for firmware load APJ_BOARD_ID 1077 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef.dat index 964323ba786d17..fafea28b338112 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-Airspeed/hwdef.dat @@ -3,8 +3,6 @@ include ../f103-periph/hwdef.inc # board ID for firmware load APJ_BOARD_ID 1077 -define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_Airspeed" - define HAL_COMPASS_MAX_SENSORS 1 define HAL_AIRSPEED_BUS_DEFAULT 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef-bl.dat index 983481f5a38b78..b2acb25ac2ed80 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef-bl.dat @@ -3,8 +3,6 @@ MCU STM32L431 STM32L431xx APJ_BOARD_ID 1109 -define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_GNSS_F9P" - OSCILLATOR_HZ 8000000 env AP_PERIPH 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 f56700a712a717..0c1f53c17c6e92 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef.dat @@ -1,8 +1,6 @@ # MCU class and specific type MCU STM32L431 STM32L431xx -define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_GNSS_F9P" - # bootloader starts firmware at 36k + 4k (STORAGE_FLASH) FLASH_RESERVE_START_KB 40 FLASH_SIZE_KB 256 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef-bl.dat index 8df1455cbd1a04..115b32e47592f6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef-bl.dat @@ -1,3 +1,2 @@ include ../AeroFox-PMU/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_PMU" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.inc index 4e017ba07679c2..afa41b7665d5d3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef.inc @@ -1,8 +1,6 @@ # MCU class and specific type MCU STM32L431 STM32L431xx -define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_PMU" - # bootloader starts firmware at 36k + 4k (STORAGE_FLASH) FLASH_RESERVE_START_KB 40 FLASH_SIZE_KB 256 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/README.md b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/README.md new file mode 100644 index 00000000000000..b49d96dd8fb242 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/README.md @@ -0,0 +1,89 @@ +# BETAFPV F405 AIO Flight Controller + +The BETAFPV F405 AIO is a flight controller produced by [BETAFPV](https://betafpv.com/collections/brushless-flight-controller/products/f4-1s-12a-aio-brushless-flight-controller-v3-0). + +## Features + + - MCU: STM32F405RGT6, 168MHz + - Gyro: ICM42688-P + - 16Mb Onboard Flash + - BEC output: 5V, 2A@4V + - Barometer: BMP280 + - OSD: AT7456E + - 5 UARTS: (UART1, UART3, UART4, UART5, UART6) + - 5 PWM outputs (4 motor outputs used internally for integrated 4-in-1 ESC and 1 integrated LED) + - Integrated 4-in-1 BlueJay ESC + +## Pinout + +![BETAFPV F405 AIO Board](betafpv_f405_pinout.jpg "BETAFPV F405 AIO") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. +|Name|Pin|Function| +|:-|:-|:-| +|SERIAL0|COMPUTER|USB| +|SERIAL1|RX1/TX1|UART1 (GPS, DMA-enabled)| +|SERIAL3|TX3/RX3|UART3 (ELRS, internal) +|SERIAL4|TX4/RX4|UART4 (DJI)| +|SERIAL5|RX5|UART5 (RX-only)| +|SERIAL6|RX6|UART6 (SBUS, RX-only, inverted, DMA-enabled)| + +## RC Input + +RC input is configured on the on-board ELRS on UART3 or through (UART6_RX/UART6_TX) pins. It supports all serial RC protocols. + +## OSD Support + +The BETAFPV F405 AIO supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The BETAFPV F405 AIO has 4 PWM outputs internally connected to its 4-in-1 ESC. The pads for motor output are M1 to M4 on the board. All 4 outputs support bi-directional DShot and DShot, as well as all PWM types. The default configuration is for bi-directional DShot using the already installed BlueJay firmware. + +The PWM are in in two groups: + + - PWM 1-2 in group1 + - PWM 3-4 in group2 + - PWM 5 in group3 + - PWM 6 in group4 + - PWM 7 in group5 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. + +## Battery Monitoring + +The board has a builtin voltage 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 10.9 + - 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 BETAFPV F405 AIO does not have a builtin compass. + +## NeoPixel LED + +The board includes a NeoPixel LED on the underside which is pre-configured to output ArduPilot sequences. This is the seventh 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/BETAFPV-F405/betafpv_f405_pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/betafpv_f405_pinout.jpg new file mode 100644 index 00000000000000..8cf3c2e8d02d8a Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/betafpv_f405_pinout.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/defaults.parm new file mode 100644 index 00000000000000..adfa560b76d054 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/defaults.parm @@ -0,0 +1,8 @@ +# setup for LEDs on chan5 +SERVO5_FUNCTION 120 +NTF_LED_TYPES 257 +# Bluejay installed by default +SERVO_BLH_AUTO 1 +SERVO_BLH_BDMASK 15 +SERVO_DSHOT_ESC 2 +MOT_PWM_TYPE 6 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef-bl.dat new file mode 100644 index 00000000000000..bfadaebd7bac1d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef-bl.dat @@ -0,0 +1,44 @@ + +# hw definition file for processing by chibios_hwdef.py +# for BETAFPVF405 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1125 + +# 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 +PB3 BARO1_CS CS +PB12 FLASH1_CS CS +PA15 OSD1_CS CS +PA4 GYRO1_CS CS + +PB5 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat new file mode 100644 index 00000000000000..42e25402bed324 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat @@ -0,0 +1,141 @@ +# hw definition file for processing by chibios_hwdef.py +# for BETAFPVF405 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1125 + +# 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 + +STM32_ST_USE_TIMER 5 + +# 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 +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PC12 SPI3_MOSI SPI3 + +# Chip select pins +PB3 BARO1_CS CS +PB12 FLASH1_CS CS +PA15 OSD1_CS CS +PA4 GYRO1_CS CS + +# Beeper +PB4 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 EMPTY USART3 UART4 EMPTY USART6 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 (GPS) +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_GPS + +# USART3 (ELRS) +PB10 USART3_TX USART3 +PB11 USART3_RX USART3 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_RCIN + +# UART4 (DJI) +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_DJI_FPV + +# USART6 (SBUS, inverted) +PC7 USART6_RX USART6 + +# I2C ports +I2C_ORDER +# Servos + +# ADC ports + +# ADC1 +PC0 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 10 +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_CURR_SCALE 70.8 +PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 12 +define HAL_BATT_VOLT_SCALE 11.0 +define HAL_BATT_MONITOR_DEFAULT 4 + +# MOTORS +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) # M1 +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) BIDIR # M2 +PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52) BIDIR # M3 +PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) # M4 + +# LEDs +PB5 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 +# LED strip +PB6 TIM4_CH1 TIM4 PWM(5) GPIO(56) # M7 +define HAL_GPIO_LED_OFF 1 + +# Dataflash setup +SPIDEV dataflash SPI2 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ + +define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# OSD setup +SPIDEV osd SPI3 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 + +# BARO setup +SPIDEV baro SPI3 DEVID2 BARO1_CS MODE3 1*MHZ 8*MHZ +BARO BMP280 SPI:baro +define HAL_BARO_ALLOW_INIT_NO_BARO 1 +define AP_BARO_BACKEND_DEFAULT_ENABLED 0 +define AP_BARO_BMP280_ENABLED 1 + +# IMU setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ +IMU Invensensev3 SPI:imu1 ROTATION_YAW_180 +DMA_NOSHARE SPI1* +DMA_PRIORITY TIM3* TIM2* 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 + +# This is a whoop AIO board, not really suitable for anything other than copter +AUTOBUILD_TARGETS Copter diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef-bl.dat index a4aa9c23ce724c..afe6830664e287 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef-bl.dat @@ -66,11 +66,6 @@ define HAL_DISABLE_LOOP_DELAY PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PB2 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.birdcandy" - # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat index 6fca9fdc6f57c1..9d1acaebd73ebc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BirdCANdy/hwdef.dat @@ -96,11 +96,6 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW - - - -define CAN_APP_NODE_NAME "org.ardupilot.birdcandy" - define HAL_GCS_ENABLED 0 define HAL_NO_LOGGING define HAL_NO_MONITOR_THREAD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef-bl.dat index a8d8edfac384bd..c1de57c0e18182 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef-bl.dat @@ -66,11 +66,6 @@ define HAL_DISABLE_LOOP_DELAY # enable CAN support PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 -define HAL_USE_CAN TRUE -define STM32_CAN_USE_CAN1 TRUE - -define CAN_APP_NODE_NAME "org.ardupilot.C-RTK2-HP" - # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 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 52a9c8de093764..dfafb629c4f881 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/C-RTK2-HP/hwdef.dat @@ -92,8 +92,6 @@ PA4 RTK_RESET_N OUTPUT HIGH # PPS PA7 PPS INPUT PULLUP -define CAN_APP_NODE_NAME "org.ardupilot.C-RTK2-HP" - define HAL_NO_MONITOR_THREAD define HAL_DEVICE_THREAD_STACK 768 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/defaults.parm index 2bda2f0d4b3254..55debfdcc49c20 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora-bdshot/defaults.parm @@ -1,19 +1 @@ -# setup the temperature compensation -BRD_HEAT_TARG 45 -BRD_HEAT_P 50 -BRD_HEAT_I 0.07 - -# turn on the CAN power monitoring(default) -CAN_P1_DRIVER 1 -BATT_MONITOR 8 - -# setup the parameter for the ADC power module -BATT_VOLT_PIN 16 -BATT_CURR_PIN 17 -BATT_VOLT_MULT 18.000 -BATT_AMP_PERVLT 24.000 - -# turn on CAN RGB LED - -EK2_IMU_MASK 7 - +@include ../CUAV-Nora/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat index d262ea7cd29134..fd84470fedae89 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-Nora/hwdef.dat @@ -23,9 +23,6 @@ FLASH_RESERVE_START_KB 128 # order of UARTs (and USB) SERIAL_ORDER OTG1 USART2 USART6 USART1 UART4 UART8 UART7 USART3 OTG2 -# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 - # now we define the pins that USB is connected on PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7-bdshot/defaults.parm index d8d35f2931c641..e870f9f967bd8b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7-bdshot/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7-bdshot/defaults.parm @@ -1,18 +1 @@ -# temperature control. We need lower P/I values -# to prevent oscillation of the BMI088 temperature -# the ADIS16470 is factory temperature calibrated, -# but the BMI088 isn't, so temperature control is still -# worthwhile -BRD_HEAT_TARG 45 -BRD_HEAT_P 50 -BRD_HEAT_I 0.07 - -# turn on the CAN power monitoring(default) -CAN_P1_DRIVER 1 -BATT_MONITOR 8 - -# setup the parameter for the ADC power module -BATT_VOLT_PIN 16 -BATT_CURR_PIN 17 -BATT_VOLT_MULT 18.000 -BATT_AMP_PERVLT 24.000 +@include ../CUAV-X7/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat index e918ba579962db..fa8020580bd1c6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV-X7/hwdef.dat @@ -23,9 +23,6 @@ FLASH_RESERVE_START_KB 128 # order of UARTs (and USB) SERIAL_ORDER OTG1 USART2 USART6 USART1 UART4 UART8 UART7 OTG2 -# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 - # now we define the pins that USB is connected on PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef-bl.dat index efc354538751d8..fe01e221bdbf0f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef-bl.dat @@ -68,11 +68,6 @@ define HAL_DISABLE_LOOP_DELAY PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PB5 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.cuav_gps" - # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat index 67d70da010d917..1f70814fc62c52 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CUAV_GPS/hwdef.dat @@ -87,6 +87,7 @@ BARO BMP388 I2C:0:0x76 BARO MS56XX SPI:ms5611 BARO ICP101XX I2C:0:0x63 BARO ICP101XX I2C:0:0x64 +BARO ICP201XX I2C:0:0x64 # PWM output for buzzer PB10 TIM2_CH3 TIM2 GPIO(77) LOW ALARM @@ -126,10 +127,6 @@ PB9 CAN1_TX CAN1 PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW - - -define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps" - define HAL_NO_MONITOR_THREAD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat index c9b65a069f0ce5..ef2963d19d7751 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef-bl.dat @@ -69,6 +69,3 @@ define BOOTLOADER_BAUDRATE 57600 # use a small bootloader timeout define HAL_BOOTLOADER_TIMEOUT 1000 - - -define CAN_APP_NODE_NAME "org.ardupilot.CarbonixF405" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat index 011bf96f83caf9..2849e1e3bb9a67 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat @@ -115,8 +115,6 @@ define HAL_NO_MONITOR_THREAD define AP_PARAM_MAX_EMBEDDED_PARAM 512 -define CAN_APP_NODE_NAME "org.ardupilot.CarbonixF405" - define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_BARO define HAL_PERIPH_ENABLE_RC_OUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat index 68b3974cbb1ad6..9600da15a6bfd6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat @@ -70,5 +70,3 @@ define BOOTLOADER_BAUDRATE 57600 # use a small bootloader timeout define HAL_BOOTLOADER_TIMEOUT 1000 - -define CAN_APP_NODE_NAME "org.ardupilot.CarbonixL496" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat index 1b5ff08dc7cff8..34782ac10c937c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat @@ -118,8 +118,6 @@ define HAL_NO_MONITOR_THREAD define AP_PARAM_MAX_EMBEDDED_PARAM 512 -define CAN_APP_NODE_NAME "org.ardupilot.CarbonixL496" - define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_BARO define HAL_PERIPH_ENABLE_RC_OUT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat index 61cfed1890ab2c..effd49fee7a162 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat @@ -58,6 +58,3 @@ PD1 CAN1_TX CAN1 PB6 CAN2_TX CAN2 PB12 CAN2_RX CAN2 - - -define CAN_APP_NODE_NAME "org.ardupilot.CubeBlack-periph" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat index 4149711b4831a4..9de8b2690769b0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef.dat @@ -49,8 +49,6 @@ define HAL_BARO_ALLOW_INIT_NO_BARO define HAL_PERIPH_ENABLE_BATTERY -define CAN_APP_NODE_NAME "org.ardupilot.CubeBlack-periph" - define AP_SCRIPTING_ENABLED 0 # use blue LED @@ -60,3 +58,6 @@ MAIN_STACK 0x2000 PROCESS_STACK 0x6000 define HAL_CAN_DRIVER_DEFAULT 1 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat index 4499626b510c02..cccd5a28e00f3a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack/hwdef.dat @@ -99,3 +99,11 @@ PE3 VDD_3V3_SENSORS_EN OUTPUT LOW 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 + +# enable support for dshot on iomcu +define HAL_WITH_IO_MCU_DSHOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/hwdef.dat index 3195c728b3edaa..c02c3f21e8fd6f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-SimOnHardWare/hwdef.dat @@ -6,4 +6,7 @@ include ../include/SimOnHW.inc # short board name override (23 chars) define CHIBIOS_SHORT_BOARD_NAME "CubeOrangeSimOnHardWare" +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 + AUTOBUILD_TARGETS Copter 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 d951b4647807a6..290b72c031549f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph-heavy/hwdef.dat @@ -47,9 +47,6 @@ define HAL_NO_RCIN_THREAD define HAL_BARO_ALLOW_INIT_NO_BARO -define CAN_APP_NODE_NAME "org.ardupilot.CubeOrange-periph" - - define AP_SCRIPTING_ENABLED 0 # use blue LED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat index 0b79d42073d3b1..6d10b336b8f812 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat @@ -58,6 +58,3 @@ PD1 CAN1_TX CAN1 PB6 CAN2_TX CAN2 PB12 CAN2_RX CAN2 - - -define CAN_APP_NODE_NAME "org.ardupilot.CubeOrange-periph" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat index 6da1f6c09583b7..8aef94756f872a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat @@ -43,9 +43,6 @@ define HAL_NO_RCIN_THREAD define HAL_BARO_ALLOW_INIT_NO_BARO -define CAN_APP_NODE_NAME "org.ardupilot.CubeOrange-periph" - - define AP_SCRIPTING_ENABLED 0 # use blue LED diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/README.md b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/README.md index 7728c272c675d3..4d8df17a80146d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/README.md @@ -590,6 +590,8 @@ The numbering of the GPIOs for PIN variables in ArduPilot is: - PWM4 53 - PWM5 54 - PWM6 55 + - EXTERN_GPIO1 1 (requires custom carrier board, and alternate pin configuration 2) + - EXTERN_GPIO2 2 (requires custom carrier board, and alternate pin configuration 2) ## Analog inputs @@ -601,6 +603,8 @@ The CubeOrange has 7 analog inputs - ADC Pin4 -> Battery2 Current Sensor - ADC Pin18 -> Vdd 5V supply sense - ADC Pin8 -> ADC port input + - ADC Pin9 -> EXTERN_GPIO1 (requires custom carrier board) + - ADC Pin5 -> EXTERN_GPIO2 (requires custom carrier board) - ADC Pin103 -> RSSI voltage monitoring ## IMU Heater diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc index cca6ab7383522f..cd7ef40d20a07e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc @@ -30,6 +30,9 @@ I2C_ORDER I2C2 I2C1 # order of UARTs (and USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 +# default the 2nd interface to SLCAN +define HAL_OTG2_PROTOCOL SerialProtocol_SLCAN + # If the board has an IOMCU connected via a UART then this defines the # UART to talk to that MCU. Leave it out for boards with no IOMCU. @@ -71,10 +74,12 @@ PA14 JTCK-SWCLK SWD # PWM output for buzzer PA15 TIM2_CH1 TIM2 GPIO(77) ALARM -# This defines a couple of general purpose outputs, mapped to GPIO -# numbers 1 and 2 for users. -PB0 EXTERN_GPIO1 OUTPUT GPIO(1) -PB1 EXTERN_GPIO2 OUTPUT GPIO(2) +# Map the EXTERN_DRDY and !EXTERN_CS as analog inputs in +PB0 PB0_ADC ADC1 SCALE(1) +PB1 PB1_ADC ADC1 SCALE(1) +# also keep them available as a GPIO alt config +PB0 EXTERN_GPIO1 OUTPUT GPIO(1) ALT(2) +PB1 EXTERN_GPIO2 OUTPUT GPIO(2) ALT(2) # This defines some input pins, currently unused. PB2 BOOT1 INPUT @@ -318,6 +323,10 @@ define HAL_GPIO_PWM_VOLT_3v3 1 # ardupilot root. ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_highpolh.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* # for users who have replaced their CubeSolo with a CubeOrange: diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-SimOnHardWare/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-SimOnHardWare/defaults.parm index 05d30c8e6f1b5b..591b7847763ef2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-SimOnHardWare/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-SimOnHardWare/defaults.parm @@ -1,11 +1 @@ -# setup correct defaults for battery monitoring for cube power brick -BATT2_CURR_PIN 4 -BATT2_VOLT_PIN 13 -BATT_AMP_PERVLT 39.877 -BATT_VOLT_MULT 12.02 -BATT2_AMP_PERVLT 39.877 -BATT2_VOLT_MULT 12.02 -# setup ADSB -ADSB_TYPE 1 -SERIAL5_BAUD 57 -SERIAL5_PROTOCOL 1 +@include ../CubeOrangePlus/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-SimOnHardWare/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-SimOnHardWare/hwdef.dat index cf5b8ec4a4efc4..9f809f0f3aa75a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-SimOnHardWare/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-SimOnHardWare/hwdef.dat @@ -3,7 +3,13 @@ include ../CubeOrangePlus/hwdef.dat include ../include/SimOnHW.inc +undef INS_AUX_INSTANCES +define INS_AUX_INSTANCES 0 + # short board name override (23 chars) define CHIBIOS_SHORT_BOARD_NAME "CubeOrange+SimOnHW" +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 + AUTOBUILD_TARGETS Copter diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/README.md b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/README.md index 2144c1284dce61..021c050bb7b51d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/README.md @@ -590,6 +590,8 @@ The numbering of the GPIOs for PIN variables in ArduPilot is: - PWM4 53 - PWM5 54 - PWM6 55 + - EXTERN_GPIO1 1 (requires custom carrier board, and alternate pin configuration 2) + - EXTERN_GPIO2 2 (requires custom carrier board, and alternate pin configuration 2) ## Analog inputs @@ -601,6 +603,8 @@ The CubeOrangePlus has 7 analog inputs - ADC Pin4 -> Battery2 Current Sensor - ADC Pin18 -> Vdd 5V supply sense - ADC Pin8 -> ADC port input + - ADC Pin9 -> EXTERN_GPIO1 (requires custom carrier board) + - ADC Pin5 -> EXTERN_GPIO2 (requires custom carrier board) - ADC Pin103 -> RSSI voltage monitoring ## IMU Heater diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat index 12b6caec69e7fb..2035026661e811 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/hwdef.dat @@ -95,3 +95,6 @@ CHECK_IMU1_PRESENT $CHECK_ICM20948_EXT || $CHECK_ICM42688_EXT2 || $CHECK_IC CHECK_IMU2_PRESENT $CHECK_ICM42688_EXT || $CHECK_ICM45686_EXT BOARD_VALIDATE $CHECK_IMU0_PRESENT $CHECK_IMU1_PRESENT $CHECK_IMU2_PRESENT $CHECK_BARO0_PRESENT $CHECK_BARO1_PRESENT + +# build ABIN for flash-from-bootloader support: +env BUILD_ABIN True diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef-bl.dat index 849cb39d157054..e6f44056271bb7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef-bl.dat @@ -20,6 +20,7 @@ FLASH_RESERVE_START_KB 0 # the H757 has 128k sectors, assign 2 sectors for BL FLASH_BOOTLOADER_LOAD_KB 256 + # crystal frequency OSCILLATOR_HZ 24000000 @@ -28,14 +29,18 @@ PD0 CAN1_RX CAN1 PD1 CAN1_TX CAN1 # CAN2 -PB12 CAN2_RX CAN2 -PB13 CAN2_TX CAN2 +#PB5 CAN2_RX CAN2 +#PB6 CAN2_TX CAN2 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 # SERIAL PE7 UART7_RX UART7 PE8 UART7_TX UART7 -SERIAL_ORDER UART7 +SERIAL_ORDER OTG1 UART7 # CAN Common PG1 SLEEPCAN OUTPUT PUSHPULL SPEED_LOW LOW @@ -45,4 +50,3 @@ PG0 SHUTDOWNCAN OUTPUT PUSHPULL SPEED_LOW LOW PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -define CAN_APP_NODE_NAME "com.cubepilot.CubePilotCANMod-periph" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef.dat index 759f479cc4292c..4994a739fb77af 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef.dat @@ -4,9 +4,12 @@ # MCU class and specific type MCU STM32H7xx STM32H757xx + define CORE_CM7 define SMPS_PWR +define HAL_BUILD_AP_PERIPH + # board ID for firmware load APJ_BOARD_ID 1079 @@ -28,14 +31,18 @@ PD0 CAN1_RX CAN1 PD1 CAN1_TX CAN1 # CAN2 -PB12 CAN2_RX CAN2 -PB13 CAN2_TX CAN2 +#PB5 CAN2_RX CAN2 +#PB6 CAN2_TX CAN2 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 # SERIAL PE7 UART7_RX UART7 PE8 UART7_TX UART7 -SERIAL_ORDER UART7 +SERIAL_ORDER OTG1 UART7 # CAN Common PG1 SLEEPCAN OUTPUT PUSHPULL SPEED_LOW LOW @@ -45,9 +52,45 @@ PG0 SHUTDOWNCAN OUTPUT PUSHPULL SPEED_LOW LOW PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -define CAN_APP_NODE_NAME "com.cubepilot.CubePilotCANMod-periph" - # override following defines as needed define HAL_USE_ADC FALSE STORAGE_FLASH_PAGE 14 define HAL_STORAGE_SIZE 32768 + +# Ethernet +PC1 ETH_MDC ETH1 +PA2 ETH_MDIO ETH1 +PC4 ETH_RMII_RXD0 ETH1 +PC5 ETH_RMII_RXD1 ETH1 +PB12 ETH_RMII_TXD0 ETH1 +PB13 ETH_RMII_TXD1 ETH1 +PB11 ETH_RMII_TX_EN ETH1 +PA7 ETH_RMII_CRS_DV ETH1 +PA1 ETH_RMII_REF_CLK ETH1 + +define BOARD_PHY_ID MII_LAN8720_ID +define BOARD_PHY_RMII +define HAL_PERIPH_ENABLE_NETWORKING + +# --------------------------------------------------------------------------------------------- +# AP_Periph - boiler-plate configurations that all HW AP-Periph need +# --------------------------------------------------------------------------------------------- +define DISABLE_SERIAL_ESC_COMM TRUE +define HAL_NO_RCIN_THREAD +#define HAL_NO_GPIO_IRQ +define HAL_DISABLE_LOOP_DELAY + +################################# +# AP_Periph - configurations specific to this App +################################# + +define HAL_BARO_ALLOW_INIT_NO_BARO +define AP_RC_CHANNEL_ENABLED 1 +define AP_INERTIALSENSOR_ENABLED 0 + +define AP_NETWORKING_MAX_INSTANCES 4 + +# listen for reboot command from uploader.py script +# 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 +################################# diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePurple/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubePurple/hwdef.dat index bd853102996f74..e2d118c6c48a4f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubePurple/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubePurple/hwdef.dat @@ -35,3 +35,7 @@ COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 5 + +# enable support for dshot on iomcu +ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin +define HAL_WITH_IO_MCU_DSHOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat index 74bd399bda1ec3..625b74edc61f62 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedPrimary/hwdef.dat @@ -155,17 +155,22 @@ PF15 I2C4_SDA I2C4 I2C_ORDER I2C2 I2C4 # Ethernet -# PA1 ETH_RMII_REF_CLK ETH1 -# PA2 ETH_MDIO ETH1 -# PA7 ETH_RMII_CRS_DV ETH1 -# PB11 ETH_RMII_TX_EN ETH1 -# PB12 ETH_RMII_TXD0 ETH1 -# PB13 ETH_RMII_TXD1 ETH1 -# PC1 ETH_MDC ETH1 -# PC4 ETH_RMII_RXD0 ETH1 -# PC5 ETH_RMII_RXD1 ETH1 -# define BOARD_PHY_ID MII_LAN8720_ID -# define BOARD_PHY_RMII +PC1 ETH_MDC ETH1 +PA2 ETH_MDIO ETH1 +PC4 ETH_RMII_RXD0 ETH1 +PC5 ETH_RMII_RXD1 ETH1 +PB12 ETH_RMII_TXD0 ETH1 +PB13 ETH_RMII_TXD1 ETH1 +PB11 ETH_RMII_TX_EN ETH1 +PA7 ETH_RMII_CRS_DV ETH1 +PA1 ETH_RMII_REF_CLK ETH1 + +define BOARD_PHY_ID MII_LAN8720_ID +define BOARD_PHY_RMII + +# Refer to https://maclookup.app/vendors/cubepilot-pty-ltd +# Note, lower 3 bytes (ADDR3,4,5) will be replaced with the platform UUID +define AP_NETWORKING_DEFAULT_MAC_ADDR "A8:B0:28:00:00:00" # RCIN PB7 TIM4_CH2 TIM4 RCININT PULLDOWN diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat index a07b86a72c78dd..c3773bc7b89b80 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat @@ -475,3 +475,7 @@ STORAGE_FLASH_PAGE 1 # ardupilot root ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_highpolh.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 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat index b0947dda069902..024572edf2ee64 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Durandal/hwdef.dat @@ -26,9 +26,6 @@ FLASH_RESERVE_START_KB 128 # order of UARTs (and USB) SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2 -# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 - define HAL_STORAGE_SIZE 32768 define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_FMUV5 @@ -350,3 +347,7 @@ define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_ENABLED # note that if firmware is build with --secure-bl then DFU is # disabled ENABLE_DFU_BOOT 1 + +# enable support for dshot on iomcu +ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin +define HAL_WITH_IO_MCU_DSHOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/GOKUF405Pro_Pinout.JPG b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/GOKUF405Pro_Pinout.JPG new file mode 100644 index 00000000000000..4d4441dbcf70fe Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/GOKUF405Pro_Pinout.JPG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/README.md b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/README.md new file mode 100644 index 00000000000000..c0e0857dfa9aec --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/README.md @@ -0,0 +1,96 @@ +# GOKU F405 Pro + +https://flywoo.net/products/goku-versatile-f405-pro-fc-20x20-30-5x30-5 + +The Flywoo GOKU F405 Pro is a flight controller produced by [Flywoo](https://flywoo.net/). + +## Features + +- MCU: STM32F405 32-bit processor. 1024Kbytes Flash +- IMU: ICM42688 (SPI) +- Barometer: BMP280 +- 6 hardware UARTS (UART1,2,3,4,5,6) +- Onbord 16Mbytes for Blackbox logging +- 5V Power Out: 2.0A max +- 10V Power Out: 2.0A max +- 9 PWM outputs +- Mounting Holes: Standard 20x20 or 30.5/30.5mm square to center of holes +- Weight: 5.5g +- Input Voltage: 2-6S Lipo + +## Pinout + +![GOKU F405 Pro](GOKUF405Pro_Pinout.PNG "GOKU F405 Pro") + +## 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 (GPS)| +|SERIAL2|RX2|USART2 (ESC Telemetry)| +|SERIAL3|TX3/RX3|USART3 (DJI, DMA-enabled)| +|SERIAL4|TX4/RX4|UART4 (RX/SBUS)| +|SERIAL5|TX5/RX5|UART5| +|SERIAL6|TX6/RX6|UART6 (RX, DMA-enabled)| + +USART3 and USART6 supports RX and TX DMA. UART4 supports TX DMA. UART1, UART2 and UART5 do not support DMA. + +## RC Input + +RC input is configured on UART3, UART4 or UART6 which support serial RC protocols. SBUS *must* be used on UART4 which has hardware inversion, UART5 also has hardware inversion but no DMA so use for SBUS is not recommended. + +## OSD Support + +The GOKU F405 Pro supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The GOKU F405 Pro supports up to 9 PWM outputs. The pads for motor output ESC1 to ESC4 on the above diagram are the first 4 outputs.All 9 outputs support DShot. + +The PWM are in 5 groups: + +PWM 1-2: Group 1 +PWM 3-4: Group 2 +PWM 5,7: Group 3 +PWM 6,8: Group 4 +LED: Group 5 + +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. + +## 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 12 + - BATT_VOLT_MULT around 11 + - BATT_CURR_PIN 13 + - BATT_CURR_MULT around 59 + +These are set by default in the firmware and shouldn't need to be adjusted + +## Compass + +The GOKU F405 Pro does not have a builtin compass but it does have an external I2C connector. + +## NeoPixel LED + +The board includes a NeoPixel LED pad. + +## 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/FlywooF405Pro/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/defaults.parm new file mode 100644 index 00000000000000..af3019f6bea272 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/defaults.parm @@ -0,0 +1,4 @@ +# setup the four built-in Neopixel LEDs on chan 9 +SERVO9_FUNCTION 120 +# Use 115k for GPS +GPS_DRV_OPTIONS 4 \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef-bl.dat new file mode 100644 index 00000000000000..b02a0ace60109b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef-bl.dat @@ -0,0 +1,43 @@ + +# hw definition file for processing by chibios_hwdef.py +# for FLYWOOF405PRO hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1137 + +# 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 +PB3 FLASH1_CS CS +PB14 OSD1_CS CS +PB12 GYRO1_CS CS + +PA9 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef.dat new file mode 100644 index 00000000000000..31007d5c35b279 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405Pro/hwdef.dat @@ -0,0 +1,153 @@ + +# hw definition file for processing by chibios_hwdef.py +# for FLYWOOF405PRO hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1137 + +# 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 + +STM32_ST_USE_TIMER 4 +define CH_CFG_ST_RESOLUTION 16 + +# SPI devices + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI3 +PC10 SPI3_SCK SPI3 +PC11 SPI3_MISO SPI3 +PC12 SPI3_MOSI SPI3 + +# Chip select pins +PB3 FLASH1_CS CS +PB14 OSD1_CS CS +PB12 GYRO1_CS CS + +# Beeper +PC13 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 +define HAL_BUZZER_ON 1 +define HAL_BUZZER_OFF 0 + +# 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 (GPS) +PA10 USART1_RX USART1 NODMA +PB6 USART1_TX USART1 NODMA +DEFAULT_SERIAL1_PROTOCOL SerialProtocol_GPS + +# USART2 (ESC Telemetry) +PD6 USART2_RX USART2 NODMA +DEFAULT_SERIAL2_PROTOCOL SerialProtocol_ESCTelemetry + +# USART3 (DJI) +PB10 USART3_TX USART3 +PB11 USART3_RX USART3 +DEFAULT_SERIAL3_PROTOCOL SerialProtocol_DJI_FPV + +# UART4 (SBUS) +PA0 UART4_TX UART4 +PA1 UART4_RX UART4 NODMA ALT(1) +PA1 TIM5_CH2 TIM5 RCININT PULLDOWN LOW + +# UART5 +# No suitable timer for this pin so cannot use RCININT +# and too difficult to get a DMA channel +PD2 UART5_RX UART5 NODMA +DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None + +# USART6 (RCIN) +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN + +# I2C ports +I2C_ORDER I2C1 +# I2C1 +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +BARO DPS310 I2C:0:0x76 + +# Servos + +# ADC ports + +# ADC1 +PC0 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 10 +PC2 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 12 +define HAL_BATT_CURR_SCALE 58.8 +PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 13 +define HAL_BATT_VOLT_SCALE 11.0 +define HAL_BATT_MONITOR_DEFAULT 4 + +# MOTORS +PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) # M1 +PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) BIDIR # M2 +PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52) BIDIR # M3 +PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) # M4 +PB5 TIM3_CH2 TIM3 PWM(5) GPIO(54) # M5 +PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55) # M6 +PB4 TIM3_CH1 TIM3 PWM(7) GPIO(56) # M7 +PC8 TIM8_CH3 TIM8 PWM(8) GPIO(57) # M8 + +# LEDs +PA9 TIM1_CH2 TIM1 PWM(9) GPIO(58) # M9 + +PC14 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 +define HAL_GPIO_LED_OFF 1 + +# Dataflash setup +SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ + +define HAL_LOGGING_DATAFLASH_ENABLED 1 + +# OSD setup +SPIDEV osd SPI3 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 +IMU Invensensev3 SPI:imu1 ROTATION_NONE +#DMA_NOSHARE TIM3_UP TIM2_UP TIM8_UP SPI1* +DMA_PRIORITY TIM3* TIM2* TIM8_UP SPI1* TIM1_UP + +# 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/FlywooF745Nano/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745Nano/defaults.parm index 4ea8172db90e9a..1a30c27a597b85 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745Nano/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745Nano/defaults.parm @@ -1,12 +1 @@ -# setup the four built-in Neopixel LEDs on chan 9 -SERVO9_FUNCTION 120 -NTF_LED_LEN 4 - -# setup SERIAL3 for RCIN -SERIAL3_PROTOCOL 23 - -# disable GPS on Serial 4 -SERIAL4_PROTOCOL -1 - -# setup SERIAL6 for GPS -SERIAL6_PROTOCOL 5 +@include ../FlywooF745/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef-bl.dat index d0d8263eabe37e..d8f7c7c1ba37b8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef-bl.dat @@ -63,11 +63,6 @@ define HAL_DISABLE_LOOP_DELAY PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 -define HAL_USE_CAN TRUE -define STM32_CAN_USE_CAN1 TRUE - -define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK" - # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat index 8cd958b4dfa119..636e8351a530b8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat @@ -116,8 +116,6 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 -define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK" - define HAL_NO_MONITOR_THREAD define HAL_DEVICE_THREAD_STACK 768 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef-bl.dat index 3da9e35f655e29..ccce62d4c6146b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef-bl.dat @@ -85,7 +85,5 @@ define HAL_BOOTLOADER_TIMEOUT 1000 -define CAN_APP_NODE_NAME "org.ardupilot.G4-ESC" - # Add CS pins to ensure they are high in bootloader PB12 IMU_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat index 4042240ca89494..be950cc2f23196 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/G4-ESC/hwdef.dat @@ -149,7 +149,5 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 512 env ROMFS_UNCOMPRESSED True -define CAN_APP_NODE_NAME "org.ardupilot.G4-ESC" - # don't share any DMA channels (there are enough for everyone) DMA_NOSHARE * 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 f7b17ad64a1604..350f832c1f62c1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef-bl.dat @@ -12,7 +12,6 @@ USB_STRING_PRODUCT "%BOARD%" define CORE_CM7 define SMPS_PWR -define WATCHDOG_DISABLED # crystal frequency OSCILLATOR_HZ 25000000 @@ -71,6 +70,4 @@ QSPIDEV mt25q QUADSPI1 MODE1 120*MHZ 24 8 PB13 VBUS INPUT OPENDRAIN - -define CAN_APP_NODE_NAME "org.cubepilot.H757" define BOOTLOADER_DEBUG SD1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat index 275ec38ea78af0..5e1ad94f210b11 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL/hwdef.dat @@ -14,7 +14,6 @@ USB_STRING_PRODUCT "%BOARD%" define CORE_CM7 define SMPS_PWR -define WATCHDOG_DISABLED # crystal frequency OSCILLATOR_HZ 25000000 @@ -82,6 +81,7 @@ PG6 QUADSPI_BK1_NCS QUADSPI1 PB2 QUADSPI_CLK QUADSPI1 -define CAN_APP_NODE_NAME "org.cubepilot.H757" - EXT_FLASH_SIZE_MB 32 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef-bl.dat index 8a023dc93918ab..ff5682382d3195 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef-bl.dat @@ -12,7 +12,6 @@ USB_STRING_PRODUCT "%BOARD%" define CORE_CM7 define SMPS_PWR -define WATCHDOG_DISABLED # crystal frequency OSCILLATOR_HZ 25000000 @@ -72,5 +71,4 @@ QSPIDEV mt25q QUADSPI1 MODE1 120*MHZ 24 8 PB13 VBUS INPUT OPENDRAIN -define CAN_APP_NODE_NAME "org.cubepilot.H757" define BOOTLOADER_DEBUG SD1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat index 337fbbfa6d4a26..2b82e1555e1bdb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/H757I_EVAL_intf/hwdef.dat @@ -14,7 +14,6 @@ USB_STRING_PRODUCT "%BOARD%" define CORE_CM7 define SMPS_PWR -define WATCHDOG_DISABLED # crystal frequency OSCILLATOR_HZ 25000000 @@ -82,6 +81,7 @@ PG6 QUADSPI_BK1_NCS QUADSPI1 PB2 QUADSPI_CLK QUADSPI1 -define CAN_APP_NODE_NAME "org.cubepilot.H757" - # EXT_FLASH_SIZE_MB 32 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/README.md b/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/README.md index a133f339269b21..01df50feae8e01 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/README.md @@ -26,7 +26,8 @@ receive pin for UARTn. The Tn pin is the transmit pin for UARTn. - SERIAL0 -> USB - SERIAL1 -> UART3 (UART1 on casing, DMA-enabled) - SERIAL2 -> UART1 (UART2 on casing, DMA-enabled) - - SERIAL5 -> UART5 (GPS) + - SERIAL3 -> UART5 (GPS) + - SERIAL5 -> UART6 (VTX, TX-only) - SERIAL6 -> UART2 (RCIN RX-only or RX/TX with BRD_ALT_CONFIG=1, DMA-enabled) ## RC Input diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat index 5fd12a858e52e5..6550be1e790d56 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat @@ -91,6 +91,7 @@ PA3 TIM9_CH2 TIM9 RCININT PULLDOWN # alternative with PA3 as USART2_RX PA3 USART2_RX USART2 ALT(1) +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN # USART3 - (labelled UART1 on casing) PC10 USART3_TX USART3 @@ -104,7 +105,7 @@ PA1 UART4_RX UART4 NODMA PC12 UART5_TX UART5 PD2 UART5_RX UART5 NODMA -# USART6 - (NC) +# USART6 - (VTX) PC6 USART6_TX USART6 NODMA PC7 USART6_RX USART6 NODMA @@ -193,4 +194,4 @@ define AP_RPM_PIN_ENABLED 0 define AP_RPM_GENERATOR_ENABLED 0 define HAL_PARACHUTE_ENABLED 0 -AUTOBUILD_TARGETS Plane \ No newline at end of file +AUTOBUILD_TARGETS Plane diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405v2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405v2/defaults.parm index 8099863e70f1c2..bd97dbfc6183dd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405v2/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405v2/defaults.parm @@ -1,4 +1 @@ -ALT_HOLD_RTL,5000 -ARMING_RUDDER,2 -# GPS RX DMA conflicts with CRSF and I2C1 -GPS_DRV_OPTIONS,4 \ No newline at end of file +@include ../HEEWING-F405/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/defaults.parm new file mode 100644 index 00000000000000..ae225105abba18 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/defaults.parm @@ -0,0 +1,9 @@ +# setup for ProfiLED +OUT1_FUNCTION 132 +OUT2_FUNCTION 129 +NTF_LED_TYPES 512 +NTF_LED_BRIGHT 2 +NTF_LED_LEN 4 + +# disable baro by default +BARO_ENABLE 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat new file mode 100644 index 00000000000000..8d3a751a23c920 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat @@ -0,0 +1,61 @@ +# hw definition file for processing by chibios_hwdef.py +# for H757 bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H757xx + +define CORE_CM7 +define SMPS_PWR + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# crystal frequency +OSCILLATOR_HZ 24000000 + +# board ID for firmware load +APJ_BOARD_ID 1043 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# reserve space for flash storage in last 2 sectors +FLASH_RESERVE_END_KB 256 + +# the location where the bootloader will put the firmware +# the H757 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 256 + +# enable CAN support +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 +PD2 SLEEPCAN1 OUTPUT PUSHPULL SPEED_LOW LOW +PD3 TERMCAN1 OUTPUT LOW + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 +PB10 SLEEPCAN2 OUTPUT PUSHPULL SPEED_LOW LOW +PB11 TERMCAN2 OUTPUT LOW + +# board voltage +STM32_VDD 330U + +PB8 LED_SCK OUTPUT LOW +PB9 LED_DI OUTPUT HIGH + +define HAL_NO_LOGGING TRUE +define HAL_NO_MONITOR_THREAD + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define AP_PERIPH_HAVE_LED + +# order of UARTs +SERIAL_ORDER +define HAL_USE_UART FALSE + +# setup for blanking LEDs in bootloader +define AP_BOOTLOADER_CUSTOM_HERE4 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat new file mode 100644 index 00000000000000..d91a47cd1ee4a8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef.dat @@ -0,0 +1,134 @@ +# hw definition file for processing by chibios_hwdef.py +# for H757 + +# MCU class and specific type +MCU STM32H7xx STM32H757xx + +define CORE_CM7 +define SMPS_PWR + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +FLASH_SIZE_KB 2048 +APJ_BOARD_ID 1043 + + +# the location where the bootloader will put the firmware +# the H757 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 256 +FLASH_RESERVE_START_KB 256 + +# use last 2 pages for flash storage +# H757 has 16 pages of 128k each +STORAGE_FLASH_PAGE 14 +define HAL_STORAGE_SIZE 32768 + +# reserve space for flash storage in last 2 sectors +FLASH_RESERVE_END_KB 256 + +# crystal frequency +OSCILLATOR_HZ 24000000 + +CANFD_SUPPORTED 8 + +STDOUT_SERIAL SD6 +STDOUT_BAUDRATE 57600 + +PC6 USART6_TX USART6 + +PB6 USART1_TX USART1 GPIO(7) +PB7 USART1_RX USART1 GPIO(8) + +# GPS +PD5 USART2_TX USART2 GPIO(9) +PD6 USART2_RX USART2 GPIO(10) + +PA11 UART4_RX UART4 +PA12 UART4_TX UART4 + +define GPIO_USART1_TX 7 +define GPIO_USART1_RX 8 +define GPIO_USART2_TX 9 +define GPIO_USART2_RX 10 + +# CubeID when present +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +SERIAL_ORDER USART1 UART4 UART8 USART2 + +define DRONEID_MODULE_CHAN MAVLINK_COMM_2 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define HAL_LED_ON 0 + +# enable CAN support +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 +PD2 SLEEPCAN1 OUTPUT PUSHPULL SPEED_LOW LOW +PD3 TERMCAN1 OUTPUT HIGH GPIO(3) + +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + +# single CAN for now +#PB12 CAN2_RX CAN2 +#PB13 CAN2_TX CAN2 +#PB10 SLEEPCAN2 OUTPUT PUSHPULL SPEED_LOW HIGH +#PB11 TERMCAN2 OUTPUT HIGH GPIO(4) + +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB2 SPI3_MOSI SPI3 +PB1 MAG_CS CS + +# analog input +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +define HAL_PERIPH_ENABLE_BARO TRUE + +SPIDEV rm3100 SPI3 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180 +define AP_RM3100_REVERSAL_MASK 4 + +PA8 ICM_CS CS +PA9 BARO_CS CS +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +SPIDEV icm42688 SPI1 DEVID4 ICM_CS MODE3 2*MHZ 8*MHZ +SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ + +BARO MS56XX SPI:ms5611 + +# WS2812 LED +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 + + +define HAL_PERIPH_ENABLE_GPS 1 +define HAL_PERIPH_ENABLE_MAG 1 +define GPS_MOVING_BASELINE 1 +define HAL_PERIPH_GPS_PORT_DEFAULT 3 + +#PD11 GPS_TP1 OUTPUT HIGH GPIO(5) +#PD7 GPS_PPS INPUT FLOATING GPIO(6) +#define CONFIGURE_PPS_PIN TRUE +#define HAL_GPIO_PPS 6 + +# GPS enable pin +# PD13 GPS_ENABLE OUTPUT HIGH GPIO(20) + +# for ProfiLed we need RC out and notify +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat index ce9c39a20559b9..36f1f97280d771 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat @@ -147,6 +147,4 @@ PB2 BOOT1 INPUT # passthrough CAN1 define HAL_DEFAULT_CPORT 1 -define CAN_APP_NODE_NAME "com.cubepilot.herepro" - FULL_CHIBIOS_BOOTLOADER 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat index 7b0cf621863990..0c8c2b46a8174d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef.dat @@ -64,6 +64,7 @@ FLASH_RESERVE_START_KB 256 define GPS_UBLOX_MOVING_BASELINE TRUE define HAL_GCS_ENABLED 1 define HAL_LOGGING_ENABLED TRUE +define HAL_PERIPH_ENABLE_RTC 1 define HAL_NO_MONITOR_THREAD @@ -86,6 +87,7 @@ define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 # GPS+MAG +define HAL_PERIPH_ENABLE_AHRS define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_ENABLE_MAG define AP_INERTIALSENSOR_ENABLED 1 @@ -195,8 +197,6 @@ PB2 BOOT1 INPUT -define CAN_APP_NODE_NAME "com.cubepilot.herepro" - # disabled compass cal as it doesn't work for now # define COMPASS_CAL_ENABLED 1 @@ -216,3 +216,6 @@ define AP_RC_CHANNEL_ENABLED 1 define AP_RELAY_ENABLED 1 define AP_SERVORELAYEVENTS_ENABLED 1 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef-bl.dat index f74d53921fb22c..7c759e32eaf912 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef-bl.dat @@ -21,27 +21,14 @@ OSCILLATOR_HZ 24000000 # assume 128k flash part FLASH_SIZE_KB 128 -STDOUT_SERIAL SD1 -STDOUT_BAUDRATE 57600 - -# order of UARTs -SERIAL_ORDER USART1 - # a fault LED PA6 LED_BOOTLOADER OUTPUT LOW define HAL_LED_ON 1 -# USART1 -PB6 USART1_TX USART1 SPEED_HIGH NODMA -PB7 USART1_RX USART1 SPEED_HIGH NODMA - -define HAL_USE_SERIAL TRUE - -define STM32_SERIAL_USE_USART1 TRUE +define HAL_USE_SERIAL FALSE define HAL_NO_GPIO_IRQ -define SERIAL_BUFFERS_SIZE 32 define HAL_USE_EMPTY_IO TRUE define PORT_INT_REQUIRED_STACK 64 @@ -62,17 +49,8 @@ PA12 CAN1_TX CAN1 PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# make bl baudrate match debug baudrate for easier debugging -define BOOTLOADER_BAUDRATE 57600 - -# define BOOTLOADER_DEBUG SD1 - # use a small bootloader timeout define HAL_BOOTLOADER_TIMEOUT 1000 - - -define CAN_APP_NODE_NAME "org.ardupilot.Hitec-Airspeed" - # Add CS pins to ensure they are high in bootloader PB12 IMU_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat index a41af41cdcd88c..caac8eab5775c9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Hitec-Airspeed/hwdef.dat @@ -112,8 +112,6 @@ define HAL_NO_RCOUT_THREAD env ROMFS_UNCOMPRESSED True -define CAN_APP_NODE_NAME "org.ardupilot.Hitec-Airspeed" - # don't share any DMA channels (there are enough for everyone) DMA_NOSHARE * diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef-bl.dat index 7afba4a39f3df8..6ba10c98fd4c2e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef-bl.dat @@ -73,9 +73,6 @@ PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL LOW GPIO(72) # reset for GPS PB6 nGNSS_RESET OUTPUT HIGH GPIO(73) -define HAL_USE_CAN TRUE -define STM32_CAN_USE_CAN1 TRUE - # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 @@ -90,5 +87,3 @@ define HAL_STAY_IN_BOOTLOADER_VALUE 0 # Add CS pins to ensure they are high in bootloader PB1 MAG_CS CS - -define CAN_APP_NODE_NAME "org.ardupilot.HitecMosaic" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat index 312495b0b7847b..fccfde74a802c0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HitecMosaic/hwdef.dat @@ -148,8 +148,6 @@ PA7 LED_BUS_I2C OUTPUT LOW env ROMFS_UNCOMPRESSED True -define CAN_APP_NODE_NAME "org.ardupilot.HitecMosaic" - define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_BARO diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef-bl.dat index 11644f49d761a8..d47e84b28a0475 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef-bl.dat @@ -68,8 +68,6 @@ PA11 CAN1_RX CAN1 PA12 CAN1_TX CAN1 PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_Compass" - # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef.dat index 411e722b57b73a..f13290b84d08b6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_Compass/hwdef.dat @@ -90,8 +90,6 @@ PA11 CAN1_RX CAN1 PA12 CAN1_TX CAN1 PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_Compass" - define HAL_NO_LOGGING define HAL_NO_MONITOR_THREAD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef-bl.dat index ced540c3e4760f..c2355f91e3634a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef-bl.dat @@ -72,8 +72,6 @@ PB12 CAN2_RX CAN2 PB13 CAN2_TX CAN2 PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_GPS" - # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat index 984d61749afd9c..be09c07fd220d8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroG4_GPS/hwdef.dat @@ -67,7 +67,7 @@ PA14 JTCK-SWCLK SWD PB7 I2C1_SDA I2C1 PB8 I2C1_SCL I2C1 -# I2C2 bus +# I2C2 bus (LED Driver) PA8 I2C2_SDA I2C2 PA9 I2C2_SCL I2C2 @@ -76,34 +76,22 @@ define HAL_I2C_INTERNAL_MASK 3 # I2C buses I2C_ORDER I2C1 I2C2 -# one SPI bus -PA5 SPI1_SCK SPI1 -PA6 SPI1_MISO SPI1 -PA7 SPI1_MOSI SPI1 +# one SPI bus (for IMU, unused) +#PA5 SPI1_SCK SPI1 +#PA6 SPI1_MISO SPI1 +#PA7 SPI1_MOSI SPI1 # SPI CS PC4 GYR_CS CS PB1 ACC_CS CS -PC14 ICM_CS CS +PC14 ICM_CS CS # GPS PPS PA15 GPS_PPS_IN INPUT -# SPI devices -SPIDEV bmi088_a SPI1 DEVID1 ACC_CS MODE3 10*MHZ 10*MHZ -SPIDEV bmi088_g SPI1 DEVID2 GYR_CS MODE3 10*MHZ 10*MHZ - # compass COMPASS BMM150 I2C:0:0x10 false ROTATION_YAW_90 -# baro -BARO BMP388 I2C:0:0x77 - -# IMU -IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180_YAW_90 - -define HAL_BARO_ALLOW_INIT_NO_BARO - define HAL_USE_ADC FALSE define STM32_ADC_USE_ADC1 FALSE define HAL_DISABLE_ADC_DRIVER TRUE @@ -126,11 +114,9 @@ PA11 CAN1_RX CAN1 PA12 CAN1_TX CAN1 PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -#PB12 CAN2_RX CAN2 -#PB13 CAN2_TX CAN2 -#PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW - -define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_GPS" +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 +PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW define HAL_NO_LOGGING define HAL_NO_MONITOR_THREAD @@ -150,16 +136,12 @@ DMA_NOSHARE USART3* # add support for moving baseline yaw define GPS_MOVING_BASELINE 1 -# GPS+MAG+BARO+LEDs +# GPS+MAG+LEDs define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_ENABLE_MAG -define HAL_PERIPH_ENABLE_BARO define HAL_PERIPH_ENABLE_NOTIFY define HAL_PERIPH_ENABLE_RC_OUT -# single baro -define BARO_MAX_INSTANCES 1 - # GPS on 2nd port define HAL_PERIPH_GPS_PORT_DEFAULT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef-bl.dat index edd6296d36307e..68beff06e909cf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef-bl.dat @@ -72,9 +72,6 @@ PB12 CAN2_RX CAN2 PB13 CAN2_TX CAN2 PA4 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -define CAN_APP_NODE_NAME "org.ardupilot.HolybroGPS" - - # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat index d219f37af30c39..c55bd739386a0f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat @@ -137,8 +137,6 @@ PB13 CAN2_TX CAN2 PA4 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -define CAN_APP_NODE_NAME "org.ardupilot.HolybroGPS" - define HAL_NO_LOGGING define HAL_NO_MONITOR_THREAD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB100/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JFB100/hwdef.dat index d690a3da444915..2800e021ec90f8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JFB100/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB100/hwdef.dat @@ -25,9 +25,6 @@ env OPTIMIZE -O2 # order of UARTs (and USB) SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2 -# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 - # now we define the pins that USB is connected on PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/README.md b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/README.md new file mode 100644 index 00000000000000..87f58272ae8af7 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/README.md @@ -0,0 +1,140 @@ +# JFB-110 Flight Controller + +The JFB-110 flight controller is sold by [JAE](https://www.jae.com/Motion_Sensor_Control/eVTOL/FlightController/) + +## Features + + - STM32H755 microcontroller + - Three IMUs: SCHA63T and IIM42652 x2 + - Two BAROs: MS5611 SPI barometer x2 + - builtin I2C IST8310 magnetometer + - microSD card slot + - 5 UARTs plus USB, RCIN, SBUS_OUT + - 16 PWM outputs + - Four I2C and two CAN ports + - External Buzzer (Open/Drain and 33V Out) + - external safety Switch + - voltage monitoring for servo rail and Vcc + - two dedicated power input ports for external power bricks + +## UART Mapping + + - SERIAL0 -> USB + - SERIAL1 -> UART7 (Telem1) + - SERIAL2 -> UART5 (Telem2) + - SERIAL3 -> USART1 (GPS) + - SERIAL4 -> UART4 (GPS2, marked UART/I2CB) + - SERIAL5 -> USART6 (RCIN) + - SERIAL6 -> UART8 (SBUS_OUT) + - SERIAL7 -> USART3 (debug) + - SERIAL8 -> USB (SLCAN) + + +The Telem1 and Telem2 ports have RTS/CTS pins, the other UARTs do not +have RTS/CTS. + +The USART3 connector is labelled debug, but is available as a general +purpose UART with ArduPilot. + +## RC Input + +RC input is configured on the port marked DSM/SBUS RC. This connector +supports all RC protocols. Two cables are available for this port. To +use software binding of Spektrum satellite receivers you need to use +the Spektrum satellite cable. + +## PWM Output + +The JFB-110 supports up to 16 PWM outputs. +These are directly attached to the STM32H755 and support all +PWM protocols. + +The 16 PWM outputs are in 6 groups: + - PWM 1 and 2 in group1 (TIM15) + - PWM 3 and 4 in group2 (TIM3) + - PWM 5, 11 ,12 and 13 in group3 (TIM4) + - PWM 6 ,9 and 10 in group4 (TIM1) + - PWM 7 ,8 and 15 in group5 (TIM5) + - PWM 14 and 16 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. + +## Battery Monitoring + +The board has two dedicated power monitor ports on 8 pin +connectors. The correct battery setting parameters are dependent on +the type of power brick which is connected. +Recomended input voltage is 4.9 to 5.5 volt. + +## Compass + +The JFB-110 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 16 PWM ports can be used as GPIOs (relays, buttons, RPM etc). To +use them you need to limit the number of these pins that is used for +PWM by setting the BRD_PWM_COUNT to a number less than 6. For example +if you set BRD_PWM_COUNT to 4 then PWM5 and PWM6 will be available for +use as GPIOs. + +The numbering of the GPIOs for PIN variables in ArduPilot is: + - PWM(1) 50 + - PWM(2) 51 + - PWM(3) 52 + - PWM(4) 53 + - PWM(5) 54 + - PWM(6) 55 + - PWM(7) 56 + - PWM(8) 57 + - PWM(9) 58 + - PWM(10) 59 + - PWM(11) 60 + - PWM(12) 61 + - PWM(13) 62 + - PWM(14) 63 + - PWM(15) 64 + - PWM(16) 65 + - FMU_CAP1 66 + - FMU_CAP2 67 + + +## Analog inputs + +The JFB-110 has 9 analog inputs + - ADC Pin16 -> Battery Voltage + - ADC Pin18 -> Battery Current Sensor + - ADC Pin9 -> Battery Voltage 2 + - ADC Pin6 -> Battery Current Sensor 2 + - ADC Pin5 -> ADC 5V Sense + - ADC Pin11 -> ADC 3.3V Sense + - ADC Pin10 -> RSSI voltage monitoring + - ADC Pin12 -> ADC SPARE 1 + - ADC Pin13 -> ADC SPARE 2 + +## I2C Buses + +The JFB-110 has 4 I2C interfaces. +I2C 3 is for internal only. + - the internal I2C port is bus 3 in ArduPilot (I2C3 in hardware) + - the port labelled I2CA is bus 4 in ArduPilot (I2C4 in hardware) + - the port labelled I2CB is bus 2 in ArduPilot (I2C2 in hardware) + - the port labelled GPS is bus 1 in ArduPilot (I2C1 in hardware) + +## CAN + +The JFB-110 has two independent CAN buses, with the following pinouts. + +## Debug + +The JFB-110 supports SWD debugging on the debug port + +## 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/JFB110/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm new file mode 100644 index 00000000000000..0be0b0db513489 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm @@ -0,0 +1,28 @@ +# board setting +BRD_VBUS_MIN 4.9 + +# setup SERIAL4 for BPort +SERIAL4_BAUD 57 +SERIAL4_PROTOCOL -1 +SERIAL4_OPTIONS 0 +# setup SERIAL5 to RCIN +SERIAL5_BAUD 100 +SERIAL5_PROTOCOL 23 +SERIAL5_OPTIONS 3 +# setup SERIAL6 to SBUS OUT +SERIAL6_BAUD 100 +SERIAL6_PROTOCOL 15 +SERIAL6_OPTIONS 3 +# setup SERIAL7 for debug console +SERIAL7_BAUD 921 +SERIAL7_PROTOCOL 0 +SERIAL7_OPTIONS 0 + +#Three IMU Setting +EK3_IMU_MASK 7 +INS_ENABLE_MASK 7 + +#RSSI Setting +RSSI_TYPE 1 +RSSI_ANA_PIN 10 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef-bl.dat new file mode 100644 index 00000000000000..6a7b2f739bd483 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef-bl.dat @@ -0,0 +1,139 @@ +# hw definition file for processing by chibios_hwdef.py +# for the JFB110 hardware + +# board ID for firmware load +APJ_BOARD_ID 1110 + +# MCU class and specific type +MCU STM32H7xx STM32H755xx +define CORE_CM7 +#define SMPS_PWR + +# crystal frequency 24MHz +OSCILLATOR_HZ 24000000 + +# the location where the bootloader will put the firmware +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 +# the H755 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 +# with 2M flash we can afford to optimize for speed +FLASH_SIZE_KB 2048 +HAL_STORAGE_SIZE 32768 + +env OPTIMIZE -Os + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + +# USB setup +# USB_VENDOR 0x0A8E # JAE +# USB_PRODUCT 0x8888 # This is temp Number +USB_STRING_MANUFACTURER "Japan Aviation Electronics Industry Ltd." +USB_STRING_PRODUCT "JFB-110" + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 UART5 USART3 + +# serial port for stdout, set SERIAL7_PROTOCOL 0(none) when using +# The value for STDOUT_SERIAL is a serial device name, and must be for a +# serial device for which pins are defined in this file. For example, SD3 +# is for USART3 (SD3 == "serial device 3" in ChibiOS). +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 +PA12 OTG_FS_DP OTG1 + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# CS pins +PH3 SCHA63T_G_CS CS # SPI1_CS1 +PH4 SCHA63T_A_CS CS # SPI1_CS2 +PH5 MS5611_2_CS CS # SPI1_CS3 +PG6 AT25512_CS CS # SPI1_CS4 +PG7 FRAM_CS CS # SPI3_CS1 +PF10 IIM42652_1_CS CS # SPI3_CS2 +PH15 MS5611_1_CS CS # SPI4_CS1 +PG15 IIM42652_2_CS CS # SPI4_CS2 + +# telem1 +PE8 UART7_TX UART7 +PE10 UART7_CTS UART7 +PF6 UART7_RX UART7 +PF8 UART7_RTS UART7 + +# telem2 +PC12 UART5_TX UART5 +PC9 UART5_CTS UART5 +PD2 UART5_RX UART5 +PC8 UART5_RTS UART5 + +# debug uart +PD8 USART3_TX USART3 NODMA +PD9 USART3_RX USART3 NODMA + +# armed indication +PB10 nARMED OUTPUT HIGH # TP8 + +# 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() +PG10 nVDD_5V_HIPOWER_EN OUTPUT HIGH +PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH +PG12 VDD_3V3_SENSORS_EN OUTPUT LOW +PD4 VDD_3V3_SENSORS2_EN OUTPUT LOW +PD3 VDD_3V3_SENSORS3_EN OUTPUT LOW +#VDD_3V3_SENSORS4_EN OUTPUT LOW +#VDD_3V3_SD_CARD_EN OUTPUT LOW + +# PWM output pins +# we need to disable DMA on the last 2 FMU channels +# as timer 12 doesn't have a TIMn_UP DMA option +PA2 PWMOUT1 OUTPUT LOW +PE6 PWMOUT2 OUTPUT LOW +PA7 PWMOUT3 OUTPUT LOW +PA6 PWMOUT4 OUTPUT LOW +PD15 PWMOUT5 OUTPUT LOW +PE9 PWMOUT6 OUTPUT LOW +PH11 PWMOUT7 OUTPUT LOW +PH10 PWMOUT8 OUTPUT LOW +PA10 PWMOUT9 OUTPUT LOW +PA9 PWMOUT10 OUTPUT LOW +PD14 PWMOUT11 OUTPUT LOW +PD13 PWMOUT12 OUTPUT LOW +PD12 PWMOUT13 OUTPUT LOW +PH9 PWMOUT14 OUTPUT LOW +PH12 PWMOUT15 OUTPUT LOW +PH6 PWMOUT16 OUTPUT LOW +PD11 PWM_OE OUTPUT HIGH +PD5 PWM_OE2 OUTPUT HIGH + +# controlled manually +PG13 GPIO_CAN1_SILENT OUTPUT PUSHPULL HIGH +PG8 GPIO_CAN2_SILENT OUTPUT PUSHPULL HIGH + +# Control of Spektrum power pin +PH2 SPEKTRUM_PWR OUTPUT LOW GPIO(69) + +# LEDs +#PE3 LED_RED OUTPUT OPENDRAIN GPIO(70) HIGH +##PE4 LED_GREEN OUTPUT OPENDRAIN GPIO(71) LOW +##PE5 LED_BLUE OUTPUT OPENDRAIN GPIO(72) LOW + +PE4 LED_BOOTLOADER OUTPUT HIGH +PE5 LED_ACTIVITY OUTPUT HIGH +define HAL_LED_ON 0 + +#define HAL_USE_EMPTY_STORAGE 1 +#define HAL_STORAGE_SIZE 32768 + +# enable DFU by default +#ENABLE_DFU_BOOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat new file mode 100644 index 00000000000000..6b8189410a3017 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/hwdef.dat @@ -0,0 +1,352 @@ +# hw definition file for processing by chibios_hwdef.py +# for the JFB110 hardware + +# board ID for firmware load +APJ_BOARD_ID 1110 + +# MCU class and specific type +MCU STM32H7xx STM32H755xx +define CORE_CM7 +#define SMPS_PWR + +# crystal frequency 24MHz +OSCILLATOR_HZ 24000000 + +# the H755 has 128k sectors +# bootloader is installed at 128kb offset +FLASH_BOOTLOADER_LOAD_KB 128 +FLASH_RESERVE_START_KB 128 +FLASH_SIZE_KB 2048 +HAL_STORAGE_SIZE 32768 + +# USB setup +# USB_VENDOR 0x0A8E # JAE +USB_STRING_MANUFACTURER "Japan Aviation Electronics Industry Ltd." +USB_STRING_PRODUCT "JFB-110" + +# ChibiOS system timer +STM32_ST_USE_TIMER 2 + +# enable board sub-type detection +define CONFIG_HAL_BOARD HAL_BOARD_CHIBIOS +#define HAL_CHIBIOS_ARCH_FMUV6 1 +#define AP_FEATURE_BOARD_DETECT 1 +#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_FMUV5 +#define HAL_CHIBIOS_ARCH_FMUV5 1 + +env OPTIMIZE -O2 + +# order of UARTs (and USB) +# SERIAL | 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | +SERIAL_ORDER OTG1 UART7 UART5 USART1 UART4 USART6 UART8 USART3 OTG2 +#USART6 is RX only for SBUS_IN +#UART8 is TX only for SBUS_OUT + +# serial port for stdout, set SERIAL7_PROTOCOL 5(GPS) when using +# The value for STDOUT_SERIAL is a serial device name, and must be for a +# serial device for which pins are defined in this file. For example, SD3 +# is for USART3 (SD3 == "serial device 3" in ChibiOS). +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 +PA12 OTG_FS_DP OTG1 +# default the 2nd interface to MAVLink2 +define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 + +# pins for SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# telem1 +PE8 UART7_TX UART7 SPEED_VERYLOW +PE10 UART7_CTS UART7 SPEED_VERYLOW +PF6 UART7_RX UART7 SPEED_VERYLOW +PF8 UART7_RTS UART7 SPEED_VERYLOW + +# telem2 +PC12 UART5_TX UART5 SPEED_VERYLOW +PC9 UART5_CTS UART5 SPEED_VERYLOW +PD2 UART5_RX UART5 SPEED_VERYLOW +PC8 UART5_RTS UART5 SPEED_VERYLOW + +# telem3 for future use +#PD5 TP14 OUTPUT LOW #TP14 + +# GPS1 +PB6 USART1_TX USART1 SPEED_VERYLOW +PB7 USART1_RX USART1 SPEED_VERYLOW + +# uart4 +PH13 UART4_TX UART4 SPEED_VERYLOW +PH14 UART4_RX UART4 SPEED_VERYLOW + +# TX Only, for SBUS OUT +PE0 UART8_RX UART8 SPEED_VERYLOW #TP3 +PE1 UART8_TX UART8 SPEED_VERYLOW + +# RX only, for RC input +#PG14 USART6_TX USART6 SPEED_VERYLOW #TP10 +PC7 USART6_RX USART6 SPEED_VERYLOW + +# debug uart +PD8 USART3_TX USART3 SPEED_VERYLOW NODMA +PD9 USART3_RX USART3 SPEED_VERYLOW NODMA + +# ADC +PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1) # ADC1_16 +PF12 BATT_CURRENT_SENS ADC1 SCALE(1) # ADC1_6 +PB0 BATT2_VOLTAGE_SENS ADC1 SCALE(1) # ADC1_9 +PA4 BATT2_CURRENT_SENS ADC1 SCALE(1) # ADC1_18 + +# setup scaling defaults for supplied power brick +define HAL_BATT_VOLT_SCALE 1 #18.182 +define HAL_BATT_CURR_SCALE 1 #36.364 +define HAL_BATT2_VOLT_SCALE 1 #18.182 +define HAL_BATT2_CURR_SCALE 1 #36.364 +define HAL_BATT_VOLT_PIN 16 +define HAL_BATT_CURR_PIN 6 +define HAL_BATT2_VOLT_PIN 9 +define HAL_BATT2_CURR_PIN 18 + +# Now the VDD sense pin. This is used to sense primary board voltage. +PB1 VDD_5V_SENS ADC1 SCALE(2) # ADC1_5 +define ANALOG_VCC_5V_PIN 5 +define HAL_HAVE_BOARD_VOLTAGE 1 +PB3 VBUS_RESERVED INPUT + +# JFB110 has SERVORAIL ADC +# Set SENSOR_3.3V power signal insted. +PC1 SCALED_V3V3 ADC1 SCALE(2) # ADC1_11 +PA3 FMU_SERVORAIL_VCC ADC1 SCALE(2) # ADC1_15 +define FMU_SERVORAIL_ADC_PIN 15 +define HAL_HAVE_SERVO_VOLTAGE 1 + +PC0 RSSI_IN ADC1 SCALE(1) # ADC1_10 +define RSSI_ANA_PIN 10 + +PC2 ADC1_6V6 ADC1 SCALE(2) # ADC1_12 +PC3 ADC1_3V3 ADC1 SCALE(1) # ADC1_13 + +# 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() +PG10 nVDD_5V_HIPOWER_EN OUTPUT HIGH +PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH +PG12 VDD_3V3_SENSORS_EN OUTPUT LOW +PD4 VDD_3V3_SENSORS2_EN OUTPUT LOW +PD3 VDD_3V3_SENSORS3_EN OUTPUT LOW +#VDD_3V3_SENSORS4_EN OUTPUT LOW +#VDD_3V3_SD_CARD_EN OUTPUT LOW + +# controlled manually +PG13 GPIO_CAN1_SILENT OUTPUT PUSHPULL LOW +PG8 GPIO_CAN2_SILENT OUTPUT PUSHPULL LOW + +# Control of Spektrum power pin +# no SPEKTRUM_RC pin so this is controlled +# manually +PH2 SPEKTRUM_PWR OUTPUT HIGH GPIO(69) +define HAL_GPIO_SPEKTRUM_PWR 69 +define HAL_SPEKTRUM_PWR_ENABLED 1 + +#Checked in Analogin.cpp -> MAV_POWER_STATUS +PG1 VDD_BRICK_nVALID INPUT +PG2 VDD_BRICK2_nVALID INPUT +PG3 VBUS_nVALID INPUT +PE15 VDD_5V_PERIPH_nOC INPUT +PF13 VDD_5V_HIPOWER_nOC INPUT + +# ID pins +PG0 HW_VER_REV_DRIVE OUTPUT LOW SPEED_VERYLOW +PC4 HW_VER_SENS ADC1 SCALE(1) # ADC1_4 +PC5 HW_REV_SENS ADC1 SCALE(1) # ADC1_8 + +# SPI1 - IMU1(murata),MS5611(BARO),EEPROM +PA5 SPI1_SCK SPI1 SPEED_VERYLOW +PB5 SPI1_MOSI SPI1 SPEED_VERYLOW +PG9 SPI1_MISO SPI1 SPEED_VERYLOW +PH3 SCHA63T_A_CS CS SPEED_VERYLOW # SPI1_CS1 +PH4 SCHA63T_G_CS CS SPEED_VERYLOW # SPI1_CS2 +PH5 MS5611_1_CS CS SPEED_VERYLOW # SPI1_CS3 +PG6 AT25512_CS CS SPEED_VERYLOW # SPI1_CS4 + +# SPI2 + +# SPI3 - FRAM,IMU2(42652) +PB2 SPI3_MOSI SPI3 SPEED_VERYLOW +PC10 SPI3_SCK SPI3 SPEED_VERYLOW +PC11 SPI3_MISO SPI3 SPEED_VERYLOW +PG7 FRAM_CS CS SPEED_VERYLOW # SPI3_CS1 +PF10 IIM42652_CS CS SPEED_VERYLOW # SPI3_CS2 + +# SPI4 - MS5611(BARO),IMU3(42652), +PE12 SPI4_SCK SPI4 SPEED_VERYLOW +PE13 SPI4_MISO SPI4 SPEED_VERYLOW +PE14 SPI4_MOSI SPI4 SPEED_VERYLOW +PH15 MS5611_2_CS CS SPEED_VERYLOW # SPI4_CS1 +PG15 IIM42652_2_CS CS SPEED_VERYLOW # SPI4_CS2 + +# SPI5 - External SPI I/F +#PF7 SPI5_SCK SPI5 SPEED_VERYLOW +#PH7 SPI5_MISO SPI5 SPEED_VERYLOW +#PF11 SPI5_MOSI SPI5 SPEED_VERYLOW +#PE2 SPI5_CS1 CS SPEED_VERYLOW + +# IMU Device Ready Signal Input +PF3 DRDY1_IIM42652_1 INPUT +PF2 DRDY2_IIM42652_1 INPUT +PA15 DRDY1_IIM42652_2 INPUT +PA1 DRDY2_IIM42652_2 INPUT + +PE7 SCHA63T_RESET OUTPUT LOW + +# SPI devices +SPIDEV scha63t_g SPI1 DEVID1 SCHA63T_G_CS MODE0 10*MHZ 10*MHZ +SPIDEV scha63t_a SPI1 DEVID2 SCHA63T_A_CS MODE0 10*MHZ 10*MHZ +SPIDEV ms5611_1 SPI1 DEVID3 MS5611_1_CS MODE3 20*MHZ 20*MHZ +SPIDEV at25512 SPI1 DEVID4 AT25512_CS MODE3 2*MHZ 8*MHZ +SPIDEV ramtron SPI3 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV iim42652_1 SPI3 DEVID2 IIM42652_CS MODE3 2*MHZ 8*MHZ +SPIDEV ms5611_2 SPI4 DEVID1 MS5611_2_CS MODE3 20*MHZ 20*MHZ +SPIDEV iim42652_2 SPI4 DEVID2 IIM42652_2_CS MODE3 2*MHZ 8*MHZ +#define HAL_SPI_CHECK_CLOCK_FREQ + +# JFB110 has 3 IMUs +# IMU devices for JFB110. The JFB110 board has a SCHA63T, two ICM42652, +# the SCHA63T and ICM42652_1 are on the same SPI buses and CS pins. +# The IIM42652_2 is on a different bus +IMU SCHA63T SPI:scha63t_a SPI:scha63t_g ROTATION_NONE +IMU Invensensev3 SPI:iim42652_1 ROTATION_NONE +IMU Invensensev3 SPI:iim42652_2 ROTATION_NONE + +# JFB110 has 2 BAROs +BARO MS56XX SPI:ms5611_1 +BARO MS56XX SPI:ms5611_2 + +define HAL_DEFAULT_INS_FAST_SAMPLE 7 + +# PWM output pins +# we need to disable DMA on the last 2 FMU channels +# as timer 12 doesn't have a TIMn_UP DMA option +PA2 TIM15_CH1 TIM15 PWM(1) GPIO(50) SPEED_VERYLOW +PE6 TIM15_CH2 TIM15 PWM(2) GPIO(51) SPEED_VERYLOW +PA7 TIM3_CH2 TIM3 PWM(3) GPIO(52) SPEED_VERYLOW +PA6 TIM3_CH1 TIM3 PWM(4) GPIO(53) SPEED_VERYLOW +PD15 TIM4_CH4 TIM4 PWM(5) GPIO(54) SPEED_VERYLOW +PE9 TIM1_CH1 TIM1 PWM(6) GPIO(55) SPEED_VERYLOW +PH11 TIM5_CH2 TIM5 PWM(7) GPIO(56) SPEED_VERYLOW +PH10 TIM5_CH1 TIM5 PWM(8) GPIO(57) SPEED_VERYLOW +PA10 TIM1_CH3 TIM1 PWM(9) GPIO(58) SPEED_VERYLOW +PA9 TIM1_CH2 TIM1 PWM(10) GPIO(59) SPEED_VERYLOW +PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60) SPEED_VERYLOW +PD13 TIM4_CH2 TIM4 PWM(12) GPIO(61) SPEED_VERYLOW +PD12 TIM4_CH1 TIM4 PWM(13) GPIO(62) SPEED_VERYLOW +PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) SPEED_VERYLOW NODMA +PH12 TIM5_CH3 TIM5 PWM(15) GPIO(64) SPEED_VERYLOW +PH6 TIM12_CH1 TIM12 PWM(16) GPIO(65) SPEED_VERYLOW NODMA +PD11 PWM_OE OUTPUT HIGH +PD5 PWM_OE2 OUTPUT HIGH + +# GPIOs +PE11 FMU_CAP1 INPUT GPIO(66) +PB11 FMU_CAP2 INPUT GPIO(67) + +# CAN bus +PD0 CAN1_RX CAN1 SPEED_VERYLOW +PD1 CAN1_TX CAN1 SPEED_VERYLOW +PB12 CAN2_RX CAN2 SPEED_VERYLOW +PB13 CAN2_TX CAN2 SPEED_VERYLOW + +# I2C buses +# I2C1, GPS+MAG +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# I2C2, GPS2+MAG +PF1 I2C2_SCL I2C2 +PF0 I2C2_SDA I2C2 + +# I2C3, IST8310 Internal +PA8 I2C3_SCL I2C3 SPEED_VERYLOW +PH8 I2C3_SDA I2C3 SPEED_VERYLOW + +# I2C4 external +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C3 I2C1 I2C2 I2C4 +define HAL_I2C_INTERNAL_MASK 1 + +# this board is very tight on DMA channels. To allow for more UART DMA +# we disable DMA on I2C. This also prevents a problem with DMA on I2C +# interfering with IMUs +NODMA I2C* +define STM32_I2C_USE_DMA FALSE + +# builtin compass on JAE JFB110 +define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_270 +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90 + +# armed indication +PB10 nARMED OUTPUT HIGH # TP8 + +# microSD support +PD6 SDMMC2_CK SDMMC2 SPEED_VERYLOW +PD7 SDMMC2_CMD SDMMC2 SPEED_VERYLOW +PB14 SDMMC2_D0 SDMMC2 SPEED_VERYLOW +PB15 SDMMC2_D1 SDMMC2 SPEED_VERYLOW +PG11 SDMMC2_D2 SDMMC2 SPEED_VERYLOW +PB4 SDMMC2_D3 SDMMC2 SPEED_VERYLOW +define FATFS_HAL_DEVICE SDCD2 +PC13 SD_CARD_EN INPUT + +# safety +PD10 LED_SAFETY OUTPUT +PF5 SAFETY_IN INPUT PULLDOWN + +# LEDs +PE3 LED_RED OUTPUT OPENDRAIN GPIO(70) HIGH SPEED_VERYLOW +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 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 + +# RC input (PPM) +PC6 TIM8_CH1 TIM8 RCININT PULLDOWN LOW + +# enable RAMTRON parameter storage +define HAL_STORAGE_SIZE 32768 +define HAL_WITH_RAMTRON 1 + +# allow to have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 + +DMA_PRIORITY SDMMC* UART* USART* ADC* 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 + +# External watchdog gpio +PG5 EXT_WDOG OUTPUT SPEED_VERYLOW +define EXT_WDOG_INTERVAL_MS 50 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat index 4cd11ef07947fe..5ae33ca8d5f2c9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat @@ -144,15 +144,13 @@ define STM32_PWM_USE_ADVANCED TRUE define HAL_PARACHUTE_ENABLED 0 # save FLASH, but leave above when flash issue is fixed -include ../include/minimize_features.inc +include ../include/minimize_fpv_osd.inc # disable SMBUS battery monitors to save flash undef AP_BATTERY_SMBUS_ENABLED define AP_BATTERY_SMBUS_ENABLED 0 # setup for OSD -undef OSD_ENABLED # minimize_features.inc removes this -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/KakuteH7-Wing/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-Wing/hwdef.dat index ba025780f5af79..2e70060b5c8c84 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-Wing/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7-Wing/hwdef.dat @@ -136,9 +136,9 @@ PD0 CAN1_RX CAN1 PD1 CAN1_TX CAN1 # Motors -PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) +PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) BIDIR PE11 TIM1_CH2 TIM1 PWM(2) GPIO(51) -PE13 TIM1_CH3 TIM1 PWM(3) GPIO(52) +PE13 TIM1_CH3 TIM1 PWM(3) GPIO(52) BIDIR PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53) PD14 TIM4_CH3 TIM4 PWM(5) GPIO(54) BIDIR PD15 TIM4_CH4 TIM4 PWM(6) GPIO(55) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat index b1bd8ca6de6020..fed99f38f4d14f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7/hwdef.dat @@ -152,8 +152,6 @@ BARO BMP280 I2C:0:0x76 define HAL_OS_FATFS_IO 1 # setup for OSD -undef OSD_ENABLED # minimize_features.inc removes this -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/MambaF405v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405v2/hwdef.dat index 50fc9168f6b822..41ef077b8ac8b0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaF405v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaF405v2/hwdef.dat @@ -18,7 +18,8 @@ OSCILLATOR_HZ 8000000 # board voltage STM32_VDD 330U -STM32_ST_USE_TIMER 5 +STM32_ST_USE_TIMER 4 +define CH_CFG_ST_RESOLUTION 16 # order of I2C buses I2C_ORDER I2C1 @@ -40,32 +41,40 @@ PA9 USART1_TX USART1 # Alt config to allow RCIN on UART PA10 USART1_RX USART1 ALT(1) +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN -# SBUS inversion control pin, active high -PC0 USART1_RXINV OUTPUT LOW GPIO(78) POL(1) +# SBUS inversion control pin, active low +PC0 USART1_RXINV OUTPUT HIGH GPIO(78) POL(0) -# USART3 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None + +# USART3 (VTX) PB10 USART3_TX USART3 -PB11 USART3_RX USART3 NODMA +PB11 USART3_RX USART3 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Tramp + +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None -# USART6 +# USART6 (ESC Telemetry) PC6 USART6_TX USART6 PC7 USART6_RX USART6 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_ESCTelemetry # The pins for SWD debugging with a STlinkv2 or black-magic probe (not tested) PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD # ADC -PC1 BAT_VOLT_SENS ADC1 SCALE(1) -PC2 RSSI_IN ADC1 -PC3 BAT_CURR_SENS ADC1 SCALE(1) +PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC2 RSSI_ADC ADC1 +PC3 BATT_CURRENT_SENS ADC1 SCALE(1) # PWM output. 1 - 4 on ESC header -PA3 TIM2_CH4 TIM2 PWM(1) GPIO(50) +PA3 TIM2_CH4 TIM2 PWM(1) GPIO(50) BIDIR PB0 TIM3_CH3 TIM3 PWM(2) GPIO(51) PB1 TIM3_CH4 TIM3 PWM(3) GPIO(52) BIDIR -PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) BIDIR +PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) # Board LEDs PB5 LED_BLUE OUTPUT LOW GPIO(1) @@ -74,13 +83,15 @@ define HAL_GPIO_A_LED_PIN 1 define HAL_GPIO_B_LED_PIN 2 # External LEDs -PA0 LED_EXT1 OUTPUT GPIO(30) +PA0 TIM5_CH1 TIM5 PWM(5) GPIO(54) # Buzzer PA8 BUZZER OUTPUT GPIO(80) LOW define HAL_BUZZER_PIN 80 - +# Camera control +PB9 CAM_C OUTPUT LOW GPIO(81) +define RELAY2_PIN_DEFAULT 81 # Note that this board needs PULLUP on I2C pins PB6 I2C1_SCL I2C1 PULLUP @@ -142,11 +153,12 @@ FLASH_RESERVE_START_KB 64 # define default battery setup define HAL_BATT_VOLT_PIN 11 define HAL_BATT_CURR_PIN 13 -define HAL_BATT_VOLT_SCALE 12 -define HAL_BATT_CURR_SCALE 39 +define HAL_BATT_VOLT_SCALE 11 +define HAL_BATT_CURR_SCALE 25.0 +define HAL_BATT_MONITOR_DEFAULT 4 # Analog RSSI pin (also could be used as analog airspeed input) -define BOARD_RSSI_ANA_PIN 1 +define BOARD_RSSI_ANA_PIN 12 # Setup for OSD define OSD_ENABLED 1 @@ -154,9 +166,7 @@ define HAL_OSD_TYPE_DEFAULT 1 # Font for the osd ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin -# To complementary channels work we define this -#define STM32_PWM_USE_ADVANCED TRUE +DMA_PRIORITY TIM2* TIM3* # minimal drivers to reduce flash usage -include ../include/minimal.inc -include ../include/no_bootloader_DFU.inc +include ../include/minimize_fpv_osd.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef-bl.dat index b763dfe2b3f5cc..0d979d5354dedd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef-bl.dat @@ -7,4 +7,3 @@ PD1 CAN1_TX CAN1 env AP_PERIPH 1 -define CAN_APP_NODE_NAME "org.ardupilot.MatekH743-periph" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat index ef7bcef9735709..e4195fdc27b98e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH743-periph/hwdef.dat @@ -26,8 +26,6 @@ define HAL_PERIPH_ENABLE_RC_OUT define HAL_PERIPH_ENABLE_BATTERY -define CAN_APP_NODE_NAME "org.ardupilot.MatekH743-periph" - # single GPS, compass and RF for peripherals define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 @@ -62,3 +60,6 @@ define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 # setup for MSP define HAL_MSP_ENABLED 1 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-ADSB/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-ADSB/hwdef-bl.dat new file mode 100644 index 00000000000000..b9005f84941a6a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-ADSB/hwdef-bl.dat @@ -0,0 +1,2 @@ +include ../MatekL431/hwdef-bl.inc + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-ADSB/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-ADSB/hwdef.dat new file mode 100644 index 00000000000000..ad595a85b8aa61 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-ADSB/hwdef.dat @@ -0,0 +1,11 @@ +include ../MatekL431/hwdef.inc + +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +# ENABLE ADSB +define HAL_PERIPH_ENABLE_ADSB +define HAL_PERIPH_ADSB_PORT_DEFAULT 2 + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef-bl.dat index 887b18aeaccdd1..b9005f84941a6a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef-bl.dat @@ -1,3 +1,2 @@ include ../MatekL431/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Airspeed" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef.dat index 302d5c8d88fe76..63c15f8cce2c0a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef.dat @@ -1,7 +1,5 @@ include ../MatekL431/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Airspeed" - define HAL_USE_ADC FALSE define STM32_ADC_USE_ADC1 FALSE define HAL_DISABLE_ADC_DRIVER TRUE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef-bl.dat index 1313cca1ebd72e..b9005f84941a6a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef-bl.dat @@ -1,3 +1,2 @@ include ../MatekL431/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-BattMon" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef.dat index 633a185624c808..ea4e70b0997eda 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-BattMon/hwdef.dat @@ -1,7 +1,5 @@ include ../MatekL431/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-BattMon" - # enable battery monitor define HAL_PERIPH_ENABLE_BATTERY define AP_BATTERY_INA239_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef-bl.dat index fe94bb635e4ba9..b9005f84941a6a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef-bl.dat @@ -1,3 +1,2 @@ include ../MatekL431/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-DShot" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef.dat index 3d809de636e301..76a29aa2c2d2a8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-DShot/hwdef.dat @@ -1,7 +1,5 @@ include ../MatekL431/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-DShot" - define HAL_USE_ADC FALSE undef SERIAL_ORDER diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef-bl.dat index 173d1fc2fc4dec..b9005f84941a6a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef-bl.dat @@ -1,3 +1,2 @@ include ../MatekL431/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-EFI" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef.dat index 2b122aa0c5a9fe..6200911d7ddf49 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-EFI/hwdef.dat @@ -1,7 +1,5 @@ include ../MatekL431/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-EFI" - define HAL_USE_ADC FALSE define STM32_ADC_USE_ADC1 FALSE define HAL_DISABLE_ADC_DRIVER TRUE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef-bl.dat index ce9861506d5e85..b9005f84941a6a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef-bl.dat @@ -1,3 +1,2 @@ include ../MatekL431/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-GPS" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef.dat index e54e19d18790cb..5c858285a7f4f7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-GPS/hwdef.dat @@ -1,7 +1,5 @@ include ../MatekL431/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-GPS" - # enable GPS and compass define HAL_PERIPH_ENABLE_GPS define GPS_MAX_RATE_MS 200 @@ -54,3 +52,8 @@ define HAL_CAN_POOL_SIZE 12000 define HAL_PERIPH_ENABLE_MSP define HAL_MSP_ENABLED 1 define AP_PERIPH_MSP_PORT_DEFAULT 1 + +undef PB10 +undef PB11 +PB10 USART3_TX USART3 SPEED_HIGH +PB11 USART3_RX USART3 SPEED_HIGH diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-HWTelem/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-HWTelem/hwdef-bl.dat index a26340d7f39e88..b9005f84941a6a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-HWTelem/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-HWTelem/hwdef-bl.dat @@ -1,3 +1,2 @@ include ../MatekL431/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-HWtelem" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-HWTelem/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-HWTelem/hwdef.dat index 711378febd7707..6abfb3548d9ab6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-HWTelem/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-HWTelem/hwdef.dat @@ -1,7 +1,5 @@ include ../MatekL431/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-HWtelem" - define HAL_USE_ADC FALSE define STM32_ADC_USE_ADC1 FALSE define HAL_DISABLE_ADC_DRIVER TRUE @@ -9,3 +7,5 @@ define HAL_DISABLE_ADC_DRIVER TRUE define HAL_PERIPH_ENABLE_HWESC define HAL_PERIPH_HWESC_SERIAL_PORT 2 +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef-bl.dat index dd6b5cc8873133..b9005f84941a6a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef-bl.dat @@ -1,3 +1,2 @@ include ../MatekL431/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Periph" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat index 74c9949e33085c..242986bc1e677d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Periph/hwdef.dat @@ -1,7 +1,5 @@ include ../MatekL431/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Periph" - # --------------------- PWM ----------------------- PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Proximity/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Proximity/hwdef-bl.dat index 9b1ad2a20f80d9..b9005f84941a6a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Proximity/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Proximity/hwdef-bl.dat @@ -1,3 +1,2 @@ include ../MatekL431/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Proximity" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Proximity/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Proximity/hwdef.dat index 1de33b5cec85c5..ccceb906eee656 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Proximity/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Proximity/hwdef.dat @@ -1,12 +1,11 @@ include ../MatekL431/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Proximity" - define HAL_USE_ADC FALSE define STM32_ADC_USE_ADC1 FALSE define HAL_DISABLE_ADC_DRIVER TRUE # support all proximity types +define HAL_PERIPH_ENABLE_PROXIMITY define HAL_PROXIMITY_ENABLED 1 define AP_PERIPH_PRX_PORT_DEFAULT 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-RC/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-RC/hwdef-bl.dat new file mode 100644 index 00000000000000..d394ea6a77af4f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-RC/hwdef-bl.dat @@ -0,0 +1 @@ +include ../MatekL431/hwdef-bl.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-RC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-RC/hwdef.dat new file mode 100644 index 00000000000000..693bb3f476f56e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-RC/hwdef.dat @@ -0,0 +1,27 @@ +include ../MatekL431/hwdef.inc + +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +define HAL_PERIPH_ENABLE_RCIN 1 +define AP_PERIPH_RC1_PORT_DEFAULT 2 + +# Added DMA for RC input +undef PB10 +undef PB11 +PB10 USART3_TX USART3 SPEED_HIGH +PB11 USART3_RX USART3 SPEED_HIGH + +# allow for 4 PWM outputs +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) + +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY + +# enable ESC control +define HAL_SUPPORT_RCOUT_SERIAL 1 +define HAL_WITH_ESC_TELEM 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef-bl.dat index ffb40904b014ac..b9005f84941a6a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef-bl.dat @@ -1,3 +1,2 @@ include ../MatekL431/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Rangefinder" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat index fa6f279544c522..0a2ddad9591362 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Rangefinder/hwdef.dat @@ -1,7 +1,5 @@ include ../MatekL431/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Rangefinder" - define HAL_USE_ADC FALSE define STM32_ADC_USE_ADC1 FALSE define HAL_DISABLE_ADC_DRIVER TRUE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-bdshot/hwdef-bl.dat index 8963039c763dec..b9005f84941a6a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-bdshot/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-bdshot/hwdef-bl.dat @@ -1,3 +1,2 @@ include ../MatekL431/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-BDShot" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef-bl.dat index 6c685fde904a0d..c4613198b0a12f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef-bl.dat @@ -70,6 +70,3 @@ define BOOTLOADER_BAUDRATE 57600 # use a small bootloader timeout define HAL_BOOTLOADER_TIMEOUT 1000 - - -define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L476" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat index 1d7e9c5203304f..8a9a640cc01b88 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat @@ -94,11 +94,6 @@ define HAL_NO_MONITOR_THREAD define AP_PARAM_MAX_EMBEDDED_PARAM 512 - - - -define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L476" - define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_GPS_PORT_DEFAULT 0 @@ -109,3 +104,5 @@ define HAL_I2C_INTERNAL_MASK 0 define HAL_PERIPH_ENABLE_BARO define HAL_PERIPH_ENABLE_AIRSPEED +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 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 4a4d40ff2f5b2f..8abcbbae533c4f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef-bl.dat @@ -76,6 +76,3 @@ define BOOTLOADER_BAUDRATE 57600 # use a small bootloader timeout define HAL_BOOTLOADER_TIMEOUT 1000 - - -define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L496" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat index a174b569ea6571..00a5622d58fd99 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat @@ -101,11 +101,6 @@ define HAL_NO_MONITOR_THREAD define AP_PARAM_MAX_EMBEDDED_PARAM 512 - - - -define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L496" - define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_BARO @@ -115,3 +110,6 @@ BARO MS56XX SPI:ms5611 BARO BMP388 I2C:0:0x76 # define HAL_SPI_CHECK_CLOCK_FREQ + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef.dat index 4e883079f346dd..9b4ce215a6e8fe 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/NucleoH755/hwdef.dat @@ -142,3 +142,6 @@ IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270 # compass as part of ICM20948 on newer cubes COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat index b0f5caad5968e3..d22ae701fddb04 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2/hwdef.dat @@ -127,7 +127,7 @@ define HAL_COMPASS_AUTO_ROT_DEFAULT 2 define HAL_PARACHUTE_ENABLED 0 # save FLASH, but leave above when flash issue is fixed -include ../include/minimize_features.inc +include ../include/minimize_fpv_osd.inc # disable SMBUS monitors to save flash undef AP_BATTERY_SMBUS_ENABLED @@ -136,7 +136,5 @@ define AP_BATTERY_SMBUS_ENABLED 0 # one baro BARO BMP280 SPI:bmp280 -undef OSD_ENABLED # minimize_features.inc removes this -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/PixC4-Jetson/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixC4-Jetson/hwdef.dat index b8016ac3ff4be0..311a727360e85a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixC4-Jetson/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixC4-Jetson/hwdef.dat @@ -34,9 +34,6 @@ STDOUT_BAUDRATE 57600 # USB setup USB_STRING_MANUFACTURER "Horizon31" -# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 - # now we define the pins that USB is connected on PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M-bdshot/hwdef.dat index c27099a3a78dc6..4d8bbdcf020fe1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M-bdshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-1M-bdshot/hwdef.dat @@ -38,3 +38,6 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES FLASH_SIZE_KB 1024 include ../include/minimize_features.inc undef STORAGE_FLASH_PAGE + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-bdshot/hwdef-bl.dat new file mode 100644 index 00000000000000..a71c921aa7f161 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1-bdshot/hwdef-bl.dat @@ -0,0 +1,4 @@ +# hw definition file for processing by chibios_hwdef.py +# for pixhawk1, based on fmuv3 + +include ../fmuv3/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/hwdef.dat index 59759bd34ae9cd..996a0a0dcd83e6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk1/hwdef.dat @@ -37,3 +37,7 @@ define HAL_PROBE_EXTERNAL_I2C_COMPASSES # produce this error if we are on a 1M board undef BOARD_CHECK_F427_USE_1M define BOARD_CHECK_F427_USE_1M "ERROR: 1M flash use Pixhawk1-1M" + +# enable support for dshot on iomcu +ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin +define HAL_WITH_IO_MCU_DSHOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat index b083f7afda6d92..0be4c176b5f2fe 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk5X/hwdef.dat @@ -25,9 +25,6 @@ env OPTIMIZE -O2 # order of UARTs (and USB) SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2 -# default the 2nd interface to MAVLink2 -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 - # default to all pins low to avoid ESD issues DEFAULTGPIO OUTPUT LOW PULLDOWN @@ -40,17 +37,22 @@ PA9 VBUS INPUT OPENDRAIN PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -# ethernet (not implemented yet) -#PA1 ETH_RMII_REF_CLK ETH -#PA2 ETH_MDIO ETH -#PA7 ETH_RMII_CRS_DV ETH -#PB11 ETH_RMII_TX_EN OUTPUT LOW -#PB13 ETH_RMII_TXD1 ETH -#PC1 ETH_MDC ETH -#PC4 ETH_RMII_RXD0 ETH -#PC5 ETH_RMII_RXD1 ETH -#PG15 ETH_PWR_EN OUTPUT LOW -#PG13 ETH_RMII_TXD0 ETH +# Ethernet +#PC1 ETH_MDC ETH1 +#PA2 ETH_MDIO ETH1 +#PC4 ETH_RMII_RXD0 ETH1 +#PC5 ETH_RMII_RXD1 ETH1 +#PG13 ETH_RMII_TXD0 ETH1 +#PB13 ETH_RMII_TXD1 ETH1 +#PB11 ETH_RMII_TX_EN ETH1 +#PA7 ETH_RMII_CRS_DV ETH1 +#PA1 ETH_RMII_REF_CLK ETH1 + +#PG15 GPIO_ETH_ENABLE OUTPUT HIGH GPIO(113) +#define HAL_GPIO_ETH_ENABLE 113 + +#define BOARD_PHY_ID MII_LAN8720_ID +#define BOARD_PHY_RMII # ADC PA0 SCALED1_V3V3 ADC1 SCALE(2) @@ -316,4 +318,7 @@ 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 -ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_f103_lowpolh.bin +# enable support for dshot on iomcu +ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin +define HAL_WITH_IO_MCU_DSHOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C-bdshot/defaults.parm index 311a84783e1d9b..d39cac82a5eae1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C-bdshot/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C-bdshot/defaults.parm @@ -1,5 +1 @@ -# setup correct defaults for battery monitoring for holybro power brick -BATT_MONITOR 4 - -BATT2_CURR_PIN 14 -BATT2_VOLT_PIN 5 +@include ../Pixhawk6C/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat index 7df2fad4234275..3103a5c72c75b1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat @@ -36,9 +36,6 @@ env OPTIMIZE -O2 # order of UARTs (and USB) SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 USART3 OTG2 -# default the 2nd interface to MAVLink2 -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 - # USB PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 @@ -257,4 +254,7 @@ 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 -ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_f103_lowpolh.bin +# enable support for dshot on iomcu +ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin +define HAL_WITH_IO_MCU_DSHOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat index 62d8cbc2f3c4b2..cd7183301b9570 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat @@ -31,9 +31,6 @@ env OPTIMIZE -O2 # order of UARTs (and USB) SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2 -# default the 2nd interface to MAVLink2 -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 - # default to all pins low to avoid ESD issues DEFAULTGPIO OUTPUT LOW PULLDOWN @@ -89,16 +86,22 @@ IOMCU_UART USART6 # PC7 USART6_RX USART6 # ethernet (not implemented yet) -#PA1 ETH_REF_CLK -#PA2 ETH_MDIO -#PA7 ETH_CRS_DV -#PB11 ETH_TX_EN -#PC1 ETH_MDC -#PC4 ETH_RXD0 -#PC5 ETH_RXD1 -#PG12 ETH_TXD1 -#PG13 ETH_TXD0 -#PG15 ETH_POWER_EN +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) @@ -223,7 +226,6 @@ PI11 VDD_3V3_SENSORS1_EN OUTPUT HIGH PF4 VDD_3V3_SENSORS2_EN OUTPUT HIGH PE7 VDD_3V3_SENSORS3_EN OUTPUT HIGH PG8 VDD_3V3_SENSORS4_EN OUTPUT HIGH -PG15 ETH_PWR_EN OUTPUT LOW # disable power on ethernet # start peripheral power off, then enable after init # this prevents a problem with radios that use RTS for @@ -354,7 +356,7 @@ 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 -ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin +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 @@ -363,3 +365,7 @@ ENABLE_DFU_BOOT 1 # 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_DSHOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef-bl.dat index af225d2434840d..6677e8a94bca6b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef-bl.dat @@ -50,8 +50,4 @@ PE15 MAG_CS CS PD0 CAN1_RX CAN1 PD1 CAN1_TX CAN1 -define CAN_APP_NODE_NAME "org.ardupilot.Pixracer-periph" - - - PB8 STAY_IN_BOOTLOADER INPUT FLOATING # if pulled low stay in bootloader diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat index 5b1a2781f978dc..7b4acfe486e4b1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixracer-periph/hwdef.dat @@ -51,9 +51,6 @@ define STM32_ADC_USE_ADC1 TRUE define HAL_DISABLE_ADC_DRIVER FALSE -define CAN_APP_NODE_NAME "org.ardupilot.Pixracer_periph" - - define AP_SCRIPTING_ENABLED 0 MAIN_STACK 0x2000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/README.md b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/README.md new file mode 100644 index 00000000000000..65abb3a33c91f5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/README.md @@ -0,0 +1,226 @@ +# QioTek AdeptF407 Flight Controller + +The Qiotek AdeptF407 an autopilot produced by [QioTek](https://www.qiotek.io). + +It is an autopilot used CKS MCU. + +## Features + - MCU: CKS32F407VGT6 + - Accelerometer/Gyro: ICM4 series/ICM2 series or ICM4 series/ICM4 series + - BEC output: 5V 3A for autopilot and peripheral hardware + - BEC output: 9V/12V 3A for camera and analog video transmission + - Barometer: DPS310 + - OSD: AT7456E + - builtin IST8310 magnetometer(internal I2C) + - builtin RAMTRON(SPI) + - 12 dedicated PWM/Capture inputs on FMU + - 5 UARTS: (USART1, USART2, USART3, UART4, USART7) + - 2 I2C ports + - 1 CAN port + - 2 Analog inputs of voltage / current for battery monitoring + - 2 analog video input channels + - 1 analog video output source switcher switching by relay5 + - 4 relays output control + - 1 Status LED + - 1 nARMED + +## Pinout +![QioTek AdpetF407 Board](../QioTekAdeptF407/adept_f407.jpg "QioTek AdpetF407") + +## Connectors + +**External USB** + +| Pin | Signal | Volt | +| :--: | :-----: | :---: | +| 1 | VCC | +5V | +| 2 | D+ | D_P | +| 3 | D- | D_N | +| 4 | GND | GND | + +**Telme1** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 | TX | +3.3V | +| 3 | RX | +3.3V | +| 4 | GND | GND | + +**Telme2** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 | TX | +3.3V | +| 3 | RX | +3.3V | +| 4 | NC | - - | +| 5 | NC | - - | +| 6 | GND | GND | + +**GPS1** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 | TX | +3.3V | +| 3 | RX | +3.3V | +| 4 | scl2 | +3.3V | +| 5 | sda2 | +3.3V | +| 6 | GND | GND | + +**GPS1** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 | TX | +3.3V | +| 3 | RX | +3.3V | +| 4 | scl2 | +3.3V | +| 5 | sda2 | +3.3V | +| 6 | GND | GND | + +**UART4 and UART5** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 | TX | +3.3V | +| 3 | RX | +3.3V | +| 4 | GND | GND | + +**CAN1** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 | CAN1_H | CAN_P | +| 3 | CAN1_L | CAN_N | +| 4 | GND | GND | + +**IIC1** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 | SDA1 | +3.3V | +| 3 | SCL1 | +3.3V | +| 4 | GND | GND | + +**Safety and buzzer** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC/3.3| +3.3V | +| 2 | VCC5 | +5V | +| 3 | Safety | +3.3V | +| 4 | LED | +3.3V | +| 5 | Buzzer | +3.3V | +| 6 | GND | GND | + +**VT Port** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | AV_OUT | +5V | +| 2 | S.AU ctrl. | +3.3V | +| 3 | 9V/12V | 9V/12V| +| 4 | GND | GND | + +**PWM11 and PWM12** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | PWM11 | +3.3V | +| 2 | GND | GND | +| 3 | PWM12 | +3.3V | +| 4 | GND | GND | + +**POWER1 and Power2** + +| Pin | Signal | Volt | +| :--: | :-------------: | :---: | +| 1 | VCC_IN | +5V | +| 2 | VCC_IN | +5V | +| 3 | BAT_CRRENT_ADC | +6.6V | +| 4 | BAT_VOLTAGE_ADC | +6.3V | +| 5 | GND | GND | +| 6 | GND | GND | + +**Battery Input** + +| Pin | Signal | Volt | +| :--: | :-------------: | :---: | +| 1 | Battery_VCC | MAX 30V | +| 2 | Battery_GND | 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|OTG1|USB| +|SERIAL1|TX6/RX6|UART1 (Telem1)| +|SERIAL2|TX3/RX3|UART2 (Telem2 buadrate 921600)| +|SERIAL3|TX1/RX1|UART3 (GNSS)| +|SERIAL4|TX4/RX4|UART4 (Reserve for GNSS2)| +|SERIAL5|TX2/RX2|UART5 (Debug)| + +## RC Input +RC input is configured on the RCIN pin by PA15 TIM2_CH1 TIM2 , at one end of the servo rail, marked RC in the above diagram. This pin supports PPM and S.Bus. protocols. + +## OSD Support + +QioTek AdpetF407 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The QioTek AdpetF407 AIO supports up to 12 PWM outputs. All 14 PWM outputs have GND on the top row, 5V on the middle row and signal on the bottom row. + +The 12 PWM outputs are in 3 groups: + +PWM 1 and 4 in group1 +PWM 4 and 8 in group2 +PWM 9 and 12 in group3 + +Channels within the same group need to use the same output rate. If any channel in a group uses DShot or then all channels in the group need to use DShot. + +## CAN Port + +The CAN port is disabled by default. Enable the CAN port setting the parameters CAN_P1_Driver to 1 (DroneCAN protocol). + +## 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 correct battery setting parameters are: + +BATT_VOLT_PIN 2 +BATT_CURR_PIN 3 +BATT_VOLT_MULT 20.000 +BATT_AMP_PERVLT 60.000 +BATT2_VOLT_PIN 14 +BATT2_CURR_PIN 15 +BATT2_VOLT_MULT 20.000 +BATT2_AMP_PERVLT 60.000 + +In addition, the builtin voltage divider circuit can be used by Solder pad to switching to share the battery voltage monitoring by power2 support to 6S. + +If you want to use the built-in voltage monitor on power 1, you can manually invert the BATT_ VOLT_ PIN to 14, BATT_ CURR_ PIN to 15, BATT2_ VOLT_ PIN to 2, BATT2_ CURR_ PIN to 3. + +**Built-in BEC** +The built-in BEC 5V output has a starting voltage of 2S, and 9V/12V has a starting voltage of 3S/4S respectively. + +## Compass + +The QioTek AdpetF407 has a builtin QMC5883 compass. Due to potential interference the board is usually used with an external I2C compass as part of a GPS/Compass combination. + +## 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. + +The AdeptF407 auto pilot pre-installed with an ArduPilot compatible bootloader. +Updates should be done with the *.apj firmware files. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/defaults.parm new file mode 100644 index 00000000000000..fc20ce10087e45 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/defaults.parm @@ -0,0 +1,23 @@ +# setup serial2 port defaults for ESP8266 +SERIAL2_BAUD 921 + +# setup the parameter for the ADC power module +BATT_VOLT_PIN 2 +BATT_CURR_PIN 3 +BATT_VOLT_MULT 20.000 +BATT_AMP_PERVLT 60.000 +BATT2_VOLT_PIN 14 +BATT2_CURR_PIN 15 +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 + +# Disable the safety switch by default +BRD_SAFETY_DEFLT 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef-bl.dat new file mode 100644 index 00000000000000..993f7476fbf2ea --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef-bl.dat @@ -0,0 +1,47 @@ +# hw definition file for processing by chibios_hwdef.py +# for for QioTekAdeptF407 hardware bootloader from Qio-tek.com + +MCU CKS32F4xx CKS32F407xx + +APJ_BOARD_ID 1065 + +OSCILLATOR_HZ 8000000 + +STM32_ST_USE_TIMER 5 + +# flash size +FLASH_SIZE_KB 1024 +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 16 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART6 + +PE15 LED_BOOTLOADER OUTPUT +PE12 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 + +# USART6 +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA + +#define BOOTLOADER_DEBUG SD6 + +# Add CS pins to ensure they are high in bootloader +PD3 IMU1_CS CS +PD4 IMU2_CS CS +PD7 IMU3_CS CS +PB3 Baro1_CS CS +PE4 Baro2_CS CS +PE6 AT7453_CS CS +PC13 FRAM_CS CS SPEED_VERYLOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef.dat new file mode 100644 index 00000000000000..539567b8eb4d56 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef.dat @@ -0,0 +1,201 @@ +# hw definition file for processing by chibios_hwdef.py +# for QioTekZealotF407 hardware from Qio-tek.com + +# MCU class and specific type +MCU CKS32F4xx CKS32F407xx + +# board ID for firmware load +APJ_BOARD_ID 1065 + +FLASH_SIZE_KB 1024 + +# reserve 16k for bootloader +FLASH_RESERVE_START_KB 16 + +# USB setup +USB_STRING_MANUFACTURER "Qiotek" + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# this is the pin that senses USB being connected. It is an input pin +# setup as OPENDRAIN +PA9 VBUS INPUT OPENDRAIN + +# The normal usage of this ordering is: +# 1) SERIAL0: console (primary mavlink, usually USB) +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 (recommend ESP8266) +# 4) SERIAL3: primary GPS +# 5) SERIAL4: telem3 or GPS2 +# 6) SERIAL5: extra UART or sbus output (usually RTOS debug console) + +SERIAL_ORDER OTG1 USART6 USART3 USART1 UART4 USART2 + +# UART3 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +# USART2 for Mavlink2 wifi module set baudrate to 921600 +PD5 USART2_TX USART2 NODMA +PD6 USART2_RX USART2 + +# USART1 for gps1 +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 + +# UART4 +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA + +# USART6 +PC6 USART6_TX USART6 NODMA +PC7 USART6_RX USART6 NODMA + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +# SPI1 for IMU Baro OSD +PA5 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PB5 SPI1_MOSI SPI1 +PD3 IMU1_CS CS +PD4 IMU2_CS CS +PD7 IMU3_CS CS +PB3 Baro1_CS CS +PE4 Baro2_CS CS +PE6 AT7456_CS CS + +# SPI bus for dataflash +PB13 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 +PC13 FRAM_CS CS SPEED_VERYLOW + +# SPI devices +SPIDEV imu1 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ +SPIDEV imu2 SPI1 DEVID2 IMU2_CS MODE3 2*MHZ 8*MHZ +SPIDEV imu3 SPI1 DEVID3 IMU3_CS MODE3 2*MHZ 8*MHZ +SPIDEV baro1 SPI1 DEVID2 Baro1_CS MODE3 5*MHZ 5*MHZ +SPIDEV baro2 SPI1 DEVID1 Baro2_CS MODE3 5*MHZ 5*MHZ +SPIDEV osd SPI1 DEVID2 AT7456_CS MODE0 10*MHZ 10*MHZ +SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE0 8*MHZ 8*MHZ + +# four IMUs, adi16740 is used, then imu3 will be removed +IMU Invensensev3 SPI:imu1 ROTATION_NONE +IMU Invensensev3 SPI:imu2 ROTATION_NONE +IMU Invensense SPI:imu2 ROTATION_PITCH_180 + +# two Baro sensors +BARO DPS280 SPI:baro1 +#BARO DPS280 SPI:baro2 + +# define the pins for the microSD card. +PC8 SDIO_D0 SDIO +PC9 SDIO_D1 SDIO +PC10 SDIO_D2 SDIO +PC11 SDIO_D3 SDIO +PC12 SDIO_CK SDIO +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 +PB9 I2C1_SDA I2C1 +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# look for I2C compass +COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180 +COMPASS QMC5883L I2C:0:0x0D false ROTATION_ROLL_180 +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 1 + +# PWM out pins +PA6 TIM3_CH1 TIM3 PWM(1) GPIO(50) +PA7 TIM3_CH2 TIM3 PWM(2) GPIO(51) +PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52) +PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) +PE9 TIM1_CH1 TIM1 PWM(5) GPIO(54) +PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55) +PE13 TIM1_CH3 TIM1 PWM(7) GPIO(56) +PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57) + +PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58) +PD13 TIM4_CH2 TIM4 PWM(10) GPIO(59) +PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60) +PD15 TIM4_CH4 TIM4 PWM(12) GPIO(61) + +PE7 EXTERN_GPIO1 OUTPUT GPIO(1) +PE8 EXTERN_GPIO2 OUTPUT GPIO(2) +PE2 EXTERN_GPIO3 OUTPUT GPIO(3) +PE3 EXTERN_GPIO4 OUTPUT GPIO(4) +PE1 EXTERN_GPIO5 OUTPUT GPIO(5) +PE0 EXTERN_GPIO6 OUTPUT GPIO(6) + +# also USART6_RX for serial RC +PA15 TIM2_CH1 TIM2 RCININT PULLDOWN LOW + +# LED setup is similar to PixRacer +define HAL_HAVE_PIXRACER_LED +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 HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +# analog in 6.6V +PC1 ADC_1 ADC1 SCALE(2) + +# define the primary battery connectors. +PA3 BATT_CURRENT_SENS ADC1 SCALE(2) +PA2 BATT_VOLTAGE_SENS ADC1 SCALE(2) +PC5 BATT2_CURRENT_SENS ADC1 SCALE(2) +PC4 BATT2_VOLTAGE_SENS ADC1 SCALE(2) +PA4 VDD_5V_SENS ADC1 SCALE(2) +PC0 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(12) + +#PB2 HEATER_EN OUTPUT LOW GPIO(5) +#define HAL_HEATER_GPIO_PIN 5 +#define HAL_IMU_TEMP_DEFAULT 45 + +define HAL_HAVE_SAFETY_SWITCH 1 +PB15 LED_SAFETY OUTPUT +PB12 SAFETY_IN INPUT PULLDOWN +PB14 TIM12_CH1 TIM12 ALARM + +# enable RAMTROM parameter storage +define HAL_WITH_RAMTRON 1 +define HAL_STORAGE_SIZE 16384 + +# --------------------- save flash ---------------------- +include ../include/minimize_features.inc +include ../include/minimal.inc + +# setup for OSD +undef OSD_ENABLED +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font1.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat index 64091a94ba84ff..c12e1e86545bdb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotF427/hwdef.dat @@ -196,7 +196,7 @@ PB1 BATT2_VOLTAGE_SENS ADC1 SCALE(2) PC4 VDD_5V_SENS ADC1 SCALE(2) PC5 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(12) -define HAL_BATT_MONITOR 4 +define HAL_BATT_MONITOR_DEFAULT 4 define HAL_BATT_VOLT_PIN 13 define HAL_BATT_CURR_PIN 12 define HAL_BATT_VOLT_SCALE 20 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat index e0a64a8b8b008e..250e4b5be1c039 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/QioTekZealotH743/hwdef.dat @@ -135,7 +135,7 @@ PC5 PRESSURE_SENS ADC1 SCALE(2) PB1 RSSI_IN ADC1 SCALE(2) # setup the parameter for the ADC power module -define HAL_BATT_MONITOR 4 +define HAL_BATT_MONITOR_DEFAULT 4 define HAL_BATT_VOLT_PIN 16 define HAL_BATT_CURR_PIN 17 define HAL_BATT_VOLT_SCALE 20.000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/defaults.parm index a3dcf5c5183438..b6cc0c5e93623a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/defaults.parm @@ -9,5 +9,8 @@ SERIAL1_PROTOCOL 42 # GPS on UART2 SERIAL2_PROTOCOL 5 +# ESC Telemetry on UART4 +SERIAL4_PROTOCOL 16 + # 9V regulator switch, ON on boot RELAY_DEFAULT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/hwdef.dat index 145a8d721067ce..bec3360b7872db 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/RADIX2HD/hwdef.dat @@ -173,3 +173,6 @@ DMA_PRIORITY SPI1* DMA_NOSHARE SPI1* TIM1* TIM2* TIM3* TIM4* NODMA I2C* define STM32_I2C_USE_DMA FALSE + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/README.md new file mode 100644 index 00000000000000..5f685d38a417d4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/README.md @@ -0,0 +1,403 @@ +# SIYI N7 Flight Controller + +The SIYI N7 flight controller is sold by a range of +resellers, linked from https://siyi.biz + +## Features + + - STM32H743 microcontroller + - ICM20689 and BMI088 IMUs + - internal heater for IMU temperature control + - internal vibration isolation for IMUs + - MS5611 SPI barometer + - builtin IST8310 compass + - microSD card slot + - 4 UARTs plus USB + - 13 PWM outputs + - I2C and CAN ports + - RCIN port + - external safety Switch + - voltage monitoring for servo rail and Vcc + - power input port for external power bricks + +## Pinout + +## UART Mapping + + - SERIAL0 -> USB + - SERIAL1 -> UART2 (Telem1) + - SERIAL2 -> unused + - SERIAL3 -> UART1 (GPS) + - SERIAL4 -> UART4 (GPS2, Telem4/I2C) + - SERIAL5 -> unused + - SERIAL6 -> UART7 (debug port) + - SERIAL7 -> USB2 (virtual port on same connector) + +The Telem1 port has RTS/CTS pins, the other UARTs do not have RTS/CTS. + +## Connectors + +Unless noted otherwise all connectors are JST GH + +### TELEM1 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal Volt
1 (red)VCC+5V
2 (blk)TX (OUT)+3.3V
3 (blk)RX (IN)+3.3V
4 (blk)CTS+3.3V
5 (blk)RTS+3.3V
6 (blk)GNDGND
+ + +### GPS1 port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1 (red)VCC+5V
2 (blk)TX (OUT)+3.3V
3 (blk)RX (IN)+3.3V
4 (blk)SCL I2C1+3.3V
5 (blk)SDA I2C1+3.3V
6 (blk)ButtonGND
7 (blk)button LEDGND
8 (blk)3.3V3.3
9 (blk)buzzerGND
(blk)GNDGND
+ + + +### GPS2, Telem4/I2C port + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1 (red)VCC+5V
2 (blk)TX (OUT)+3.3V
3 (blk)RX (IN)+3.3V
4 (blk)SCL I2C2+3.3V
5 (blk)SDA I2C2+3.3V
6 (blk)GNDGND
+ +### I2C + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1 (red)VCC+5V
2 (blk)SCL+3.3 (pullups)
3 (blk)SDA+3.3 (pullups)
4 (blk)GNDGND
+ + +### CAN1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1 (red)VCC+5V
2 (blk)CAN_H+12V
3 (blk)CAN_L+12V
4 (blk)GNDGND
+ + +### POWER1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1 (red)VCC+5V
2 (red)VCC+5V
3 (blk)CURRENTup to +3.3V
4 (blk)VOLTAGEup to +3.3V
5 (blk)GNDGND
6 (blk)GNDGND
+ + +### USB + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal Volt
1 (red)VCC+5V
2 (blk)D_minus+3.3V
3 (blk)D_plus+3.3V
4 (blk)GNDGND
+ +## RC Input + +RC input is configured on the RCIN pin, at one end of the servo rail, +marked RCIN in the above diagram. This pin supports all RC +protocols. + +## PWM Output + +The SIYI N7 supports up to 13 PWM outputs. First first 8 outputs +(labelled "MAIN") are controlled by a dedicated STM32F103 IO +controller. These 8 outputs support all PWM output formats, but not +DShot. + +The remaining 5 outputs (labelled AUX1 to AUX5) are the "auxiliary" +outputs. These are directly attached to the STM32H743 and support all +PWM protocols as well as DShot. + +All 13 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 4 auxiliary PWM outputs are in 2 groups: + + - PWM 1, 2, 3 and 4 in group4 + - PWM 5 in group5 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. + +## Battery Monitoring + +The board has a dedicated power monitor ports on a 6 pin +connector. The correct battery setting parameters are dependent on +the type of power brick which is connected. + +## Compass + +The SIYI N7 has one builtin IST8310 compass. + +## GPIOs + +The 5 AUX PWM ports can be used as GPIOs (relays, buttons, RPM etc). + +The numbering of the GPIOs for PIN variables in ArduPilot is: + + - PWM1 50 + - PWM2 51 + - PWM3 52 + - PWM4 53 + - PWM5 54 + +## Analog inputs + +The SIYI N7 has 7 analog inputs + + - ADC Pin16 -> Battery Voltage + - ADC Pin17 -> Battery Current Sensor + +## IMU Heater + +The IMU heater in the SIYI N7 can be controlled with the +BRD_HEAT_TARG parameter, which is in degrees C. + +## 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/SIYI_N7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef-bl.dat new file mode 100644 index 00000000000000..1bb63bfab13d71 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef-bl.dat @@ -0,0 +1,46 @@ +# 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 1123 + +# 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 + +PB1 LED_RED OUTPUT LOW # red +PC6 LED_ACTIVITY OUTPUT LOW # green +PC7 LED_BOOTLOADER OUTPUT LOW # blue +define HAL_LED_ON 0 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 UART7 + +# UART7 is debug +PF6 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# pullup buzzer for no sound in bootloader +PE5 BUZZER OUTPUT LOW PULLDOWN + +# Add CS pins to ensure they are high in bootloader +PF10 MS5611_CS CS +PF2 ICM20689_CS CS +PF4 BMI055_G_CS CS +PG10 BMI055_A_CS CS +PF5 FRAM_CS CS SPEED_VERYLOW diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat new file mode 100644 index 00000000000000..459db8cdfe7af5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat @@ -0,0 +1,239 @@ +# hw definition file for processing by chibios_hwdef.py + +DEFAULTGPIO OUTPUT LOW PULLDOWN + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1123 + +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 UARTs (and USB) +SERIAL_ORDER OTG1 USART2 EMPTY USART1 UART4 EMPTY UART7 OTG2 + +# default the 2nd interface to MAVLink2 +define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 + +define HAL_STORAGE_SIZE 32768 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# debug pins +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 - internal sensors +PG11 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI2 - FRAM +PI1 SPI2_SCK SPI2 +PI2 SPI2_MISO SPI2 +PI3 SPI2_MOSI SPI2 + +# SPI4 - sensors2 +PE2 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# sensor CS +PF10 MS5611_CS CS +PF2 ICM20689_CS CS +PF4 BMI088_G_CS CS +PG10 BMI088_A_CS CS +PF5 FRAM_CS CS SPEED_VERYLOW + +# I2C buses + +# I2C1 is on GPS port +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# I2C on uart4 connector +PF1 I2C2_SCL I2C2 +PF0 I2C2_SDA I2C2 + +# I2C for onboard mag +PH7 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +# I2C4 is on external2 +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C3 I2C1 I2C2 I2C4 + +define HAL_I2C_INTERNAL_MASK 1 + +# enable pins +PE3 VDD_3V3_SENSORS_EN OUTPUT LOW +PG7 VDD_3V3_SD_CARD_EN OUTPUT HIGH + +# drdy pins +PB4 DRDY_ICM20689 INPUT +PB14 DRDY_BMI088_GYRO INPUT +PB15 DRDY_BMI088_ACC INPUT + +PD15 DRDY7_EXTERNAL INPUT + +# UARTs + +# USART2 is telem1 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# USART1 is GPS1 +PB7 USART1_RX USART1 NODMA +PB6 USART1_TX USART1 NODMA + +# UART4 GPS2 +PD0 UART4_RX UART4 NODMA +PD1 UART4_TX UART4 NODMA + +# UART7 is debug +PF6 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +# UART8 is for IOMCU +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# UART for IOMCU +IOMCU_UART UART8 + +# PWM AUX channels +PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) +PA10 TIM1_CH3 TIM1 PWM(2) GPIO(51) +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) +PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) + +# PWM output for buzzer +PE5 TIM15_CH1 TIM15 GPIO(77) ALARM + +# analog in +PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PA1 BATT_CURRENT_SENS ADC1 SCALE(1) + +PC0 VDD_5V_SENS ADC1 SCALE(2) +PC1 SCALED_V3V3 ADC1 SCALE(2) + +# voltage divider 1/(16.9/(33+16.9)) +define HAL_IOMCU_VSERVO_SCALAR 1 / (16.9 / (33 + 16.9)) + +# CAN bus +PI9 CAN1_RX CAN1 +PH13 CAN1_TX CAN1 + +PH2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) + +# GPIOs +PA7 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 + +define HAL_HAVE_IMU_HEATER 1 +define HAL_IMU_TEMP_DEFAULT 45 + +PH5 AUX_CS CS + +PG1 VDD_BRICK_nVALID INPUT PULLUP +PG2 VDD_BRICK2_nVALID INPUT PULLUP +PA9 VBUS INPUT +PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP +PE15 VDD_5V_PERIPH_nOC INPUT PULLUP +PB10 nSPI5_RESET_EXTERNAL OUTPUT HIGH + +# SPI devices +SPIDEV ms5611 SPI4 DEVID1 MS5611_CS MODE3 20*MHZ 20*MHZ +SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ +SPIDEV bmi088_g SPI1 DEVID3 BMI088_G_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_a SPI1 DEVID4 BMI088_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ + +# Two IMUs +IMU Invensense SPI:icm20689 ROTATION_NONE +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_ROLL_180_YAW_90 + +define HAL_DEFAULT_INS_FAST_SAMPLE 3 + +# 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 +PB1 LED_RED OUTPUT GPIO(90) + +# green LED +PC6 LED_GREEN OUTPUT GPIO(91) LOW + +# blue LED +PC7 LED_BLUE OUTPUT GPIO(92) HIGH + +# setup for 2 LEDs +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 +define HAL_WITH_RAMTRON 1 + +# safety switch pin +PE10 LED_SAFETY OUTPUT +PE12 SAFETY_IN INPUT PULLDOWN +define HAL_HAVE_SAFETY_SWITCH 1 + +# one baro +BARO MS56XX SPI:ms5611 + +# one builtin compass, plus one on the default GPS that is external with +# a non-default orientation +COMPASS IST8310 I2C:0:0x0e false ROTATION_PITCH_180_YAW_270 + +define AP_COMPASS_IST8310_DEFAULT_ROTATION ROTATION_PITCH_180_YAW_270 + +# compensate for magnetic field generated by the heater on the internal IST8310 +define HAL_HEATER_MAG_OFFSET {AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_I2C,0,0xe,0x0a),Vector3f(15,35,-6)} + +# also probe for external compasses +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +# don't share IOMCU DMA +DMA_NOSHARE UART8* SPI1* TIM*UP* + +DMA_PRIORITY UART8* ADC* SPI1* + +# battery setup +define HAL_BATT_MONITOR_DEFAULT 4 +define HAL_BATT_VOLT_PIN 16 +define HAL_BATT_CURR_PIN 17 +define HAL_BATT_VOLT_SCALE 18.182 +define HAL_BATT_CURR_SCALE 36.364 + +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/README.md index f31370c7e9ce01..4c848bb09a2b39 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/README.md @@ -1,23 +1,30 @@ -# Serious Pro Racing H6 Extreme Flight Controller +# Serious Pro Racing H7 RF Flight Controller -The SPRacingH7 Extreme is a flight controller produced by [Seriously Pro Racing](http://www.seriouslypro.com/). +The SPRacingH7 RF Extreme is a flight controller produced by [Seriously Pro Racing](http://www.seriouslypro.com/). + +![SPRacingH7 RF Top](spracingh7rf.jpg "SPRacingH7-top") ## Features - - MCU - STM32H750 32-bit processor running at 400 MHz - - 16MByte Serial NOR flash via QuadSPI - - IMUs - 2x ICM20602 + - MCU - STM32H730 32-bit processor running at 520 MHz + - 2MByte Serial NOR flash via QuadSPI for firmware + - IMUs - ICM42688 - Barometer - BMP388 - - OSD - AT7456E + - OSD - Pixel, not supported currently by ArduPilot + - I2C port - Onboard Flash: 128Mbits - - 7x UARTs (1,2,3,4,5,6,8) - - 11x PWM Outputs (10 Motor Output, 1 LED) - - Battery input voltage: 2S-6S - - BEC 5V 1A + - Integrated ELRS receiver, not supported currently by ArduPilot + - microSD card socket + - 5x UARTs (2,3,4,5,8) + - 9x PWM Outputs (8 Motor Output, 1 LED) + - Battery input voltage: 2S-8S + - BEC 5V ?A ## Pinout -![SPRacingH7 Board](SPRacingH7_Board.JPG "SPRacingH7") +![SPRacingH7 RF Top](spracingh7rf_top.jpg "SPRacingH7-top") +![SPRacingH7 RF Bottom](spracingh7rf_bottom.jpg "SPRacingH7-bottom") +![SPRacingH7 RF onnectors](spracingh7rf_connectors.jpg "SPRacingH7-connectors") ## UART Mapping @@ -25,67 +32,65 @@ The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the receive pin for UARTn. The Tn pin is the transmit pin for UARTn. - SERIAL0 -> USB - - SERIAL1 -> UART1 (DMA-enabled) - - SERIAL2 -> UART2 (RCIN one wire, DMA-enabled) - - SERIAL3 -> UART3 (DMA-enabled) - - SERIAL4 -> UART4 (DMA-enabled) - - SERIAL5 -> UART5 (DMA-enabled) - - SERIAL6 -> UART6 (On motor pads 7/8, with alt config 1, DMA-enabled) - - SERIAL8 -> UART8 (DMA-enabled) + - SERIAL2 -> UART2 (RC input) + - SERIAL3 -> UART3 (DJI) + - SERIAL4 -> UART4 (GPS) + - SERIAL5 -> UART5 (ESC Telemetry, RX only) + - SERIAL8 -> UART8 (USER) + + All UARTS are DMA capable ## RC Input -RC input is configured on the T2 (UART2_TX) pin. It supports all serial RC -protocols. For protocols requiring half-duplex serial to transmit +Ardupilot does not currently support the integrated ELRS chip. + +RC input is configured on the R2 pin. It supports all serial RC +protocols. PPM is not supoorted. For protocols requiring half-duplex serial to transmit telemetry (such as FPort) you should setup SERIAL2 as an RC input serial port, -with half-duplex, pin-swap and inversion enabled. - -## FrSky Telemetry +with half-duplex, pin-swap and inversion enabled. For duplex protocols, like CRSF/ELRS, T2 must also be connected to the receiver. -FrSky Telemetry is supported using the T2 pin (UART2 transmit). You need to set the following parameters to enable support for FrSky S.PORT - - - SERIAL2_PROTOCOL 10 - - SERIAL2_OPTIONS 7 -## OSD Support +## Pixel OSD Support -The SPRacingH7 supports OSD using OSD_TYPE 1 (MAX7456 driver). +Ardupilot does not currently support the integrated OSD chip. UART3 is setup fir use with DisplayPort goggles with OSD. ## PWM Output -The SPRacingH7 supports up to 11 PWM outputs. The pads for motor output -M1 to M4 on the motor connectors and M5 to M8 on separate pads, plus -M11 for LED strip or another PWM output. M9 and M10 are only available on the stacking connector. +The SPRacingH7 RF supports up to 9 PWM outputs. PWM 1-8 support DShot and Bi-Directional DShot. The pads for motor output +M1 to M4 on ESC connector 1, and M5 to M8 on ESC connector 2, plus +M9 for LED strip or another PWM output. The PWM is in 5 groups: - PWM 1-4 in group1 - - PWM 5, 6 in group2 - - PWM 7, 8 in group3 - - PWM 9, 10 in group4 - - PWM 11 in group5 + - PWM 5-8 in group2 + - PWM 9 (LED) in group3 + Channels within the same group need to use the same output rate. If any channel in a group uses DShot then all channels in the group need -to use DShot. Channels 1-4 support bi-directional dshot. +to use 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 +The board has a built-in voltage sesnor and current sensor input from the ESC connectors. 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_PIN 13 - BATT_CURR_PIN 11 - - BATT_VOLT_MULT 11.1 - - BATT_AMP_PERVLT 59.5 + - BATT_VOLT_MULT 10.9 + - BATT_AMP_PERVLT 28.5 (will need adjustment for the current sensor range of the ESC) ## Compass -The SPRacingH7 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. +The SPRacingH7 RF does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## User Manual + +http://seriouslypro.com/files/SPRacingH7RF-Manual-latest.pdf ## Loading Firmware diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/SPRacingH7_Board.JPG b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/SPRacingH7_Board.JPG deleted file mode 100644 index bde98e1a7b5df9..00000000000000 Binary files a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/SPRacingH7_Board.JPG and /dev/null differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/defaults.parm index 39cc0c6d2e3d9b..1515538fc9c221 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/defaults.parm @@ -5,6 +5,13 @@ NTF_LED_TYPES 257 # setup SERIAL2 for RCIN SERIAL2_BAUD 115 SERIAL2_OPTIONS 8 +SERIAL2_PROTOCOL 23 # pinswap UART5 for ESC telemetry SERIAL5_OPTIONS 8 +SERIAL5_PRTOCOL 16 + +# setup SERIAL3 for DJI +SERIAL3_PROTOCOL 42 +OSD_ENABLED 1 +OSD_TYPE 5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf.jpg b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf.jpg new file mode 100644 index 00000000000000..98a9611e1579d9 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf_bottom.jpg b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf_bottom.jpg new file mode 100644 index 00000000000000..cd2bc9b772ac3c Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf_bottom.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf_connectors.jpg b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf_connectors.jpg new file mode 100644 index 00000000000000..0338f16813e34e Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf_connectors.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf_top.jpg b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf_top.jpg new file mode 100644 index 00000000000000..acc4c0f8599aa2 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SPRacingH7RF/spracingh7rf_top.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/L4R5-24MHz/L4R5-24MHz.ioc b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/L4R5-24MHz/L4R5-24MHz.ioc old mode 100755 new mode 100644 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/L4R5-8MHz/L4R5-8MHz.ioc b/libraries/AP_HAL_ChibiOS/hwdef/STM32CubeConf/L4R5-8MHz/L4R5-8MHz.ioc old mode 100755 new mode 100644 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef-bl.dat index 20b703dfa6f94d..a4581750c5fb3f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef-bl.dat @@ -50,11 +50,6 @@ PA14 JTCK-SWCLK SWD PA11 CAN1_RX CAN1 PA12 CAN1_TX CAN1 -define HAL_USE_CAN TRUE -define STM32_CAN_USE_CAN1 TRUE - -define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F405" - # use DNA define HAL_CAN_DEFAULT_NODE_ID 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat index 4492d3d06144f4..fd75416be1b5ce 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F405/hwdef.dat @@ -67,8 +67,6 @@ CAN_ORDER 1 # use DNA for node allocation -define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F405" - # order of UARTs SERIAL_ORDER USART1 EMPTY EMPTY USART2 @@ -131,3 +129,5 @@ define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 define DEFAULT_NTF_LED_TYPES 455 +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef-bl.dat index d5553d7573ec60..e0a5ef36a73416 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef-bl.dat @@ -47,11 +47,6 @@ PA14 JTCK-SWCLK SWD PA11 CAN1_RX CAN1 PA12 CAN1_TX CAN1 -define HAL_USE_CAN TRUE -define STM32_CAN_USE_CAN1 TRUE - -define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F412" - # use DNA define HAL_CAN_DEFAULT_NODE_ID 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat index 729070cb71983b..1e8df2f261288c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F412/hwdef.dat @@ -98,7 +98,6 @@ PA12 CAN1_TX CAN1 # use DNA define HAL_CAN_DEFAULT_NODE_ID 0 -define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F412" define HAL_NO_MONITOR_THREAD define HAL_BUILD_AP_PERIPH @@ -134,3 +133,5 @@ PC7 M9SB INPUT define DEFAULT_NTF_LED_TYPES 455 +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef-bl.dat index 84bc95a9d6385c..bcb61628a18c66 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef-bl.dat @@ -59,10 +59,6 @@ define HAL_DISABLE_LOOP_DELAY PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -define HAL_USE_CAN TRUE -define STM32_CAN_USE_CAN1 TRUE - -define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F9P" # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat index ecb05e70795232..e8096fd5c1c4fc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-F9P/hwdef.dat @@ -108,8 +108,6 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F9P" - define HAL_NO_MONITOR_THREAD define HAL_BUILD_AP_PERIPH define HAL_DEVICE_THREAD_STACK 768 @@ -133,6 +131,7 @@ define GPS_MOVING_BASELINE 1 # Logging define HAL_LOGGING_ENABLED 1 +define HAL_PERIPH_ENABLE_RTC 1 define HAL_OS_FATFS_IO 1 # SD Card pins @@ -152,3 +151,6 @@ define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 #Sensors Enable & ESP Enable PB0 VDD_3V3_SENSORS_EN OUTPUT HIGH PC2 ESP_PWR_EN OUTPUT LOW + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef-bl.dat index ca62f80361ce88..43e872faa1b65a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef-bl.dat @@ -67,7 +67,5 @@ define BOOTLOADER_BAUDRATE 57600 # use a small bootloader timeout define HAL_BOOTLOADER_TIMEOUT 1000 -define CAN_APP_NODE_NAME "org.ardupilot.Sierra-L431" - # Add CS pins to ensure they are high in bootloader PB12 MAG_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat index 1b3f6a787dda02..c156bdaf2a5e0e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-L431/hwdef.dat @@ -99,8 +99,6 @@ define HAL_NO_MONITOR_THREAD define HAL_NO_LOGGING define AP_PARAM_MAX_EMBEDDED_PARAM 512 -define CAN_APP_NODE_NAME "org.ardupilot.Sierra-L431" - define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_AIRSPEED define AIRSPEED_MAX_SENSORS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/defaults.parm new file mode 100644 index 00000000000000..874095e8452e54 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/defaults.parm @@ -0,0 +1,5 @@ +# setup for NeoPixels +OUT1_FUNCTION 120 +NTF_LED_TYPES 512 +NTF_LED_BRIGHT 3 +NTF_LED_LEN 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef-bl.dat new file mode 100644 index 00000000000000..504e00a4885a2f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef-bl.dat @@ -0,0 +1,90 @@ +# hw definition file for processing by chibios_pins.py + +# Sierra-PrecisionPoint + +# MCU class and specific type +MCU STM32F4xx STM32F412Rx + +FLASH_RESERVE_START_KB 0 + +# two sectors for bootloader, two for storage +FLASH_BOOTLOADER_LOAD_KB 64 + +# board ID for firmware load +APJ_BOARD_ID 1095 + +# 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 + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +# USB +PA11 USB_FS_DM OTG1 +PA12 USB_FS_DP OTG1 +PA9 VBUS INPUT OPENDRAIN + +# USB setup +USB_STRING_MANUFACTURER "Sierra Aerospace" +USB_STRING_PRODUCT "Sierra-PrecisionPoint-BL" + +# workaround missing define in headers +define RCC_AHB1RSTR_OTGHRST 0x20000000 + +# order of UARTs +SERIAL_ORDER OTG1 USART1 + +# 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 FALSE +define STM32_SERIAL_USE_USART3 FALSE + +define HAL_NO_GPIO_IRQ +define HAL_USE_EMPTY_IO TRUE +define DMA_RESERVE_SIZE 0 +define HAL_DISABLE_LOOP_DELAY + +# avoid timer and RCIN threads to save memory +define HAL_NO_TIMER_THREAD +define HAL_NO_RCIN_THREAD + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PB13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PB14 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW + +define CAN_APP_NODE_NAME "in.sierraaerospace.PrecisionPoint" + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 1000 + +# Add CS pins to ensure they are high in bootloader +PC0 RM3100_CS CS +PC1 DPS310_CS CS +Pc4 ICM42688_CS CS + +# USB select +PC6 USB_SEL OUTPUT PUSHPULL SPEED_LOW HIGH + +PB12 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat new file mode 100644 index 00000000000000..70fe852ca5b51c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-PrecisionPoint/hwdef.dat @@ -0,0 +1,146 @@ +# hw definition file for processing by chibios_pins.py + +# Sierra-PrecisionPoint + +# MCU class and specific type +MCU STM32F4xx STM32F412Rx + +# bootloader starts firmware at 64k +FLASH_RESERVE_START_KB 64 + +# store parameters in pages 2 and 3 +STORAGE_FLASH_PAGE 2 +define HAL_STORAGE_SIZE 8192 + +# board ID for firmware load +APJ_BOARD_ID 1095 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +STM32_ST_USE_TIMER 5 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# assume 512k flash part +FLASH_SIZE_KB 512 + +# USB +PA11 USB_FS_DM OTG1 +PA12 USB_FS_DP OTG1 +PA9 VBUS INPUT OPENDRAIN + +# USB setup +USB_STRING_MANUFACTURER "Sierra Aerospace" +USB_STRING_PRODUCT "Sierra-PrecisionPoint" + +# order of UARTs +SERIAL_ORDER OTG1 USART1 USART2 + +# USART1 for debug +PB6 USART1_TX USART1 NODMA +PB7 USART1_RX USART1 NODMA + +# USART2 for GPS +PA2 USART2_TX USART2 SPEED_HIGH +PA3 USART2_RX USART2 SPEED_HIGH + +# GPS on 2nd port +define HAL_PERIPH_GPS_PORT_DEFAULT 1 + +# SWD debugging +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# Add CS pins +PC0 RM3100_CS CS +PC1 DPS310_CS CS +PC4 ICM42688_CS CS + +# --------------------- SPI1 ICM42688 ----------------------- +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PC5 ICM42688_DRDY INPUT + +SPIDEV icm42688 SPI1 DEVID1 ICM42688_CS MODE3 2*MHZ 8*MHZ +IMU Invensensev3 SPI:icm42688 ROTATION_YAW_90 + +# SPI1 FSYNC for ICM42688p +# PB0 TIM3_CH3 TIM3 + +# --------------------- SPI2 DPS310+RM3100 ----------------------- +PB10 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 + +# Baro probe +SPIDEV dps310 SPI2 DEVID2 DPS310_CS MODE3 5*MHZ 5*MHZ +BARO DPS310 SPI:dps310 + +# Mag probe +SPIDEV rm3100 SPI2 DEVID1 RM3100_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180 +# define AP_RM3100_REVERSAL_MASK 7 + +# WS2812 LEDs +PA15 TIM2_CH1 TIM2 PWM(1) + +# Board voltage ADC +define HAL_USE_ADC TRUE +PA0 VDD_5V_SENS ADC1 SCALE(2) + +# enable CAN support +PB8 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 +PB13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PB14 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW + +define CAN_APP_NODE_NAME "in.sierraaerospace.PrecisionPoint" + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +# disable dual GPS and GPS blending to save flash space +define GPS_MAX_RECEIVERS 1 +define GPS_MAX_INSTANCES 1 +define HAL_COMPASS_MAX_SENSORS 1 + +# GPS+MAG+BARO+NeoPixels +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_BARO +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY + +# PB5 GPS_PPS INPUT FLOATING GPIO(6) +# define CONFIGURE_PPS_PIN TRUE +# define HAL_GPIO_PPS 6 +# PB4 F9P_TX_READY INPUT + +# allow for F9P GPS modules with moving baseline +define GPS_MOVING_BASELINE 1 +define GPS_MAX_RATE_MS 200 + +# Logging +define HAL_LOGGING_ENABLED 1 +define HAL_PERIPH_ENABLE_RTC 1 +define HAL_OS_FATFS_IO 1 + +# SD Card pins +PC8 SDIO_D0 SDIO +PC9 SDIO_D1 SDIO +PC10 SDIO_D2 SDIO +PC11 SDIO_D3 SDIO +PC12 SDIO_CK SDIO +PD2 SDIO_CMD SDIO + +# reserve 256 bytes for comms between app and bootloader +RAM_RESERVE_START 256 + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# USB select +PC6 USB_SEL OUTPUT PUSHPULL SPEED_LOW HIGH diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/defaults.parm new file mode 100644 index 00000000000000..9b64ede5950c0a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/defaults.parm @@ -0,0 +1,4 @@ +# setup for Neopixel +OUT1_FUNCTION 120 +NTF_LED_TYPES 455 +NTF_LED_LEN 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef-bl.dat new file mode 100644 index 00000000000000..a0243c78e166e9 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef-bl.dat @@ -0,0 +1,60 @@ +# HW definition file for Sierra-TrueNav Pro + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1091 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# Flash info +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 36 +FLASH_SIZE_KB 256 + +# reserve some space for params +APP_START_OFFSET_KB 4 + +# a fault LED +PA1 LED_BOOTLOADER OUTPUT LOW # amber +define HAL_LED_ON 1 + +# enable CAN support +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PB1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PB6 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH + +CAN_ORDER 1 + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 1000 + +define HAL_USE_SERIAL FALSE +define HAL_NO_GPIO_IRQ +define HAL_USE_EMPTY_IO TRUE +define PORT_INT_REQUIRED_STACK 64 +define DMA_RESERVE_SIZE 0 + +MAIN_STACK 0x800 +PROCESS_STACK 0x800 + +define HAL_DISABLE_LOOP_DELAY + +# Add CS pins to ensure they are high in bootloader +PB12 RM3100_CS CS +PA8 BARO_CS CS + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNavPro" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat new file mode 100644 index 00000000000000..621c68b9539f3f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNavPro/hwdef.dat @@ -0,0 +1,118 @@ +# HW definition file for Sierra-TrueNav Pro + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# bootloader starts firmware at 36k + 4k (STORAGE_FLASH) +FLASH_RESERVE_START_KB 40 +FLASH_SIZE_KB 256 + +# store parameters in pages 18 and 19 +STORAGE_FLASH_PAGE 18 +define HAL_STORAGE_SIZE 800 + +# ChibiOS system timer +STM32_ST_USE_TIMER 15 +define CH_CFG_ST_RESOLUTION 16 + +# board ID for firmware load +APJ_BOARD_ID 1091 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +env AP_PERIPH 1 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +# MAIN_STACK is stack for ISR handlers +MAIN_STACK 0x300 + +# PROCESS_STACK controls stack for main thread +PROCESS_STACK 0xA00 + +# save memory +define HAL_DISABLE_LOOP_DELAY +define HAL_GCS_ENABLED 0 +define HAL_NO_MONITOR_THREAD +define HAL_NO_LOGGING +define HAL_USE_ADC FALSE +define HAL_NO_RCIN_THREAD + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# --------------------- SPI1 RM3100+DPS310 ----------------------- +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PB12 RM3100_CS CS +PA8 BARO_CS CS + +# Baro probe +SPIDEV dps310 SPI1 DEVID3 BARO_CS MODE3 5*MHZ 5*MHZ +BARO DPS310 SPI:dps310 + +# Mag probe +SPIDEV rm3100 SPI1 DEVID1 RM3100_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180 +define AP_RM3100_REVERSAL_MASK 7 + +# ---------------------- CAN bus ------------------------- +CAN_ORDER 1 + +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PB1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PB6 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW + +define HAL_CAN_POOL_SIZE 12000 + +# ---------------------- UARTs --------------------------- +SERIAL_ORDER USART1 + +# USART1 for GPS +PA9 USART1_TX USART1 SPEED_HIGH +PA10 USART1_RX USART1 SPEED_HIGH + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True + +# enable GPS and compass +define HAL_PERIPH_ENABLE_GPS +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_BARO +define HAL_PERIPH_ENABLE_RC_OUT +define HAL_PERIPH_ENABLE_NOTIFY + +# 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 +define HAL_PERIPH_GPS_PORT_DEFAULT 0 + +# minimal GPS drivers to reduce flash usage +include ../include/minimal_GPS.inc + +# GPS PPS +PA15 GPS_PPS_IN INPUT + +# PWM, WS2812 LED +PB10 TIM2_CH3 TIM2 PWM(1) GPIO(50) + +define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNavPro" + +# Enable GPS LDO +PC13 VDD_3V3_SENSORS_EN OUTPUT HIGH diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef-bl.dat new file mode 100644 index 00000000000000..18f62d71c17e50 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef-bl.dat @@ -0,0 +1,57 @@ +# HW definition file for Sierra-TrueNorth + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1093 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# Flash info +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 36 +FLASH_SIZE_KB 256 + +# reserve some space for params +APP_START_OFFSET_KB 4 + +# a fault LED +PB14 LED_BOOTLOADER OUTPUT LOW # amber +define HAL_LED_ON 1 + +# enable CAN support +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PA10 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PB12 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH + +CAN_ORDER 1 + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 1000 + +define HAL_USE_SERIAL FALSE +define HAL_NO_GPIO_IRQ +define HAL_USE_EMPTY_IO TRUE +define PORT_INT_REQUIRED_STACK 64 +define DMA_RESERVE_SIZE 0 + +MAIN_STACK 0x800 +PROCESS_STACK 0x800 + +define HAL_DISABLE_LOOP_DELAY + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNorth" +PA4 RM3100_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef.dat new file mode 100644 index 00000000000000..eaee7e1247665a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueNorth/hwdef.dat @@ -0,0 +1,97 @@ +# HW definition file for Sierra-TrueNorth + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# bootloader starts firmware at 36k + 4k (STORAGE_FLASH) +FLASH_RESERVE_START_KB 40 +FLASH_SIZE_KB 256 + +# store parameters in pages 18 and 19 +STORAGE_FLASH_PAGE 18 +define HAL_STORAGE_SIZE 800 + +# ChibiOS system timer +STM32_ST_USE_TIMER 15 +define CH_CFG_ST_RESOLUTION 16 + +# board ID for firmware load +APJ_BOARD_ID 1093 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +env AP_PERIPH 1 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +# MAIN_STACK is stack for ISR handlers +MAIN_STACK 0x300 + +# PROCESS_STACK controls stack for main thread +PROCESS_STACK 0xA00 + +# save memory +define HAL_DISABLE_LOOP_DELAY +define HAL_GCS_ENABLED 0 +define HAL_NO_MONITOR_THREAD +define HAL_NO_LOGGING +define HAL_USE_ADC FALSE +define HAL_NO_RCIN_THREAD + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# ---------------------- CAN bus ------------------------- +CAN_ORDER 1 + +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PA10 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PB12 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH + +define HAL_CAN_POOL_SIZE 6000 + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True + +# enable compass and airspeed +define HAL_PERIPH_ENABLE_MAG +define HAL_COMPASS_MAX_SENSORS 1 + +# PWM, WS2812 LED +PA2 TIM2_CH3 TIM2 PWM(1) GPIO(50) +PA3 TIM2_CH4 TIM2 PWM(2) GPIO(51) + +define CAN_APP_NODE_NAME "in.sierraaerospace.TrueNorth" + +# SPI1 bus for RM3100 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +PA4 RM3100_CS CS + +SPIDEV rm3100 SPI1 DEVID1 RM3100_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180 + +# LEDs +PB14 LED OUTPUT LOW GPIO(1) + +# ---------------------- UARTs --------------------------- +SERIAL_ORDER USART1 + +# USART1 +PA9 USART1_TX USART1 SPEED_HIGH +PB7 USART1_RX USART1 SPEED_HIGH diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef-bl.dat new file mode 100644 index 00000000000000..2b08e87d4c2d6f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef-bl.dat @@ -0,0 +1,56 @@ +# HW definition file for Sierra-TrueSpeed + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1094 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# Flash info +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 36 +FLASH_SIZE_KB 256 + +# reserve some space for params +APP_START_OFFSET_KB 4 + +# a fault LED +PA1 LED_BOOTLOADER OUTPUT LOW # amber +define HAL_LED_ON 1 + +# enable CAN support +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PB1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PB6 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH + +CAN_ORDER 1 + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +define HAL_BOOTLOADER_TIMEOUT 1000 + +define HAL_USE_SERIAL FALSE +define HAL_NO_GPIO_IRQ +define HAL_USE_EMPTY_IO TRUE +define PORT_INT_REQUIRED_STACK 64 +define DMA_RESERVE_SIZE 0 + +MAIN_STACK 0x800 +PROCESS_STACK 0x800 + +define HAL_DISABLE_LOOP_DELAY + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define CAN_APP_NODE_NAME "in.sierraaerospace.TrueSpeed" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef.dat new file mode 100644 index 00000000000000..9f132ff08ad4c8 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Sierra-TrueSpeed/hwdef.dat @@ -0,0 +1,109 @@ +# HW definition file for Sierra-TrueSpeed + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# bootloader starts firmware at 36k + 4k (STORAGE_FLASH) +FLASH_RESERVE_START_KB 40 +FLASH_SIZE_KB 256 + +# store parameters in pages 18 and 19 +STORAGE_FLASH_PAGE 18 +define HAL_STORAGE_SIZE 800 + +# ChibiOS system timer +STM32_ST_USE_TIMER 15 +define CH_CFG_ST_RESOLUTION 16 + +# board ID for firmware load +APJ_BOARD_ID 1094 + +# crystal frequency +OSCILLATOR_HZ 16000000 + +env AP_PERIPH 1 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +# MAIN_STACK is stack for ISR handlers +MAIN_STACK 0x300 + +# PROCESS_STACK controls stack for main thread +PROCESS_STACK 0xA00 + +# save memory +define HAL_DISABLE_LOOP_DELAY +define HAL_GCS_ENABLED 0 +define HAL_NO_MONITOR_THREAD +define HAL_NO_LOGGING +define HAL_USE_ADC FALSE +define HAL_NO_RCIN_THREAD + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# order of I2C buses +I2C_ORDER I2C1 I2C2 + +# I2C bus for magnetometer +PB13 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +# I2C bus for DLVR +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# Mag probe +COMPASS BMM150 I2C:0:0x10 false ROTATION_NONE + +# default to DLVR 10in +AIRSPEED DLVR I2C:0:0x28 10 +define HAL_AIRSPEED_BUS_DEFAULT 0 +define HAL_AIRSPEED_TYPE_DEFAULT 9 + +# ---------------------- CAN bus ------------------------- +CAN_ORDER 1 + +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PB1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW +PB6 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW HIGH + +define HAL_CAN_POOL_SIZE 6000 + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True + +# enable compass and airspeed +define HAL_PERIPH_ENABLE_MAG +define HAL_PERIPH_ENABLE_AIRSPEED +define HAL_COMPASS_MAX_SENSORS 1 +define AIRSPEED_MAX_SENSORS 1 + +# PWM, WS2812 LED +PA2 TIM2_CH3 TIM2 PWM(1) GPIO(50) +PA3 TIM2_CH4 TIM2 PWM(2) GPIO(51) + +define CAN_APP_NODE_NAME "in.sierraaerospace.TrueSpeed" + +# LEDs +PA1 LED OUTPUT LOW GPIO(1) + +# ---------------------- UARTs --------------------------- +SERIAL_ORDER USART1 + +# USART1 +PA9 USART1_TX USART1 SPEED_HIGH +PA10 USART1_RX USART1 SPEED_HIGH diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/hwdef.dat index aef033bcab3712..9c6561cb95e1dc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SkystarsH7HD-bdshot/hwdef.dat @@ -4,7 +4,7 @@ include ../SkystarsH7HD/hwdef.dat undef PB0 PB1 PD12 PA0 PA2 PC7 PC6 PD8 PD9 PB5 PB6 PE0 PE1 -undef HAL_I2C_INTERNAL_MASK DMA_PRIORITY DMA_NOSHARE +undef DMA_PRIORITY DMA_NOSHARE HAL_I2C_INTERNAL_MASK undef DEFAULT_SERIAL6_PROTOCOL DEFAULT_SERIAL6_BAUD MCU_CLOCKRATE_MHZ 480 @@ -12,7 +12,7 @@ MCU_CLOCKRATE_MHZ 480 DMA_PRIORITY TIM3* TIM4* TIM2* SPI1* SPI3* SPI4* TIM1* DMA_NOSHARE TIM3* TIM4* TIM2* SPI1* SPI3* -define HAL_I2C_INTERNAL_MASK 2 +define HAL_I2C_INTERNAL_MASK 1 define RELAY2_PIN_DEFAULT 81 # Pit-1 define RELAY3_PIN_DEFAULT 82 # PIN-EN diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/README.md new file mode 100644 index 00000000000000..1954a85c27dbbb --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/README.md @@ -0,0 +1,102 @@ +# SpeedyBee F405 Mini Flight Controller + +The SpeedyBee F405 Mini is a flight controller produced by [SpeedyBee](http://www.speedybee.com/). + +## Features + + - STM32F405 microcontroller + - ICM42688-P IMU + - DPS310 barometer + - 8Mb flash logging + - AT7456E OSD + - 6 UARTs + - 5 PWM outputs + +## Pinout + +![SpeedyBee F405 Mini](SpeedyBee_F405_Mini_Board.JPG "SpeedyBee F405 Mini") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (DJI-VTX, DMA-enabled) + - SERIAL2 -> UART2 (RX, DMA-enabled) + - SERIAL3 -> UART3 + - SERIAL4 -> UART4 (connected to internal BT module, not currently usable by ArduPilot) + - SERIAL5 -> UART5 (ESC Telemetry, RX only on ESC connector) + - SERIAL6 -> UART6 (GPS, DMA-enabled) + +## RC Input + +RC input is configured on the R2 (UART2_RX) pin for most RC unidirectional protocols except SBUS which should be applied at the SBUS pin. PPM is not supported. +For Fport, a bi-directional inverter will be required. See https://ardupilot.org/plane/docs/common-connecting-sport-fport.html +For CRSF/ELRS/SRXL2 connection of the receiver to T2 will also be required. + +## FrSky Telemetry + +FrSky Telemetry is supported using the Tx pin of any UART including SERIAL2/UART2. You need to set the following parameters to enable support for FrSky S.PORT (example shows SERIAL3). + + - SERIAL3_PROTOCOL 10 + - SERIAL3_OPTIONS 7 + +## OSD Support + +The SpeedyBee F405 Mini supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## VTX Support + +The JST-GH-6P connector supports a standard DJI HD VTX connection. Pin 1 of the connector is 9v so be careful not to connect +this to a peripheral requiring 5v. + +## PWM Output + +The SpeedyBee F405 Mini supports up to 5 PWM outputs. The pads for motor output +M1 to M4 on the motor connector, plus M5 for LED strip or another +PWM output. + +The PWM is in 3 groups: + + - PWM 1-2 in group1 + - PWM 3-4 in group2 + - PWM 5 in group3 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. Channels 1-4 support bi-directional DShot. + +## Battery Monitoring + +The board has a internal voltage sensor and connections on the ESC connector for an external current sensor input. +The voltage sensor can handle up to 6S. +LiPo batteries. + +The default battery parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11.2 + - BATT_AMP_PERVLT 40 (will need to be adjusted for whichever current sensor is attached) + + +## RSSI + +Analog RSSI input (pin 15) + +## Compass + +The SpeedyBee F405 Mini 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/SpeedyBeeF405Mini/SpeedyBee_F405_Mini_Board.JPG b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/SpeedyBee_F405_Mini_Board.JPG new file mode 100644 index 00000000000000..1b091e18fe15a8 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/SpeedyBee_F405_Mini_Board.JPG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef-bl.dat new file mode 100644 index 00000000000000..e043e37c018fdc --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef-bl.dat @@ -0,0 +1,43 @@ + +# hw definition file for processing by chibios_hwdef.py +# for SPEEDYBEEF405MINI hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1135 + +# 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 +PB12 OSD1_CS CS +PA4 GYRO1_CS CS + +PA8 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef.dat new file mode 100644 index 00000000000000..9717ab8d56a2a5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405Mini/hwdef.dat @@ -0,0 +1,152 @@ + +# hw definition file for processing by chibios_hwdef.py +# for SPEEDYBEEF405MINI hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1135 + +# 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 + +# 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 +PB12 OSD1_CS CS +PA4 GYRO1_CS CS + +# Beeper +PC15 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 (DJI) +PA10 USART1_RX USART1 +PA9 USART1_TX USART1 +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_DJI_FPV + +# USART2 (RX/SBUS) +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 +PC10 USART3_TX USART3 +PC11 USART3_RX USART3 +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None + +# UART4 (Bluetooth) +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None + +# UART5 (ESC) +PD2 UART5_RX UART5 NODMA +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry + +# USART6 (GPS) +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_GPS + +# I2C ports +I2C_ORDER I2C1 +# I2C1 +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# Servos +PB14 CAMERA1 OUTPUT GPIO(70) LOW +define RELAY2_PIN_DEFAULT 70 + +# 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 15 +define HAL_BATT_MONITOR_DEFAULT 4 + +# MOTORS +PB6 TIM4_CH1 TIM4 PWM(1) GPIO(50) # M1 +PB7 TIM4_CH2 TIM4 PWM(2) GPIO(51) BIDIR # M2 +PB1 TIM3_CH4 TIM3 PWM(3) GPIO(52) BIDIR # M3 +PB0 TIM3_CH3 TIM3 PWM(4) GPIO(53) # M4 + +# LEDs +PA8 TIM1_CH1 TIM1 PWM(5) GPIO(54) # M5 + +PC13 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 +define HAL_GPIO_LED_OFF 1 + +# 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 + +# Barometer setup +BARO DPS310 I2C:0:0x76 + +# IMU setup + +# IMU setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ + +IMU Invensensev3 SPI:imu1 ROTATION_PITCH_180_YAW_90 +#DMA_NOSHARE TIM4_UP TIM3_UP SPI1* +DMA_PRIORITY TIM4* TIM3* 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 3 +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/Readme.md b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/Readme.md index 7f53b54bd9932d..214f68b1eaba7e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/Readme.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/Readme.md @@ -12,7 +12,7 @@ The SpeedyBeeF405WING is a flight controller produced by [SpeedyBee](http://www. Power 2S - 6S Lipo input voltage with voltage monitoring 90A Cont., 215A peak current monitor - 9V/12/5V, 1.8A BEC for powering Video Transmitter + 9V/12/5V, 1.8A BEC for powering Video Transmitter controlled by GPIO 4.9V/6V/7.2V, 4.5A BEC for servos 5V, 2.4A BEC for internal and peripherals Interfaces @@ -90,6 +90,10 @@ The correct battery setting parameters are set by default and are: The SpeedyBeeF405Wing 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". Setting this GPIO high removes voltage supply to pins. + ## Loading Firmware Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled “SpeedyBeeF405Wing”. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat index e3f0538e2ab94f..1ddcd7c9eb8aa9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat @@ -164,6 +164,9 @@ 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 + define STM32_PWM_USE_ADVANCED TRUE # reduce max size of embedded params for apj_tool.py @@ -218,6 +221,7 @@ define AP_AIRSPEED_ASP5033_ENABLED 1 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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/README.md b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/README.md new file mode 100644 index 00000000000000..992bc8639e56d1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/README.md @@ -0,0 +1,86 @@ +# T-Motor H7 Mini Flight Controller + +The T-Motor H7 Mini is a flight controller produced by [T-Motor](https://store.tmotor.com/goods-1295-H7+MINI.html). + +## Features + + - MCU - STM32H743 32-bit processor running at 480 MHz + - IMU - ICM42688/BMI270 + - Barometer - DPS310 + - OSD - AT7456E + - Onboard Flash: 128Mbits + - 6x UARTs (1,5,6,7,9) + - 9x PWM Outputs (8 Motor Output, 1 LED) + - Battery input voltage: 2S-6S + - BEC 5V/2A, 10V/1.5A + +## Pinout + +![T-Motor H7 Mini Board](TMotorH7Mini_Board.JPG "T-Motor H7 Mini") + +## 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 (ESC Telemetry) + - SERIAL3 -> UART3 + - SERIAL5 -> UART5 (GPS, DMA-enabled) + - SERIAL6 -> UART6 (RX, DMA-enabled) + - SERIAL7 -> UART7 (DJI VTX, DMA-enabled) + - SERIAL8 -> UART8 (SBUS, DMA-enabled) + +## RC Input + +RC input is configured on the R6/TX6 (UART6_RX/UART6_TX) pins. It supports all serial RC +protocols. For protocols requiring half-duplex serial to transmit +telemetry (such as FPort) you should setup SERIAL6 with half-duplex, pin-swap and inversion enabled. + +## OSD Support + +The T-Motor H7 Mini supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## PWM Output + +The T-Motor H7 Mini supports up to 5 PWM outputs. The pads for motor output +M1 to M4 on the motor connectors and separate pads, plus +M5 for LED strip or another PWM output. + +The PWM is in 2 groups: + + - PWM 1-4 in group1 + - PWM 5 in group2 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. Channels 1-4 support bi-directional dshot. + +## 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.0 + - BATT_AMP_PERVLT 50.0 + +## Compass + +The T-Motor H7 Mini 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/TMotorH743/TMotorH7Mini_Board.JPG b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/TMotorH7Mini_Board.JPG new file mode 100644 index 00000000000000..ab26e00e526341 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/TMotorH7Mini_Board.JPG differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef-bl.dat new file mode 100644 index 00000000000000..69385f40cf3c6d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef-bl.dat @@ -0,0 +1,44 @@ + +# hw definition file for processing by chibios_hwdef.py +# for TMH7 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1138 + +# 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 + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + + +# 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/TMotorH743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef.dat new file mode 100644 index 00000000000000..211d73b8e5f9cf --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TMotorH743/hwdef.dat @@ -0,0 +1,166 @@ + +# hw definition file for processing by chibios_hwdef.py +# for TMH7 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# board ID for firmware load +APJ_BOARD_ID 1138 + +# 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 EMPTY USART3 EMPTY UART5 USART6 UART7 UART8 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 (ESC Telemetry) +PA10 USART1_RX USART1 NODMA +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_ESCTelemetry + +# UART3 +PD8 USART3_TX USART3 NODMA +PD9 USART3_RX USART3 NODMA +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None + +# UART5 (GPS) +PC12 UART5_TX UART5 +PD2 UART5_RX UART5 +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_GPS + +# USART6 (RX) +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN + +# UART7 (DJI) +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 +define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_DJI_FPV + +# UART8 (SBUS/SmartAudio) +PE0 UART8_RX UART8 # no suitable timer for RCININT +PE1 UART8_TX UART8 + +# I2C ports +I2C_ORDER I2C1 +# I2C1 +PB6 I2C1_SCL I2C1 +PB7 I2C1_SDA I2C1 + +# One baro +BARO DPS310 I2C:0:0x76 + +# Servos +PB8 CAMERA1 OUTPUT GPIO(70) LOW +define RELAY2_PIN_DEFAULT 70 + +# ADC ports + +# ADC1 +PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 11 +define HAL_BATT_VOLT_SCALE 11.0 +PC2 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 12 +PC3 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 13 +define HAL_BATT_CURR_SCALE 50.0 +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 + +# LEDs +PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) # M9 + +PE5 LED1 OUTPUT LOW GPIO(91) +define HAL_GPIO_A_LED_PIN 91 + +PE4 LED2 OUTPUT LOW GPIO(92) +define HAL_GPIO_B_LED_PIN 92 +define HAL_GPIO_LED_OFF 1 + +# 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 icm42688 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 16*MHZ +SPIDEV bmi270 SPI4 DEVID1 GYRO2_CS MODE3 1*MHZ 8*MHZ + +IMU BMI270 SPI:bmi270 ROTATION_PITCH_180_YAW_90 +IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_90 + +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 +define AP_SCRIPTING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat index a32031d082d3d7..905b6516156a8b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6/hwdef.dat @@ -51,9 +51,6 @@ PE1 UART8_TX UART8 PE7 UART7_RX UART7 NODMA PE8 UART7_TX UART7 NODMA -# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 - # these are the pins for SWD debugging with a STlinkv2 or black-magic probe PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/README.md b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/README.md new file mode 100644 index 00000000000000..370716c572de56 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/README.md @@ -0,0 +1,214 @@ +# A6SE Flight Controller + +The A6SE flight controller is manufactured and sold by [YJUAV](http://www.yjuav.net). + +## Features + + - STM32H750 microcontroller + - Onboard Flash: 128Mbits/16Mbytes + - Two IMUs: ICM42688, ICM42688 + - Internal ITS8310 I2C magnetometer + - Internal DPS310 SPI barometer + - Internal RGB LED + - microSD card slot port + - 1 analog power ports + - 5 UARTs and 1 USB ports + - 3 I2C and 2 CAN ports + - 11 PWM output ports + - Safety switch port + - External SPI port + - Buzzer port + - RC IN port + +## Pinout +![YJUAV_A6SE Board](YJUAV_A6SE-pinout.jpg "YJUAV_A6SE") + + +## Connectors + +**POWER ADC** + +| Pin | Signal | Volt | +| :--: | :-------------: | :---: | +| 1 | VCC_IN | +5V | +| 2 | VCC_IN | +5V | +| 3 | BAT_CRRENT_ADC | +3.3V | +| 4 | BAT_VOLTAGE_ADC | +3.3V | +| 5 | GND | GND | +| 6 | GND | GND | + +**TELEM1&TELEM2** + +| Pin | Signal | Volt | +| :--: | :-----: | :---: | +| 1 | VCC | +5V | +| 2 | UART_TX | +3.3V | +| 3 | UART_RX | +3.3V | +| 4 | CTS | +3.3V | +| 5 | RTS | +3.3V | +| 6 | GND | GND | + +**ADC** + +| Pin | Signal | Volt | +| :--: | :-----: | :---: | +| 1 | VCC | +5V | +| 2 | ADC_3V3 | +3.3V | +| 3 | ADC_6V6 | +6.6V | +| 4 | GND | GND | + +**SPI** + +| Pin | Signal | Volt | +| :--: | :------: | :---: | +| 1 | VCC | +5V | +| 2 | SPI_SCK | +3.3V | +| 3 | SPI_MISO | +3.3V | +| 4 | SPI_MOSI | +3.3V | +| 5 | SPI_CS | +3.3V | +| 6 | GND | GND | + +**I2C** + +| Pin | Signal | Volt | +| :--: | :-----: | :---: | +| 1 | VCC | +5V | +| 2 | I2C_SCL | +3.3V | +| 3 | I2C_SDA | +3.3V | +| 4 | GND | GND | + +**CAN1&CAN2** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 | CAN_P | +3.3V | +| 3 | CAN_N | +3.3V | +| 4 | GND | GND | + +**GPS1** + +| Pin | Signal | Volt | +| :--: | :-----: | :---: | +| 1 | VCC | +5V | +| 2 | UART_TX | +3.3V | +| 3 | UART_RX | +3.3V | +| 4 | I2C_SCL | +3.3V | +| 5 | I2C_SDA | +3.3V | +| 6 | GND | GND | + +**GPS2&SAFETY** + +| Pin | Signal | Volt | +| :--: | :-----------: | :---: | +| 1 | VCC | +5V | +| 2 | UART_TX | +3.3V | +| 3 | UART_RX | +3.3V | +| 4 | I2C_SCL | +3.3V | +| 5 | I2C_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 | + +**DEBUG** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC | +5V | +| 2 | TX | +3.3V | +| 3 | RX | +3.3V | +| 4 | SWDIO | +3.3V | +| 5 | SWCLK | +3.3V | +| 6 | GND | GND | + +**SAFETY** + +| Pin | Signal | Volt | +| :--: | :-----------: | :---: | +| 1 | 3V3_OUT | +3.3V | +| 2 | SAFETY_SW | +3.3V | +| 3 | SAFETY_SW_LED | +3.3V | +| 4 | SBUS_OUT | +3.3V | +| 5 | RSSI | +3.3V | +| 6 | GND | GND | + +**USB EX** + +| Pin | Signal | Volt | +| :--: | :----: | :---: | +| 1 | VCC_IN | +5V | +| 2 | DM | +3.3V | +| 3 | DP | +3.3V | +| 4 | GND | GND | + +## UART Mapping + + - SERIAL0 -> USB (OTG1) + - SERIAL1 -> USART1 (Telem1) + - SERIAL2 -> USART6 (Telem2) + - SERIAL3 -> USART3 (GPS1), NODMA + - SERIAL4 -> USART2 (GPS2), NODMA + - SERIAL5 -> UART8 (SBUS) + - SERIAL6 -> UART7 (Debug), NODMA + - SERIAL7 -> USB2 (OTG2) + +## RC Input + +The remote control signal should be connected to the “RC IN” pin, at one side of the servo channels. + +This signal pin supports two types of remote control signal inputs, SBUS and PPM signals. + +## PWM Output + +The A6SE supports up to 11 PWM outputs,support all PWM protocols as well as DShot. All 11 PWM outputs have GND on the bottom row, 5V on the middle row and signal on the top row. + +The 11 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 in group3 + +Channels 1-8 support bi-directional Dshot. +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 11 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 Channels | Pin | PWM Channels | Pin | +| ------------ | ---- | ------------ | ---- | +| PWM1 | 50 | PWM8 | 57 | +| PWM2 | 51 | PWM9 | 58 | +| PWM3 | 52 | PWM10 | 59 | +| PWM4 | 53 | PWM11 | 60 | +| PWM5 | 54 | | | +| PWM6 | 55 | | | +| PWM7 | 56 | | | + +## Analog inputs + +The A6SE flight controller has 5 analog inputs + + - ADC Pin4 -> Battery Current + - ADC Pin2 -> Battery Voltage + - ADC Pin8 -> ADC 3V3 Sense + - ADC Pin10 -> ADC 6V6 Sense + - ADC Pin11 -> RSSI voltage monitoring + +## Build the FC + +./waf configure --board=YJUAV_A6SE +./waf copter + +The compiled firmware is located in folder **"build/YJUAV_A6SE/bin/arducopter.apj"**. + + + +## Loading Firmware + +The A6SE 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/YJUAV_A6SE/YJUAV_A6SE-pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/YJUAV_A6SE-pinout.jpg new file mode 100644 index 00000000000000..095c7ed56d1c27 Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/YJUAV_A6SE-pinout.jpg differ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/defaults.parm new file mode 100644 index 00000000000000..bd31bbe1fd1aca --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/defaults.parm @@ -0,0 +1,15 @@ +# setup the heater temperature to 45 degree +BRD_HEAT_TARG 45 + +# turn on the CAN power monitoring(default) +CAN_P1_DRIVER 1 +BATT_MONITOR 4 + +# setup the parameter for the ADC power module +BATT_VOLT_PIN 2 +BATT_CURR_PIN 4 +BATT_VOLT_MULT 18.000 +BATT_AMP_PERVLT 24.000 + +# setup the parameter for the ADC rssi +RSSI_ANA_PIN 11 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/hwdef-bl.dat new file mode 100644 index 00000000000000..4c5ca09058a984 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/hwdef-bl.dat @@ -0,0 +1,64 @@ +# hw definition file for processing by chibios_hwdef.py +# for A6SE_YJUAV board + +# MCU class and specific type +MCU STM32H7xx STM32H750xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1127 + +FLASH_SIZE_KB 128 +FLASH_RESERVE_START_KB 0 +FLASH_RESERVE_END_KB 0 +FLASH_BOOTLOADER_LOAD_KB 128 + +# 16MB external flash +EXT_FLASH_SIZE_MB 16 +EXT_FLASH_RESERVE_START_KB 1024 +EXT_FLASH_RESERVE_END_KB 448 + +# QuadSPI Flash +PD11 QUADSPI_BK1_IO0 QUADSPI1 SPEED_HIGH +PD12 QUADSPI_BK1_IO1 QUADSPI1 SPEED_HIGH +PE2 QUADSPI_BK1_IO2 QUADSPI1 SPEED_HIGH +PD13 QUADSPI_BK1_IO3 QUADSPI1 SPEED_HIGH +PB6 QUADSPI_BK1_NCS QUADSPI1 SPEED_HIGH +PB2 QUADSPI_CLK QUADSPI1 SPEED_HIGH + +# IFace Device Name Bus QSPI Mode Clk Freq Size (Pow2) NCS Delay +QSPIDEV w25q-dtr QUADSPI1 MODE3 100*MHZ 24 1 + +# order of UARTs (and USB). Allow bootloading on USB and Debug +SERIAL_ORDER OTG1 UART7 + +# UART7 DEBUG +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA +define BOOTLOADER_DEBUG SD7 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PE15 LED_RED OUTPUT OPENDRAIN HIGH # red +PD10 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green +PG0 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue +define HAL_LED_ON 0 + + +# Add CS pins to ensure they are high in bootloader +PE4 IMU1_CS CS +PA0 IMU2_CS CS +PE10 FRAM_CS CS +PE9 BAROMETER_CS CS +PE3 COMPASS_CS CS +PC15 RESERVE_CS CS + +# Extra SPI CS +PE5 EXT_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/hwdef.dat new file mode 100644 index 00000000000000..bc59ca460b8b56 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE/hwdef.dat @@ -0,0 +1,246 @@ +# hw definition file for processing by chibios_hwdef.py for A6SE_YJUAV + +# MCU class and specific type +MCU STM32H7xx STM32H750xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1127 + +env OPTIMIZE -O2 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +# internal flash is off limits +FLASH_SIZE_KB 128 +FLASH_RESERVE_START_KB 0 +define HAL_FLASH_PROTECTION 1 + +EXT_FLASH_SIZE_MB 16 +EXT_FLASH_RESERVE_START_KB 1024 +EXT_FLASH_RESERVE_END_KB 448 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART6 USART3 USART1 UART8 UART7 OTG2 + +# now we define the pins that USB is connected on +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART2 TELEM1 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# USART6 TELEM2 +PC7 USART6_RX USART6 +PC6 USART6_TX USART6 +PG13 USART6_CTS USART6 +PG8 USART6_RTS USART6 + +# USART3 GPS1 +PD9 USART3_RX USART3 NODMA +PD8 USART3_TX USART3 NODMA + +# USART1 GPS2 +PB7 USART1_RX USART1 NODMA +PA9 USART1_TX USART1 NODMA + +# SBUS, DSM port +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# UART7 DEBUG +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +# these are the pins for SWD debugging with a STlinkv2 or black-magic probe +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 -IMU1 +PB3 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI6 -IMU2 -IMU3 +PA5 SPI6_SCK SPI6 +PA6 SPI6_MISO SPI6 +PA7 SPI6_MOSI SPI6 + +# SPI5 +PF7 SPI5_SCK SPI5 +PF8 SPI5_MISO SPI5 +PF9 SPI5_MOSI SPI5 + +# SPI4 -Extra SPI +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# sensors cs +PE4 IMU1_CS CS +PA0 IMU2_CS CS +PE10 FRAM_CS CS +PE9 BAROMETER1_CS CS +PE3 BAROMETER2_CS CS +PC15 RESERVE_CS CS + +# Extra SPI CS +PE5 EXT_CS CS + +# I2C buses +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +PH7 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +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 1 + +# PWM channels +PA15 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR +PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51) +PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52) BIDIR +PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53) +PA8 TIM1_CH1 TIM1 PWM(5) GPIO(54) BIDIR +PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55) +PA10 TIM1_CH3 TIM1 PWM(7) GPIO(56) BIDIR +PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57) +PB5 TIM3_CH2 TIM3 PWM(9) GPIO(58) +PB0 TIM3_CH3 TIM3 PWM(10) GPIO(59) +PB1 TIM3_CH4 TIM3 PWM(11) GPIO(60) + +# PWM output for buzzer +PD14 TIM4_CH3 TIM4 GPIO(77) ALARM + +# RC input +PI7 TIM8_CH3 TIM8 RCININT PULLUP LOW + +# Analog in +PC4 BATT_CURRENT_SENS ADC1 SCALE(1) +PF11 BATT_VOLTAGE_SENS ADC1 SCALE(1) + +# Analog sys 5v +PF12 VDD_5V_SENS ADC1 SCALE(2) + +# ADC3.3/ADC6.6 +PC5 SPARE1_ADC1 ADC1 SCALE(1) +PC0 SPARE2_ADC1 ADC1 SCALE(2) + +PC1 RSSI_IN ADC1 SCALE(1) + +PC3 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(3) + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 + +# GPIOs +PC13 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 +define HAL_HAVE_IMU_HEATER 1 + +# enable pins +PC14 VDD_3V3_SENSORS_EN OUTPUT LOW + +# red LED marked as B/E +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 HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +# use pixracer style 3-LED indicators +define HAL_HAVE_PIXRACER_LED + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 +PB15 LED_SAFETY OUTPUT +PA4 SAFETY_IN INPUT PULLDOWN + +# SPI devices +SPIDEV imu1 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ +SPIDEV imu2 SPI6 DEVID1 IMU2_CS MODE3 2*MHZ 8*MHZ +SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV dps310 SPI5 DEVID3 BAROMETER1_CS MODE3 5*MHZ 5*MHZ +SPIDEV ms5611 SPI5 DEVID3 BAROMETER2_CS MODE3 5*MHZ 5*MHZ + +# IMU1 +IMU Invensense SPI:imu1 ROTATION_NONE +IMU Invensensev3 SPI:imu1 ROTATION_NONE + +# IMU2 +IMU Invensense SPI:imu2 ROTATION_NONE +IMU Invensensev3 SPI:imu2 ROTATION_NONE + +define HAL_DEFAULT_INS_FAST_SAMPLE 5 + +# baro +BARO DPS310 SPI:dps310 +BARO MS56XX SPI:ms5611 +BARO ICP201XX I2C:0:0x64 + +# compass +define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90 +COMPASS IST8310 I2C:0:0x0E false ROTATION_YAW_180 + +# QuadSPI Flash +PD11 QUADSPI_BK1_IO0 QUADSPI1 SPEED_HIGH +PD12 QUADSPI_BK1_IO1 QUADSPI1 SPEED_HIGH +PE2 QUADSPI_BK1_IO2 QUADSPI1 SPEED_HIGH +PD13 QUADSPI_BK1_IO3 QUADSPI1 SPEED_HIGH +PB6 QUADSPI_BK1_NCS QUADSPI1 SPEED_HIGH +PB2 QUADSPI_CLK QUADSPI1 SPEED_HIGH + +# 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 + +# 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 +#define HAL_USE_EMPTY_STORAGE 1 + +DMA_PRIORITY SPI1* TIM*UP* +DMA_NOSHARE SPI1* TIM*UP* + +# Enable Sagetech MXS ADSB transponder +define HAL_ADSB_SAGETECH_MXS_ENABLED HAL_ADSB_ENABLED + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat index 53f4626d9eac60..93e1ae4447143c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef-bl.dat @@ -16,9 +16,6 @@ env AP_PERIPH 1 define HAL_BOARD_AP_PERIPH_ZUBAXGNSS -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_ZubaxGNSS" - - # crystal frequency OSCILLATOR_HZ 16000000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat index a508ceda532624..fb747418cfb5ae 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat @@ -7,8 +7,6 @@ define STM32F107_MCUCONF define HAL_BOARD_AP_PERIPH_ZUBAXGNSS -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_ZubaxGNSS" - # bootloader starts firmware at 34k FLASH_RESERVE_START_KB 34 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk index 893b358f549685..821fcf0981229a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk @@ -68,6 +68,10 @@ ifeq ($(USE_FATFS),yes) include $(CHIBIOS)/os/various/fatfs_bindings/fatfs.mk endif +ifeq ($(USE_LWIP),yes) +include $(CHIBIOS)/os/various/lwip_bindings/lwip.mk +endif + # # Build global options ############################################################################## @@ -145,6 +149,10 @@ CSRC += $(CHIBIOS)/os/various/scsi_bindings/lib_scsi.c \ $(CHIBIOS)/os/hal/src/hal_usb_msd.c endif +ifeq ($(USE_LWIP),yes) +CSRC += $(CHIBIOS)/os/various/evtimer.c +endif + # $(TESTSRC) \ # test.c ifneq ($(CRASHCATCHER),) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c index 11c49cf8483eef..1e7fae3d282e99 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/flash.c @@ -235,6 +235,8 @@ static void stm32_flash_clear_errors(void) #if STM32_FLASH_NBANKS > 1 FLASH->CCR2 = ~0; #endif +#elif defined (STM32L4PLUS) + FLASH->SR = 0x0000C3FBU; #else FLASH->SR = 0xF3; #endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h new file mode 100644 index 00000000000000..5b8b2aa6f55ef4 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h @@ -0,0 +1,2149 @@ +/** + * @file + * + * lwIP Options Configuration + */ + +/* + * Copyright (c) 2001-2004 Swedish Institute of Computer Science. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. The name of the author may not be used to endorse or promote products + * derived from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT + * SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, + * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT + * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING + * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY + * OF SUCH DAMAGE. + * + * This file is part of the lwIP TCP/IP stack. + * + * Author: Adam Dunkels + * + */ +#ifndef __LWIPOPT_H__ +#define __LWIPOPT_H__ + +#include "stdio.h" +#include "stm32_util.h" + +#define LWIP_ERRNO_STDINCLUDE + +/* + ----------------------------------------------- + ---------- Platform specific locking ---------- + ----------------------------------------------- +*/ + +#define LWIP_PLATFORM_DIAG(x) do {__wrap_printf x; } while(0) +// #define LWIP_DEBUG +#define U16_F "u" +#define X8_F "x" +#define X16_F "x" +#define LWIP_STATS_DISPLAY 1 +#define ETHARP_STATS 1 +#define LWIP_IGMP 1 +#define DHCP_DEBUG LWIP_DBG_ON + +#ifndef LWIP_IPV6 + // This uses an additional 18KB Flash + #define LWIP_IPV6 0 +#endif + +/** + * SYS_LIGHTWEIGHT_PROT==1: if you want inter-task protection for certain + * critical regions during buffer allocation, deallocation and memory + * allocation and deallocation. + */ +#ifndef SYS_LIGHTWEIGHT_PROT +#define SYS_LIGHTWEIGHT_PROT 0 +#endif + +/** + * NO_SYS==1: Provides VERY minimal functionality. Otherwise, + * use lwIP facilities. + */ +#ifndef NO_SYS +#define NO_SYS 0 +#endif + +/** + * NO_SYS_NO_TIMERS==1: Drop support for sys_timeout when NO_SYS==1 + * Mainly for compatibility to old versions. + */ +#ifndef NO_SYS_NO_TIMERS +#define NO_SYS_NO_TIMERS 0 +#endif + +/** + * MEMCPY: override this if you have a faster implementation at hand than the + * one included in your C library + */ +#ifndef MEMCPY +#define MEMCPY(dst,src,len) memcpy(dst,src,len) +#endif + +/** + * SMEMCPY: override this with care! Some compilers (e.g. gcc) can inline a + * call to memcpy() if the length is known at compile time and is small. + */ +#ifndef SMEMCPY +#define SMEMCPY(dst,src,len) memcpy(dst,src,len) +#endif + +/* + ------------------------------------ + ---------- Memory options ---------- + ------------------------------------ +*/ +/** + * MEM_LIBC_MALLOC==1: Use malloc/free/realloc provided by your C-library + * instead of the lwip internal allocator. Can save code size if you + * already use it. + */ +#ifndef MEM_LIBC_MALLOC +#define MEM_LIBC_MALLOC 0 +#endif + +/** +* MEMP_MEM_MALLOC==1: Use mem_malloc/mem_free instead of the lwip pool allocator. +* Especially useful with MEM_LIBC_MALLOC but handle with care regarding execution +* speed and usage from interrupts! +*/ +#ifndef MEMP_MEM_MALLOC +#define MEMP_MEM_MALLOC 0 +#endif + +/** + * MEM_ALIGNMENT: should be set to the alignment of the CPU + * 4 byte alignment -> #define MEM_ALIGNMENT 4 + * 2 byte alignment -> #define MEM_ALIGNMENT 2 + */ +#ifndef MEM_ALIGNMENT +#define MEM_ALIGNMENT 4 +#endif + +/** + * MEM_SIZE: the size of the heap memory. If the application will send + * a lot of data that needs to be copied, this should be set high. + */ +#ifndef MEM_SIZE +#define MEM_SIZE 16000 +#endif + +/** + * MEMP_SEPARATE_POOLS: if defined to 1, each pool is placed in its own array. + * This can be used to individually change the location of each pool. + * Default is one big array for all pools + */ +#ifndef MEMP_SEPARATE_POOLS +#define MEMP_SEPARATE_POOLS 0 +#endif + +/** + * MEMP_OVERFLOW_CHECK: memp overflow protection reserves a configurable + * amount of bytes before and after each memp element in every pool and fills + * it with a prominent default value. + * MEMP_OVERFLOW_CHECK == 0 no checking + * MEMP_OVERFLOW_CHECK == 1 checks each element when it is freed + * MEMP_OVERFLOW_CHECK >= 2 checks each element in every pool every time + * memp_malloc() or memp_free() is called (useful but slow!) + */ +#ifndef MEMP_OVERFLOW_CHECK +#define MEMP_OVERFLOW_CHECK 0 +#endif + +/** + * MEMP_SANITY_CHECK==1: run a sanity check after each memp_free() to make + * sure that there are no cycles in the linked lists. + */ +#ifndef MEMP_SANITY_CHECK +#define MEMP_SANITY_CHECK 0 +#endif + +/** + * MEM_USE_POOLS==1: Use an alternative to malloc() by allocating from a set + * of memory pools of various sizes. When mem_malloc is called, an element of + * the smallest pool that can provide the length needed is returned. + * To use this, MEMP_USE_CUSTOM_POOLS also has to be enabled. + */ +#ifndef MEM_USE_POOLS +#define MEM_USE_POOLS 0 +#endif + +/** + * MEM_USE_POOLS_TRY_BIGGER_POOL==1: if one malloc-pool is empty, try the next + * bigger pool - WARNING: THIS MIGHT WASTE MEMORY but it can make a system more + * reliable. */ +#ifndef MEM_USE_POOLS_TRY_BIGGER_POOL +#define MEM_USE_POOLS_TRY_BIGGER_POOL 0 +#endif + +/** + * MEMP_USE_CUSTOM_POOLS==1: whether to include a user file lwippools.h + * that defines additional pools beyond the "standard" ones required + * by lwIP. If you set this to 1, you must have lwippools.h in your + * inlude path somewhere. + */ +#ifndef MEMP_USE_CUSTOM_POOLS +#define MEMP_USE_CUSTOM_POOLS 0 +#endif + +/** + * Set this to 1 if you want to free PBUF_RAM pbufs (or call mem_free()) from + * interrupt context (or another context that doesn't allow waiting for a + * semaphore). + * If set to 1, mem_malloc will be protected by a semaphore and SYS_ARCH_PROTECT, + * while mem_free will only use SYS_ARCH_PROTECT. mem_malloc SYS_ARCH_UNPROTECTs + * with each loop so that mem_free can run. + * + * ATTENTION: As you can see from the above description, this leads to dis-/ + * enabling interrupts often, which can be slow! Also, on low memory, mem_malloc + * can need longer. + * + * If you don't want that, at least for NO_SYS=0, you can still use the following + * functions to enqueue a deallocation call which then runs in the tcpip_thread + * context: + * - pbuf_free_callback(p); + * - mem_free_callback(m); + */ +#ifndef LWIP_ALLOW_MEM_FREE_FROM_OTHER_CONTEXT +#define LWIP_ALLOW_MEM_FREE_FROM_OTHER_CONTEXT 0 +#endif + +/* + ------------------------------------------------ + ---------- Internal Memory Pool Sizes ---------- + ------------------------------------------------ +*/ +/** + * MEMP_NUM_PBUF: the number of memp struct pbufs (used for PBUF_ROM and PBUF_REF). + * If the application sends a lot of data out of ROM (or other static memory), + * this should be set high. + */ +#ifndef MEMP_NUM_PBUF +#define MEMP_NUM_PBUF 16 +#endif + +/** + * MEMP_NUM_RAW_PCB: Number of raw connection PCBs + * (requires the LWIP_RAW option) + */ +#ifndef MEMP_NUM_RAW_PCB +#define MEMP_NUM_RAW_PCB 4 +#endif + +/** + * MEMP_NUM_UDP_PCB: the number of UDP protocol control blocks. One + * per active UDP "connection". + * (requires the LWIP_UDP option) + */ +#ifndef MEMP_NUM_UDP_PCB +#define MEMP_NUM_UDP_PCB 4 +#endif + +/** + * MEMP_NUM_TCP_PCB: the number of simulatenously active TCP connections. + * (requires the LWIP_TCP option) + */ +#ifndef MEMP_NUM_TCP_PCB +#define MEMP_NUM_TCP_PCB 5 +#endif + +/** + * MEMP_NUM_TCP_PCB_LISTEN: the number of listening TCP connections. + * (requires the LWIP_TCP option) + */ +#ifndef MEMP_NUM_TCP_PCB_LISTEN +#define MEMP_NUM_TCP_PCB_LISTEN 8 +#endif + +/** + * MEMP_NUM_TCP_SEG: the number of simultaneously queued TCP segments. + * (requires the LWIP_TCP option) + */ +#ifndef MEMP_NUM_TCP_SEG +#define MEMP_NUM_TCP_SEG 16 +#endif + +/** + * MEMP_NUM_REASSDATA: the number of IP packets simultaneously queued for + * reassembly (whole packets, not fragments!) + */ +#ifndef MEMP_NUM_REASSDATA +#define MEMP_NUM_REASSDATA 5 +#endif + +/** + * MEMP_NUM_FRAG_PBUF: the number of IP fragments simultaneously sent + * (fragments, not whole packets!). + * This is only used with IP_FRAG_USES_STATIC_BUF==0 and + * LWIP_NETIF_TX_SINGLE_PBUF==0 and only has to be > 1 with DMA-enabled MACs + * where the packet is not yet sent when netif->output returns. + */ +#ifndef MEMP_NUM_FRAG_PBUF +#define MEMP_NUM_FRAG_PBUF 15 +#endif + +/** + * MEMP_NUM_ARP_QUEUE: the number of simulateously queued outgoing + * packets (pbufs) that are waiting for an ARP request (to resolve + * their destination address) to finish. + * (requires the ARP_QUEUEING option) + */ +#ifndef MEMP_NUM_ARP_QUEUE +#define MEMP_NUM_ARP_QUEUE 30 +#endif + +/** + * MEMP_NUM_IGMP_GROUP: The number of multicast groups whose network interfaces + * can be members et the same time (one per netif - allsystems group -, plus one + * per netif membership). + * (requires the LWIP_IGMP option) + */ +#ifndef MEMP_NUM_IGMP_GROUP +#define MEMP_NUM_IGMP_GROUP 8 +#endif + +/** + * MEMP_NUM_SYS_TIMEOUT: the number of simulateously active timeouts. + * (requires NO_SYS==0) + * The default number of timeouts is calculated here for all enabled modules. + * The formula expects settings to be either '0' or '1'. + */ +#ifndef MEMP_NUM_SYS_TIMEOUT +#define MEMP_NUM_SYS_TIMEOUT (LWIP_TCP + IP_REASSEMBLY + LWIP_ARP + (2*LWIP_DHCP) + LWIP_AUTOIP + LWIP_IGMP + LWIP_DNS + PPP_SUPPORT + (LWIP_IPV6 * (1 + LWIP_IPV6_REASS + LWIP_IPV6_MLD))) + 2 +#endif + +/** + * MEMP_NUM_NETBUF: the number of struct netbufs. + * (only needed if you use the sequential API, like api_lib.c) + */ +#ifndef MEMP_NUM_NETBUF +#define MEMP_NUM_NETBUF 2 +#endif + +/** + * MEMP_NUM_NETCONN: the number of struct netconns. + * (only needed if you use the sequential API, like api_lib.c) + */ +#ifndef MEMP_NUM_NETCONN +#define MEMP_NUM_NETCONN 4 +#endif + +/** + * MEMP_NUM_TCPIP_MSG_API: the number of struct tcpip_msg, which are used + * for callback/timeout API communication. + * (only needed if you use tcpip.c) + */ +#ifndef MEMP_NUM_TCPIP_MSG_API +#define MEMP_NUM_TCPIP_MSG_API 8 +#endif + +/** + * MEMP_NUM_TCPIP_MSG_INPKT: the number of struct tcpip_msg, which are used + * for incoming packets. + * (only needed if you use tcpip.c) + */ +#ifndef MEMP_NUM_TCPIP_MSG_INPKT +#define MEMP_NUM_TCPIP_MSG_INPKT 8 +#endif + +/** + * MEMP_NUM_SNMP_NODE: the number of leafs in the SNMP tree. + */ +#ifndef MEMP_NUM_SNMP_NODE +#define MEMP_NUM_SNMP_NODE 50 +#endif + +/** + * MEMP_NUM_SNMP_ROOTNODE: the number of branches in the SNMP tree. + * Every branch has one leaf (MEMP_NUM_SNMP_NODE) at least! + */ +#ifndef MEMP_NUM_SNMP_ROOTNODE +#define MEMP_NUM_SNMP_ROOTNODE 30 +#endif + +/** + * MEMP_NUM_SNMP_VARBIND: the number of concurrent requests (does not have to + * be changed normally) - 2 of these are used per request (1 for input, + * 1 for output) + */ +#ifndef MEMP_NUM_SNMP_VARBIND +#define MEMP_NUM_SNMP_VARBIND 2 +#endif + +/** + * MEMP_NUM_SNMP_VALUE: the number of OID or values concurrently used + * (does not have to be changed normally) - 3 of these are used per request + * (1 for the value read and 2 for OIDs - input and output) + */ +#ifndef MEMP_NUM_SNMP_VALUE +#define MEMP_NUM_SNMP_VALUE 3 +#endif + +/** + * MEMP_NUM_NETDB: the number of concurrently running lwip_addrinfo() calls + * (before freeing the corresponding memory using lwip_freeaddrinfo()). + */ +#ifndef MEMP_NUM_NETDB +#define MEMP_NUM_NETDB 1 +#endif + +/** + * MEMP_NUM_LOCALHOSTLIST: the number of host entries in the local host list + * if DNS_LOCAL_HOSTLIST_IS_DYNAMIC==1. + */ +#ifndef MEMP_NUM_LOCALHOSTLIST +#define MEMP_NUM_LOCALHOSTLIST 1 +#endif + +/** + * MEMP_NUM_PPPOE_INTERFACES: the number of concurrently active PPPoE + * interfaces (only used with PPPOE_SUPPORT==1) + */ +#ifndef MEMP_NUM_PPPOE_INTERFACES +#define MEMP_NUM_PPPOE_INTERFACES 1 +#endif + +/** + * PBUF_POOL_SIZE: the number of buffers in the pbuf pool. + */ +#ifndef PBUF_POOL_SIZE +#define PBUF_POOL_SIZE 16 +#endif + +/* + --------------------------------- + ---------- ARP options ---------- + --------------------------------- +*/ +/** + * LWIP_ARP==1: Enable ARP functionality. + */ +#ifndef LWIP_ARP +#define LWIP_ARP 1 +#endif + +/** + * ARP_TABLE_SIZE: Number of active MAC-IP address pairs cached. + */ +#ifndef ARP_TABLE_SIZE +#define ARP_TABLE_SIZE 10 +#endif + +/** + * ARP_QUEUEING==1: Multiple outgoing packets are queued during hardware address + * resolution. By default, only the most recent packet is queued per IP address. + * This is sufficient for most protocols and mainly reduces TCP connection + * startup time. Set this to 1 if you know your application sends more than one + * packet in a row to an IP address that is not in the ARP cache. + */ +#ifndef ARP_QUEUEING +#define ARP_QUEUEING 0 +#endif + +/** + * ETHARP_TRUST_IP_MAC==1: Incoming IP packets cause the ARP table to be + * updated with the source MAC and IP addresses supplied in the packet. + * You may want to disable this if you do not trust LAN peers to have the + * correct addresses, or as a limited approach to attempt to handle + * spoofing. If disabled, lwIP will need to make a new ARP request if + * the peer is not already in the ARP table, adding a little latency. + * The peer *is* in the ARP table if it requested our address before. + * Also notice that this slows down input processing of every IP packet! + */ +#ifndef ETHARP_TRUST_IP_MAC +#define ETHARP_TRUST_IP_MAC 0 +#endif + +/** + * ETHARP_SUPPORT_VLAN==1: support receiving ethernet packets with VLAN header. + * Additionally, you can define ETHARP_VLAN_CHECK to an u16_t VLAN ID to check. + * If ETHARP_VLAN_CHECK is defined, only VLAN-traffic for this VLAN is accepted. + * If ETHARP_VLAN_CHECK is not defined, all traffic is accepted. + * Alternatively, define a function/define ETHARP_VLAN_CHECK_FN(eth_hdr, vlan) + * that returns 1 to accept a packet or 0 to drop a packet. + */ +#ifndef ETHARP_SUPPORT_VLAN +#define ETHARP_SUPPORT_VLAN 0 +#endif + +/** LWIP_ETHERNET==1: enable ethernet support for PPPoE even though ARP + * might be disabled + */ +#ifndef LWIP_ETHERNET +#define LWIP_ETHERNET (LWIP_ARP || PPPOE_SUPPORT) +#endif + +/** ETH_PAD_SIZE: number of bytes added before the ethernet header to ensure + * alignment of payload after that header. Since the header is 14 bytes long, + * without this padding e.g. addresses in the IP header will not be aligned + * on a 32-bit boundary, so setting this to 2 can speed up 32-bit-platforms. + */ +#ifndef ETH_PAD_SIZE +#define ETH_PAD_SIZE 0 +#endif + +/** ETHARP_SUPPORT_STATIC_ENTRIES==1: enable code to support static ARP table + * entries (using etharp_add_static_entry/etharp_remove_static_entry). + */ +#ifndef ETHARP_SUPPORT_STATIC_ENTRIES +#define ETHARP_SUPPORT_STATIC_ENTRIES 0 +#endif + + +/* + -------------------------------- + ---------- IP options ---------- + -------------------------------- +*/ +/** + * IP_FORWARD==1: Enables the ability to forward IP packets across network + * interfaces. If you are going to run lwIP on a device with only one network + * interface, define this to 0. + */ +#ifndef IP_FORWARD +#define IP_FORWARD 0 +#endif + +/** + * IP_OPTIONS_ALLOWED: Defines the behavior for IP options. + * IP_OPTIONS_ALLOWED==0: All packets with IP options are dropped. + * IP_OPTIONS_ALLOWED==1: IP options are allowed (but not parsed). + */ +#ifndef IP_OPTIONS_ALLOWED +#define IP_OPTIONS_ALLOWED 1 +#endif + +/** + * IP_REASSEMBLY==1: Reassemble incoming fragmented IP packets. Note that + * this option does not affect outgoing packet sizes, which can be controlled + * via IP_FRAG. + */ +#ifndef IP_REASSEMBLY +#define IP_REASSEMBLY 1 +#endif + +/** + * IP_FRAG==1: Fragment outgoing IP packets if their size exceeds MTU. Note + * that this option does not affect incoming packet sizes, which can be + * controlled via IP_REASSEMBLY. + */ +#ifndef IP_FRAG +#define IP_FRAG 1 +#endif + +/** + * IP_REASS_MAXAGE: Maximum time (in multiples of IP_TMR_INTERVAL - so seconds, normally) + * a fragmented IP packet waits for all fragments to arrive. If not all fragments arrived + * in this time, the whole packet is discarded. + */ +#ifndef IP_REASS_MAXAGE +#define IP_REASS_MAXAGE 3 +#endif + +/** + * IP_REASS_MAX_PBUFS: Total maximum amount of pbufs waiting to be reassembled. + * Since the received pbufs are enqueued, be sure to configure + * PBUF_POOL_SIZE > IP_REASS_MAX_PBUFS so that the stack is still able to receive + * packets even if the maximum amount of fragments is enqueued for reassembly! + */ +#ifndef IP_REASS_MAX_PBUFS +#define IP_REASS_MAX_PBUFS 10 +#endif + +/** + * IP_FRAG_USES_STATIC_BUF==1: Use a static MTU-sized buffer for IP + * fragmentation. Otherwise pbufs are allocated and reference the original + * packet data to be fragmented (or with LWIP_NETIF_TX_SINGLE_PBUF==1, + * new PBUF_RAM pbufs are used for fragments). + * ATTENTION: IP_FRAG_USES_STATIC_BUF==1 may not be used for DMA-enabled MACs! + */ +#ifndef IP_FRAG_USES_STATIC_BUF +#define IP_FRAG_USES_STATIC_BUF 0 +#endif + +/** + * IP_FRAG_MAX_MTU: Assumed max MTU on any interface for IP frag buffer + * (requires IP_FRAG_USES_STATIC_BUF==1) + */ +#if IP_FRAG_USES_STATIC_BUF && !defined(IP_FRAG_MAX_MTU) +#define IP_FRAG_MAX_MTU 1500 +#endif + +/** + * IP_DEFAULT_TTL: Default value for Time-To-Live used by transport layers. + */ +#ifndef IP_DEFAULT_TTL +#define IP_DEFAULT_TTL 255 +#endif + +/** + * IP_SOF_BROADCAST=1: Use the SOF_BROADCAST field to enable broadcast + * filter per pcb on udp and raw send operations. To enable broadcast filter + * on recv operations, you also have to set IP_SOF_BROADCAST_RECV=1. + */ +#ifndef IP_SOF_BROADCAST +#define IP_SOF_BROADCAST 1 +#endif + +/** + * IP_SOF_BROADCAST_RECV (requires IP_SOF_BROADCAST=1) enable the broadcast + * filter on recv operations. + */ +#ifndef IP_SOF_BROADCAST_RECV +#define IP_SOF_BROADCAST_RECV 1 +#endif + +/** + * IP_FORWARD_ALLOW_TX_ON_RX_NETIF==1: allow ip_forward() to send packets back + * out on the netif where it was received. This should only be used for + * wireless networks. + * ATTENTION: When this is 1, make sure your netif driver correctly marks incoming + * link-layer-broadcast/multicast packets as such using the corresponding pbuf flags! + */ +#ifndef IP_FORWARD_ALLOW_TX_ON_RX_NETIF +#define IP_FORWARD_ALLOW_TX_ON_RX_NETIF 0 +#endif + +/** + * LWIP_RANDOMIZE_INITIAL_LOCAL_PORTS==1: randomize the local port for the first + * local TCP/UDP pcb (default==0). This can prevent creating predictable port + * numbers after booting a device. + */ +#ifndef LWIP_RANDOMIZE_INITIAL_LOCAL_PORTS +#define LWIP_RANDOMIZE_INITIAL_LOCAL_PORTS 0 +#endif + +/* + ---------------------------------- + ---------- ICMP options ---------- + ---------------------------------- +*/ +/** + * LWIP_ICMP==1: Enable ICMP module inside the IP stack. + * Be careful, disable that make your product non-compliant to RFC1122 + */ +#ifndef LWIP_ICMP +#define LWIP_ICMP 1 +#endif + +/** + * ICMP_TTL: Default value for Time-To-Live used by ICMP packets. + */ +#ifndef ICMP_TTL +#define ICMP_TTL (IP_DEFAULT_TTL) +#endif + +/** + * LWIP_BROADCAST_PING==1: respond to broadcast pings (default is unicast only) + */ +#ifndef LWIP_BROADCAST_PING +#define LWIP_BROADCAST_PING 0 +#endif + +/** + * LWIP_MULTICAST_PING==1: respond to multicast pings (default is unicast only) + */ +#ifndef LWIP_MULTICAST_PING +#define LWIP_MULTICAST_PING 0 +#endif + +/* + --------------------------------- + ---------- RAW options ---------- + --------------------------------- +*/ +/** + * LWIP_RAW==1: Enable application layer to hook into the IP layer itself. + */ +#ifndef LWIP_RAW +#define LWIP_RAW 1 +#endif + +/** + * LWIP_RAW==1: Enable application layer to hook into the IP layer itself. + */ +#ifndef RAW_TTL +#define RAW_TTL (IP_DEFAULT_TTL) +#endif + +/* + ---------------------------------- + ---------- DHCP options ---------- + ---------------------------------- +*/ +/** + * LWIP_DHCP==1: Enable DHCP module. + */ +#ifndef LWIP_DHCP +// Flash use: 7960 Bytes (9100 on IPv6) +#define LWIP_DHCP 1 +#endif + +/** + * DHCP_DOES_ARP_CHECK==1: Do an ARP check on the offered address. + */ +#ifndef DHCP_DOES_ARP_CHECK +#define DHCP_DOES_ARP_CHECK ((LWIP_DHCP) && (LWIP_ARP)) +#endif + +/* + ------------------------------------ + ---------- AUTOIP options ---------- + ------------------------------------ +*/ +/** + * LWIP_AUTOIP==1: Enable AUTOIP module. + */ +#ifndef LWIP_AUTOIP +#define LWIP_AUTOIP 0 +#endif + +/** + * LWIP_DHCP_AUTOIP_COOP==1: Allow DHCP and AUTOIP to be both enabled on + * the same interface at the same time. + */ +#ifndef LWIP_DHCP_AUTOIP_COOP +#define LWIP_DHCP_AUTOIP_COOP 0 +#endif + +/** + * LWIP_DHCP_AUTOIP_COOP_TRIES: Set to the number of DHCP DISCOVER probes + * that should be sent before falling back on AUTOIP. This can be set + * as low as 1 to get an AutoIP address very quickly, but you should + * be prepared to handle a changing IP address when DHCP overrides + * AutoIP. + */ +#ifndef LWIP_DHCP_AUTOIP_COOP_TRIES +#define LWIP_DHCP_AUTOIP_COOP_TRIES 9 +#endif + +/* + ---------------------------------- + ---------- SNMP options ---------- + ---------------------------------- +*/ +/** + * LWIP_SNMP==1: Turn on SNMP module. UDP must be available for SNMP + * transport. + */ +#ifndef LWIP_SNMP +#define LWIP_SNMP 0 +#endif + +/** + * SNMP_CONCURRENT_REQUESTS: Number of concurrent requests the module will + * allow. At least one request buffer is required. + * Does not have to be changed unless external MIBs answer request asynchronously + */ +#ifndef SNMP_CONCURRENT_REQUESTS +#define SNMP_CONCURRENT_REQUESTS 1 +#endif + +/** + * SNMP_TRAP_DESTINATIONS: Number of trap destinations. At least one trap + * destination is required + */ +#ifndef SNMP_TRAP_DESTINATIONS +#define SNMP_TRAP_DESTINATIONS 1 +#endif + +/** + * SNMP_PRIVATE_MIB: + * When using a private MIB, you have to create a file 'private_mib.h' that contains + * a 'struct mib_array_node mib_private' which contains your MIB. + */ +#ifndef SNMP_PRIVATE_MIB +#define SNMP_PRIVATE_MIB 0 +#endif + +/** + * Only allow SNMP write actions that are 'safe' (e.g. disabeling netifs is not + * a safe action and disabled when SNMP_SAFE_REQUESTS = 1). + * Unsafe requests are disabled by default! + */ +#ifndef SNMP_SAFE_REQUESTS +#define SNMP_SAFE_REQUESTS 1 +#endif + +/** + * The maximum length of strings used. This affects the size of + * MEMP_SNMP_VALUE elements. + */ +#ifndef SNMP_MAX_OCTET_STRING_LEN +#define SNMP_MAX_OCTET_STRING_LEN 127 +#endif + +/** + * The maximum depth of the SNMP tree. + * With private MIBs enabled, this depends on your MIB! + * This affects the size of MEMP_SNMP_VALUE elements. + */ +#ifndef SNMP_MAX_TREE_DEPTH +#define SNMP_MAX_TREE_DEPTH 15 +#endif + +/** + * The size of the MEMP_SNMP_VALUE elements, normally calculated from + * SNMP_MAX_OCTET_STRING_LEN and SNMP_MAX_TREE_DEPTH. + */ +#ifndef SNMP_MAX_VALUE_SIZE +#define SNMP_MAX_VALUE_SIZE LWIP_MAX((SNMP_MAX_OCTET_STRING_LEN)+1, sizeof(s32_t)*(SNMP_MAX_TREE_DEPTH)) +#endif + +/* + ---------------------------------- + ---------- IGMP options ---------- + ---------------------------------- +*/ +/** + * LWIP_IGMP==1: Turn on IGMP module. + */ +#ifndef LWIP_IGMP +#define LWIP_IGMP 0 +#endif + +/* + ---------------------------------- + ---------- DNS options ----------- + ---------------------------------- +*/ +/** + * LWIP_DNS==1: Turn on DNS module. UDP must be available for DNS + * transport. + */ +#ifndef LWIP_DNS +#define LWIP_DNS 1 +#endif + +/** DNS maximum number of entries to maintain locally. */ +#ifndef DNS_TABLE_SIZE +#define DNS_TABLE_SIZE 4 +#endif + +/** DNS maximum host name length supported in the name table. */ +#ifndef DNS_MAX_NAME_LENGTH +#define DNS_MAX_NAME_LENGTH 256 +#endif + +/** The maximum of DNS servers */ +#ifndef DNS_MAX_SERVERS +#define DNS_MAX_SERVERS 2 +#endif + +/** DNS do a name checking between the query and the response. */ +#ifndef DNS_DOES_NAME_CHECK +#define DNS_DOES_NAME_CHECK 1 +#endif + +/** DNS message max. size. Default value is RFC compliant. */ +#ifndef DNS_MSG_SIZE +#define DNS_MSG_SIZE 512 +#endif + +/** DNS_LOCAL_HOSTLIST: Implements a local host-to-address list. If enabled, + * you have to define + * #define DNS_LOCAL_HOSTLIST_INIT {{"host1", 0x123}, {"host2", 0x234}} + * (an array of structs name/address, where address is an u32_t in network + * byte order). + * + * Instead, you can also use an external function: + * #define DNS_LOOKUP_LOCAL_EXTERN(x) extern u32_t my_lookup_function(const char *name) + * that returns the IP address or INADDR_NONE if not found. + */ +#ifndef DNS_LOCAL_HOSTLIST +#define DNS_LOCAL_HOSTLIST 0 +#endif /* DNS_LOCAL_HOSTLIST */ + +/** If this is turned on, the local host-list can be dynamically changed + * at runtime. */ +#ifndef DNS_LOCAL_HOSTLIST_IS_DYNAMIC +#define DNS_LOCAL_HOSTLIST_IS_DYNAMIC 0 +#endif /* DNS_LOCAL_HOSTLIST_IS_DYNAMIC */ + +/* + --------------------------------- + ---------- UDP options ---------- + --------------------------------- +*/ +/** + * LWIP_UDP==1: Turn on UDP. + */ +#ifndef LWIP_UDP +#define LWIP_UDP 1 +#endif + +/** + * LWIP_UDPLITE==1: Turn on UDP-Lite. (Requires LWIP_UDP) + */ +#ifndef LWIP_UDPLITE +#define LWIP_UDPLITE 0 +#endif + +/** + * UDP_TTL: Default Time-To-Live value. + */ +#ifndef UDP_TTL +#define UDP_TTL (IP_DEFAULT_TTL) +#endif + +/** + * LWIP_NETBUF_RECVINFO==1: append destination addr and port to every netbuf. + */ +#ifndef LWIP_NETBUF_RECVINFO +#define LWIP_NETBUF_RECVINFO 0 +#endif + +/* + --------------------------------- + ---------- TCP options ---------- + --------------------------------- +*/ +/** + * LWIP_TCP==1: Turn on TCP. + */ +#ifndef LWIP_TCP +#define LWIP_TCP 1 +#endif + +/** + * TCP_TTL: Default Time-To-Live value. + */ +#ifndef TCP_TTL +#define TCP_TTL (IP_DEFAULT_TTL) +#endif + +/** + * TCP_WND: The size of a TCP window. This must be at least + * (2 * TCP_MSS) for things to work well + */ +#ifndef TCP_WND +#define TCP_WND (4 * TCP_MSS) +#endif + +/** + * TCP_MAXRTX: Maximum number of retransmissions of data segments. + */ +#ifndef TCP_MAXRTX +#define TCP_MAXRTX 12 +#endif + +/** + * TCP_SYNMAXRTX: Maximum number of retransmissions of SYN segments. + */ +#ifndef TCP_SYNMAXRTX +#define TCP_SYNMAXRTX 6 +#endif + +/** + * TCP_QUEUE_OOSEQ==1: TCP will queue segments that arrive out of order. + * Define to 0 if your device is low on memory. + */ +#ifndef TCP_QUEUE_OOSEQ +#define TCP_QUEUE_OOSEQ (LWIP_TCP) +#endif + +/** + * TCP_MSS: TCP Maximum segment size. (default is 536, a conservative default, + * you might want to increase this.) + * For the receive side, this MSS is advertised to the remote side + * when opening a connection. For the transmit size, this MSS sets + * an upper limit on the MSS advertised by the remote host. + */ +#ifndef TCP_MSS +#define TCP_MSS 1480 +#endif + +/** + * TCP_CALCULATE_EFF_SEND_MSS: "The maximum size of a segment that TCP really + * sends, the 'effective send MSS,' MUST be the smaller of the send MSS (which + * reflects the available reassembly buffer size at the remote host) and the + * largest size permitted by the IP layer" (RFC 1122) + * Setting this to 1 enables code that checks TCP_MSS against the MTU of the + * netif used for a connection and limits the MSS if it would be too big otherwise. + */ +#ifndef TCP_CALCULATE_EFF_SEND_MSS +#define TCP_CALCULATE_EFF_SEND_MSS 1 +#endif + + +/** + * TCP_SND_BUF: TCP sender buffer space (bytes). + * To achieve good performance, this should be at least 2 * TCP_MSS. + */ +#ifndef TCP_SND_BUF +#define TCP_SND_BUF (2 * TCP_MSS) +#endif + +/** + * TCP_SND_QUEUELEN: TCP sender buffer space (pbufs). This must be at least + * as much as (2 * TCP_SND_BUF/TCP_MSS) for things to work. + */ +#ifndef TCP_SND_QUEUELEN +#define TCP_SND_QUEUELEN ((4 * (TCP_SND_BUF) + (TCP_MSS - 1))/(TCP_MSS)) +#endif + +/** + * TCP_SNDLOWAT: TCP writable space (bytes). This must be less than + * TCP_SND_BUF. It is the amount of space which must be available in the + * TCP snd_buf for select to return writable (combined with TCP_SNDQUEUELOWAT). + */ +#ifndef TCP_SNDLOWAT +#define TCP_SNDLOWAT LWIP_MIN(LWIP_MAX(((TCP_SND_BUF)/2), (2 * TCP_MSS) + 1), (TCP_SND_BUF) - 1) +#endif + +/** + * TCP_SNDQUEUELOWAT: TCP writable bufs (pbuf count). This must be less + * than TCP_SND_QUEUELEN. If the number of pbufs queued on a pcb drops below + * this number, select returns writable (combined with TCP_SNDLOWAT). + */ +#ifndef TCP_SNDQUEUELOWAT +#define TCP_SNDQUEUELOWAT LWIP_MAX(((TCP_SND_QUEUELEN)/2), 5) +#endif + +/** + * TCP_OOSEQ_MAX_BYTES: The maximum number of bytes queued on ooseq per pcb. + * Default is 0 (no limit). Only valid for TCP_QUEUE_OOSEQ==0. + */ +#ifndef TCP_OOSEQ_MAX_BYTES +#define TCP_OOSEQ_MAX_BYTES 0 +#endif + +/** + * TCP_OOSEQ_MAX_PBUFS: The maximum number of pbufs queued on ooseq per pcb. + * Default is 0 (no limit). Only valid for TCP_QUEUE_OOSEQ==0. + */ +#ifndef TCP_OOSEQ_MAX_PBUFS +#define TCP_OOSEQ_MAX_PBUFS 0 +#endif + +/** + * TCP_LISTEN_BACKLOG: Enable the backlog option for tcp listen pcb. + */ +#ifndef TCP_LISTEN_BACKLOG +#define TCP_LISTEN_BACKLOG 0 +#endif + +/** + * The maximum allowed backlog for TCP listen netconns. + * This backlog is used unless another is explicitly specified. + * 0xff is the maximum (u8_t). + */ +#ifndef TCP_DEFAULT_LISTEN_BACKLOG +#define TCP_DEFAULT_LISTEN_BACKLOG 0xff +#endif + +/** + * TCP_OVERSIZE: The maximum number of bytes that tcp_write may + * allocate ahead of time in an attempt to create shorter pbuf chains + * for transmission. The meaningful range is 0 to TCP_MSS. Some + * suggested values are: + * + * 0: Disable oversized allocation. Each tcp_write() allocates a new + pbuf (old behaviour). + * 1: Allocate size-aligned pbufs with minimal excess. Use this if your + * scatter-gather DMA requires aligned fragments. + * 128: Limit the pbuf/memory overhead to 20%. + * TCP_MSS: Try to create unfragmented TCP packets. + * TCP_MSS/4: Try to create 4 fragments or less per TCP packet. + */ +#ifndef TCP_OVERSIZE +#define TCP_OVERSIZE TCP_MSS +#endif + +/** + * LWIP_TCP_TIMESTAMPS==1: support the TCP timestamp option. + */ +#ifndef LWIP_TCP_TIMESTAMPS +#define LWIP_TCP_TIMESTAMPS 0 +#endif + +/** + * TCP_WND_UPDATE_THRESHOLD: difference in window to trigger an + * explicit window update + */ +#ifndef TCP_WND_UPDATE_THRESHOLD +#define TCP_WND_UPDATE_THRESHOLD (TCP_WND / 4) +#endif + +/** + * LWIP_EVENT_API and LWIP_CALLBACK_API: Only one of these should be set to 1. + * LWIP_EVENT_API==1: The user defines lwip_tcp_event() to receive all + * events (accept, sent, etc) that happen in the system. + * LWIP_CALLBACK_API==1: The PCB callback function is called directly + * for the event. This is the default. + */ +#if !defined(LWIP_EVENT_API) && !defined(LWIP_CALLBACK_API) +#define LWIP_EVENT_API 0 +#define LWIP_CALLBACK_API 1 +#endif + + +/* + ---------------------------------- + ---------- Pbuf options ---------- + ---------------------------------- +*/ +/** + * PBUF_LINK_HLEN: the number of bytes that should be allocated for a + * link level header. The default is 14, the standard value for + * Ethernet. + */ +#ifndef PBUF_LINK_HLEN +#define PBUF_LINK_HLEN (14 + ETH_PAD_SIZE) +#endif + +/** + * PBUF_POOL_BUFSIZE: the size of each pbuf in the pbuf pool. The default is + * designed to accomodate single full size TCP frame in one pbuf, including + * TCP_MSS, IP header, and link header. + */ +#ifndef PBUF_POOL_BUFSIZE +#define PBUF_POOL_BUFSIZE LWIP_MEM_ALIGN_SIZE(TCP_MSS+40+PBUF_LINK_HLEN) +#endif + +/* + ------------------------------------------------ + ---------- Network Interfaces options ---------- + ------------------------------------------------ +*/ +/** + * LWIP_NETIF_HOSTNAME==1: use DHCP_OPTION_HOSTNAME with netif's hostname + * field. + */ +#ifndef LWIP_NETIF_HOSTNAME +#define LWIP_NETIF_HOSTNAME 0 +#endif + +/** + * LWIP_NETIF_API==1: Support netif api (in netifapi.c) + */ +#ifndef LWIP_NETIF_API +#define LWIP_NETIF_API 0 +#endif + +/** + * LWIP_NETIF_STATUS_CALLBACK==1: Support a callback function whenever an interface + * changes its up/down status (i.e., due to DHCP IP acquistion) + */ +#ifndef LWIP_NETIF_STATUS_CALLBACK +#define LWIP_NETIF_STATUS_CALLBACK 0 +#endif + +/** + * LWIP_NETIF_LINK_CALLBACK==1: Support a callback function from an interface + * whenever the link changes (i.e., link down) + */ +#ifndef LWIP_NETIF_LINK_CALLBACK +#define LWIP_NETIF_LINK_CALLBACK 0 +#endif + +/** + * LWIP_NETIF_REMOVE_CALLBACK==1: Support a callback function that is called + * when a netif has been removed + */ +#ifndef LWIP_NETIF_REMOVE_CALLBACK +#define LWIP_NETIF_REMOVE_CALLBACK 0 +#endif + +/** + * LWIP_NETIF_HWADDRHINT==1: Cache link-layer-address hints (e.g. table + * indices) in struct netif. TCP and UDP can make use of this to prevent + * scanning the ARP table for every sent packet. While this is faster for big + * ARP tables or many concurrent connections, it might be counterproductive + * if you have a tiny ARP table or if there never are concurrent connections. + */ +#ifndef LWIP_NETIF_HWADDRHINT +#define LWIP_NETIF_HWADDRHINT 0 +#endif + +/** + * LWIP_NETIF_LOOPBACK==1: Support sending packets with a destination IP + * address equal to the netif IP address, looping them back up the stack. + */ +#ifndef LWIP_NETIF_LOOPBACK +#define LWIP_NETIF_LOOPBACK 0 +#endif + +/** + * LWIP_LOOPBACK_MAX_PBUFS: Maximum number of pbufs on queue for loopback + * sending for each netif (0 = disabled) + */ +#ifndef LWIP_LOOPBACK_MAX_PBUFS +#define LWIP_LOOPBACK_MAX_PBUFS 0 +#endif + +/** + * LWIP_NETIF_LOOPBACK_MULTITHREADING: Indicates whether threading is enabled in + * the system, as netifs must change how they behave depending on this setting + * for the LWIP_NETIF_LOOPBACK option to work. + * Setting this is needed to avoid reentering non-reentrant functions like + * tcp_input(). + * LWIP_NETIF_LOOPBACK_MULTITHREADING==1: Indicates that the user is using a + * multithreaded environment like tcpip.c. In this case, netif->input() + * is called directly. + * LWIP_NETIF_LOOPBACK_MULTITHREADING==0: Indicates a polling (or NO_SYS) setup. + * The packets are put on a list and netif_poll() must be called in + * the main application loop. + */ +#ifndef LWIP_NETIF_LOOPBACK_MULTITHREADING +#define LWIP_NETIF_LOOPBACK_MULTITHREADING (!NO_SYS) +#endif + +/** + * LWIP_NETIF_TX_SINGLE_PBUF: if this is set to 1, lwIP tries to put all data + * to be sent into one single pbuf. This is for compatibility with DMA-enabled + * MACs that do not support scatter-gather. + * Beware that this might involve CPU-memcpy before transmitting that would not + * be needed without this flag! Use this only if you need to! + * + * @todo: TCP and IP-frag do not work with this, yet: + */ +#ifndef LWIP_NETIF_TX_SINGLE_PBUF +#define LWIP_NETIF_TX_SINGLE_PBUF 0 +#endif /* LWIP_NETIF_TX_SINGLE_PBUF */ + +/* + ------------------------------------ + ---------- LOOPIF options ---------- + ------------------------------------ +*/ +/** + * LWIP_HAVE_LOOPIF==1: Support loop interface (127.0.0.1) and loopif.c + */ +#ifndef LWIP_HAVE_LOOPIF +#define LWIP_HAVE_LOOPIF 0 +#endif + +/* + ------------------------------------ + ---------- SLIPIF options ---------- + ------------------------------------ +*/ +/** + * LWIP_HAVE_SLIPIF==1: Support slip interface and slipif.c + */ +#ifndef LWIP_HAVE_SLIPIF +#define LWIP_HAVE_SLIPIF 0 +#endif + +/* + ------------------------------------ + ---------- Thread options ---------- + ------------------------------------ +*/ +/** + * TCPIP_THREAD_NAME: The name assigned to the main tcpip thread. + */ +#ifndef TCPIP_THREAD_NAME +#define TCPIP_THREAD_NAME "tcpip_thread" +#endif + +/** + * TCPIP_THREAD_STACKSIZE: The stack size used by the main tcpip thread. + * The stack size value itself is platform-dependent, but is passed to + * sys_thread_new() when the thread is created. + */ +#ifndef TCPIP_THREAD_STACKSIZE +#define TCPIP_THREAD_STACKSIZE 1024 +#endif + +/** + * TCPIP_THREAD_PRIO: The priority assigned to the main tcpip thread. + * The priority value itself is platform-dependent, but is passed to + * sys_thread_new() when the thread is created. + */ +#ifndef TCPIP_THREAD_PRIO +#define TCPIP_THREAD_PRIO (LOWPRIO + 1) +#endif + +/** + * TCPIP_MBOX_SIZE: The mailbox size for the tcpip thread messages + * The queue size value itself is platform-dependent, but is passed to + * sys_mbox_new() when tcpip_init is called. + */ +#ifndef TCPIP_MBOX_SIZE +#define TCPIP_MBOX_SIZE MEMP_NUM_PBUF +#endif + +/** + * SLIPIF_THREAD_NAME: The name assigned to the slipif_loop thread. + */ +#ifndef SLIPIF_THREAD_NAME +#define SLIPIF_THREAD_NAME "slipif_loop" +#endif + +/** + * SLIP_THREAD_STACKSIZE: The stack size used by the slipif_loop thread. + * The stack size value itself is platform-dependent, but is passed to + * sys_thread_new() when the thread is created. + */ +#ifndef SLIPIF_THREAD_STACKSIZE +#define SLIPIF_THREAD_STACKSIZE 1024 +#endif + +/** + * SLIPIF_THREAD_PRIO: The priority assigned to the slipif_loop thread. + * The priority value itself is platform-dependent, but is passed to + * sys_thread_new() when the thread is created. + */ +#ifndef SLIPIF_THREAD_PRIO +#define SLIPIF_THREAD_PRIO (LOWPRIO + 1) +#endif + +/** + * PPP_THREAD_NAME: The name assigned to the pppInputThread. + */ +#ifndef PPP_THREAD_NAME +#define PPP_THREAD_NAME "pppInputThread" +#endif + +/** + * PPP_THREAD_STACKSIZE: The stack size used by the pppInputThread. + * The stack size value itself is platform-dependent, but is passed to + * sys_thread_new() when the thread is created. + */ +#ifndef PPP_THREAD_STACKSIZE +#define PPP_THREAD_STACKSIZE 1024 +#endif + +/** + * PPP_THREAD_PRIO: The priority assigned to the pppInputThread. + * The priority value itself is platform-dependent, but is passed to + * sys_thread_new() when the thread is created. + */ +#ifndef PPP_THREAD_PRIO +#define PPP_THREAD_PRIO (LOWPRIO + 1) +#endif + +/** + * DEFAULT_THREAD_NAME: The name assigned to any other lwIP thread. + */ +#ifndef DEFAULT_THREAD_NAME +#define DEFAULT_THREAD_NAME "lwIP" +#endif + +/** + * DEFAULT_THREAD_STACKSIZE: The stack size used by any other lwIP thread. + * The stack size value itself is platform-dependent, but is passed to + * sys_thread_new() when the thread is created. + */ +#ifndef DEFAULT_THREAD_STACKSIZE +#define DEFAULT_THREAD_STACKSIZE 1024 +#endif + +/** + * DEFAULT_THREAD_PRIO: The priority assigned to any other lwIP thread. + * The priority value itself is platform-dependent, but is passed to + * sys_thread_new() when the thread is created. + */ +#ifndef DEFAULT_THREAD_PRIO +#define DEFAULT_THREAD_PRIO (LOWPRIO + 1) +#endif + +/** + * DEFAULT_RAW_RECVMBOX_SIZE: The mailbox size for the incoming packets on a + * NETCONN_RAW. The queue size value itself is platform-dependent, but is passed + * to sys_mbox_new() when the recvmbox is created. + */ +#ifndef DEFAULT_RAW_RECVMBOX_SIZE +#define DEFAULT_RAW_RECVMBOX_SIZE 4 +#endif + +/** + * DEFAULT_UDP_RECVMBOX_SIZE: The mailbox size for the incoming packets on a + * NETCONN_UDP. The queue size value itself is platform-dependent, but is passed + * to sys_mbox_new() when the recvmbox is created. + */ +#ifndef DEFAULT_UDP_RECVMBOX_SIZE +#define DEFAULT_UDP_RECVMBOX_SIZE 4 +#endif + +/** + * DEFAULT_TCP_RECVMBOX_SIZE: The mailbox size for the incoming packets on a + * NETCONN_TCP. The queue size value itself is platform-dependent, but is passed + * to sys_mbox_new() when the recvmbox is created. + */ +#ifndef DEFAULT_TCP_RECVMBOX_SIZE +#define DEFAULT_TCP_RECVMBOX_SIZE 40 +#endif + +/** + * DEFAULT_ACCEPTMBOX_SIZE: The mailbox size for the incoming connections. + * The queue size value itself is platform-dependent, but is passed to + * sys_mbox_new() when the acceptmbox is created. + */ +#ifndef DEFAULT_ACCEPTMBOX_SIZE +#define DEFAULT_ACCEPTMBOX_SIZE 4 +#endif + +/* + ---------------------------------------------- + ---------- Sequential layer options ---------- + ---------------------------------------------- +*/ +/** + * LWIP_TCPIP_CORE_LOCKING: (EXPERIMENTAL!) + * Don't use it if you're not an active lwIP project member + */ +#ifndef LWIP_TCPIP_CORE_LOCKING +#define LWIP_TCPIP_CORE_LOCKING 0 +#endif + +/** + * LWIP_TCPIP_CORE_LOCKING_INPUT: (EXPERIMENTAL!) + * Don't use it if you're not an active lwIP project member + */ +#ifndef LWIP_TCPIP_CORE_LOCKING_INPUT +#define LWIP_TCPIP_CORE_LOCKING_INPUT 0 +#endif + +/** + * LWIP_NETCONN==1: Enable Netconn API (require to use api_lib.c) + */ +#ifndef LWIP_NETCONN +#define LWIP_NETCONN 1 +#endif + +/** LWIP_TCPIP_TIMEOUT==1: Enable tcpip_timeout/tcpip_untimeout tod create + * timers running in tcpip_thread from another thread. + */ +#ifndef LWIP_TCPIP_TIMEOUT +#define LWIP_TCPIP_TIMEOUT 1 +#endif + +/* + ------------------------------------ + ---------- Socket options ---------- + ------------------------------------ +*/ +/** + * LWIP_SOCKET==1: Enable Socket API (require to use sockets.c) + */ +#ifndef LWIP_SOCKET +#define LWIP_SOCKET 1 +#endif + +/** + * LWIP_COMPAT_SOCKETS==1: Enable BSD-style sockets functions names. + * (only used if you use sockets.c) + */ +#ifndef LWIP_COMPAT_SOCKETS +#define LWIP_COMPAT_SOCKETS 2 +#endif + +/** + * LWIP_POSIX_SOCKETS_IO_NAMES==1: Enable POSIX-style sockets functions names. + * Disable this option if you use a POSIX operating system that uses the same + * names (read, write & close). (only used if you use sockets.c) + */ +#ifndef LWIP_POSIX_SOCKETS_IO_NAMES +#define LWIP_POSIX_SOCKETS_IO_NAMES 1 +#endif + +/** + * LWIP_TCP_KEEPALIVE==1: Enable TCP_KEEPIDLE, TCP_KEEPINTVL and TCP_KEEPCNT + * options processing. Note that TCP_KEEPIDLE and TCP_KEEPINTVL have to be set + * in seconds. (does not require sockets.c, and will affect tcp.c) + */ +#ifndef LWIP_TCP_KEEPALIVE +#define LWIP_TCP_KEEPALIVE 0 +#endif + +/** + * LWIP_SO_SNDTIMEO==1: Enable send timeout for sockets/netconns and + * SO_SNDTIMEO processing. + */ +#ifndef LWIP_SO_SNDTIMEO +#define LWIP_SO_SNDTIMEO 0 +#endif + +/** + * LWIP_SO_RCVTIMEO==1: Enable receive timeout for sockets/netconns and + * SO_RCVTIMEO processing. + */ +#ifndef LWIP_SO_RCVTIMEO +#define LWIP_SO_RCVTIMEO 0 +#endif + +/** + * LWIP_SO_RCVBUF==1: Enable SO_RCVBUF processing. + */ +#ifndef LWIP_SO_RCVBUF +#define LWIP_SO_RCVBUF 0 +#endif + +/** + * If LWIP_SO_RCVBUF is used, this is the default value for recv_bufsize. + */ +#ifndef RECV_BUFSIZE_DEFAULT +#define RECV_BUFSIZE_DEFAULT INT_MAX +#endif + +/** + * SO_REUSE==1: Enable SO_REUSEADDR option. + */ +#ifndef SO_REUSE +#define SO_REUSE 0 +#endif + +/** + * SO_REUSE_RXTOALL==1: Pass a copy of incoming broadcast/multicast packets + * to all local matches if SO_REUSEADDR is turned on. + * WARNING: Adds a memcpy for every packet if passing to more than one pcb! + */ +#ifndef SO_REUSE_RXTOALL +#define SO_REUSE_RXTOALL 0 +#endif + +/* + ---------------------------------------- + ---------- Statistics options ---------- + ---------------------------------------- +*/ +/** + * LWIP_STATS==1: Enable statistics collection in lwip_stats. + */ +#ifndef LWIP_STATS +#define LWIP_STATS 1 +#endif + +#if LWIP_STATS + +/** + * LWIP_STATS_DISPLAY==1: Compile in the statistics output functions. + */ +#ifndef LWIP_STATS_DISPLAY +#define LWIP_STATS_DISPLAY 0 +#endif + +/** + * LINK_STATS==1: Enable link stats. + */ +#ifndef LINK_STATS +#define LINK_STATS 1 +#endif + +/** + * ETHARP_STATS==1: Enable etharp stats. + */ +#ifndef ETHARP_STATS +#define ETHARP_STATS (LWIP_ARP) +#endif + +/** + * IP_STATS==1: Enable IP stats. + */ +#ifndef IP_STATS +#define IP_STATS 1 +#endif + +/** + * IPFRAG_STATS==1: Enable IP fragmentation stats. Default is + * on if using either frag or reass. + */ +#ifndef IPFRAG_STATS +#define IPFRAG_STATS (IP_REASSEMBLY || IP_FRAG) +#endif + +/** + * ICMP_STATS==1: Enable ICMP stats. + */ +#ifndef ICMP_STATS +#define ICMP_STATS 1 +#endif + +/** + * IGMP_STATS==1: Enable IGMP stats. + */ +#ifndef IGMP_STATS +#define IGMP_STATS (LWIP_IGMP) +#endif + +/** + * UDP_STATS==1: Enable UDP stats. Default is on if + * UDP enabled, otherwise off. + */ +#ifndef UDP_STATS +#define UDP_STATS (LWIP_UDP) +#endif + +/** + * TCP_STATS==1: Enable TCP stats. Default is on if TCP + * enabled, otherwise off. + */ +#ifndef TCP_STATS +#define TCP_STATS (LWIP_TCP) +#endif + +/** + * MEM_STATS==1: Enable mem.c stats. + */ +#ifndef MEM_STATS +#define MEM_STATS ((MEM_LIBC_MALLOC == 0) && (MEM_USE_POOLS == 0)) +#endif + +/** + * MEMP_STATS==1: Enable memp.c pool stats. + */ +#ifndef MEMP_STATS +#define MEMP_STATS (MEMP_MEM_MALLOC == 0) +#endif + +/** + * SYS_STATS==1: Enable system stats (sem and mbox counts, etc). + */ +#ifndef SYS_STATS +#define SYS_STATS (NO_SYS == 0) +#endif + +#else + +#define LINK_STATS 0 +#define IP_STATS 0 +#define IPFRAG_STATS 0 +#define ICMP_STATS 0 +#define IGMP_STATS 0 +#define UDP_STATS 0 +#define TCP_STATS 0 +#define MEM_STATS 0 +#define MEMP_STATS 0 +#define SYS_STATS 0 +#define LWIP_STATS_DISPLAY 0 + +#endif /* LWIP_STATS */ + +/* + --------------------------------- + ---------- PPP options ---------- + --------------------------------- +*/ +/** + * PPP_SUPPORT==1: Enable PPP. + */ +#ifndef PPP_SUPPORT +#define PPP_SUPPORT 0 +#endif + +/** + * PPPOE_SUPPORT==1: Enable PPP Over Ethernet + */ +#ifndef PPPOE_SUPPORT +#define PPPOE_SUPPORT 0 +#endif + +/** + * PPPOS_SUPPORT==1: Enable PPP Over Serial + */ +#ifndef PPPOS_SUPPORT +#define PPPOS_SUPPORT PPP_SUPPORT +#endif + +#if PPP_SUPPORT + +/** + * NUM_PPP: Max PPP sessions. + */ +#ifndef NUM_PPP +#define NUM_PPP 1 +#endif + +/** + * PAP_SUPPORT==1: Support PAP. + */ +#ifndef PAP_SUPPORT +#define PAP_SUPPORT 0 +#endif + +/** + * CHAP_SUPPORT==1: Support CHAP. + */ +#ifndef CHAP_SUPPORT +#define CHAP_SUPPORT 0 +#endif + +/** + * MSCHAP_SUPPORT==1: Support MSCHAP. CURRENTLY NOT SUPPORTED! DO NOT SET! + */ +#ifndef MSCHAP_SUPPORT +#define MSCHAP_SUPPORT 0 +#endif + +/** + * CBCP_SUPPORT==1: Support CBCP. CURRENTLY NOT SUPPORTED! DO NOT SET! + */ +#ifndef CBCP_SUPPORT +#define CBCP_SUPPORT 0 +#endif + +/** + * CCP_SUPPORT==1: Support CCP. CURRENTLY NOT SUPPORTED! DO NOT SET! + */ +#ifndef CCP_SUPPORT +#define CCP_SUPPORT 0 +#endif + +/** + * VJ_SUPPORT==1: Support VJ header compression. + */ +#ifndef VJ_SUPPORT +#define VJ_SUPPORT 0 +#endif + +/** + * MD5_SUPPORT==1: Support MD5 (see also CHAP). + */ +#ifndef MD5_SUPPORT +#define MD5_SUPPORT 0 +#endif + +/* + * Timeouts + */ +#ifndef FSM_DEFTIMEOUT +#define FSM_DEFTIMEOUT 6 /* Timeout time in seconds */ +#endif + +#ifndef FSM_DEFMAXTERMREQS +#define FSM_DEFMAXTERMREQS 2 /* Maximum Terminate-Request transmissions */ +#endif + +#ifndef FSM_DEFMAXCONFREQS +#define FSM_DEFMAXCONFREQS 10 /* Maximum Configure-Request transmissions */ +#endif + +#ifndef FSM_DEFMAXNAKLOOPS +#define FSM_DEFMAXNAKLOOPS 5 /* Maximum number of nak loops */ +#endif + +#ifndef UPAP_DEFTIMEOUT +#define UPAP_DEFTIMEOUT 6 /* Timeout (seconds) for retransmitting req */ +#endif + +#ifndef UPAP_DEFREQTIME +#define UPAP_DEFREQTIME 30 /* Time to wait for auth-req from peer */ +#endif + +#ifndef CHAP_DEFTIMEOUT +#define CHAP_DEFTIMEOUT 6 /* Timeout time in seconds */ +#endif + +#ifndef CHAP_DEFTRANSMITS +#define CHAP_DEFTRANSMITS 10 /* max # times to send challenge */ +#endif + +/* Interval in seconds between keepalive echo requests, 0 to disable. */ +#ifndef LCP_ECHOINTERVAL +#define LCP_ECHOINTERVAL 0 +#endif + +/* Number of unanswered echo requests before failure. */ +#ifndef LCP_MAXECHOFAILS +#define LCP_MAXECHOFAILS 3 +#endif + +/* Max Xmit idle time (in jiffies) before resend flag char. */ +#ifndef PPP_MAXIDLEFLAG +#define PPP_MAXIDLEFLAG 100 +#endif + +/* + * Packet sizes + * + * Note - lcp shouldn't be allowed to negotiate stuff outside these + * limits. See lcp.h in the pppd directory. + * (XXX - these constants should simply be shared by lcp.c instead + * of living in lcp.h) + */ +#define PPP_MTU 1500 /* Default MTU (size of Info field) */ +#ifndef PPP_MAXMTU +/* #define PPP_MAXMTU 65535 - (PPP_HDRLEN + PPP_FCSLEN) */ +#define PPP_MAXMTU 1500 /* Largest MTU we allow */ +#endif +#define PPP_MINMTU 64 +#define PPP_MRU 1500 /* default MRU = max length of info field */ +#define PPP_MAXMRU 1500 /* Largest MRU we allow */ +#ifndef PPP_DEFMRU +#define PPP_DEFMRU 296 /* Try for this */ +#endif +#define PPP_MINMRU 128 /* No MRUs below this */ + +#ifndef MAXNAMELEN +#define MAXNAMELEN 256 /* max length of hostname or name for auth */ +#endif +#ifndef MAXSECRETLEN +#define MAXSECRETLEN 256 /* max length of password or secret */ +#endif + +#endif /* PPP_SUPPORT */ + +/* + -------------------------------------- + ---------- Checksum options ---------- + -------------------------------------- +*/ +/** + * CHECKSUM_GEN_IP==1: Generate checksums in software for outgoing IP packets. + */ +#ifndef CHECKSUM_GEN_IP +#define CHECKSUM_GEN_IP 1 +#endif + +/** + * CHECKSUM_GEN_UDP==1: Generate checksums in software for outgoing UDP packets. + */ +#ifndef CHECKSUM_GEN_UDP +#define CHECKSUM_GEN_UDP 1 +#endif + +/** + * CHECKSUM_GEN_TCP==1: Generate checksums in software for outgoing TCP packets. + */ +#ifndef CHECKSUM_GEN_TCP +#define CHECKSUM_GEN_TCP 1 +#endif + +/** + * CHECKSUM_GEN_ICMP==1: Generate checksums in software for outgoing ICMP packets. + */ +#ifndef CHECKSUM_GEN_ICMP +#define CHECKSUM_GEN_ICMP 1 +#endif + +/** + * CHECKSUM_CHECK_IP==1: Check checksums in software for incoming IP packets. + */ +#ifndef CHECKSUM_CHECK_IP +#define CHECKSUM_CHECK_IP 1 +#endif + +/** + * CHECKSUM_CHECK_UDP==1: Check checksums in software for incoming UDP packets. + */ +#ifndef CHECKSUM_CHECK_UDP +#define CHECKSUM_CHECK_UDP 1 +#endif + +/** + * CHECKSUM_CHECK_TCP==1: Check checksums in software for incoming TCP packets. + */ +#ifndef CHECKSUM_CHECK_TCP +#define CHECKSUM_CHECK_TCP 1 +#endif + +/** + * LWIP_CHECKSUM_ON_COPY==1: Calculate checksum when copying data from + * application buffers to pbufs. + */ +#ifndef LWIP_CHECKSUM_ON_COPY +#define LWIP_CHECKSUM_ON_COPY 0 +#endif + +/* + --------------------------------------- + ---------- Hook options --------------- + --------------------------------------- +*/ + +/* Hooks are undefined by default, define them to a function if you need them. */ + +/** + * LWIP_HOOK_IP4_INPUT(pbuf, input_netif): + * - called from ip_input() (IPv4) + * - pbuf: received struct pbuf passed to ip_input() + * - input_netif: struct netif on which the packet has been received + * Return values: + * - 0: Hook has not consumed the packet, packet is processed as normal + * - != 0: Hook has consumed the packet. + * If the hook consumed the packet, 'pbuf' is in the responsibility of the hook + * (i.e. free it when done). + */ + +/** + * LWIP_HOOK_IP4_ROUTE(dest): + * - called from ip_route() (IPv4) + * - dest: destination IPv4 address + * Returns the destination netif or NULL if no destination netif is found. In + * that case, ip_route() continues as normal. + */ + +/* + --------------------------------------- + ---------- Debugging options ---------- + --------------------------------------- +*/ +/** + * LWIP_DBG_MIN_LEVEL: After masking, the value of the debug is + * compared against this value. If it is smaller, then debugging + * messages are written. + */ +#ifndef LWIP_DBG_MIN_LEVEL +#define LWIP_DBG_MIN_LEVEL LWIP_DBG_LEVEL_ALL +#endif + +/** + * LWIP_DBG_TYPES_ON: A mask that can be used to globally enable/disable + * debug messages of certain types. + */ +#ifndef LWIP_DBG_TYPES_ON +#define LWIP_DBG_TYPES_ON LWIP_DBG_ON +#endif + +/** + * ETHARP_DEBUG: Enable debugging in etharp.c. + */ +#ifndef ETHARP_DEBUG +#define ETHARP_DEBUG LWIP_DBG_ON +#endif + +/** + * NETIF_DEBUG: Enable debugging in netif.c. + */ +#ifndef NETIF_DEBUG +#define NETIF_DEBUG LWIP_DBG_OFF +#endif + +/** + * PBUF_DEBUG: Enable debugging in pbuf.c. + */ +#ifndef PBUF_DEBUG +#define PBUF_DEBUG LWIP_DBG_OFF +#endif + +/** + * API_LIB_DEBUG: Enable debugging in api_lib.c. + */ +#ifndef API_LIB_DEBUG +#define API_LIB_DEBUG LWIP_DBG_OFF +#endif + +/** + * API_MSG_DEBUG: Enable debugging in api_msg.c. + */ +#ifndef API_MSG_DEBUG +#define API_MSG_DEBUG LWIP_DBG_OFF +#endif + +/** + * SOCKETS_DEBUG: Enable debugging in sockets.c. + */ +#ifndef SOCKETS_DEBUG +#define SOCKETS_DEBUG LWIP_DBG_OFF +#endif + +/** + * ICMP_DEBUG: Enable debugging in icmp.c. + */ +#ifndef ICMP_DEBUG +#define ICMP_DEBUG LWIP_DBG_OFF +#endif + +/** + * IGMP_DEBUG: Enable debugging in igmp.c. + */ +#ifndef IGMP_DEBUG +#define IGMP_DEBUG LWIP_DBG_OFF +#endif + +/** + * INET_DEBUG: Enable debugging in inet.c. + */ +#ifndef INET_DEBUG +#define INET_DEBUG LWIP_DBG_OFF +#endif + +/** + * IP_DEBUG: Enable debugging for IP. + */ +#ifndef IP_DEBUG +#define IP_DEBUG LWIP_DBG_OFF +#endif + +/** + * IP_REASS_DEBUG: Enable debugging in ip_frag.c for both frag & reass. + */ +#ifndef IP_REASS_DEBUG +#define IP_REASS_DEBUG LWIP_DBG_OFF +#endif + +/** + * RAW_DEBUG: Enable debugging in raw.c. + */ +#ifndef RAW_DEBUG +#define RAW_DEBUG LWIP_DBG_ON +#endif + +/** + * MEM_DEBUG: Enable debugging in mem.c. + */ +#ifndef MEM_DEBUG +#define MEM_DEBUG LWIP_DBG_ON +#endif + +/** + * MEMP_DEBUG: Enable debugging in memp.c. + */ +#ifndef MEMP_DEBUG +#define MEMP_DEBUG LWIP_DBG_OFF +#endif + +/** + * SYS_DEBUG: Enable debugging in sys.c. + */ +#ifndef SYS_DEBUG +#define SYS_DEBUG LWIP_DBG_ON +#endif + +/** + * TIMERS_DEBUG: Enable debugging in timers.c. + */ +#ifndef TIMERS_DEBUG +#define TIMERS_DEBUG LWIP_DBG_OFF +#endif + +/** + * TCP_DEBUG: Enable debugging for TCP. + */ +#ifndef TCP_DEBUG +#define TCP_DEBUG LWIP_DBG_OFF +#endif + +/** + * TCP_INPUT_DEBUG: Enable debugging in tcp_in.c for incoming debug. + */ +#ifndef TCP_INPUT_DEBUG +#define TCP_INPUT_DEBUG LWIP_DBG_OFF +#endif + +/** + * TCP_FR_DEBUG: Enable debugging in tcp_in.c for fast retransmit. + */ +#ifndef TCP_FR_DEBUG +#define TCP_FR_DEBUG LWIP_DBG_OFF +#endif + +/** + * TCP_RTO_DEBUG: Enable debugging in TCP for retransmit + * timeout. + */ +#ifndef TCP_RTO_DEBUG +#define TCP_RTO_DEBUG LWIP_DBG_OFF +#endif + +/** + * TCP_CWND_DEBUG: Enable debugging for TCP congestion window. + */ +#ifndef TCP_CWND_DEBUG +#define TCP_CWND_DEBUG LWIP_DBG_OFF +#endif + +/** + * TCP_WND_DEBUG: Enable debugging in tcp_in.c for window updating. + */ +#ifndef TCP_WND_DEBUG +#define TCP_WND_DEBUG LWIP_DBG_OFF +#endif + +/** + * TCP_OUTPUT_DEBUG: Enable debugging in tcp_out.c output functions. + */ +#ifndef TCP_OUTPUT_DEBUG +#define TCP_OUTPUT_DEBUG LWIP_DBG_OFF +#endif + +/** + * TCP_RST_DEBUG: Enable debugging for TCP with the RST message. + */ +#ifndef TCP_RST_DEBUG +#define TCP_RST_DEBUG LWIP_DBG_OFF +#endif + +/** + * TCP_QLEN_DEBUG: Enable debugging for TCP queue lengths. + */ +#ifndef TCP_QLEN_DEBUG +#define TCP_QLEN_DEBUG LWIP_DBG_OFF +#endif + +/** + * UDP_DEBUG: Enable debugging in UDP. + */ +#ifndef UDP_DEBUG +#define UDP_DEBUG LWIP_DBG_OFF +#endif + +/** + * TCPIP_DEBUG: Enable debugging in tcpip.c. + */ +#ifndef TCPIP_DEBUG +#define TCPIP_DEBUG LWIP_DBG_ON +#endif + +/** + * PPP_DEBUG: Enable debugging for PPP. + */ +#ifndef PPP_DEBUG +#define PPP_DEBUG LWIP_DBG_OFF +#endif + +/** + * SLIP_DEBUG: Enable debugging in slipif.c. + */ +#ifndef SLIP_DEBUG +#define SLIP_DEBUG LWIP_DBG_OFF +#endif + +/** + * DHCP_DEBUG: Enable debugging in dhcp.c. + */ +#ifndef DHCP_DEBUG +#define DHCP_DEBUG LWIP_DBG_OFF +#endif + +/** + * AUTOIP_DEBUG: Enable debugging in autoip.c. + */ +#ifndef AUTOIP_DEBUG +#define AUTOIP_DEBUG LWIP_DBG_OFF +#endif + +/** + * SNMP_MSG_DEBUG: Enable debugging for SNMP messages. + */ +#ifndef SNMP_MSG_DEBUG +#define SNMP_MSG_DEBUG LWIP_DBG_OFF +#endif + +/** + * SNMP_MIB_DEBUG: Enable debugging for SNMP MIBs. + */ +#ifndef SNMP_MIB_DEBUG +#define SNMP_MIB_DEBUG LWIP_DBG_OFF +#endif + +/** + * DNS_DEBUG: Enable debugging for DNS. + */ +#ifndef DNS_DEBUG +#define DNS_DEBUG LWIP_DBG_OFF +#endif + +#define LWIP_RAND chibios_rand_generate + +#endif /* __LWIPOPT_H__ */ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c index 100e1742459795..d9b30d5a69379b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c @@ -39,6 +39,7 @@ #define MEM_REGION_FLAG_DMA_OK 1 #define MEM_REGION_FLAG_FAST 2 #define MEM_REGION_FLAG_AXI_BUS 4 +#define MEM_REGION_FLAG_ETH_SAFE 8 #ifdef HAL_CHIBIOS_ENABLE_MALLOC_GUARD static mutex_t mem_mutex; @@ -125,8 +126,16 @@ static void *malloc_flags(size_t size, uint32_t flags) if (size == 0) { return NULL; } - const uint8_t dma_flags = (MEM_REGION_FLAG_DMA_OK | MEM_REGION_FLAG_AXI_BUS); - const uint8_t alignment = (flags&dma_flags?DMA_ALIGNMENT:MIN_ALIGNMENT); + const uint8_t dma_flags = (MEM_REGION_FLAG_DMA_OK | MEM_REGION_FLAG_AXI_BUS | MEM_REGION_FLAG_ETH_SAFE); + size_t alignment = (flags&dma_flags?DMA_ALIGNMENT:MIN_ALIGNMENT); + if (flags & MEM_REGION_FLAG_ETH_SAFE) { + // alignment needs to same as size + alignment = size; + // also size needs to be power of 2, if not return NULL + if ((size & (size-1)) != 0) { + return NULL; + } + } void *p = NULL; uint8_t i; @@ -159,6 +168,10 @@ static void *malloc_flags(size_t size, uint32_t flags) !(memory_regions[i].flags & MEM_REGION_FLAG_FAST)) { continue; } + if ((flags & MEM_REGION_FLAG_ETH_SAFE) && + !(memory_regions[i].flags & MEM_REGION_FLAG_ETH_SAFE)) { + continue; + } p = chHeapAllocAligned(&heaps[i], size, alignment); if (p) { goto found; @@ -371,6 +384,19 @@ void *malloc_axi_sram(size_t size) #endif } +/* + allocate memory for ethernet DMA +*/ +void *malloc_eth_safe(size_t size) +{ +#if defined(STM32H7) + return malloc_flags(size, MEM_REGION_FLAG_ETH_SAFE); +#else + (void)size; + return NULL; +#endif +} + /* allocate fast memory */ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h index a91c9725961116..0a56342d256fdb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h @@ -41,6 +41,7 @@ size_t mem_available(void); void *malloc_dma(size_t size); void *malloc_axi_sram(size_t size); void *malloc_fastmem(size_t size); +void *malloc_eth_safe(size_t size); thread_t *thread_create_alloc(size_t size, const char *name, tprio_t prio, tfunc_t pf, void *arg); struct memory_region { @@ -177,6 +178,9 @@ bool stm32_rand_generate_blocking(unsigned char* output, unsigned int sz, uint32 unsigned int stm32_rand_generate_nonblocking(unsigned char* output, unsigned int sz); #endif +// To be defined in HAL code +extern uint32_t chibios_rand_generate(void); + void stm32_flash_protect_flash(bool bootloader, bool protect); void stm32_flash_unprotect_flash(void); diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f1_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f1_mcuconf.h index 535f09edbd3d8b..2c0e37b12bb35a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f1_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32f1_mcuconf.h @@ -57,13 +57,21 @@ #define STM32_PLL2MUL_VALUE 16 #define STM32_PLL3MUL_VALUE 16 #elif STM32_HSECLK == 24000000U -#define STM32_SW STM32_SW_HSE +/* 24Mhz crystal on F103 is strictly illegal, but some boards (Pixhwak6X) have this. */ #define STM32_PLLSRC STM32_PLLSRC_HSE -#define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1 -#define STM32_PLLMUL_VALUE 9 +#define STM32_PLLMUL_VALUE 3 +#ifdef STM32F103_MCUCONF +#define STM32_SW STM32_SW_PLL +#define STM32_PPRE1 STM32_PPRE1_DIV2 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_ADCPRE STM32_ADCPRE_DIV4 +#else +#define STM32_SW STM32_SW_HSE #define STM32_PPRE1 STM32_PPRE1_DIV1 #define STM32_PPRE2 STM32_PPRE2_DIV1 #define STM32_ADCPRE STM32_ADCPRE_DIV2 +#endif +#define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1 #define STM32_HPRE STM32_HPRE_DIV1 #else #error "Unsupported STM32F1xx clock frequency" @@ -135,6 +143,13 @@ #define STM32_PWM_TIM5_IRQ_PRIORITY 7 #define STM32_PWM_TIM8_IRQ_PRIORITY 7 +#ifdef STM32F100_MCUCONF +#define STM32_TIM15_NUMBER 24 +#define STM32_TIM15_HANDLER VectorA0 +#define STM32_TIM17_NUMBER 26 +#define STM32_TIM17_HANDLER VectorA8 +#endif + /* * RTC driver system settings. */ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h index 6ad2e4ab691786..aeae4a3f7b56ac 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h @@ -65,11 +65,10 @@ /* * Memory attributes settings. */ -// Disable ChibiOS memory protection which is fixed to SRAM1-3 -#define STM32_NOCACHE_ENABLE FALSE -//#define STM32_NOCACHE_MPU_REGION MPU_REGION_6 -//#define STM32_NOCACHE_RBAR 0x24000000U -//#define STM32_NOCACHE_RASR MPU_RASR_SIZE_16K +// #define STM32_NOCACHE_ENABLE TRUE +#define STM32_NOCACHE_MPU_REGION_ETH MPU_REGION_6 +// #define STM32_NOCACHE_RBAR 0x30040000U +// #define STM32_NOCACHE_RASR MPU_RASR_SIZE_32K // enable memory protection on SRAM4, used for bdshot #define STM32_NOCACHE_MPU_REGION_1 MPU_REGION_5 @@ -286,9 +285,15 @@ #ifndef STM32_MCO1SEL #define STM32_MCO1SEL STM32_MCO1SEL_HSE_CK #endif +#ifndef STM32_MCO1PRE_VALUE #define STM32_MCO1PRE_VALUE 4 +#endif +#ifndef STM32_MCO2SEL #define STM32_MCO2SEL STM32_MCO2SEL_SYS_CK +#endif +#ifndef STM32_MCO2PRE_VALUE #define STM32_MCO2PRE_VALUE 4 +#endif #define STM32_TIMPRE_ENABLE TRUE #define STM32_HRTIMSEL 0 #define STM32_STOPKERWUCK 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_type2_mcuconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_type2_mcuconf.h index 197b3bcb5b72eb..e4e220f2d0751a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_type2_mcuconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_type2_mcuconf.h @@ -228,10 +228,18 @@ * Peripherals clocks static settings. * Reading STM32 Reference Manual is required. */ +#ifndef STM32_MCO1SEL #define STM32_MCO1SEL STM32_MCO1SEL_HSE_CK +#endif +#ifndef STM32_MCO1PRE_VALUE #define STM32_MCO1PRE_VALUE 1 +#endif +#ifndef STM32_MCO2SEL #define STM32_MCO2SEL STM32_MCO2SEL_SYS_CK +#endif +#ifndef STM32_MCO2PRE_VALUE #define STM32_MCO2PRE_VALUE 1 +#endif #define STM32_TIMPRE_ENABLE TRUE #define STM32_HRTIMSEL 0 #define STM32_STOPKERWUCK 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef-bl.dat index 5afebaac584cee..aa8b8b5a85113a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef-bl.dat @@ -1,5 +1,4 @@ include ../f103-periph/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_adsb" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat index 322adffe2df56e..333f3120cb3157 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-ADSB/hwdef.dat @@ -3,9 +3,6 @@ include ../f103-periph/hwdef.inc #STDOUT_SERIAL SD1 #STDOUT_BAUDRATE 115200 -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_adsb" - - define HAL_AIRSPEED_BUS_DEFAULT 0 define AIRSPEED_MAX_SENSORS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef-bl.dat index 2caf38d993213d..aa8b8b5a85113a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef-bl.dat @@ -1,5 +1,4 @@ include ../f103-periph/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.f103_airspeed" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef.dat index 1b6a8301c6ebed..e2d6cd654a0ff7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-Airspeed/hwdef.dat @@ -1,7 +1,5 @@ include ../f103-periph/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.f103_airspeed" - define HAL_AIRSPEED_BUS_DEFAULT 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef-bl.dat index 751f46aa651fb3..3f51ff61334697 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef-bl.dat @@ -1,4 +1,3 @@ include ../f103-periph/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat index d4130ac8e60df5..fa460f05c985c4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-GPS/hwdef.dat @@ -1,8 +1,6 @@ include ../f103-periph/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps" - # and support all external compass types define HAL_PROBE_EXTERNAL_I2C_COMPASSES # .... except BMM150: diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef-bl.dat index 7cc46df6faf5fb..9d4fdbc25f60c0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef-bl.dat @@ -2,4 +2,3 @@ include ../f103-periph/hwdef-bl.inc # start with a fixed node ID so the board is usable without DNA -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat index e5943d8ea455de..1148897580ef19 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-HWESC/hwdef.dat @@ -1,6 +1,4 @@ include ../f103-periph/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC" - define HAL_PERIPH_ENABLE_HWESC diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef-bl.dat index 6b957507a1eab8..aa8b8b5a85113a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef-bl.dat @@ -1,5 +1,4 @@ include ../f103-periph/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.f103Qiotek_Periph" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat index b5010ad49fe231..bbfec631fad60c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat @@ -1,7 +1,5 @@ include ../f103-periph/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.f103Qiotek_Periph" - undef HAL_COMPASS_MAX_SENSORS 1 define HAL_COMPASS_MAX_SENSORS 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef-bl.dat index 3ec41d6f5a4f1f..aa8b8b5a85113a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef-bl.dat @@ -1,6 +1,4 @@ include ../f103-periph/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_rangefinder" - diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat index d09f33d048ca8e..f5d9a57489d9d0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-RangeFinder/hwdef.dat @@ -1,7 +1,5 @@ include ../f103-periph/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_rangefinder" - define HAL_AIRSPEED_BUS_DEFAULT 0 define AIRSPEED_MAX_SENSORS 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef-bl.dat index 83eb480cb9b0be..3f51ff61334697 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef-bl.dat @@ -1,4 +1,3 @@ include ../f103-periph/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_trigger" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat index 9aaac36f979b82..14424c7a5836b5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-Trigger/hwdef.dat @@ -6,8 +6,6 @@ include ../f103-periph/hwdef.inc env AP_PERIPH 1 -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_trigger" - # PWM input to hardpoint out define HAL_PERIPH_ENABLE_PWM_HARDPOINT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.inc index cb5f175aeeec1a..ed5f1a9bd0a7d6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef-bl.inc @@ -23,35 +23,15 @@ define CH_CFG_ST_FREQUENCY 1000 # assume 128k flash part FLASH_SIZE_KB 128 -STDOUT_SERIAL SD1 -STDOUT_BAUDRATE 57600 - - -# order of UARTs -SERIAL_ORDER define HAL_USE_UART FALSE +define HAL_USE_SERIAL FALSE PA4 LED_BOOTLOADER OUTPUT LOW define HAL_LED_ON 1 -# USART1 -PA9 USART1_TX USART1 SPEED_HIGH -PA10 USART1_RX USART1 SPEED_HIGH - -# USART2 -PA2 USART2_TX USART2 SPEED_HIGH -PA3 USART2_RX USART2 SPEED_HIGH - -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 CH_CFG_ST_TIMEDELTA 0 #define CH_CFG_USE_DYNAMIC FALSE -define SERIAL_BUFFERS_SIZE 32 define HAL_USE_EMPTY_IO TRUE define PORT_INT_REQUIRED_STACK 64 @@ -71,9 +51,6 @@ PA12 CAN_TX CAN define HAL_USE_CAN TRUE define STM32_CAN_USE_CAN1 TRUE -# make bl baudrate match debug baudrate for easier debugging -define BOOTLOADER_BAUDRATE 57600 - # use a small bootloader timeout define HAL_BOOTLOADER_TIMEOUT 1000 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef-bl.dat index ac5591ab646565..98ddd5c83f235f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef-bl.dat @@ -1,4 +1,3 @@ include ../f303-periph/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat index 67e512fa4630a6..74679b18c5b7f8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-GPS/hwdef.dat @@ -1,8 +1,6 @@ include ../f303-periph/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps" - # added rm3100 mag on SPI SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ COMPASS RM3100 SPI:rm3100 false ROTATION_NONE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef-bl.dat index f0582a15057214..98ddd5c83f235f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef-bl.dat @@ -1,4 +1,3 @@ include ../f303-periph/hwdef-bl.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat index 43a756f5e18545..0b451af91dec68 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-HWESC/hwdef.dat @@ -1,6 +1,4 @@ include ../f303-periph/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC" - define HAL_PERIPH_ENABLE_HWESC diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef-bl.dat index 0ea72cbdaa0520..2ebf261d90681a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef-bl.dat @@ -2,4 +2,3 @@ include ../f303-periph/hwdef-bl.inc # start as DNA -define CAN_APP_NODE_NAME "org.ardupilot.mro_m10025" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat index 667514ecea3847..4d8a73e5edd638 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10025/hwdef.dat @@ -2,8 +2,6 @@ include ../f303-periph/hwdef.inc # start as DNA -define CAN_APP_NODE_NAME "org.ardupilot.mro_m10025" - # added rm3100 mag on SPI SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ COMPASS RM3100 SPI:rm3100 false ROTATION_NONE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef-bl.dat index da417ac1955998..d70ec3175b98fb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef-bl.dat @@ -3,6 +3,3 @@ include ../f303-periph/hwdef-bl.inc # mRo Location One CAN GPS # M10084 -# start as DNA - -define CAN_APP_NODE_NAME "io.mrobotics.m10070_loc1_BL" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat index 8e9236ca7d6838..31d44a99bd11ce 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-M10070/hwdef.dat @@ -3,8 +3,6 @@ include ../f303-periph/hwdef.inc # mRo Location One CAN GPS # M10070B -# start as DNA - define CAN_APP_NODE_NAME "io.mrobotics.m10070_loc1" # added rm3100 mag on SPI diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef-bl.dat index a1b7bd07b65c0a..202494dbf86b4c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef-bl.dat @@ -69,8 +69,6 @@ define HAL_DISABLE_LOOP_DELAY # enable CAN support PA11 CAN_RX CAN PA12 CAN_TX CAN -define HAL_USE_CAN TRUE -define STM32_CAN_USE_CAN1 TRUE # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 @@ -84,6 +82,3 @@ define HAL_BOOTLOADER_TIMEOUT 1000 # want to stay in the bootloader PB6 STAY_IN_BOOTLOADER INPUT FLOATING - - -define CAN_APP_NODE_NAME "org.ardupilot.f303_MatekGPS" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat index 45f83e68ec932a..5fbe6af4be41c3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat @@ -118,8 +118,6 @@ PB11 USART3_RX USART3 SPEED_HIGH # use DNA for node allocation -define CAN_APP_NODE_NAME "org.ardupilot.f303_MatekGPS" - # added QMC5883L mag on I2C COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef-bl.dat index fd1e5c332f8815..817e00be92fde6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef-bl.dat @@ -1,4 +1,2 @@ include ../f303-periph/hwdef-bl.inc - -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_PWM" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef.dat index 898d0715e8da83..9e8694b6ecbe65 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-PWM/hwdef.dat @@ -1,8 +1,6 @@ include ../f303-periph/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_PWM" - undef PA2 undef PA3 undef PB14 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-TempSensor/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-TempSensor/hwdef-bl.dat new file mode 100644 index 00000000000000..98ddd5c83f235f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-TempSensor/hwdef-bl.dat @@ -0,0 +1,3 @@ +include ../f303-periph/hwdef-bl.inc + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-TempSensor/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-TempSensor/hwdef.dat index 27f0acfbb08f06..827a5d339e93ea 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-TempSensor/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-TempSensor/hwdef.dat @@ -1,7 +1,5 @@ include ../f303-periph/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.TempSensor" - # These are tied to ground undef PA5 undef PA6 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef-bl.dat index bc24ce71f57eb2..817e00be92fde6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef-bl.dat @@ -1,4 +1,2 @@ include ../f303-periph/hwdef-bl.inc - -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_universal" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat index afb04ead2be7f6..9c0a941a1e85a5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-Universal/hwdef.dat @@ -1,8 +1,6 @@ include ../f303-periph/hwdef.inc -define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_universal" - # and support all external compass and baro types define HAL_PROBE_EXTERNAL_I2C_COMPASSES diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.inc index 09da6d4213f63f..78585ab9674bf2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef-bl.inc @@ -64,8 +64,6 @@ define HAL_DISABLE_LOOP_DELAY # enable CAN support PA11 CAN_RX CAN PA12 CAN_TX CAN -define HAL_USE_CAN TRUE -define STM32_CAN_USE_CAN1 TRUE # debugger support PA13 JTMS-SWDIO SWD diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekAirspeed/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekAirspeed/hwdef-bl.dat index af5a0423d3eb69..d563bd589fcd23 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekAirspeed/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekAirspeed/hwdef-bl.dat @@ -5,7 +5,4 @@ env AP_PERIPH 1 include ../f405-MatekGPS/hwdef-bl.dat -# Rename to f405_MatekAirspeed -undef CAN_APP_NODE_NAME -define CAN_APP_NODE_NAME "org.ardupilot.f405_MatekAirspeed" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekAirspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekAirspeed/hwdef.dat index b7e5a5798994e1..7633eb0fee77b5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekAirspeed/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekAirspeed/hwdef.dat @@ -5,10 +5,6 @@ env AP_PERIPH 1 include ../f405-MatekGPS/hwdef.dat -# Rename to f405_MatekAirspeed -undef CAN_APP_NODE_NAME -define CAN_APP_NODE_NAME "org.ardupilot.f405_MatekAirspeed" - # Setup Airspeed Sensor to be I2C-DLVR-10in undef HAL_AIRSPEED_TYPE_DEFAULT define HAL_AIRSPEED_TYPE_DEFAULT 9 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef-bl.dat index 91fd9eae63f6fb..92a17a0db240cf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef-bl.dat @@ -45,12 +45,6 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PC13 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_MatekGPS" - - # Add CS pins to ensure they are high in bootloader PA4 MPU_CS CS PB12 MAG_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat index 4ed9c4e433e289..6ac2a044f78122 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f405-MatekGPS/hwdef.dat @@ -102,11 +102,6 @@ PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW -# use DNA for node allocation - -define CAN_APP_NODE_NAME "org.ardupilot.f405_MatekGPS" - - # ---------------------- UARTs --------------------------- # | sr0 | sr1 | sr2 | GPS | MSP | SERIAL_ORDER USART1 USART2 USART3 UART4 UART5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat index 52cf485c71ab09..d6d69a2d96e439 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv2/hwdef.dat @@ -19,3 +19,6 @@ include ../include/minimal.inc # produce this error if we are on a 2M board and using 1M firmware define BOARD_CHECK_F427_USE_2M "2M flash - use fmuv3 firmware" + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3-bdshot/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3-bdshot/hwdef-bl.dat new file mode 100644 index 00000000000000..a71c921aa7f161 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3-bdshot/hwdef-bl.dat @@ -0,0 +1,4 @@ +# hw definition file for processing by chibios_hwdef.py +# for pixhawk1, based on fmuv3 + +include ../fmuv3/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat index 3ef2f2492de86b..3d997e90986bd8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv5/hwdef.dat @@ -25,9 +25,6 @@ env OPTIMIZE -O2 # order of UARTs (and USB) SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2 -# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers -define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 - # now we define the pins that USB is connected on PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 @@ -304,6 +301,9 @@ DMA_PRIORITY SDMMC* UART8* ADC* SPI* TIM* define HAL_OS_FATFS_IO 1 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_lowpolh.bin +define HAL_WITH_IO_MCU_DSHOT 1 # uncomment block below to enable a 2nd MS5611 baro on SPI5 #PF7 SPI5_SCK SPI5 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc index e5e18f3d6821f6..cd519bdd32839b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimal_GPS.inc @@ -2,4 +2,6 @@ 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 new file mode 100644 index 00000000000000..9309f1d2de8cde --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc @@ -0,0 +1,115 @@ +# this include file is used to remove features which will never be +# wanted on any low-flash board in our standard builds. It is to be +# included by other minimize_*.inc files and not generally used +# otherwise. + +# disable emitting nice strings when activating RC channel aux functions: +define AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED 0 + +# low-end boards aren't expected to be used in environments where +# things like satellite communications are required: +define HAL_HIGH_LATENCY2_ENABLED 0 + +# Gripper isn't a vital feature for smaller boards +define AP_GRIPPER_ENABLED 0 + +# Sprayer isn't a vital feature for smaller boards +define HAL_SPRAYER_ENABLED 0 + +# disable use of onboard FFT library: +define HAL_GYROFFT_ENABLED 0 + +# several notify backends are rare and not supported by default on smaller boards: +define AP_NOTIFY_NCP5623_ENABLED 0 + +# HOTT telemetry is quite rare, so we don't include it on smaller boards +define HAL_HOTT_TELEM_ENABLED 0 + +# smaller boards lose SIRF GPS support +define AP_GPS_SIRF_ENABLED 0 + +# no moving baseline support: +define GPS_MOVING_BASELINE 0 + +# No LTM telemetry on minimized boards: +define AP_LTM_TELEM_ENABLED 0 + +# various structures increase the flash size when using >16 servos: +define NUM_SERVO_CHANNELS 16 + +# no Winch if minimized: +define AP_WINCH_ENABLED 0 + +# prune out some odd camera backends: +define AP_CAMERA_BACKEND_DEFAULT_ENABLED 0 +define AP_CAMERA_RELAY_ENABLED AP_CAMERA_ENABLED +define AP_CAMERA_SERVO_ENABLED AP_CAMERA_ENABLED + +# no SLCAN on these boards (use can-over-mavlink if required) +define AP_CAN_SLCAN_ENABLED 0 + +# no PiccoloCAN: +define HAL_PICCOLO_CAN_ENABLE 0 + +# no beacon support on minimized boards: +define AP_BEACON_ENABLED 0 + +# restricted battery backends: +define AP_BATTERY_BACKEND_DEFAULT_ENABLED 0 +define AP_BATTERY_ANALOG_ENABLED 1 +define AP_BATTERY_ESC_ENABLED 1 +define AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED HAL_ENABLE_DRONECAN_DRIVERS +define AP_BATTERY_SUM_ENABLED 1 +define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 1 +define AP_BATTERY_SMBUS_ENABLED 1 +define AP_BATTERY_SMBUS_GENERIC_ENABLED AP_BATTERY_SMBUS_ENABLED +define AP_BATTERY_SMBUS_NEODESIGN_ENABLED AP_BATTERY_SMBUS_ENABLED +define AP_BATTERY_SMBUS_SUI_ENABLED AP_BATTERY_SMBUS_ENABLED +define AP_BATTERY_SMBUS_MAXELL_ENABLED AP_BATTERY_SMBUS_ENABLED +define AP_BATTERY_SMBUS_ROTOYE_ENABLED AP_BATTERY_SMBUS_ENABLED + +# don't probe for external Barometers: +define AP_BARO_PROBE_EXTERNAL_I2C_BUSES 0 + +# no wind compensation code: +define HAL_BARO_WIND_COMP_ENABLED 0 + +# no mounts: +define HAL_MOUNT_ENABLED 0 + +# no generator: +define HAL_GENERATOR_ENABLED 0 + +# no NMEA output: +define HAL_NMEA_OUTPUT_ENABLED 0 + +# no Notify Display support: +define HAL_DISPLAY_ENABLED 0 + +# remove support for killing IMUs at runtime - a developer feature: +define AP_INERTIALSENSOR_KILL_IMU_ENABLED 0 + +# shortened names in @SYS/taskinfo.txt +define AP_SCHEDULER_EXTENDED_TASKINFO_ENABLED 0 + +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 + +# Copter-specific defines; these defines are only used in the Copter +# directory, but are seen across the entire codebase: +define MODE_FLOWHOLD_ENABLED 0 +define MODE_ZIGZAG_ENABLED 0 +define AC_NAV_GUIDED 0 +define AC_OAPATHPLANNER_ENABLED 0 +define MODE_FOLLOW_ENABLED 0 +define MODE_GUIDED_NOGPS_ENABLED 0 +define MODE_SYSTEMID_ENABLED 0 +define WEATHERVANE_ENABLED 0 +define MODE_AUTOROTATE_ENABLED 0 + +# don't send RELAY_STATUS messages: +define AP_MAVLINK_MSG_RELAY_STATUS_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_features.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_features.inc index 29375b1f724090..4c5a45d6a0fb49 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_features.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_features.inc @@ -1,119 +1,37 @@ -# for now we make this define, but we should migrate from this to much -# more specific defines - added below. -define HAL_MINIMIZE_FEATURES 1 +# this is an include file to be used on low-flash boards which are not +# generally used for FPV/OSD purposes. Care must be taken to +# preserve existing features on these boards. -# disable emitting nice strings when activating RC channel aux functions: -define AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED 0 +include minimize_common.inc -# low-end boards aren't expected to be used in environments where -# things like satellite communications are required: -define HAL_HIGH_LATENCY2_ENABLED 0 +# remove various OSD features by default: +define OSD_ENABLED 0 +define HAL_PLUSCODE_ENABLE 0 +define HAL_OSD_SIDEBAR_ENABLE 0 +define OSD_PARAM_ENABLED 0 # Crossfire telemetry must be explicitly enabled on minimized boards: define HAL_CRSF_TELEM_ENABLED 0 -# Gripper isn't a vital feature for smaller boards -define AP_GRIPPER_ENABLED 0 - -# Sprayer isn't a vital feature for smaller boards -define HAL_SPRAYER_ENABLED 0 - -# RunCam control isn't available on smaller boards -define HAL_RUNCAM_ENABLED 0 - -# disable use of onboard FFT library: -define HAL_GYROFFT_ENABLED 0 - -# several notify backends are rare and not supported by default on smaller boards: -define AP_NOTIFY_NCP5623_ENABLED 0 - # Soaring is off by defauult on of smaller boards. define HAL_SOARING_ENABLED 0 -# HOTT telemetry is quite rare, so we don't include it on smaller boards -define HAL_HOTT_TELEM_ENABLED 0 - -# smaller boards lose SIRF GPS support -define AP_GPS_SIRF_ENABLED 0 - -# no moving baseline support: -define GPS_MOVING_BASELINE 0 +# RunCam control isn't available on smaller boards +define HAL_RUNCAM_ENABLED 0 # minimized boards don't get configuration via SmartAudio by default: define AP_SMARTAUDIO_ENABLED 0 -# minimized boards don't get configuration via Tramp by default: -define AP_TRAMP_ENABLED 0 - -# No LTM telemetry on minimized boards: -define AP_LTM_TELEM_ENABLED 0 +# can't fit Turtle mode on minimized boards: +define MODE_TURTLE_ENABLED 0 # no Spektrum telemetry: define HAL_SPEKTRUM_TELEM_ENABLED 0 -# various structures increase the flash size when using >16 servos: -define NUM_SERVO_CHANNELS 16 - -# remove various OSD features by default: -define OSD_ENABLED 0 -define HAL_PLUSCODE_ENABLE 0 -define HAL_OSD_SIDEBAR_ENABLE 0 -define OSD_PARAM_ENABLED 0 - -# no Winch if minimized: -define AP_WINCH_ENABLED 0 - -# prune out some odd camera backends: -define AP_CAMERA_BACKEND_DEFAULT_ENABLED 0 -define AP_CAMERA_RELAY_ENABLED AP_CAMERA_ENABLED -define AP_CAMERA_SERVO_ENABLED AP_CAMERA_ENABLED - -# no SLCAN on these boards (use can-over-mavlink if required) -define AP_CAN_SLCAN_ENABLED 0 - -# no PiccoloCAN: -define HAL_PICCOLO_CAN_ENABLE 0 - -# no beacon support on minimized boards: -define AP_BEACON_ENABLED 0 - -# restricted battery backends: -define AP_BATTERY_BACKEND_DEFAULT_ENABLED 0 -define AP_BATTERY_ANALOG_ENABLED 1 -define AP_BATTERY_ESC_ENABLED 1 -define AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED HAL_ENABLE_DRONECAN_DRIVERS -define AP_BATTERY_SUM_ENABLED 1 -define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 1 -define AP_BATTERY_SMBUS_ENABLED 1 -define AP_BATTERY_SMBUS_GENERIC_ENABLED AP_BATTERY_SMBUS_ENABLED -define AP_BATTERY_SMBUS_NEODESIGN_ENABLED AP_BATTERY_SMBUS_ENABLED -define AP_BATTERY_SMBUS_SUI_ENABLED AP_BATTERY_SMBUS_ENABLED -define AP_BATTERY_SMBUS_MAXELL_ENABLED AP_BATTERY_SMBUS_ENABLED -define AP_BATTERY_SMBUS_ROTOYE_ENABLED AP_BATTERY_SMBUS_ENABLED - -# don't probe for external Barometers: -define AP_BARO_PROBE_EXTERNAL_I2C_BUSES 0 - -# no wind compensation code: -define HAL_BARO_WIND_COMP_ENABLED 0 - -# no mounts: -define HAL_MOUNT_ENABLED 0 - -# no generator: -define HAL_GENERATOR_ENABLED 0 - -# no NMEA output: -define HAL_NMEA_OUTPUT_ENABLED 0 - -# no Notify Display support: -define HAL_DISPLAY_ENABLED 0 - -# remove support for killing IMUs at runtime - a developer feature: -define AP_INERTIALSENSOR_KILL_IMU_ENABLED 0 - # no MSP: define HAL_MSP_ENABLED 0 -# shortened names in @SYS/taskinfo.txt -define AP_SCHEDULER_EXTENDED_TASKINFO_ENABLED 0 +# Copter-specific defines; these defines are only used in the Copter +# directory, but are seen across the entire codebase: +define MODE_FLOWHOLD_ENABLED 0 +define MODE_TURTLE_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 new file mode 100644 index 00000000000000..05a48aec9219d1 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_fpv_osd.inc @@ -0,0 +1,31 @@ +# this is an include file for low-flash boards typically used in +# vehicles used for FPV/OSD flight. These boards are unlikely to need +# drivers for rare sensors and power systems. + +include minimize_common.inc + +define AP_OPTICALFLOW_ENABLED 0 + +define AP_GPS_BACKEND_DEFAULT_ENABLED 0 +define AP_GPS_UBLOX_ENABLED 1 +define AP_GPS_NMEA_ENABLED 1 +define HAL_MSP_GPS_ENABLED HAL_MSP_SENSORS_ENABLED + +define AP_MOTORS_FRAME_DEFAULT_ENABLED 0 +define AP_MOTORS_FRAME_QUAD_ENABLED 1 +define AP_MOTORS_FRAME_HEXA_ENABLED 1 +define AP_MOTORS_FRAME_OCTA_ENABLED 1 + +define AP_SBUSOUTPUT_ENABLED 0 + +define AP_ICENGINE_ENABLED 0 + +define AP_ADVANCEDFAILSAFE_ENABLED 0 + +define AC_PRECLAND_ENABLED 0 + +# force Tramp support even in face of normal 1MB limit: +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 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.dat new file mode 100644 index 00000000000000..9ea8e191425ff2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.dat @@ -0,0 +1,6 @@ +# hw definition file for processing by chibios_pins.py + +# MCU class and specific type +MCU STM32F100 STM32F100xB + +include ../iomcu-dshot/hwdef.inc \ No newline at end of file diff --git a/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.inc new file mode 100644 index 00000000000000..5f6404aa15dc71 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.inc @@ -0,0 +1,49 @@ +# hw definition file for processing by chibios_pins.py + +include ../iomcu/hwdef.inc + +undef AP_FASTBOOT_ENABLED AP_BOOTLOADER_FLASHING_ENABLED +undef HAL_DSHOT_ENABLED + +# PPM uses a DMA channel that is required for TIM2, and no remapping of PA8 is possible +undef PA8 +undef STM32_ICU_USE_TIM1 RCIN_ICU_TIMER STM32_RCIN_DMA_STREAM HAL_USE_ICU +undef PORT_INT_REQUIRED_STACK MAIN_STACK +undef CH_CFG_ST_TIMEDELTA CH_CFG_ST_FREQUENCY +undef AP_HAL_SHARED_DMA_ENABLED + +# TIM2_UP required for PWM1/2 +define STM32_TIM_TIM2_UP_DMA_STREAM STM32_DMA_STREAM_ID(1, 2) +define STM32_TIM_TIM2_UP_DMA_CHAN 1 + +# TIM4_UP (PWM 3/4) cannot be used with sharing as channels used by high speed USART2 RX/TX +define AP_HAL_SHARED_DMA_ENABLED 1 +define STM32_TIM_TIM4_UP_DMA_STREAM STM32_DMA_STREAM_ID(1, 7) +define STM32_TIM_TIM4_UP_DMA_CHAN 1 +define SHARED_DMA_MASK (1U< 15360: self.error("HAL_STORAGE_SIZE invalid, needs to be 15360") + def get_numeric_board_id(self): + '''return a numeric board ID, which may require mapping a string to a + number via board_list.txt''' + some_id = self.get_config('APJ_BOARD_ID') + if some_id.isnumeric(): + return some_id + + board_types_filename = "board_types.txt" + topdir = os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../../..') + board_types_dirpath = os.path.join(topdir, "Tools", "AP_Bootloader") + board_types_filepath = os.path.join(board_types_dirpath, board_types_filename) + for line in open(board_types_filepath, 'r'): + m = re.match(r"(?P[-\w]+)\s+(?P\d+)", line) + if m is None: + continue + if m.group('name') == some_id: + return m.group('board_id') + + raise ValueError("Unable to map (%s) to a board ID using %s" % + (some_id, board_types_filepath)) + def write_mcu_config(self, f): '''write MCU config defines''' f.write('#define CHIBIOS_BOARD_NAME "%s"\n' % os.path.basename(os.path.dirname(args.hwdef[0]))) @@ -931,6 +958,20 @@ def write_mcu_config(self, f): if 'OTG2' in self.bytype: f.write('#define STM32_USB_USE_OTG2 TRUE\n') + if 'ETH1' in self.bytype: + f.write('// Configure for Ethernet support\n') + f.write('#define CH_CFG_USE_MAILBOXES TRUE\n') + f.write('#define HAL_USE_MAC TRUE\n') + f.write('#define MAC_USE_EVENTS TRUE\n') + f.write('#define STM32_ETH_BUFFERS_EXTERN\n') + f.write('#define AP_NETWORKING_ENABLED TRUE\n') + self.build_flags.append('USE_LWIP=yes') + self.env_vars['WITH_NETWORKING'] = True + else: + f.write('#define AP_NETWORKING_ENABLED FALSE\n') + self.build_flags.append('USE_LWIP=no') + self.env_vars['WITH_NETWORKING'] = False + defines = self.get_mcu_config('DEFINES', False) if defines is not None: for d in defines.keys(): @@ -982,7 +1023,7 @@ def write_mcu_config(self, f): if result: self.intdefines[result.group(1)] = int(result.group(2)) - if self.intdefines.get('HAL_USE_USB_MSD',0) == 1: + if self.intdefines.get('HAL_USE_USB_MSD', 0) == 1: self.build_flags.append('USE_USB_MSD=yes') if self.have_type_prefix('CAN') and not using_chibios_can: @@ -1014,8 +1055,8 @@ def write_mcu_config(self, f): f.write('#define CRT0_AREAS_NUMBER 1\n') if self.env_vars['INT_FLASH_PRIMARY']: - # this will put methods with low latency requirements into external flash - # and save internal flash space + # this will put methods with low latency requirements into external flash + # and save internal flash space f.write('#define __EXTFLASHFUNC__ __attribute__ ((__section__(".extflash")))\n') else: f.write('#define __EXTFLASHFUNC__\n') @@ -1026,7 +1067,7 @@ def write_mcu_config(self, f): if not args.bootloader: f.write('#define STORAGE_FLASH_PAGE %u\n' % storage_flash_page) self.validate_flash_storage_size() - elif self.get_config('FLASH_RESERVE_END_KB', type=int, required = False) is None: + elif self.get_config('FLASH_RESERVE_END_KB', type=int, required=False) is None: # ensure the flash page leaves room for bootloader offset = self.get_flash_page_offset_kb(storage_flash_page) bl_offset = self.get_config('FLASH_BOOTLOADER_LOAD_KB', type=int) @@ -1085,7 +1126,7 @@ def write_mcu_config(self, f): f.write('#define UDID_START 0x%08x\n\n' % udid_start) f.write('\n// APJ board ID (for bootloaders)\n') - f.write('#define APJ_BOARD_ID %s\n' % self.get_config('APJ_BOARD_ID')) + f.write('#define APJ_BOARD_ID %s\n' % self.get_numeric_board_id()) # support ALT_BOARD_ID for px4 firmware alt_id = self.get_config('ALT_BOARD_ID', required=False) @@ -1217,6 +1258,7 @@ def write_mcu_config(self, f): #ifndef CH_CFG_USE_DYNAMIC #define CH_CFG_USE_DYNAMIC FALSE #endif +#define STM32_FLASH_DISABLE_ISR 0 ''') if not self.env_vars['EXT_FLASH_SIZE_MB'] and not args.signed_fw: f.write(''' @@ -1373,11 +1415,8 @@ def write_ldscript(self, fname): } INCLUDE common.ld -''' % (ext_flash_base, ext_flash_length, - instruction_ram_base, instruction_ram_length, - ram0_start, ram0_len, - ram1_start, ram1_len, - ram2_start, ram2_len)) +''' % (ext_flash_base, ext_flash_length, instruction_ram_base, instruction_ram_length, ram0_start, ram0_len, ram1_start, ram1_len, ram2_start, ram2_len)) # noqa + f.close() def copy_common_linkerscript(self, outdir): dirpath = os.path.dirname(os.path.realpath(__file__)) @@ -1406,7 +1445,8 @@ def get_USB_IDs(self): else: default_vid = 0x1209 default_pid = 0x5741 - return (self.get_config('USB_VENDOR', type=int, default=default_vid), self.get_config('USB_PRODUCT', type=int, default=default_pid)) + return (self.get_config('USB_VENDOR', type=int, default=default_vid), + self.get_config('USB_PRODUCT', type=int, default=default_pid)) def write_USB_config(self, f): '''write USB config defines''' @@ -1416,11 +1456,12 @@ def write_USB_config(self, f): (USB_VID, USB_PID) = self.get_USB_IDs() f.write('#define HAL_USB_VENDOR_ID 0x%04x\n' % int(USB_VID)) f.write('#define HAL_USB_PRODUCT_ID 0x%04x\n' % int(USB_PID)) - f.write('#define HAL_USB_STRING_MANUFACTURER %s\n' % self.get_config("USB_STRING_MANUFACTURER", default="\"ArduPilot\"")) + f.write('#define HAL_USB_STRING_MANUFACTURER %s\n' % + self.get_config("USB_STRING_MANUFACTURER", default="\"ArduPilot\"")) default_product = "%BOARD%" if args.bootloader: default_product += "-BL" - product_string = self.get_config("USB_STRING_PRODUCT", default="\"%s\""%default_product) + product_string = self.get_config("USB_STRING_PRODUCT", default="\"%s\"" % default_product) if args.bootloader and args.signed_fw: product_string = product_string.replace("-BL", "-Secure-BL-v10") f.write('#define HAL_USB_STRING_PRODUCT %s\n' % product_string) @@ -1429,7 +1470,6 @@ def write_USB_config(self, f): f.write('\n\n') - def write_SPI_table(self, f): '''write SPI device table''' f.write('\n// SPI device table\n') @@ -1455,8 +1495,8 @@ def write_SPI_table(self, f): if not lowspeed.endswith('*MHZ') and not lowspeed.endswith('*KHZ'): self.error("Bad lowspeed value %s in SPIDEV line %s" % (lowspeed, dev)) if not highspeed.endswith('*MHZ') and not highspeed.endswith('*KHZ'): - self.error("Bad highspeed value %s in SPIDEV line %s" % (highspeed, - dev)) + self.error("Bad highspeed value %s in SPIDEV line %s" % + (highspeed, dev)) cs_pin = self.bylabel[cs] pal_line = 'PAL_LINE(GPIO%s,%uU)' % (cs_pin.port, cs_pin.pin) devidx = len(devlist) @@ -1467,10 +1507,9 @@ def write_SPI_table(self, f): devlist.append('HAL_SPI_DEVICE%u' % devidx) f.write('#define HAL_SPI_DEVICE_LIST %s\n\n' % ','.join(devlist)) for dev in self.spidev: - f.write("#define HAL_WITH_SPI_%s 1\n" % dev[0].upper().replace("-","_")) + f.write("#define HAL_WITH_SPI_%s 1\n" % dev[0].upper().replace("-", "_")) f.write("\n") - def write_SPI_config(self, f): '''write SPI config defines''' for t in list(self.bytype.keys()) + list(self.alttype.keys()): @@ -1490,7 +1529,6 @@ def write_SPI_config(self, f): f.write('#define HAL_SPI_BUS_LIST %s\n\n' % ','.join(devlist)) self.write_SPI_table(f) - def write_WSPI_table(self, f): '''write SPI device table''' f.write('\n// WSPI device table\n') @@ -1525,7 +1563,6 @@ def write_WSPI_table(self, f): f.write("#define HAL_OSPI%d_CLK (%s)" % (int(bus[7:]), speed)) f.write("\n") - def write_WSPI_config(self, f): '''write SPI config defines''' # only the bootloader must run the hal lld (and QSPI clock) otherwise it is not possible to @@ -1559,7 +1596,7 @@ def write_WSPI_config(self, f): def write_check_firmware(self, f): '''add AP_CHECK_FIRMWARE_ENABLED if needed''' - if self.is_periph_fw() or self.intdefines.get('AP_OPENDRONEID_ENABLED',0) == 1: + if self.is_periph_fw() or self.intdefines.get('AP_OPENDRONEID_ENABLED', 0) == 1: f.write(''' #ifndef AP_CHECK_FIRMWARE_ENABLED #define AP_CHECK_FIRMWARE_ENABLED 1 @@ -1573,7 +1610,6 @@ def parse_spi_device(self, dev): self.error("Bad SPI device: %s" % dev) return 'hal.spi->get_device("%s")' % a[1] - def parse_i2c_device(self, dev): '''parse a I2C:xxx:xxx device item''' a = dev.split(':') @@ -1589,7 +1625,6 @@ def parse_i2c_device(self, dev): busnum = int(a[1]) return ('', 'GET_I2C_DEVICE(%u,0x%02x)' % (busnum, busaddr)) - def seen_str(self, dev): '''return string representation of device for checking for duplicates''' ret = dev[:2] @@ -1624,13 +1659,11 @@ def write_IMU_config(self, f): n = len(devlist)+1 devlist.append('HAL_INS_PROBE%u' % n) if aux_devid != -1: - f.write( - '#define HAL_INS_PROBE%u %s ADD_BACKEND_AUX(AP_InertialSensor_%s::probe(*this,%s),%d)\n' - % (n, wrapper, driver, ','.join(dev[1:]), aux_devid)) + f.write('#define HAL_INS_PROBE%u %s ADD_BACKEND_AUX(AP_InertialSensor_%s::probe(*this,%s),%d)\n' % + (n, wrapper, driver, ','.join(dev[1:]), aux_devid)) elif instance != -1: - f.write( - '#define HAL_INS_PROBE%u %s ADD_BACKEND_INSTANCE(AP_InertialSensor_%s::probe(*this,%s),%d)\n' - % (n, wrapper, driver, ','.join(dev[1:]), instance)) + f.write('#define HAL_INS_PROBE%u %s ADD_BACKEND_INSTANCE(AP_InertialSensor_%s::probe(*this,%s),%d)\n' % + (n, wrapper, driver, ','.join(dev[1:]), instance)) elif dev[-1].startswith("BOARD_MATCH("): f.write( '#define HAL_INS_PROBE%u %s ADD_BACKEND_BOARD_MATCH(%s, AP_InertialSensor_%s::probe(*this,%s))\n' @@ -1644,7 +1677,6 @@ def write_IMU_config(self, f): f.write('#define INS_MAX_INSTANCES %u\n' % len(devlist)) f.write('#define HAL_INS_PROBE_LIST %s\n\n' % ';'.join(devlist)) - def write_MAG_config(self, f): '''write MAG config defines''' devlist = [] @@ -1673,7 +1705,6 @@ def write_MAG_config(self, f): if len(devlist) > 0: f.write('#define HAL_MAG_PROBE_LIST %s\n\n' % ';'.join(devlist)) - def write_BARO_config(self, f): '''write barometer config defines''' devlist = [] @@ -1755,7 +1786,7 @@ def substitute_alias(m): for check_name in sorted(validate_dict.keys()): validate_string += "!" + validate_dict[check_name] + "?" + "\"" + check_name + "\"" + ":" validate_string += "nullptr" - f.write('#define HAL_VALIDATE_BOARD (%s)\n\n' % validate_string) + f.write('#define HAL_VALIDATE_BOARD (%s)\n\n' % validate_string) def get_gpio_bylabel(self, label): '''get GPIO(n) setting on a pin label, or -1''' @@ -1764,7 +1795,6 @@ def get_gpio_bylabel(self, label): return -1 return p.extra_value('GPIO', type=int, default=-1) - def get_extra_bylabel(self, label, name, default=None): '''get extra setting for a label by name''' p = self.bylabel.get(label) @@ -1782,7 +1812,7 @@ def get_UART_ORDER(self): if args.bootloader: # in bootloader SERIAL_ORDER is treated the same as UART_ORDER return serial_order - map = [ 0, 3, 1, 2, 4, 5, 6, 7, 8, 9, 10, 11, 12 ] + map = [0, 3, 1, 2, 4, 5, 6, 7, 8, 9, 10, 11, 12] while len(serial_order) < 4: serial_order += ['EMPTY'] uart_order = [] @@ -1798,6 +1828,19 @@ def write_UART_config(self, f): return f.write('\n// UART configuration\n') + # write out which serial ports we actually have + idx = 0 + nports = 0 + serial_order = self.get_config('SERIAL_ORDER', required=False, aslist=True) + for serial in serial_order: + if serial == 'EMPTY': + f.write('#define HAL_HAVE_SERIAL%u 0\n' % idx) + else: + f.write('#define HAL_HAVE_SERIAL%u 1\n' % idx) + nports = nports + 1 + idx += 1 + f.write('#define HAL_NUM_SERIAL_PORTS %u\n' % nports) + # write out driver declarations for HAL_ChibOS_Class.cpp devnames = "ABCDEFGHIJ" sdev = 0 @@ -1818,7 +1861,7 @@ def write_UART_config(self, f): (devnames[idx], devnames[idx])) if 'IOMCU_UART' in self.config: - if not 'io_firmware.bin' in self.romfs: + if 'io_firmware.bin' not in self.romfs: self.error("Need io_firmware.bin in ROMFS for IOMCU") f.write('#define HAL_WITH_IO_MCU 1\n') @@ -1875,14 +1918,12 @@ def write_UART_config(self, f): if dev.startswith('OTG2'): f.write( - '#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2}\n' - % dev) + '#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2}\n' % dev) # noqa OTG2_index = uart_list.index(dev) self.dual_USB_enabled = True elif dev.startswith('OTG'): f.write( - '#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU1, 1, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}\n' - % dev) + '#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU1, 1, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}\n' % dev) # noqa else: need_uart_driver = True f.write( @@ -1908,7 +1949,7 @@ def write_UART_config(self, f): f.write(''' #if defined(HAL_NUM_CAN_IFACES) && HAL_NUM_CAN_IFACES #ifndef HAL_OTG2_PROTOCOL -#define HAL_OTG2_PROTOCOL SerialProtocol_SLCAN +#define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2 #endif #define DEFAULT_SERIAL%d_PROTOCOL HAL_OTG2_PROTOCOL #define DEFAULT_SERIAL%d_BAUD 115200 @@ -1929,7 +1970,6 @@ def write_UART_config(self, f): self.error("Exceeded max num UARTs of 10 (%u)" % num_uarts) f.write('#define HAL_UART_NUM_SERIAL_PORTS %u\n' % num_uarts) - def write_UART_config_bootloader(self, f): '''write UART config defines''' uart_list = self.get_UART_ORDER() @@ -1960,7 +2000,6 @@ def write_UART_config_bootloader(self, f): #endif ''') - def write_I2C_config(self, f): '''write I2C config defines''' if not self.have_type_prefix('I2C'): @@ -1997,7 +2036,6 @@ def write_I2C_config(self, f): % (n, n, n, n, n, n, n, scl_line, sda_line, n, n, n, scl_line, sda_line)) f.write('\n#define HAL_I2C_DEVICE_LIST %s\n\n' % ','.join(devlist)) - def parse_timer(self, str): '''parse timer channel string, i.e TIM8_CH2N''' result = re.match(r'TIM([0-9]*)_CH([1234])(N?)', str) @@ -2011,7 +2049,6 @@ def parse_timer(self, str): else: self.error("Bad timer definition %s" % str) - def write_PWM_config(self, f, ordered_timers): '''write PWM config defines''' rc_in = None @@ -2021,9 +2058,8 @@ def write_PWM_config(self, f, ordered_timers): pwm_out = [] # start with the ordered list from the dma resolver pwm_timers = ordered_timers - has_bidir = False - for l in self.bylabel.keys(): - p = self.bylabel[l] + for label in self.bylabel.keys(): + p = self.bylabel[label] if p.type.startswith('TIM'): if p.has_extra('RCIN'): rc_in = p @@ -2039,7 +2075,6 @@ def write_PWM_config(self, f, ordered_timers): if p.type not in pwm_timers: pwm_timers.append(p.type) - f.write('#define HAL_PWM_COUNT %u\n' % len(pwm_out)) if not pwm_out and not alarm: print("No PWM output defined") @@ -2170,9 +2205,9 @@ def write_PWM_config(self, f, ordered_timers): if bidir is not None: hal_icu_cfg = '\n {' hal_icu_def = '\n' - for i in range(1,5): + for i in range(1, 5): hal_icu_cfg += '{HAL_IC%u_CH%u_DMA_CONFIG},' % (n, i) - hal_icu_def +='''#if defined(STM32_TIM_TIM%u_CH%u_DMA_STREAM) && defined(STM32_TIM_TIM%u_CH%u_DMA_CHAN) + hal_icu_def += '''#if defined(STM32_TIM_TIM%u_CH%u_DMA_STREAM) && defined(STM32_TIM_TIM%u_CH%u_DMA_CHAN) # define HAL_IC%u_CH%u_DMA_CONFIG true, STM32_TIM_TIM%u_CH%u_DMA_STREAM, STM32_TIM_TIM%u_CH%u_DMA_CHAN #else # define HAL_IC%u_CH%u_DMA_CONFIG false, 0, 0 @@ -2180,7 +2215,6 @@ def write_PWM_config(self, f, ordered_timers): ''' % (n, i, n, i, n, i, n, i, n, i, n, i) hal_icu_cfg += '}, \\' - f.write('''#if defined(STM32_TIM_TIM%u_UP_DMA_STREAM) && defined(STM32_TIM_TIM%u_UP_DMA_CHAN) # define HAL_PWM%u_DMA_CONFIG true, STM32_TIM_TIM%u_UP_DMA_STREAM, STM32_TIM_TIM%u_UP_DMA_CHAN #else @@ -2214,14 +2248,13 @@ def write_PWM_config(self, f, ordered_timers): if need_advanced: f.write('#define STM32_PWM_USE_ADVANCED TRUE\n') - def write_ADC_config(self, f): '''write ADC config defines''' f.write('// ADC config\n') adc_chans = [[], [], []] analogset = {252, 253, 254} # reserved values for VSENSE, VREF and VBAT in H7 - for l in self.bylabel: - p = self.bylabel[l] + for label in self.bylabel: + p = self.bylabel[label] if not p.type.startswith('ADC'): continue if p.type.startswith('ADC1'): @@ -2234,7 +2267,7 @@ def write_ADC_config(self, f): index = 2 chan = self.get_ADC3_chan(self.mcu_type, p.portpin) else: - raise ValueSelf.Error("Unknown ADC type %s" % p.type) + self.error("Unknown ADC type %s" % p.type) scale = p.extra_value('SCALE', default=None) analog = p.extra_value('ANALOG', type=int, default=chan) # default to ADC channel if not specified if analog in analogset: @@ -2282,8 +2315,8 @@ def write_ADC_config(self, f): scale_str = '%.2f/4096' % vdd if scale is not None and scale != '1': scale_str = scale + '*' + scale_str - f.write('{ %2u, %2u, %12s }, /* %s %s */ \\\n' % (chan, analog, scale_str, portpin, - label)) + f.write('{ %2u, %2u, %12s }, /* %s %s */ \\\n' % + (chan, analog, scale_str, portpin, label)) f.write('\n\n') if len(adc_chans[1]) > 0: f.write('#define STM32_ADC_SAMPLES_SIZE 32\n') @@ -2294,18 +2327,18 @@ def write_ADC_config(self, f): scale_str = '%.2f/4096' % vdd if scale is not None and scale != '1': scale_str = scale + '*' + scale_str - f.write('{ %2u, %2u, %12s }, /* %s %s */ \\\n' % (chan, analog, scale_str, portpin, - label)) + f.write('{ %2u, %2u, %12s }, /* %s %s */ \\\n' % + (chan, analog, scale_str, portpin, label)) f.write('\n\n') if len(adc_chans[2]) > 0: - f.write('#define STM32_ADC_USE_ADC3 TRUE\n') + f.write('#define STM32_ADC_USE_ADC3 TRUE\n') f.write('#define HAL_ANALOG3_PINS \\\n') for (chan, analog, scale, label, portpin) in adc_chans[2]: scale_str = '%.2f/4096' % vdd if scale is not None and scale != '1': scale_str = scale + '*' + scale_str - f.write('{ %2u, %2u, %12s }, /* %s %s */ \\\n' % (chan, analog, scale_str, portpin, - label)) + f.write('{ %2u, %2u, %12s }, /* %s %s */ \\\n' % + (chan, analog, scale_str, portpin, label)) f.write('\n\n') def write_GPIO_config(self, f): @@ -2313,8 +2346,8 @@ def write_GPIO_config(self, f): f.write('// GPIO config\n') gpios = [] gpioset = set() - for l in self.bylabel: - p = self.bylabel[l] + for label in self.bylabel: + p = self.bylabel[label] gpio = p.extra_value('GPIO', type=int) if gpio is None: continue @@ -2336,7 +2369,7 @@ def write_GPIO_config(self, f): if gpio in gpioset: # check existing entry existing_gpio = [item for item in gpios if item[0] == gpio] - if (existing_gpio[0][4].label == p.label) and (existing_gpio[0][3] == p.pin) and (existing_gpio[0][2] == p.port): + if (existing_gpio[0][4].label == p.label) and (existing_gpio[0][3] == p.pin) and (existing_gpio[0][2] == p.port): # noqa # alt item is identical to exiting, do not add again continue self.error("Duplicate GPIO value %u, %s != %s" % (gpio, p, existing_gpio[0][4])) @@ -2359,8 +2392,8 @@ def write_GPIO_config(self, f): f.write('}\n\n') f.write('// full pin define list\n') last_label = None - for l in sorted(list(set(self.bylabel.keys()))): - p = self.bylabel[l] + for label in sorted(list(set(self.bylabel.keys()))): + p = self.bylabel[label] label = p.label label = label.replace('-', '_') if label == last_label: @@ -2370,7 +2403,6 @@ def write_GPIO_config(self, f): (label, p.port, p.pin)) f.write('\n') - def bootloader_path(self): # always embed a bootloader if it is available this_dir = os.path.realpath(__file__) @@ -2383,23 +2415,28 @@ def bootloader_path(self): bootloader_filename) return bootloader_path - def embed_bootloader(self, f): '''added bootloader to ROMFS''' if not self.intdefines.get('AP_BOOTLOADER_FLASHING_ENABLED', 1): # or, you know, not... return + if self.is_bootloader_fw(): + return + + if self.is_io_fw(): + return + bp = self.bootloader_path() if not os.path.exists(bp): - return + self.error("Bootloader (%s) does not exist and AP_BOOTLOADER_FLASHING_ENABLED" % + (bp,)) bp = os.path.realpath(bp) self.romfs["bootloader.bin"] = bp f.write("#define AP_BOOTLOADER_FLASHING_ENABLED 1\n") - def write_ROMFS(self, outdir): '''create ROMFS embedded header''' romfs_list = [] @@ -2407,15 +2444,13 @@ def write_ROMFS(self, outdir): romfs_list.append((k, self.romfs[k])) self.env_vars['ROMFS_FILES'] = romfs_list - def setup_apj_IDs(self): '''setup the APJ board IDs''' - self.env_vars['APJ_BOARD_ID'] = self.get_config('APJ_BOARD_ID') + self.env_vars['APJ_BOARD_ID'] = self.get_numeric_board_id() self.env_vars['APJ_BOARD_TYPE'] = self.get_config('APJ_BOARD_TYPE', default=self.mcu_type) (USB_VID, USB_PID) = self.get_USB_IDs() self.env_vars['USBID'] = '0x%04x/0x%04x' % (USB_VID, USB_PID) - def write_peripheral_enable(self, f): '''write peripheral enable lines''' f.write('// peripherals enabled\n') @@ -2434,7 +2469,6 @@ def write_peripheral_enable(self, f): if type.startswith('OCTOSPI'): f.write('#define STM32_WSPI_USE_%s TRUE\n' % type) - def get_dma_exclude(self, periph_list): '''return list of DMA devices to exclude from DMA''' dma_exclude = set() @@ -2454,7 +2488,6 @@ def get_dma_exclude(self, periph_list): dma_exclude.add(periph) return list(dma_exclude) - def write_alt_config(self, f): '''write out alternate config settings''' if len(self.altmap.keys()) == 0: @@ -2470,7 +2503,8 @@ def write_alt_config(self, f): for alt in sorted(self.altmap.keys()): for pp in sorted(self.altmap[alt].keys()): p = self.altmap[alt][pp] - f.write(" { %u, %s, PAL_LINE(GPIO%s,%uU), %s, %u}, /* %s */ \\\n" % (alt, p.pal_modeline(), p.port, p.pin, p.periph_type(), p.periph_instance(), str(p))) + f.write(" { %u, %s, PAL_LINE(GPIO%s,%uU), %s, %u}, /* %s */ \\\n" % + (alt, p.pal_modeline(), p.port, p.pin, p.periph_type(), p.periph_instance(), str(p))) f.write('}\n\n') def write_all_lines(self, hwdat): @@ -2546,10 +2580,17 @@ def write_hwdef_header(self, outfilename): # add in ADC3 on H7 to get MCU temperature and reference voltage self.periph_list.append('ADC3') - dma_unassigned, ordered_timers = dma_resolver.write_dma_header(f, self.periph_list, self.mcu_type, - dma_exclude=self.get_dma_exclude(self.periph_list), - dma_priority=self.get_config('DMA_PRIORITY', default='TIM* SPI*', spaces=True), - dma_noshare=self.dma_noshare) + if self.get_config('DMA_NOMAP', required=False) is not None: + dma_unassigned, ordered_timers = [], [] + else: + dma_unassigned, ordered_timers = dma_resolver.write_dma_header( + f, + self.periph_list, + self.mcu_type, + dma_exclude=self.get_dma_exclude(self.periph_list), + dma_priority=self.get_config('DMA_PRIORITY', default='TIM* SPI*', spaces=True), + dma_noshare=self.dma_noshare + ) if not args.bootloader: self.write_PWM_config(f, ordered_timers) @@ -2679,7 +2720,6 @@ def write_hwdef_header(self, outfilename): pass os.rename(tmpfile, outfilename) - def build_peripheral_list(self): '''build a list of peripherals for DMA resolver to work on''' peripherals = [] @@ -2747,14 +2787,14 @@ def get_processed_defaults_file(self, defaults_filepath, depth=0): line = defaults_fh.readline() if line == "": break - m = re.match("^@include\s*([^\s]+)", line) + m = re.match(r"^@include\s*([^\s]+)", line) if m is None: ret += line continue # we've found an include; do that... include_filepath = os.path.join(os.path.dirname(defaults_filepath), m.group(1)) try: -# ret += "# Begin included file (%s)" % include_filepath + # ret += "# Begin included file (%s)" % include_filepath ret += self.get_processed_defaults_file(include_filepath, depth=depth+1) # ret += "# End included file (%s)" % include_filepath except FileNotFoundError: @@ -2762,7 +2802,6 @@ def get_processed_defaults_file(self, defaults_filepath, depth=0): (defaults_filepath, include_filepath)) return ret - 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') @@ -2787,19 +2826,16 @@ def write_processed_defaults_file(self, filepath): self.env_vars['DEFAULT_PARAMETERS'] = filepath - def write_env_py(self, filename): '''write out env.py for environment variables to control the build process''' # CHIBIOS_BUILD_FLAGS is passed to the ChibiOS makefile self.env_vars['CHIBIOS_BUILD_FLAGS'] = ' '.join(self.build_flags) pickle.dump(self.env_vars, open(filename, "wb")) - def romfs_add(self, romfs_filename, filename): '''add a file to ROMFS''' self.romfs[romfs_filename] = filename - def romfs_wildcard(self, pattern): '''add a set of files to ROMFS by wildcard''' base_path = os.path.join(os.path.dirname(__file__), '..', '..', '..', '..') @@ -2824,9 +2860,11 @@ def romfs_add_dir(self, subdirs): def valid_type(self, ptype, label): '''check type of a pin line is valid''' - patterns = [ 'INPUT', 'OUTPUT', 'TIM\d+', 'USART\d+', 'UART\d+', 'ADC\d+', - 'SPI\d+', 'OTG\d+', 'SWD', 'CAN\d?', 'I2C\d+', 'CS', - 'SDMMC\d+', 'SDIO', 'QUADSPI\d', 'OCTOSPI\d' ] + patterns = [ + r'INPUT', r'OUTPUT', r'TIM\d+', r'USART\d+', r'UART\d+', r'ADC\d+', + r'SPI\d+', r'OTG\d+', r'SWD', r'CAN\d?', r'I2C\d+', r'CS', + r'SDMMC\d+', r'SDIO', r'QUADSPI\d', r'OCTOSPI\d', r'ETH\d', r'RCC', + ] matches = False for p in patterns: if re.match(p, ptype): @@ -2835,25 +2873,25 @@ def valid_type(self, ptype, label): if not matches: return False # special checks for common errors - m1 = re.match('TIM(\d+)', ptype) - m2 = re.match('TIM(\d+)_CH\d+', label) + m1 = re.match(r'TIM(\d+)', ptype) + m2 = re.match(r'TIM(\d+)_CH\d+', label) if (m1 and not m2) or (m2 and not m1) or (m1 and m1.group(1) != m2.group(1)): '''timer numbers need to match''' return False - m1 = re.match('CAN(\d+)', ptype) - m2 = re.match('CAN(\d+)_(RX|TX)', label) + m1 = re.match(r'CAN(\d+)', ptype) + m2 = re.match(r'CAN(\d+)_(RX|TX)', label) if (m1 and not m2) or (m2 and not m1) or (m1 and m1.group(1) != m2.group(1)): '''CAN numbers need to match''' return False - if ptype == 'OUTPUT' and re.match('US?ART\d+_(TXINV|RXINV)', label): + if ptype == 'OUTPUT' and re.match(r'US?ART\d+_(TXINV|RXINV)', label): return True - m1 = re.match('USART(\d+)', ptype) - m2 = re.match('USART(\d+)_(RX|TX|CTS|RTS)', label) + m1 = re.match(r'USART(\d+)', ptype) + m2 = re.match(r'USART(\d+)_(RX|TX|CTS|RTS)', 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('UART(\d+)', ptype) - m2 = re.match('UART(\d+)_(RX|TX|CTS|RTS)', label) + m1 = re.match(r'UART(\d+)', ptype) + m2 = re.match(r'UART(\d+)_(RX|TX|CTS|RTS)', 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 @@ -2882,7 +2920,7 @@ def process_line(self, line): if not self.valid_type(type, label): self.error("bad type on line: %s" % a) - p = self.generic_pin(port, pin, label, type, extra, self.mcu_type, self.mcu_series, self.get_ADC1_chan, self.get_ADC2_chan, self.get_ADC3_chan, self.af_labels) + p = self.generic_pin(port, pin, label, type, extra, self.mcu_type, self.mcu_series, self.get_ADC1_chan, self.get_ADC2_chan, self.get_ADC3_chan, self.af_labels) # noqa af = self.get_alt_function(self.mcu_type, a[0], label) if af is not None: p.af = af @@ -2956,19 +2994,20 @@ def process_line(self, line): self.bylabel.pop(u, '') self.alttype.pop(u, '') self.altlabel.pop(u, '') + self.intdefines.pop(u, '') for dev in self.spidev: if u == dev[0]: self.spidev.remove(dev) # also remove all occurences of defines in previous lines if any for line in self.alllines[:]: - if line.startswith('define') and u == line.split()[1]: + if line.startswith('define') and u == line.split()[1] or line.startswith('STM32_') and u == line.split()[0]: # noqa self.alllines.remove(line) newpins = [] for pin in self.allpins: if pin.type == u or pin.label == u or pin.portpin == u: if pin.label is not None: self.bylabel.pop(pin.label, '') - self.portmap[pin.port][pin.pin] = self.generic_pin(pin.port, pin.pin, None, 'INPUT', [], self.mcu_type, self.mcu_series, self.get_ADC1_chan, self.get_ADC2_chan, self.get_ADC3_chan, self.af_labels) + self.portmap[pin.port][pin.pin] = self.generic_pin(pin.port, pin.pin, None, 'INPUT', [], self.mcu_type, self.mcu_series, self.get_ADC1_chan, self.get_ADC2_chan, self.get_ADC3_chan, self.af_labels) # noqa continue newpins.append(pin) self.allpins = newpins @@ -2984,8 +3023,11 @@ def process_line(self, line): print("Adding environment %s" % ' '.join(a[1:])) if len(a[1:]) < 2: self.error("Bad env line for %s" % a[0]) - self.env_vars[a[1]] = ' '.join(a[2:]) - + name = a[1] + value = ' '.join(a[2:]) + if name == 'AP_PERIPH' and value != "1": + raise ValueError("AP_PERIPH may only have value 1") + self.env_vars[name] = value def process_file(self, filename): '''process a hwdef.dat file''' @@ -3016,468 +3058,65 @@ def add_apperiph_defaults(self, f): # not AP_Periph return - print("Setting up as AP_Periph") - f.write(''' -// AP_Periph defaults - -#ifndef AP_SCHEDULER_ENABLED -#define AP_SCHEDULER_ENABLED 0 -#endif - -#ifndef HAL_LOGGING_ENABLED -#define HAL_LOGGING_ENABLED 0 -#endif - -#ifndef HAL_GCS_ENABLED -#define HAL_GCS_ENABLED 0 -#endif - -/* - AP_Periph doesn't include the SERIAL parameter tree, instead each - supported serial device type has it's own parameter within AP_Periph - for which port is used. - */ -#define DEFAULT_SERIAL0_PROTOCOL SerialProtocol_None -#define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_None -#define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None -#define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None -#define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None -#define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None -#define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_None -#define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_None -#define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_None -#define DEFAULT_SERIAL9_PROTOCOL SerialProtocol_None - -#ifndef HAL_LOGGING_MAVLINK_ENABLED -#define HAL_LOGGING_MAVLINK_ENABLED 0 -#endif - -#ifndef AP_MISSION_ENABLED -#define AP_MISSION_ENABLED 0 -#endif - -#ifndef HAL_RALLY_ENABLED -#define HAL_RALLY_ENABLED 0 -#endif - -#ifndef HAL_NMEA_OUTPUT_ENABLED -#define HAL_NMEA_OUTPUT_ENABLED 0 -#endif - -#ifndef HAL_CAN_DEFAULT_NODE_ID -#define HAL_CAN_DEFAULT_NODE_ID 0 -#endif - -#define PERIPH_FW TRUE -#define HAL_BUILD_AP_PERIPH - -#ifndef HAL_WATCHDOG_ENABLED_DEFAULT -#define HAL_WATCHDOG_ENABLED_DEFAULT true -#endif - -#ifndef AP_FETTEC_ONEWIRE_ENABLED -#define AP_FETTEC_ONEWIRE_ENABLED 0 -#endif - -#ifndef AP_KDECAN_ENABLED -#define AP_KDECAN_ENABLED 0 -#endif - -#ifndef HAL_GENERATOR_ENABLED -#define HAL_GENERATOR_ENABLED 0 -#endif - -#ifndef HAL_BARO_WIND_COMP_ENABLED -#define HAL_BARO_WIND_COMP_ENABLED 0 -#endif - -#ifndef HAL_UART_STATS_ENABLED -#define HAL_UART_STATS_ENABLED (HAL_GCS_ENABLED || HAL_LOGGING_ENABLED) -#endif - -#ifndef HAL_SUPPORT_RCOUT_SERIAL -#define HAL_SUPPORT_RCOUT_SERIAL 0 -#endif - -#ifndef AP_AIRSPEED_AUTOCAL_ENABLE -#define AP_AIRSPEED_AUTOCAL_ENABLE 0 -#endif - -#ifndef AP_STATS_ENABLED -#define AP_STATS_ENABLED 0 -#endif - -#ifndef AP_VOLZ_ENABLED -#define AP_VOLZ_ENABLED 0 -#endif - -#ifndef AP_ROBOTISSERVO_ENABLED -#define AP_ROBOTISSERVO_ENABLED 0 -#endif - -#ifndef AP_SBUSOUTPUT_ENABLED -#define AP_SBUSOUTPUT_ENABLED 0 -#endif - -// by default an AP_Periph defines as many servo output channels as -// there are PWM outputs: -#ifndef NUM_SERVO_CHANNELS -#ifdef HAL_PWM_COUNT -#define NUM_SERVO_CHANNELS HAL_PWM_COUNT -#else -#define NUM_SERVO_CHANNELS 0 -#endif -#endif - -#ifndef AP_STATS_ENABLED -#define AP_STATS_ENABLED 0 -#endif - -#ifndef AP_BATTERY_ESC_ENABLED -#define AP_BATTERY_ESC_ENABLED 0 -#endif - -// disable compass calibrations on periphs; cal is done on the autopilot -#ifndef COMPASS_CAL_ENABLED -#define COMPASS_CAL_ENABLED 0 -#endif -#ifndef COMPASS_MOT_ENABLED -#define COMPASS_MOT_ENABLED 0 -#endif -#ifndef COMPASS_LEARN_ENABLED -#define COMPASS_LEARN_ENABLED 0 -#endif - -#ifndef HAL_EXTERNAL_AHRS_ENABLED -#define HAL_EXTERNAL_AHRS_ENABLED 0 -#endif + self.add_firmware_defaults_from_file(f, "defaults_periph.h", "AP_Periph") -// disable RC_Channels library: -#ifndef AP_RC_CHANNEL_ENABLED -#define AP_RC_CHANNEL_ENABLED 0 -#endif - -#ifndef AP_RCPROTOCOL_ENABLED -#define AP_RCPROTOCOL_ENABLED 0 -#endif - -#define HAL_CRSF_TELEM_ENABLED 0 - -#ifndef AP_SERVORELAYEVENTS_ENABLED -#define AP_SERVORELAYEVENTS_ENABLED 0 -#endif - -#ifndef AP_RELAY_ENABLED -#define AP_RELAY_ENABLED 0 -#endif - -/* - * GPS Backends - we selectively turn backends on. - * Note also that f103-GPS explicitly disables some of these backends. - */ -#define AP_GPS_BACKEND_DEFAULT_ENABLED 0 - -#ifndef AP_GPS_ERB_ENABLED -#define AP_GPS_ERB_ENABLED 0 -#endif - -#ifndef AP_GPS_GSOF_ENABLED -#define AP_GPS_GSOF_ENABLED defined(HAL_PERIPH_ENABLE_GPS) -#endif - -#ifndef AP_GPS_NMEA_ENABLED -#define AP_GPS_NMEA_ENABLED 0 -#endif - -#ifndef AP_GPS_SBF_ENABLED -#define AP_GPS_SBF_ENABLED defined(HAL_PERIPH_ENABLE_GPS) -#endif - -#ifndef AP_GPS_SBP_ENABLED -#define AP_GPS_SBP_ENABLED 0 -#endif - -#ifndef AP_GPS_SBP2_ENABLED -#define AP_GPS_SBP2_ENABLED 0 -#endif - -#ifndef AP_GPS_SIRF_ENABLED -#define AP_GPS_SIRF_ENABLED 0 -#endif - -#ifndef AP_GPS_MAV_ENABLED -#define AP_GPS_MAV_ENABLED 0 -#endif - -#ifndef AP_GPS_NOVA_ENABLED -#define AP_GPS_NOVA_ENABLED defined(HAL_PERIPH_ENABLE_GPS) -#endif - -#ifndef HAL_SIM_GPS_ENABLED -#define HAL_SIM_GPS_ENABLED (AP_SIM_ENABLED && defined(HAL_PERIPH_ENABLE_GPS)) -#endif - -/* - * Airspeed Backends - we selectively turn backends *off* - */ -#ifndef AP_AIRSPEED_ANALOG_ENABLED -#define AP_AIRSPEED_ANALOG_ENABLED 0 -#endif - -// disable various rangefinder backends -#define AP_RANGEFINDER_ANALOG_ENABLED 0 -#define AP_RANGEFINDER_HC_SR04_ENABLED 0 -#define AP_RANGEFINDER_PWM_ENABLED 0 - -// no CAN manager in AP_Periph: -#define HAL_CANMANAGER_ENABLED 0 - -// SLCAN is off by default: -#ifndef AP_CAN_SLCAN_ENABLED -#define AP_CAN_SLCAN_ENABLED 0 -#endif - -// Periphs don't use the FFT library: -#ifndef HAL_GYROFFT_ENABLED -#define HAL_GYROFFT_ENABLED 0 -#endif - -// MSP parsing is off by default in AP_Periph: -#ifndef HAL_MSP_ENABLED -#define HAL_MSP_ENABLED 0 -#endif - -// periph does not make use of compass scaling or diagonals -#ifndef AP_COMPASS_DIAGONALS_ENABLED -#define AP_COMPASS_DIAGONALS_ENABLED 0 -#endif - -// disable various battery monitor backends: -#ifndef AP_BATTERY_SYNTHETIC_CURRENT_ENABLED -#define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 0 -#endif - -#ifndef AP_BATT_MONITOR_MAX_INSTANCES -#define AP_BATT_MONITOR_MAX_INSTANCES 1 -#endif - -#ifndef RANGEFINDER_MAX_INSTANCES -#define RANGEFINDER_MAX_INSTANCES 1 -#endif - -// by default AP_Periphs don't use INS: -#ifndef AP_INERTIALSENSOR_ENABLED -#define AP_INERTIALSENSOR_ENABLED 0 -#endif - -// no fence by default in AP_Periph: -#ifndef AP_FENCE_ENABLED -#define AP_FENCE_ENABLED 0 -#endif - -// periph does not save temperature cals etc: -#ifndef HAL_ENABLE_SAVE_PERSISTENT_PARAMS -#define HAL_ENABLE_SAVE_PERSISTENT_PARAMS 0 -#endif - -#ifndef AP_WINCH_ENABLED -#define AP_WINCH_ENABLED 0 -#endif - -#ifndef AP_VIDEOTX_ENABLED -#define AP_VIDEOTX_ENABLED 0 -#endif - -#ifndef AP_FRSKY_TELEM_ENABLED -#define AP_FRSKY_TELEM_ENABLED 0 -#endif - -#ifndef HAL_SPEKTRUM_TELEM_ENABLED -#define HAL_SPEKTRUM_TELEM_ENABLED 0 -#endif - -#ifndef AP_FILESYSTEM_ROMFS_ENABLED -#define AP_FILESYSTEM_ROMFS_ENABLED 0 -#endif - -#ifndef NOTIFY_LED_OVERRIDE_DEFAULT -#define NOTIFY_LED_OVERRIDE_DEFAULT 1 // rgb_source_t::mavlink -#endif - -#ifndef HAL_PROXIMITY_ENABLED -#define HAL_PROXIMITY_ENABLED 0 -#endif - -#ifndef AP_SCRIPTING_ENABLED -#define AP_SCRIPTING_ENABLED 0 -#endif - -#define AP_BATTERY_ENABLED defined(HAL_PERIPH_ENABLE_BATTERY) -#define AP_AHRS_ENABLED defined(HAL_PERIPH_ENABLE_AHRS) -#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) - -#ifndef AP_BOOTLOADER_ALWAYS_ERASE -#define AP_BOOTLOADER_ALWAYS_ERASE 1 -#endif - -#ifndef GPS_MOVING_BASELINE -#define GPS_MOVING_BASELINE 0 -#endif - -#ifndef AP_UART_MONITOR_ENABLED -#define AP_UART_MONITOR_ENABLED AP_GPS_ENABLED && (GPS_MOVING_BASELINE || BOARD_FLASH_SIZE>=256) -#endif - -#ifndef HAL_BOARD_LOG_DIRECTORY -#define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" -#endif - -#ifndef HAL_BOARD_TERRAIN_DIRECTORY -#define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" -#endif - -// end AP_Periph defaults -''') + def is_bootloader_fw(self): + return args.bootloader def add_bootloader_defaults(self, f): '''add default defines for peripherals''' - if not args.bootloader: + if not self.is_bootloader_fw(): return - print("Setting up as Bootloader") - f.write(''' -// AP_Bootloader defaults - -#define HAL_DSHOT_ALARM_ENABLED 0 -#define HAL_LOGGING_ENABLED 0 -#define HAL_SCHEDULER_ENABLED 0 - -// bootloaders *definitely* don't use the FFT library: -#ifndef HAL_GYROFFT_ENABLED -#define HAL_GYROFFT_ENABLED 0 -#endif - -// bootloaders don't talk to the GCS: -#ifndef HAL_GCS_ENABLED -#define HAL_GCS_ENABLED 0 -#endif - -// by default bootloaders don't use INS: -#ifndef AP_INERTIALSENSOR_ENABLED -#define AP_INERTIALSENSOR_ENABLED 0 -#endif + self.add_firmware_defaults_from_file(f, "defaults_bootloader.h", "bootloader") -#define HAL_MAX_CAN_PROTOCOL_DRIVERS 0 + def add_firmware_defaults_from_file(self, f, filename, description): + print("Setting up as %s" % description) -// bootloader does not save temperature cals etc: -#ifndef HAL_ENABLE_SAVE_PERSISTENT_PARAMS -#define HAL_ENABLE_SAVE_PERSISTENT_PARAMS 0 -#endif + dirpath = os.path.dirname(os.path.realpath(__file__)) + filepath = os.path.join(dirpath, filename) -#ifndef HAL_GCS_ENABLED -#define HAL_GCS_ENABLED 0 -#endif + content = open(filepath, 'r').read() + f.write(''' +// %s defaults -// make diagnosing Faults (e.g. HardFault) harder, but save bytes: -#ifndef AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED -#define AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED 0 -#endif +%s -#ifndef AP_WATCHDOG_SAVE_FAULT_ENABLED -#define AP_WATCHDOG_SAVE_FAULT_ENABLED 0 -#endif +// end %s defaults +''' % (description, content, description)) -// end AP_Bootloader defaults -''') + def is_io_fw(self): + return int(self.env_vars.get('IOMCU_FW', 0)) != 0 def add_iomcu_firmware_defaults(self, f): '''add default defines IO firmwares''' - if self.env_vars.get('IOMCU_FW', 0) == 0: + if not self.is_io_fw(): # not IOMCU firmware return - print("Setting up as IO firmware") - f.write(''' -// IOMCU Firmware defaults - -#define HAL_DSHOT_ALARM_ENABLED 0 - -#define HAL_LOGGING_ENABLED 0 - -// IOMCUs *definitely* don't use the FFT library: -#ifndef HAL_GYROFFT_ENABLED -#define HAL_GYROFFT_ENABLED 0 -#endif - -// by default IOMCUs don't use INS: -#ifndef AP_INERTIALSENSOR_ENABLED -#define AP_INERTIALSENSOR_ENABLED 0 -#endif - -// no RC_Channels library: -#ifndef AP_RC_CHANNEL_ENABLED -#define AP_RC_CHANNEL_ENABLED 0 -#endif - -#ifndef AP_VIDEOTX_ENABLED -#define AP_VIDEOTX_ENABLED 0 -#endif - -// make diagnosing Faults (e.g. HardFault) harder, but save bytes: -#ifndef AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED -#define AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED 0 -#endif - -// disable some protocols on iomcu: -#define AP_RCPROTOCOL_FASTSBUS_ENABLED 0 - -// no crossfire telemetry from iomcu! -#define HAL_CRSF_TELEM_ENABLED 0 - -// allow the IOMCU to have its allowed protocols to be set: -#define AP_RCPROTOCOL_ENABLE_SET_RC_PROTOCOLS 1 - -// end IOMCU Firmware defaults -''') + self.add_firmware_defaults_from_file(f, "defaults_iofirmware.h", "IOMCU Firmware") def is_periph_fw(self): - return self.env_vars.get('AP_PERIPH', 0) != 0 + return int(self.env_vars.get('AP_PERIPH', 0)) != 0 - def add_normal_firmware_defaults(self, f): - '''add default defines to builds with are not bootloader, periph or IOMCU''' - if self.env_vars.get('IOMCU_FW', 0) != 0: + def is_normal_fw(self): + if self.is_io_fw(): # IOMCU firmware - return + return False if self.is_periph_fw(): # Periph firmware - return - if args.bootloader: + return False + if self.is_bootloader_fw(): # guess - return - - print("Setting up as normal firmware") - f.write(''' -// firmware defaults - -#ifndef HAL_DSHOT_ALARM_ENABLED -#define HAL_DSHOT_ALARM_ENABLED (HAL_PWM_COUNT>0) -#endif - -#ifndef HAL_BOARD_LOG_DIRECTORY -#define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" -#endif - -#ifndef HAL_BOARD_TERRAIN_DIRECTORY -#define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" -#endif + return False + return True -// enable terrain only if there's an SD card available: -#define AP_TERRAIN_AVAILABLE HAL_OS_FATFS_IO + def add_normal_firmware_defaults(self, f): + '''add default defines to builds with are not bootloader, periph or IOMCU''' + if not self.is_normal_fw(): + return -// end firmware defaults -''') + self.add_firmware_defaults_from_file(f, "defaults_normal.h", "normal") def run(self): @@ -3517,6 +3156,7 @@ def run(self): self.write_env_py(os.path.join(self.outdir, "env.py")) + if __name__ == '__main__': parser = argparse.ArgumentParser("chibios_pins.py") 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 4c1a259e7929e8..0a360657503f84 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_betaflight_unified.py @@ -45,6 +45,7 @@ "CW90FLIP" : "ROTATION_ROLL_180", "CW180FLIP" : "ROTATION_ROLL_180_YAW_90", "CW270FLIP" : "ROTATION_PITCH_180", + "DEFAULT" : "ROTATION_NONE", } parser = argparse.ArgumentParser("convert_betaflight_unified.py") @@ -106,8 +107,25 @@ def write_imu_config(f, n): f.write(''' # IMU setup SPIDEV imu%s SPI%s DEVID1 GYRO%s_CS MODE3 1*MHZ 8*MHZ -IMU Invensense SPI:imu%s %s -''' % (n, bus, n, n, alignment[align])) +''' % (n, bus, n)) + + c = 0 + for define in defines: + for imudefine in ['USE_GYRO_SPI_', 'USE_ACCGYRO_']: + if define.startswith(imudefine): + imu = define[len(imudefine):] + c = c + 1 + if c == int(n): + if imu == 'ICM42688P': + imudriver = 'Invensensev3' + elif imu == 'BMI270': + imudriver = 'BMI270' + else: + imudriver = 'Invensense' + f.write(''' +IMU %s SPI:imu%s %s +''' % (imudriver, n, alignment[align])) + dma = "SPI" + bus + "*" dma_noshare[dma] = dma @@ -139,6 +157,11 @@ def convert_file(fname, board_id): reserve_start = 96 elif mcuclass == "H7": reserve_start = 384 + else: + mcuclass = "F4" + mcu = "F405" + flash_size = 1024 + reserve_start = 48 # preamble @@ -316,7 +339,7 @@ def convert_file(fname, board_id): f.write("%s BATT_CURRENT_SENS %s SCALE(1)\n" % (adc[1], name)) f.write('''define HAL_BATT_CURR_PIN %s define HAL_BATT_CURR_SCALE %.1f -''' % (get_ADC1_chan(mcu, adc[1]), int(settings['ibata_scale']) * 59.5 / 168 )) # scale taken from KakuteH7 +''' % (get_ADC1_chan(mcu, adc[1]), 10000 / int(settings['ibata_scale']))) elif (adc[3] == "ADC_RSSI"): f.write("%s RSSI_ADC %s\n" % (adc[1], name)) f.write("define BOARD_RSSI_ANA_PIN %s\n" % (get_ADC1_chan(mcu, adc[1]))) @@ -437,6 +460,11 @@ def convert_bootloader(fname, board_id): reserve_start = 96 elif mcuclass == "H7": reserve_start = 384 + else: + mcuclass = "F4" + mcu = "F405" + flash_size = 1024 + reserve_start = 48 # preamble diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h new file mode 100644 index 00000000000000..c002446c74b436 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_bootloader.h @@ -0,0 +1,37 @@ +// this file is inserted (by chibios_hwdef.py) into hwdef.h when +// configuring for bootloader builds + +#define HAL_DSHOT_ALARM_ENABLED 0 +#define HAL_LOGGING_ENABLED 0 +#define HAL_SCHEDULER_ENABLED 0 + +// bootloaders *definitely* don't use the FFT library: +#ifndef HAL_GYROFFT_ENABLED +#define HAL_GYROFFT_ENABLED 0 +#endif + +// bootloaders don't talk to the GCS: +#ifndef HAL_GCS_ENABLED +#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: +#ifndef HAL_ENABLE_SAVE_PERSISTENT_PARAMS +#define HAL_ENABLE_SAVE_PERSISTENT_PARAMS 0 +#endif + +// make diagnosing Faults (e.g. HardFault) harder, but save bytes: +#ifndef AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED +#define AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED 0 +#endif + +#ifndef AP_WATCHDOG_SAVE_FAULT_ENABLED +#define AP_WATCHDOG_SAVE_FAULT_ENABLED 0 +#endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h new file mode 100644 index 00000000000000..7cd350f397347f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h @@ -0,0 +1,43 @@ +// this file is inserted (by chibios_hwdef.py) into hwdef.h when +// configuring for iofirmware builds + +#define HAL_DSHOT_ALARM_ENABLED 0 + +#define HAL_LOGGING_ENABLED 0 + +// IOMCUs *definitely* don't use the FFT library: +#ifndef HAL_GYROFFT_ENABLED +#define HAL_GYROFFT_ENABLED 0 +#endif + +// by default IOMCUs don't use INS: +#ifndef AP_INERTIALSENSOR_ENABLED +#define AP_INERTIALSENSOR_ENABLED 0 +#endif + +// no RC_Channels library: +#ifndef AP_RC_CHANNEL_ENABLED +#define AP_RC_CHANNEL_ENABLED 0 +#endif + +#ifndef AP_VIDEOTX_ENABLED +#define AP_VIDEOTX_ENABLED 0 +#endif + +// make diagnosing Faults (e.g. HardFault) harder, but save bytes: +#ifndef AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED +#define AP_FAULTHANDLER_DEBUG_VARIABLES_ENABLED 0 +#endif + +// disable some protocols on iomcu: +#define AP_RCPROTOCOL_FASTSBUS_ENABLED 0 + +// no crossfire telemetry from iomcu! +#define HAL_CRSF_TELEM_ENABLED 0 + +// allow the IOMCU to have its allowed protocols to be set: +#define AP_RCPROTOCOL_ENABLE_SET_RC_PROTOCOLS 1 + +#ifndef AP_INTERNALERROR_ENABLED +#define AP_INTERNALERROR_ENABLED 0 +#endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_normal.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_normal.h new file mode 100644 index 00000000000000..718da256e00650 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_normal.h @@ -0,0 +1,18 @@ +// this file is inserted (by chibios_hwdef.py) into hwdef.h when +// configuring for "normal" builds - typically vehicle binaries but +// also examples. + +#ifndef HAL_DSHOT_ALARM_ENABLED +#define HAL_DSHOT_ALARM_ENABLED (HAL_PWM_COUNT>0) +#endif + +#ifndef HAL_BOARD_LOG_DIRECTORY +#define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +#endif + +#ifndef HAL_BOARD_TERRAIN_DIRECTORY +#define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" +#endif + +// enable terrain only if there's an SD card available: +#define AP_TERRAIN_AVAILABLE HAL_OS_FATFS_IO diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h new file mode 100644 index 00000000000000..a3ea17ea757b9e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h @@ -0,0 +1,354 @@ +// this file is inserted (by chibios_hwdef.py) into hwdef.h when +// configuring for AP_Periph builds + +#ifndef AP_SCHEDULER_ENABLED +#define AP_SCHEDULER_ENABLED 0 +#endif + +#ifndef HAL_LOGGING_ENABLED +#define HAL_LOGGING_ENABLED 0 +#endif + +#ifndef HAL_GCS_ENABLED +#define HAL_GCS_ENABLED 0 +#endif + +/* + AP_Periph doesn't include the SERIAL parameter tree, instead each + supported serial device type has it's own parameter within AP_Periph + for which port is used. + */ +#define DEFAULT_SERIAL0_PROTOCOL SerialProtocol_None +#define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_None +#define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None +#define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None +#define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None +#define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None +#define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_None +#define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_None +#define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_None +#define DEFAULT_SERIAL9_PROTOCOL SerialProtocol_None + +#ifndef HAL_LOGGING_MAVLINK_ENABLED +#define HAL_LOGGING_MAVLINK_ENABLED 0 +#endif + +#ifndef AP_MISSION_ENABLED +#define AP_MISSION_ENABLED 0 +#endif + +#ifndef HAL_RALLY_ENABLED +#define HAL_RALLY_ENABLED 0 +#endif + +#ifndef HAL_NMEA_OUTPUT_ENABLED +#define HAL_NMEA_OUTPUT_ENABLED 0 +#endif + +#ifndef HAL_CAN_DEFAULT_NODE_ID +#define HAL_CAN_DEFAULT_NODE_ID 0 +#endif + +#define PERIPH_FW TRUE +#define HAL_BUILD_AP_PERIPH + +#ifndef HAL_WATCHDOG_ENABLED_DEFAULT +#define HAL_WATCHDOG_ENABLED_DEFAULT true +#endif + +#ifndef AP_FETTEC_ONEWIRE_ENABLED +#define AP_FETTEC_ONEWIRE_ENABLED 0 +#endif + +#ifndef HAL_TORQEEDO_ENABLED +#define HAL_TORQEEDO_ENABLED 0 +#endif + +#ifndef AP_KDECAN_ENABLED +#define AP_KDECAN_ENABLED 0 +#endif + +#ifndef HAL_GENERATOR_ENABLED +#define HAL_GENERATOR_ENABLED 0 +#endif + +#ifndef HAL_BARO_WIND_COMP_ENABLED +#define HAL_BARO_WIND_COMP_ENABLED 0 +#endif + +#ifndef HAL_UART_STATS_ENABLED +#define HAL_UART_STATS_ENABLED (HAL_GCS_ENABLED || HAL_LOGGING_ENABLED) +#endif + +#ifndef HAL_SUPPORT_RCOUT_SERIAL +#define HAL_SUPPORT_RCOUT_SERIAL 0 +#endif + +#ifndef AP_AIRSPEED_AUTOCAL_ENABLE +#define AP_AIRSPEED_AUTOCAL_ENABLE 0 +#endif + +#ifndef AP_STATS_ENABLED +#define AP_STATS_ENABLED 0 +#endif + +#ifndef AP_VOLZ_ENABLED +#define AP_VOLZ_ENABLED 0 +#endif + +#ifndef AP_ROBOTISSERVO_ENABLED +#define AP_ROBOTISSERVO_ENABLED 0 +#endif + +#ifndef AP_SBUSOUTPUT_ENABLED +#define AP_SBUSOUTPUT_ENABLED 0 +#endif + +// by default an AP_Periph defines as many servo output channels as +// there are PWM outputs: +#ifndef NUM_SERVO_CHANNELS +#ifdef HAL_PWM_COUNT +#define NUM_SERVO_CHANNELS HAL_PWM_COUNT +#else +#define NUM_SERVO_CHANNELS 0 +#endif +#endif + +#ifndef AP_STATS_ENABLED +#define AP_STATS_ENABLED 0 +#endif + +#ifndef AP_BATTERY_ESC_ENABLED +#define AP_BATTERY_ESC_ENABLED 0 +#endif + +// disable compass calibrations on periphs; cal is done on the autopilot +#ifndef COMPASS_CAL_ENABLED +#define COMPASS_CAL_ENABLED 0 +#endif +#ifndef COMPASS_MOT_ENABLED +#define COMPASS_MOT_ENABLED 0 +#endif +#ifndef COMPASS_LEARN_ENABLED +#define COMPASS_LEARN_ENABLED 0 +#endif + +#ifndef HAL_EXTERNAL_AHRS_ENABLED +#define HAL_EXTERNAL_AHRS_ENABLED 0 +#endif + +// disable RC_Channels library: +#ifndef AP_RC_CHANNEL_ENABLED +#define AP_RC_CHANNEL_ENABLED 0 +#endif + +#define HAL_CRSF_TELEM_ENABLED 0 + +#ifndef AP_SERVORELAYEVENTS_ENABLED +#define AP_SERVORELAYEVENTS_ENABLED 0 +#endif + +#ifndef AP_RELAY_ENABLED +#define AP_RELAY_ENABLED 0 +#endif + +/* + * GPS Backends - we selectively turn backends on. + * Note also that f103-GPS explicitly disables some of these backends. + */ +#define AP_GPS_BACKEND_DEFAULT_ENABLED 0 +#ifndef AP_GPS_UBLOX_ENABLED +#define AP_GPS_UBLOX_ENABLED defined(HAL_PERIPH_ENABLE_GPS) +#endif +#ifndef HAL_MSP_GPS_ENABLED +#define HAL_MSP_GPS_ENABLED defined(HAL_PERIPH_ENABLE_GPS) && HAL_MSP_SENSORS_ENABLED +#endif + +#ifndef AP_GPS_ERB_ENABLED +#define AP_GPS_ERB_ENABLED 0 +#endif + +#ifndef AP_GPS_GSOF_ENABLED +#define AP_GPS_GSOF_ENABLED defined(HAL_PERIPH_ENABLE_GPS) +#endif + +#ifndef AP_GPS_NMEA_ENABLED +#define AP_GPS_NMEA_ENABLED 0 +#endif + +#ifndef AP_GPS_SBF_ENABLED +#define AP_GPS_SBF_ENABLED defined(HAL_PERIPH_ENABLE_GPS) +#endif + +#ifndef AP_GPS_SBP_ENABLED +#define AP_GPS_SBP_ENABLED 0 +#endif + +#ifndef AP_GPS_SBP2_ENABLED +#define AP_GPS_SBP2_ENABLED 0 +#endif + +#ifndef AP_GPS_SIRF_ENABLED +#define AP_GPS_SIRF_ENABLED 0 +#endif + +#ifndef AP_GPS_MAV_ENABLED +#define AP_GPS_MAV_ENABLED 0 +#endif + +#ifndef AP_GPS_NOVA_ENABLED +#define AP_GPS_NOVA_ENABLED defined(HAL_PERIPH_ENABLE_GPS) +#endif + +#ifndef HAL_SIM_GPS_ENABLED +#define HAL_SIM_GPS_ENABLED (AP_SIM_ENABLED && defined(HAL_PERIPH_ENABLE_GPS)) +#endif + +/* + * Airspeed Backends - we selectively turn backends *off* + */ +#ifndef AP_AIRSPEED_ANALOG_ENABLED +#define AP_AIRSPEED_ANALOG_ENABLED 0 +#endif + +// disable various rangefinder backends +#define AP_RANGEFINDER_ANALOG_ENABLED 0 +#define AP_RANGEFINDER_HC_SR04_ENABLED 0 +#define AP_RANGEFINDER_PWM_ENABLED 0 + +// AP_Periph expects ROTATION_NONE +#ifndef AP_RANGEFINDER_DEFAULT_ORIENTATION +#define AP_RANGEFINDER_DEFAULT_ORIENTATION ROTATION_NONE +#endif + +// no CAN manager in AP_Periph: +#define HAL_CANMANAGER_ENABLED 0 + +// SLCAN is off by default: +#ifndef AP_CAN_SLCAN_ENABLED +#define AP_CAN_SLCAN_ENABLED 0 +#endif + +// Periphs don't use the FFT library: +#ifndef HAL_GYROFFT_ENABLED +#define HAL_GYROFFT_ENABLED 0 +#endif + +// MSP parsing is off by default in AP_Periph: +#ifndef HAL_MSP_ENABLED +#define HAL_MSP_ENABLED 0 +#endif + +// periph does not make use of compass scaling or diagonals +#ifndef AP_COMPASS_DIAGONALS_ENABLED +#define AP_COMPASS_DIAGONALS_ENABLED 0 +#endif + +// disable various battery monitor backends: +#ifndef AP_BATTERY_SYNTHETIC_CURRENT_ENABLED +#define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 0 +#endif + +#ifndef AP_BATT_MONITOR_MAX_INSTANCES +#define AP_BATT_MONITOR_MAX_INSTANCES 1 +#endif + +// Capacity tracking off +#ifndef AP_BATT_MONITOR_BATTERY_CAPACITY +#define AP_BATT_MONITOR_BATTERY_CAPACITY 0 +#endif + +#ifndef RANGEFINDER_MAX_INSTANCES +#define RANGEFINDER_MAX_INSTANCES 1 +#endif + +// by default AP_Periphs don't use INS: +#ifndef AP_INERTIALSENSOR_ENABLED +#define AP_INERTIALSENSOR_ENABLED 0 +#endif + +// no fence by default in AP_Periph: +#ifndef AP_FENCE_ENABLED +#define AP_FENCE_ENABLED 0 +#endif + +// periph does not save temperature cals etc: +#ifndef HAL_ENABLE_SAVE_PERSISTENT_PARAMS +#define HAL_ENABLE_SAVE_PERSISTENT_PARAMS 0 +#endif + +#ifndef AP_WINCH_ENABLED +#define AP_WINCH_ENABLED 0 +#endif + +#ifndef AP_VIDEOTX_ENABLED +#define AP_VIDEOTX_ENABLED 0 +#endif + +#ifndef AP_FRSKY_TELEM_ENABLED +#define AP_FRSKY_TELEM_ENABLED 0 +#endif + +#ifndef HAL_SPEKTRUM_TELEM_ENABLED +#define HAL_SPEKTRUM_TELEM_ENABLED 0 +#endif + +#ifndef AP_FILESYSTEM_ROMFS_ENABLED +#define AP_FILESYSTEM_ROMFS_ENABLED 0 +#endif + +#ifndef NOTIFY_LED_OVERRIDE_DEFAULT +#define NOTIFY_LED_OVERRIDE_DEFAULT 1 // rgb_source_t::mavlink +#endif + +#ifndef HAL_PROXIMITY_ENABLED +#define HAL_PROXIMITY_ENABLED 0 +#endif + +#ifndef AP_SCRIPTING_ENABLED +#define AP_SCRIPTING_ENABLED 0 +#endif + +#ifndef AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED +#define AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED 0 +#endif + +#define AP_BATTERY_ENABLED defined(HAL_PERIPH_ENABLE_BATTERY) +#define AP_AHRS_ENABLED defined(HAL_PERIPH_ENABLE_AHRS) +#define AP_COMPASS_ENABLED defined(HAL_PERIPH_ENABLE_MAG) +#define AP_BARO_ENABLED defined(HAL_PERIPH_ENABLE_BARO) +#define AP_GPS_ENABLED 1 // FIXME: should be defined(HAL_PERIPH_ENABLE_GPS) +#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) + +#ifndef AP_BOOTLOADER_ALWAYS_ERASE +#define AP_BOOTLOADER_ALWAYS_ERASE 1 +#endif + +#ifndef GPS_MOVING_BASELINE +#define GPS_MOVING_BASELINE 0 +#endif + +#ifndef AP_UART_MONITOR_ENABLED +#define AP_UART_MONITOR_ENABLED defined(HAL_PERIPH_ENABLE_GPS) && (GPS_MOVING_BASELINE || BOARD_FLASH_SIZE>=256) +#endif + +#ifndef HAL_BOARD_LOG_DIRECTORY +#define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +#endif + +#ifndef HAL_BOARD_TERRAIN_DIRECTORY +#define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" +#endif + +#ifndef HAL_MAVLINK_BINDINGS_ENABLED +#define HAL_MAVLINK_BINDINGS_ENABLED defined(HAL_PERIPH_ENABLE_ADSB) || HAL_GCS_ENABLED +#endif + +// for boards other than AP_Periph we are always expecting delays when +// not initialised. We can't afford that on AP_Periph as you may end +// up with a bricked node if you write a bad firmware to it. +#ifndef AP_HAL_CHIBIOS_IN_EXPECTED_DELAY_WHEN_NOT_INITIALISED +#define AP_HAL_CHIBIOS_IN_EXPECTED_DELAY_WHEN_NOT_INITIALISED 0 +#endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py index 16f43097b35427..4f78382deb3c56 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py @@ -340,7 +340,24 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[], for p in peripheral_list: forbidden_map[p] = forbidden_list(p, peripheral_list) + # force sharing of TIMx_UP and TIMx_CHy if possible + periphs = peripheral_list.copy() + forbidden_streams = [] for periph in peripheral_list: + if "_UP" in periph: + for periph2 in peripheral_list: + if "_CH" in periph2 and periph[:4] == periph2[:4]: + shared_channels = [value for value in dma_map[periph] if value in dma_map[periph2]] + if len(shared_channels) > 0: + stream = (shared_channels[0][0], shared_channels[0][1]) + curr_dict[periph] = stream + curr_dict[periph2] = stream + forbidden_streams.append(stream) + periphs.remove(periph) + periphs.remove(periph2) + print("Sharing channel %s for %s %s" % (stream, periph, periph2)) + + for periph in periphs: if "_CH" in periph: has_bdshot = True # the list contains a CH port if periph in dma_exclude: @@ -359,7 +376,7 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[], print('........Possibility for', periph, streamchan) stream = (streamchan[0], streamchan[1]) if check_possibility(periph, stream, curr_dict, dma_map, - check_list, [], forbidden_map): + check_list, forbidden_streams, forbidden_map): curr_dict[periph] = stream if debug: print ('....................... Setting', periph, stream) 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 5c4eb701ae29ea..acad0918627d0f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-f412-rev1/hwdef.dat @@ -129,4 +129,7 @@ define HAL_BARO_20789_I2C_ADDR_PRESS 0x63 define HAL_WITH_ESC_TELEM 0 define AP_FETTEC_ONEWIRE_ENABLED 0 +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 + AUTOBUILD_TARGETS Copter diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat index eddb9ad0393ddb..67af5681fe33db 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/hwdef.dat @@ -132,4 +132,7 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 8192 define HAL_WITH_ESC_TELEM 0 define AP_FETTEC_ONEWIRE_ENABLED 0 +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 + AUTOBUILD_TARGETS Copter diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat index ccb8dbf624947c..831c079648e98b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat @@ -72,7 +72,6 @@ define AP_BEACON_ENABLED 0 define AP_OPTICALFLOW_ENABLED 0 define AP_FRSKY_TELEM_ENABLED 0 define AP_BEACON_ENABLED 0 -define GPS_MOVING_BASELINE 0 define HAL_ADSB_SAGETECH_ENABLED 0 define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED 0 define AP_AIS_ENABLED 0 @@ -113,6 +112,8 @@ define AP_BARO_ICM20789_ENABLED 1 define AP_GPS_BACKEND_DEFAULT_ENABLED 0 define AP_GPS_UBLOX_ENABLED 1 define AP_GPS_MAV_ENABLED 1 +define GPS_MOVING_BASELINE 0 +define GPS_MAX_RECEIVERS 1 # removes blended support # enable only the QUAD frame define AP_MOTORS_FRAME_DEFAULT_ENABLED 0 @@ -210,4 +211,10 @@ define AP_SCRIPTING_ENABLED 0 define AP_BATT_MONITOR_MAX_INSTANCES 1 define AP_MAVLINK_BATTERY2_ENABLED 0 +# SkyViper doesn't use the Plane landing library: +define HAL_LANDING_DEEPSTALL_ENABLED 0 + +# bootloader embedding / bootloader flashing not available +define AP_BOOTLOADER_FLASHING_ENABLED 0 + AUTOBUILD_TARGETS Copter diff --git a/libraries/AP_HAL_ChibiOS/hwdef/sw-nav-f405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/sw-nav-f405/hwdef-bl.dat new file mode 100644 index 00000000000000..069792922ba697 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/sw-nav-f405/hwdef-bl.dat @@ -0,0 +1,38 @@ +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# crystal frequency +OSCILLATOR_HZ 8000000 + +APJ_BOARD_ID 6002 + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +define CAN_APP_NODE_NAME "sw-nav-f405-bl" + +FLASH_RESERVE_START_KB 0 +FLASH_SIZE_KB 1024 +FLASH_BOOTLOADER_LOAD_KB 64 + +# jtag +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# status light +PC4 LED_BOOTLOADER OUTPUT LOW GPIO(0) +define HAL_LED_ON 1 + +# strap LED/nav lights off +PA3 LED_CTRL_VIS OUTPUT LOW GPIO(1) # vis light power +PA1 LED_COLOR OUTPUT LOW GPIO(2) # red/green +PA2 LED_WHITE OUTPUT LOW GPIO(3) # white +PB0 LED_IR OUTPUT LOW GPIO(4) # IR + +# can +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PA15 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +# disable serial +define HAL_USE_SERIAL FALSE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/sw-nav-f405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/sw-nav-f405/hwdef.dat new file mode 100644 index 00000000000000..d4dac2c2048e3d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/sw-nav-f405/hwdef.dat @@ -0,0 +1,83 @@ +# hw definition file for f405 Matek CAN GPS + +# 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 6002 + +define CAN_APP_NODE_NAME "sw-nav-f405" + +env AP_PERIPH 1 + +define STM32_ST_USE_TIMER 5 +define CH_CFG_ST_RESOLUTION 32 + +# crystal frequency +OSCILLATOR_HZ 8000000 + +# status light, normally disabled so as to not confuse nav light functionality +#PC4 LED OUTPUT LOW GPIO(0) +#define HAL_LED_ON 1 + +## debug +#PA13 JTMS-SWDIO SWD +#PA14 JTCK-SWCLK SWD + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 256 + +# keep ROMFS uncompressed although we do have the runtime ram needed +env ROMFS_UNCOMPRESSED True + +# i2c +I2C_ORDER I2C1 + +PB7 I2C1_SDA I2C1 +PB6 I2C1_SCL I2C1 + +# can +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +PA15 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +# disable serial +define HAL_USE_SERIAL FALSE +define HAL_NO_UARTDRIVER TRUE + +define HAL_USE_ADC FALSE + +# compass +define HAL_PERIPH_ENABLE_MAG + +COMPASS MMC3416 I2C:0:0x30 false ROTATION_NONE + +define HAL_COMPASS_MAX_SENSORS 1 + +# notify led +define HAL_PERIPH_ENABLE_NOTIFY +define HAL_PERIPH_ENABLE_RC_OUT + +define DEFAULT_NTF_LED_TYPES 131072 # discrete rgb led (1 << 17) + +define AP_NOTIFY_DISCRETE_RGB_ENABLED 1 +PA3 LED_CTRL_VIS OUTPUT HIGH GPIO(1) # vis light power +PA1 LED_COLOR OUTPUT LOW GPIO(2) # red/green +PA2 LED_WHITE OUTPUT LOW GPIO(3) # white +PB0 LED_IR OUTPUT LOW GPIO(4) # IR + +define DISCRETE_RGB_RED_PIN 3 +define DISCRETE_RGB_GREEN_PIN 2 +define DISCRETE_RGB_BLUE_PIN 4 +define DISCRETE_RGB_POLARITY true + +# don't build on firmware.ardupilot.org +AUTOBUILD_TARGETS None diff --git a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat index 2af43c42c3f88e..827c5ff9592282 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat @@ -282,7 +282,3 @@ DMA_PRIORITY USART6* SPI* # is "ROMFS ROMFS-filename source-filename". Paths are relative to the # ardupilot root. ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin - -# for users running fmuv3 on their Solo: -define HAL_OREO_LED_ENABLED (BOARD_FLASH_SIZE > 1024) -define HAL_SOLO_GIMBAL_ENABLED (HAL_MOUNT_ENABLED && BOARD_FLASH_SIZE > 1024) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat index c916328bcb6955..4122e0fa579919 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat @@ -282,7 +282,3 @@ DMA_PRIORITY USART6* SPI* # is "ROMFS ROMFS-filename source-filename". Paths are relative to the # ardupilot root. ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin - -# for users running fmuv3 on their Solo: -define HAL_OREO_LED_ENABLED (BOARD_FLASH_SIZE > 1024) -define HAL_SOLO_GIMBAL_ENABLED (HAL_MOUNT_ENABLED && BOARD_FLASH_SIZE > 1024) diff --git a/libraries/AP_HAL_ChibiOS/system.cpp b/libraries/AP_HAL_ChibiOS/system.cpp index 82b948fce3fcfe..d58b069f7b73f7 100644 --- a/libraries/AP_HAL_ChibiOS/system.cpp +++ b/libraries/AP_HAL_ChibiOS/system.cpp @@ -304,6 +304,13 @@ void __entry_hook() } #endif +uint32_t chibios_rand_generate() +{ + uint32_t val; + hal.util->get_random_vals((uint8_t*)&val, sizeof(val)); + return val; +} + } namespace AP_HAL { @@ -382,30 +389,4 @@ __FASTRAMFUNC__ uint64_t millis64() } -__FASTRAMFUNC__ uint32_t native_micros() -{ - return micros(); -} - -__FASTRAMFUNC__ uint32_t native_millis() -{ - return millis(); -} - -__FASTRAMFUNC__ uint16_t native_millis16() -{ - return millis16(); -} - -__FASTRAMFUNC__ uint64_t native_micros64() -{ - return micros64(); -} - -__FASTRAMFUNC__ uint64_t native_millis64() -{ - return millis64(); -} - - } // namespace AP_HAL diff --git a/libraries/AP_HAL_ESP32/Scheduler.cpp b/libraries/AP_HAL_ESP32/Scheduler.cpp index 66be0ef5ee2168..f4d26dde3ae0ed 100644 --- a/libraries/AP_HAL_ESP32/Scheduler.cpp +++ b/libraries/AP_HAL_ESP32/Scheduler.cpp @@ -28,6 +28,7 @@ #include "esp_task_wdt.h" #include +#include #include //#define SCHEDULERDEBUG 1 @@ -50,6 +51,7 @@ void disableCore0WDT() //print("Failed to remove Core 0 IDLE task from WDT"); } } + void disableCore1WDT() { TaskHandle_t idle_1 = xTaskGetIdleTaskHandleForCPU(1); @@ -292,9 +294,14 @@ void Scheduler::_timer_thread(void *arg) printf("%s:%d start\n", __PRETTY_FUNCTION__, __LINE__); #endif Scheduler *sched = (Scheduler *)arg; + +#if HAL_INS_DEFAULT != HAL_INS_NONE + // wait to ensure INS system inits unless using HAL_INS_NONE while (!_initialized) { sched->delay_microseconds(1000); } +#endif + #ifdef SCHEDDEBUG printf("%s:%d initialised\n", __PRETTY_FUNCTION__, __LINE__); #endif @@ -507,17 +514,25 @@ void Scheduler::print_stats(void) // printf("loop_rate_hz: %d",get_loop_rate_hz()); } +// Run every 10s +void Scheduler::print_main_loop_rate(void) +{ + static int64_t last_run = 0; + if (AP_HAL::millis64() - last_run > 10000) { + last_run = AP_HAL::millis64(); + 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", + (uint16_t)actual_loop_rate, (uint16_t)expected_loop_rate); + } +} + void IRAM_ATTR Scheduler::_main_thread(void *arg) { #ifdef SCHEDDEBUG printf("%s:%d start\n", __PRETTY_FUNCTION__, __LINE__); #endif Scheduler *sched = (Scheduler *)arg; - hal.serial(0)->begin(115200); - hal.serial(1)->begin(57600); - hal.serial(2)->begin(57600); - //hal.uartC->begin(921600); - hal.serial(3)->begin(115200); #ifndef HAL_DISABLE_ADC_DRIVER hal.analogin->init(); @@ -535,7 +550,9 @@ void IRAM_ATTR Scheduler::_main_thread(void *arg) sched->callbacks->loop(); sched->delay_microseconds(250); - sched->print_stats(); // only runs every 60 seconds. + // run stats periodically + sched->print_stats(); + sched->print_main_loop_rate(); } } diff --git a/libraries/AP_HAL_ESP32/Scheduler.h b/libraries/AP_HAL_ESP32/Scheduler.h index eb676b8bdb6ae0..237f9532eaef2d 100644 --- a/libraries/AP_HAL_ESP32/Scheduler.h +++ b/libraries/AP_HAL_ESP32/Scheduler.h @@ -49,6 +49,8 @@ class ESP32::Scheduler : public AP_HAL::Scheduler bool is_system_initialized() override; void print_stats(void) ; + void print_main_loop_rate(void); + uint16_t get_loop_rate_hz(void); AP_Int16 _active_loop_rate_hz; AP_Int16 _loop_rate_hz; diff --git a/libraries/AP_HAL_ESP32/Storage.h b/libraries/AP_HAL_ESP32/Storage.h index 45f8376e6976da..ff066b96d60d60 100644 --- a/libraries/AP_HAL_ESP32/Storage.h +++ b/libraries/AP_HAL_ESP32/Storage.h @@ -23,7 +23,7 @@ #include "esp_partition.h" #define STORAGE_SIZE HAL_STORAGE_SIZE -#define STORAGE_SECTOR_SIZE (64*1024) +#define STORAGE_SECTOR_SIZE (128*1024) #define STORAGE_LINE_SHIFT 3 diff --git a/libraries/AP_HAL_ESP32/boards/esp32empty.h b/libraries/AP_HAL_ESP32/boards/esp32empty.h index 4ca5f006081546..33f5d7c219ca99 100644 --- a/libraries/AP_HAL_ESP32/boards/esp32empty.h +++ b/libraries/AP_HAL_ESP32/boards/esp32empty.h @@ -23,108 +23,128 @@ #define HAL_ESP32_BOARD_NAME "esp32-empty" -#define TRUE 1 -#define FALSE 0 +#define TRUE 1 +#define FALSE 0 //Protocols -//list of protocols/enum: ardupilot/libraries/AP_SerialManager/AP_SerialManager.h -//default protocols: ardupilot/libraries/AP_SerialManager/AP_SerialManager.cpp -//ESP32 serials: AP_HAL_ESP32/HAL_ESP32_Class.cpp +// list of protocols/enum: ardupilot/libraries/AP_SerialManager/AP_SerialManager.h +// default protocols: ardupilot/libraries/AP_SerialManager/AP_SerialManager.cpp +// ESP32 serials: AP_HAL_ESP32/HAL_ESP32_Class.cpp -//#define DEFAULT_SERIAL0_PROTOCOL SerialProtocol_MAVLink2 //A UART0: Always: Console, MAVLink2 -//#define DEFAULT_SERIAL0_BAUD AP_SERIALMANAGER_CONSOLE_BAUD/1000 //115200 +//#define DEFAULT_SERIAL0_PROTOCOL SerialProtocol_MAVLink2 //A UART0: Always: Console, MAVLink2 +//#define DEFAULT_SERIAL0_BAUD AP_SERIALMANAGER_CONSOLE_BAUD/1000 //115200 -//#define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_MAVLink2 //C WiFi: TCP, UDP, or disable (depends on HAL_ESP32_WIFI) -//#define DEFAULT_SERIAL1_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000 //57600 +//#define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_MAVLink2 //C WiFi: TCP, UDP, or disable (depends on HAL_ESP32_WIFI) +//#define DEFAULT_SERIAL1_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000 //57600 -#define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_MAVLink2 //D UART2: Always: MAVLink2 on ESP32 -//#define DEFAULT_SERIAL2_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000 //57600 +#define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_MAVLink2 //D UART2 +#define DEFAULT_SERIAL2_BAUD AP_SERIALMANAGER_MAVLINK_BAUD/1000 //57600 -#define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_GPS //B UART1: GPS1 -//#define DEFAULT_SERIAL4_BAUD AP_SERIALMANAGER_GPS_BAUD/1000 //38400, Can not define default baudrate here (by config only) +#define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_GPS //B UART1: GPS1 +#define DEFAULT_SERIAL3_BAUD AP_SERIALMANAGER_GPS_BAUD/1000 //38400, Can not define default baudrate here (by config only) +//#define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None //B +//#define DEFAULT_SERIAL3_BAUD (115200/1000) -#define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None //E -//#define DEFAULT_SERIAL4_BAUD AP_SERIALMANAGER_GPS_BAUD/1000 //38400, Can not define default baudrate here (by config only) +#define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None //E +#define DEFAULT_SERIAL5_BAUD (115200/1000) -#define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None //F -#define DEFAULT_SERIAL5_BAUD (115200/1000) +#define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None //F +#define DEFAULT_SERIAL5_BAUD (115200/1000) -#define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_None //G -#define DEFAULT_SERIAL6_BAUD (115200/1000) +#define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_None //G +#define DEFAULT_SERIAL6_BAUD (115200/1000) -#define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_None //H -#define DEFAULT_SERIAL7_BAUD (115200/1000) +#define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_None //H +#define DEFAULT_SERIAL7_BAUD (115200/1000) -#define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_None //I -#define DEFAULT_SERIAL8_BAUD (115200/1000) +#define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_None //I +#define DEFAULT_SERIAL8_BAUD (115200/1000) -#define DEFAULT_SERIAL9_PROTOCOL SerialProtocol_None //J -#define DEFAULT_SERIAL9_BAUD (115200/1000) +#define DEFAULT_SERIAL9_PROTOCOL SerialProtocol_None //J +#define DEFAULT_SERIAL9_BAUD (115200/1000) //Inertial sensors -//#define HAL_INS_DEFAULT HAL_INS_MPU9250_I2C -//#define PROBE_IMU_I2C(driver, bus, addr, args ...) ADD_BACKEND(AP_InertialSensor_ ## driver::probe(*this,GET_I2C_DEVICE(bus, addr),##args)) -//#define HAL_INS_PROBE_LIST PROBE_IMU_I2C(Invensense, 0, 0x68, ROTATION_NONE) +#define HAL_INS_DEFAULT HAL_INS_NONE +//#define HAL_INS_DEFAULT HAL_INS_MPU9250_I2C +//#define PROBE_IMU_I2C(driver, bus, addr, args ...) ADD_BACKEND(AP_InertialSensor_ ## driver::probe(*this,GET_I2C_DEVICE(bus, addr),##args)) +//#define HAL_INS_PROBE_LIST PROBE_IMU_I2C(Invensense, 0, 0x68, ROTATION_NONE) //I2C Buses -#define HAL_ESP32_I2C_BUSES {.port=I2C_NUM_0, .sda=GPIO_NUM_13, .scl=GPIO_NUM_14, .speed=400*KHZ, .internal=true, .soft=true} +#define HAL_ESP32_I2C_BUSES {.port=I2C_NUM_0, .sda=GPIO_NUM_13, .scl=GPIO_NUM_14, .speed=400*KHZ, .internal=true, .soft=true} //SPI Buses -#define HAL_ESP32_SPI_BUSES {} +#define HAL_ESP32_SPI_BUSES {} //SPI Devices -#define HAL_ESP32_SPI_DEVICES {} +#define HAL_ESP32_SPI_DEVICES {} //RCIN -#define HAL_ESP32_RCIN GPIO_NUM_36 +#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 } +#define HAL_ESP32_RCOUT {GPIO_NUM_25, GPIO_NUM_27, GPIO_NUM_33, GPIO_NUM_32, GPIO_NUM_22, GPIO_NUM_21} + +//AIRSPEED +#define AP_AIRSPEED_ENABLED 0 +#define AP_AIRSPEED_ANALOG_ENABLED 0 +#define AP_AIRSPEED_BACKEND_DEFAULT_ENABLED 0 //BAROMETER -#define HAL_BARO_ALLOW_INIT_NO_BARO 1 +#define HAL_BARO_ALLOW_INIT_NO_BARO 1 + +//IMU +// #define AP_INERTIALSENSOR_ENABLED 1 +// #define AP_INERTIALSENSOR_KILL_IMU_ENABLED 0 //COMPASS +#define AP_COMPASS_ENABLE_DEFAULT 0 #define ALLOW_ARM_NO_COMPASS +//See boards.py +#ifndef ENABLE_HEAP +#define ENABLE_HEAP 1 +#endif + //WIFI -#define HAL_ESP32_WIFI 1 //1-TCP, 2-UDP, comment this line = without wifi -#define WIFI_SSID "ardupilot-empty" -#define WIFI_PWD "ardupilot-empty" +#define HAL_ESP32_WIFI 1 //1-TCP, 2-UDP, comment this line = without wifi +#define WIFI_SSID "ardupilot-esp32" +#define WIFI_PWD "ardupilot-esp32" //UARTs +// UART_NUM_0 and UART_NUM_2 are configured to use defaults #define HAL_ESP32_UART_DEVICES \ {.port=UART_NUM_0, .rx=GPIO_NUM_3 , .tx=GPIO_NUM_1 },\ {.port=UART_NUM_1, .rx=GPIO_NUM_34, .tx=GPIO_NUM_18},\ - {.port=UART_NUM_2, .rx=GPIO_NUM_35, .tx=GPIO_NUM_19} + {.port=UART_NUM_2, .rx=GPIO_NUM_16, .tx=GPIO_NUM_17} //ADC -#define HAL_DISABLE_ADC_DRIVER 1 -#define HAL_USE_ADC 0 +#define HAL_DISABLE_ADC_DRIVER 1 +#define HAL_USE_ADC 0 //LED -#define DEFAULT_NTF_LED_TYPES Notify_LED_None +#define DEFAULT_NTF_LED_TYPES Notify_LED_None //RMT pin number -#define HAL_ESP32_RMT_RX_PIN_NUMBER 4 +#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, -// and spi is more flexible pinouts.... dont forget vspi/hspi should be selected to NOT conflict with HAL_ESP32_SPI_BUSES +// 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, +// and spi is more flexible pinouts.... +// dont forget vspi/hspi should be selected to NOT conflict with HAL_ESP32_SPI_BUSES //#define HAL_ESP32_SDCARD //after enabled, uncomment one of below //#define HAL_ESP32_SDMMC -//#define HAL_ESP32_SDSPI {.host=VSPI_HOST, .dma_ch=2, .mosi=GPIO_NUM_2, .miso=GPIO_NUM_15, .sclk=GPIO_NUM_26, .cs=GPIO_NUM_21} +//#define HAL_ESP32_SDSPI {.host=VSPI_HOST, .dma_ch=2, .mosi=GPIO_NUM_2, .miso=GPIO_NUM_15, .sclk=GPIO_NUM_26, .cs=GPIO_NUM_21} -#define HAL_LOGGING_FILESYSTEM_ENABLED 0 -#define HAL_LOGGING_DATAFLASH_ENABLED 0 -#define HAL_LOGGING_MAVLINK_ENABLED 0 +#define HAL_LOGGING_FILESYSTEM_ENABLED 0 +#define HAL_LOGGING_DATAFLASH_ENABLED 0 +#define HAL_LOGGING_MAVLINK_ENABLED 0 -#define HAL_BOARD_LOG_DIRECTORY "/SDCARD/APM/LOGS" -#define HAL_BOARD_STORAGE_DIRECTORY "/SDCARD/APM/STORAGE" -#define HAL_BOARD_LOG_DIRECTORY "/SDCARD/APM/LOGS" -#define HAL_BOARD_TERRAIN_DIRECTORY "/SDCARD/APM/TERRAIN" +#define HAL_BOARD_LOG_DIRECTORY "/SDCARD/APM/LOGS" +#define HAL_BOARD_STORAGE_DIRECTORY "/SDCARD/APM/STORAGE" +#define HAL_BOARD_LOG_DIRECTORY "/SDCARD/APM/LOGS" +#define HAL_BOARD_TERRAIN_DIRECTORY "/SDCARD/APM/TERRAIN" -#define HAL_LOGGING_BACKENDS_DEFAULT 1 +#define HAL_LOGGING_BACKENDS_DEFAULT 1 diff --git a/libraries/AP_HAL_ESP32/targets/esp32/partitions.csv b/libraries/AP_HAL_ESP32/targets/esp32/partitions.csv index 70f23f3af89566..8a292ba165f517 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32/partitions.csv +++ b/libraries/AP_HAL_ESP32/targets/esp32/partitions.csv @@ -2,4 +2,4 @@ nvs, data, nvs, , 0x6000 phy_init, data, phy, , 0x1000 factory, app, factory, , 3M -storage, 0x45, 0x0, , 128K +storage, 0x45, 0x0, , 256K diff --git a/libraries/AP_HAL_Linux/CANSocketIface.cpp b/libraries/AP_HAL_Linux/CANSocketIface.cpp index b7c34e2d12bd4b..03f3be88da8c59 100644 --- a/libraries/AP_HAL_Linux/CANSocketIface.cpp +++ b/libraries/AP_HAL_Linux/CANSocketIface.cpp @@ -269,7 +269,7 @@ void CANIface::_pollWrite() while (_hasReadyTx()) { WITH_SEMAPHORE(sem); const CanTxItem tx = _tx_queue.top(); - uint64_t curr_time = AP_HAL::native_micros64(); + 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); const int res = _write(tx.frame); @@ -279,11 +279,12 @@ void CANIface::_pollWrite() _pending_loopback_ids.insert(tx.frame.id); } stats.tx_success++; + stats.last_transmit_us = curr_time; } else if (res == 0) { // Not transmitted, nor is it an error - stats.tx_full++; + stats.tx_overflow++; break; // Leaving the loop, the frame remains enqueued for the next retry } else { // Transmission error - stats.tx_write_fail++; + stats.tx_rejected++; } } else { // hal.console->printf("TDEAD: %lu CURRT: %lu DEL: %lu\n", tx.deadline, curr_time, curr_time-tx.deadline); @@ -302,7 +303,7 @@ bool CANIface::_pollRead() { iterations_count++; CanRxItem rx; - rx.timestamp_us = AP_HAL::native_micros64(); // Monotonic timestamp is not required to be precise (unlike UTC) + rx.timestamp_us = AP_HAL::micros64(); // Monotonic timestamp is not required to be precise (unlike UTC) bool loopback = false; const int res = _read(rx.frame, rx.timestamp_us, loopback); if (res == 1) { @@ -389,7 +390,7 @@ int CANIface::_read(AP_HAL::CANFrame& frame, uint64_t& timestamp_us, bool& loopb /* * Timestamp */ - timestamp_us = AP_HAL::native_micros64(); + timestamp_us = AP_HAL::micros64(); return 1; } @@ -506,8 +507,8 @@ bool CANIface::select(bool &read_select, bool &write_select, stats.num_tx_poll_req++; } } - if (_evt_handle != nullptr && blocking_deadline > AP_HAL::native_micros64()) { - _evt_handle->wait(blocking_deadline - AP_HAL::native_micros64()); + if (_evt_handle != nullptr && blocking_deadline > AP_HAL::micros64()) { + _evt_handle->wait(blocking_deadline - AP_HAL::micros64()); } } @@ -591,8 +592,8 @@ bool CANIface::CANSocketEventSource::wait(uint16_t duration_us, AP_HAL::EventHan void CANIface::get_stats(ExpandingString &str) { str.printf("tx_requests: %u\n" - "tx_write_fail: %u\n" - "tx_full: %u\n" + "tx_rejected: %u\n" + "tx_overflow: %u\n" "tx_confirmed: %u\n" "tx_success: %u\n" "tx_timedout: %u\n" @@ -605,8 +606,8 @@ void CANIface::get_stats(ExpandingString &str) "num_poll_tx_events: %u\n" "num_poll_rx_events: %u\n", stats.tx_requests, - stats.tx_write_fail, - stats.tx_full, + stats.tx_rejected, + stats.tx_overflow, stats.tx_confirmed, stats.tx_success, stats.tx_timedout, diff --git a/libraries/AP_HAL_Linux/CANSocketIface.h b/libraries/AP_HAL_Linux/CANSocketIface.h index 583faca14f00e8..a7e85f45753c6f 100644 --- a/libraries/AP_HAL_Linux/CANSocketIface.h +++ b/libraries/AP_HAL_Linux/CANSocketIface.h @@ -174,15 +174,8 @@ class CANIface: public AP_HAL::CANIface { std::unordered_multiset _pending_loopback_ids; std::vector _hw_filters_container; - struct { - uint32_t tx_requests; - uint32_t tx_full; + struct bus_stats : public AP_HAL::CANIface::bus_stats_t { uint32_t tx_confirmed; - uint32_t tx_write_fail; - uint32_t tx_success; - uint32_t tx_timedout; - uint32_t rx_received; - uint32_t rx_errors; uint32_t num_downs; uint32_t num_rx_poll_req; uint32_t num_tx_poll_req; diff --git a/libraries/AP_HAL_Linux/GPIO_Navigator.h b/libraries/AP_HAL_Linux/GPIO_Navigator.h index 56ba66051f54c0..1310c91d42a075 100644 --- a/libraries/AP_HAL_Linux/GPIO_Navigator.h +++ b/libraries/AP_HAL_Linux/GPIO_Navigator.h @@ -14,8 +14,9 @@ class GPIO_Navigator : public GPIO_RPI uint8_t read(uint8_t pin) override; void write(uint8_t pin, uint8_t value) override; private: - uint8_t AllowedGPIOS[2] = { - RPI_GPIO_<26>(), // Aux Output for PWMs + uint8_t AllowedGPIOS[3] = { + RPI_GPIO_<18>(), // Aux Output for PWMs + RPI_GPIO_<26>(), // PCA OUTPUT_ENABLE RPI_GPIO_<27>() // Leak detection }; bool pinAllowed(uint8_t pin); diff --git a/libraries/AP_HAL_Linux/RCInput.cpp b/libraries/AP_HAL_Linux/RCInput.cpp index 9b4b5d135efbbc..b4e933d096450b 100644 --- a/libraries/AP_HAL_Linux/RCInput.cpp +++ b/libraries/AP_HAL_Linux/RCInput.cpp @@ -15,9 +15,9 @@ #include #include #include +#include #include "RCInput.h" -#include "sbus.h" #define MIN_NUM_CHANNELS 5 @@ -182,10 +182,10 @@ void RCInput::_process_sbus_pulse(uint16_t width_s0, uint16_t width_s1) } uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS]; uint16_t num_values=0; - bool sbus_failsafe=false, sbus_frame_drop=false; - if (sbus_decode(bytes, values, &num_values, - &sbus_failsafe, &sbus_frame_drop, - LINUX_RC_INPUT_NUM_CHANNELS) && + bool sbus_failsafe=false; + if (AP_RCProtocol_SBUS::sbus_decode(bytes, values, &num_values, + sbus_failsafe, + LINUX_RC_INPUT_NUM_CHANNELS) && num_values >= MIN_NUM_CHANNELS) { for (i=0; i= MIN_NUM_CHANNELS) { for (uint8_t i=0; i - -#include "sbus.h" - -#define SBUS_FRAME_SIZE 25 -#define SBUS_INPUT_CHANNELS 16 -#define SBUS_FLAGS_BYTE 23 -#define SBUS_FAILSAFE_BIT 3 -#define SBUS_FRAMELOST_BIT 2 - -/* define range mapping here, -+100% -> 1000..2000 */ -#define SBUS_RANGE_MIN 200.0f -#define SBUS_RANGE_MAX 1800.0f - -#define SBUS_TARGET_MIN 1000.0f -#define SBUS_TARGET_MAX 2000.0f - -/* pre-calculate the floating point stuff as far as possible at compile time */ -#define SBUS_SCALE_FACTOR ((SBUS_TARGET_MAX - SBUS_TARGET_MIN) / (SBUS_RANGE_MAX - SBUS_RANGE_MIN)) -#define SBUS_SCALE_OFFSET (int)(SBUS_TARGET_MIN - (SBUS_SCALE_FACTOR * SBUS_RANGE_MIN + 0.5f)) - -/* - * S.bus decoder matrix. - * - * Each channel value can come from up to 3 input bytes. Each row in the - * matrix describes up to three bytes, and each entry gives: - * - * - byte offset in the data portion of the frame - * - right shift applied to the data byte - * - mask for the data byte - * - left shift applied to the result into the channel value - */ -struct sbus_bit_pick { - uint8_t byte; - uint8_t rshift; - uint8_t mask; - uint8_t lshift; -}; -static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = { - /* 0 */ { { 0, 0, 0xff, 0}, { 1, 0, 0x07, 8}, { 0, 0, 0x00, 0} }, - /* 1 */ { { 1, 3, 0x1f, 0}, { 2, 0, 0x3f, 5}, { 0, 0, 0x00, 0} }, - /* 2 */ { { 2, 6, 0x03, 0}, { 3, 0, 0xff, 2}, { 4, 0, 0x01, 10} }, - /* 3 */ { { 4, 1, 0x7f, 0}, { 5, 0, 0x0f, 7}, { 0, 0, 0x00, 0} }, - /* 4 */ { { 5, 4, 0x0f, 0}, { 6, 0, 0x7f, 4}, { 0, 0, 0x00, 0} }, - /* 5 */ { { 6, 7, 0x01, 0}, { 7, 0, 0xff, 1}, { 8, 0, 0x03, 9} }, - /* 6 */ { { 8, 2, 0x3f, 0}, { 9, 0, 0x1f, 6}, { 0, 0, 0x00, 0} }, - /* 7 */ { { 9, 5, 0x07, 0}, {10, 0, 0xff, 3}, { 0, 0, 0x00, 0} }, - /* 8 */ { {11, 0, 0xff, 0}, {12, 0, 0x07, 8}, { 0, 0, 0x00, 0} }, - /* 9 */ { {12, 3, 0x1f, 0}, {13, 0, 0x3f, 5}, { 0, 0, 0x00, 0} }, - /* 10 */ { {13, 6, 0x03, 0}, {14, 0, 0xff, 2}, {15, 0, 0x01, 10} }, - /* 11 */ { {15, 1, 0x7f, 0}, {16, 0, 0x0f, 7}, { 0, 0, 0x00, 0} }, - /* 12 */ { {16, 4, 0x0f, 0}, {17, 0, 0x7f, 4}, { 0, 0, 0x00, 0} }, - /* 13 */ { {17, 7, 0x01, 0}, {18, 0, 0xff, 1}, {19, 0, 0x03, 9} }, - /* 14 */ { {19, 2, 0x3f, 0}, {20, 0, 0x1f, 6}, { 0, 0, 0x00, 0} }, - /* 15 */ { {20, 5, 0x07, 0}, {21, 0, 0xff, 3}, { 0, 0, 0x00, 0} } -}; - - -bool -sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values, - bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values) -{ - /* check frame boundary markers to avoid out-of-sync cases */ - if ((frame[0] != 0x0f)) { - return false; - } - - switch (frame[24]) { - case 0x00: - /* this is S.BUS 1 */ - break; - case 0x03: - /* S.BUS 2 SLOT0: RX battery and external voltage */ - break; - case 0x83: - /* S.BUS 2 SLOT1 */ - break; - case 0x43: - case 0xC3: - case 0x23: - case 0xA3: - case 0x63: - case 0xE3: - break; - default: - /* we expect one of the bits above, but there are some we don't know yet */ - break; - } - - unsigned chancount = (max_values > SBUS_INPUT_CHANNELS) ? - SBUS_INPUT_CHANNELS : max_values; - - /* use the decoder matrix to extract channel data */ - for (unsigned channel = 0; channel < chancount; channel++) { - unsigned value = 0; - - for (unsigned pick = 0; pick < 3; pick++) { - const struct sbus_bit_pick *decode = &sbus_decoder[channel][pick]; - - if (decode->mask != 0) { - unsigned piece = frame[1 + decode->byte]; - piece >>= decode->rshift; - piece &= decode->mask; - piece <<= decode->lshift; - - value |= piece; - } - } - - - /* convert 0-2048 values to 1000-2000 ppm encoding in a not too sloppy fashion */ - values[channel] = (uint16_t)(value * SBUS_SCALE_FACTOR +.5f) + SBUS_SCALE_OFFSET; - } - - /* decode switch channels if data fields are wide enough */ - if (max_values > 17 && chancount > 15) { - chancount = 18; - - /* channel 17 (index 16) */ - values[16] = (frame[SBUS_FLAGS_BYTE] & (1 << 0)) * 1000 + 998; - /* channel 18 (index 17) */ - values[17] = (frame[SBUS_FLAGS_BYTE] & (1 << 1)) * 1000 + 998; - } - - /* note the number of channels decoded */ - *num_values = chancount; - - /* decode and handle failsafe and frame-lost flags */ - if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */ - /* report that we failed to read anything valid off the receiver */ - *sbus_failsafe = true; - *sbus_frame_drop = true; - } - else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */ - /* set a special warning flag - * - * Attention! This flag indicates a skipped frame only, not a total link loss! Handling this - * condition as fail-safe greatly reduces the reliability and range of the radio link, - * e.g. by prematurely issuing return-to-launch!!! */ - - *sbus_failsafe = false; - *sbus_frame_drop = true; - } else { - *sbus_failsafe = false; - *sbus_frame_drop = false; - } - - return true; -} diff --git a/libraries/AP_HAL_Linux/sbus.h b/libraries/AP_HAL_Linux/sbus.h deleted file mode 100644 index 41e1fbccdd5236..00000000000000 --- a/libraries/AP_HAL_Linux/sbus.h +++ /dev/null @@ -1,6 +0,0 @@ -/* - declarations for sbus.h - */ -bool sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values, - bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values); - diff --git a/libraries/AP_HAL_Linux/system.cpp b/libraries/AP_HAL_Linux/system.cpp index faa42d49ffb0d9..0e0bb8e4f73ab2 100644 --- a/libraries/AP_HAL_Linux/system.cpp +++ b/libraries/AP_HAL_Linux/system.cpp @@ -79,43 +79,4 @@ uint64_t millis64() (state.start_time.tv_nsec*1.0e-9))); } - -uint32_t native_micros() -{ - return native_micros64() & 0xFFFFFFFF; -} - -uint32_t native_millis() -{ - return native_millis64() & 0xFFFFFFFF; -} - -/* - we define a millis16() here to avoid an issue with sitl builds in cygwin - */ -uint16_t native_millis16() -{ - return native_millis64() & 0xFFFF; -} - - -uint64_t native_micros64() -{ - struct timespec ts; - clock_gettime(CLOCK_MONOTONIC, &ts); - return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) - - (state.start_time.tv_sec + - (state.start_time.tv_nsec*1.0e-9))); -} - -uint64_t native_millis64() -{ - struct timespec ts; - clock_gettime(CLOCK_MONOTONIC, &ts); - return 1.0e3*((ts.tv_sec + (ts.tv_nsec*1.0e-9)) - - (state.start_time.tv_sec + - (state.start_time.tv_nsec*1.0e-9))); -} - - } // namespace AP_HAL diff --git a/libraries/AP_HAL_SITL/AP_HAL_SITL_Namespace.h b/libraries/AP_HAL_SITL/AP_HAL_SITL_Namespace.h index 88dfa91107b54f..5a360cbf591140 100644 --- a/libraries/AP_HAL_SITL/AP_HAL_SITL_Namespace.h +++ b/libraries/AP_HAL_SITL/AP_HAL_SITL_Namespace.h @@ -3,6 +3,7 @@ namespace HALSITL { class UARTDriver; class Scheduler; +class SITL_State_Common; class SITL_State; class Storage; class AnalogIn; diff --git a/libraries/AP_HAL_SITL/CANSocketIface.cpp b/libraries/AP_HAL_SITL/CANSocketIface.cpp index b4e9735a481457..abe9330acf1959 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.cpp +++ b/libraries/AP_HAL_SITL/CANSocketIface.cpp @@ -32,164 +32,32 @@ #include #include -#include #include #include -#include #include #include "Scheduler.h" #include #include +#include "CAN_Multicast.h" +#include "CAN_SocketCAN.h" extern const AP_HAL::HAL& hal; using namespace HALSITL; #if HAL_CANMANAGER_ENABLED -#define Debug(fmt, args...) do { AP::can().log_text(AP_CANManager::LOG_DEBUG, "CANLinuxIface", fmt, ##args); } while (0) +#define Debug(fmt, args...) do { AP::can().log_text(AP_CANManager::LOG_DEBUG, "CANSITLIface", fmt, ##args); } while (0) #else #define Debug(fmt, args...) #endif CANIface::CANSocketEventSource CANIface::evt_can_socket[HAL_NUM_CAN_IFACES]; -uint8_t CANIface::next_interface; - -static can_frame makeSocketCanFrame(const AP_HAL::CANFrame& uavcan_frame) -{ - can_frame sockcan_frame { uavcan_frame.id& AP_HAL::CANFrame::MaskExtID, uavcan_frame.dlc, { }, }; - memset(sockcan_frame.data, 0, sizeof(sockcan_frame.data)); - std::copy(uavcan_frame.data, uavcan_frame.data + uavcan_frame.dlc, sockcan_frame.data); - if (uavcan_frame.isExtended()) { - sockcan_frame.can_id |= CAN_EFF_FLAG; - } - if (uavcan_frame.isErrorFrame()) { - sockcan_frame.can_id |= CAN_ERR_FLAG; - } - if (uavcan_frame.isRemoteTransmissionRequest()) { - sockcan_frame.can_id |= CAN_RTR_FLAG; - } - return sockcan_frame; -} - -static canfd_frame makeSocketCanFDFrame(const AP_HAL::CANFrame& uavcan_frame) -{ - canfd_frame sockcan_frame { uavcan_frame.id& AP_HAL::CANFrame::MaskExtID, AP_HAL::CANFrame::dlcToDataLength(uavcan_frame.dlc), CANFD_BRS, 0, 0, { }, }; - memset(sockcan_frame.data, 0, sizeof(sockcan_frame.data)); - std::copy(uavcan_frame.data, uavcan_frame.data + AP_HAL::CANFrame::dlcToDataLength(uavcan_frame.dlc), sockcan_frame.data); - if (uavcan_frame.isExtended()) { - sockcan_frame.can_id |= CAN_EFF_FLAG; - } - if (uavcan_frame.isErrorFrame()) { - sockcan_frame.can_id |= CAN_ERR_FLAG; - } - if (uavcan_frame.isRemoteTransmissionRequest()) { - sockcan_frame.can_id |= CAN_RTR_FLAG; - } - return sockcan_frame; -} - -static AP_HAL::CANFrame makeCanFrame(const can_frame& sockcan_frame) -{ - AP_HAL::CANFrame can_frame(sockcan_frame.can_id & CAN_EFF_MASK, sockcan_frame.data, sockcan_frame.can_dlc); - if (sockcan_frame.can_id & CAN_EFF_FLAG) { - can_frame.id |= AP_HAL::CANFrame::FlagEFF; - } - if (sockcan_frame.can_id & CAN_ERR_FLAG) { - can_frame.id |= AP_HAL::CANFrame::FlagERR; - } - if (sockcan_frame.can_id & CAN_RTR_FLAG) { - can_frame.id |= AP_HAL::CANFrame::FlagRTR; - } - return can_frame; -} - -static AP_HAL::CANFrame makeCanFDFrame(const canfd_frame& sockcan_frame) -{ - AP_HAL::CANFrame can_frame(sockcan_frame.can_id & CAN_EFF_MASK, sockcan_frame.data, sockcan_frame.len, true); - if (sockcan_frame.can_id & CAN_EFF_FLAG) { - can_frame.id |= AP_HAL::CANFrame::FlagEFF; - } - if (sockcan_frame.can_id & CAN_ERR_FLAG) { - can_frame.id |= AP_HAL::CANFrame::FlagERR; - } - if (sockcan_frame.can_id & CAN_RTR_FLAG) { - can_frame.id |= AP_HAL::CANFrame::FlagRTR; - } - return can_frame; -} +uint8_t CANIface::_num_interfaces; bool CANIface::is_initialized() const { - return _initialized; -} - -int CANIface::_openSocket(const std::string& iface_name) -{ - errno = 0; - - int s = socket(PF_CAN, SOCK_RAW, CAN_RAW); - if (s < 0) { - return s; - } - - std::shared_ptr defer(&s, [](int* fd) { if (*fd >= 0) close(*fd); }); - const int ret = s; - - // Detect the iface index - auto ifr = ifreq(); - if (iface_name.length() >= IFNAMSIZ) { - errno = ENAMETOOLONG; - return -1; - } - std::strncpy(ifr.ifr_name, iface_name.c_str(), iface_name.length()); - if (ioctl(s, SIOCGIFINDEX, &ifr) < 0 || ifr.ifr_ifindex < 0) { - return -1; - } - - // Bind to the specified CAN iface - { - auto addr = sockaddr_can(); - addr.can_family = AF_CAN; - addr.can_ifindex = ifr.ifr_ifindex; - if (bind(s, reinterpret_cast(&addr), sizeof(addr)) < 0) { - return -1; - } - } - - // Configure - { - const int on = 1; - // Timestamping - if (setsockopt(s, SOL_SOCKET, SO_TIMESTAMP, &on, sizeof(on)) < 0) { - return -1; - } - // Socket loopback - if (setsockopt(s, SOL_CAN_RAW, CAN_RAW_RECV_OWN_MSGS, &on, sizeof(on)) < 0) { - return -1; - } - // Allow CANFD - if (setsockopt(s, SOL_CAN_RAW, CAN_RAW_FD_FRAMES, &on, sizeof(on)) < 0) { - return -1; - } - // Non-blocking - if (fcntl(s, F_SETFL, O_NONBLOCK) < 0) { - return -1; - } - } - - // Validate the resulting socket - { - int socket_error = 0; - socklen_t errlen = sizeof(socket_error); - getsockopt(s, SOL_SOCKET, SO_ERROR, reinterpret_cast(&socket_error), &errlen); - if (socket_error != 0) { - errno = socket_error; - return -1; - } - } - s = -1; - return ret; + return transport != nullptr; } int16_t CANIface::send(const AP_HAL::CANFrame& frame, const uint64_t tx_deadline, @@ -251,180 +119,60 @@ bool CANIface::_hasReadyRx() void CANIface::_poll(bool read, bool write) { if (read) { - stats.num_poll_rx_events++; _pollRead(); // Read poll must be executed first because it may decrement _frames_in_socket_tx_queue } if (write) { - stats.num_poll_tx_events++; _pollWrite(); } } -bool CANIface::configureFilters(const CanFilterConfig* const filter_configs, - const uint16_t num_configs) -{ -#if 0 - if (filter_configs == nullptr || mode_ != FilteredMode) { - return false; - } - _hw_filters_container.clear(); - _hw_filters_container.resize(num_configs); - - for (unsigned i = 0; i < num_configs; i++) { - const CanFilterConfig& fc = filter_configs[i]; - _hw_filters_container[i].can_id = fc.id & AP_HAL::CANFrame::MaskExtID; - _hw_filters_container[i].can_mask = fc.mask & AP_HAL::CANFrame::MaskExtID; - if (fc.id & AP_HAL::CANFrame::FlagEFF) { - _hw_filters_container[i].can_id |= CAN_EFF_FLAG; - } - if (fc.id & AP_HAL::CANFrame::FlagRTR) { - _hw_filters_container[i].can_id |= CAN_RTR_FLAG; - } - if (fc.mask & AP_HAL::CANFrame::FlagEFF) { - _hw_filters_container[i].can_mask |= CAN_EFF_FLAG; - } - if (fc.mask & AP_HAL::CANFrame::FlagRTR) { - _hw_filters_container[i].can_mask |= CAN_RTR_FLAG; - } - } -#endif - return true; -} - -/** - * SocketCAN emulates the CAN filters in software, so the number of filters is virtually unlimited. - * This method returns a constant value. - */ -static constexpr unsigned NumFilters = CAN_FILTER_NUMBER; -uint16_t CANIface::getNumFilters() const { return NumFilters; } - uint32_t CANIface::getErrorCount() const { - uint32_t ec = 0; - for (auto& kv : _errors) { ec += kv.second; } - return ec; + return 0; } void CANIface::_pollWrite() { + if (transport == nullptr) { + return; + } while (_hasReadyTx()) { WITH_SEMAPHORE(sem); const CanTxItem tx = _tx_queue.top(); - uint64_t curr_time = AP_HAL::native_micros64(); + 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); - const int res = _write(tx.frame); - if (res == 1) { // Transmitted successfully - _incrementNumFramesInSocketTxQueue(); - if (tx.loopback) { - _pending_loopback_ids.insert(tx.frame.id); - } + bool ok = transport->send(tx.frame); + if (ok) { stats.tx_success++; - } else if (res == 0) { // Not transmitted, nor is it an error - stats.tx_full++; - break; // Leaving the loop, the frame remains enqueued for the next retry - } else { // Transmission error - stats.tx_rejected++; + stats.last_transmit_us = curr_time; + } else { + break; } } else { - // hal.console->printf("TDEAD: %lu CURRT: %lu DEL: %lu\n", tx.deadline, curr_time, curr_time-tx.deadline); stats.tx_timedout++; } - // Removing the frame from the queue even if transmission failed + // Removing the frame from the queue (void)_tx_queue.pop(); } } bool CANIface::_pollRead() { - uint8_t iterations_count = 0; - while (iterations_count < CAN_MAX_POLL_ITERATIONS_COUNT) - { - CanRxItem rx; - rx.timestamp_us = AP_HAL::native_micros64(); // Monotonic timestamp is not required to be precise (unlike UTC) - bool loopback = false; - int res; - res = _read(rx.frame, rx.timestamp_us, loopback); - if (res == 1) { - bool accept = true; - if (loopback) { // We receive loopback for all CAN frames - _confirmSentFrame(); - rx.flags |= Loopback; - accept = _wasInPendingLoopbackSet(rx.frame); - stats.tx_confirmed++; - } - if (accept) { - WITH_SEMAPHORE(sem); - add_to_rx_queue(rx); - stats.rx_received++; - return true; - } - } else if (res == 0) { - break; - } else { - stats.rx_errors++; - break; - } - } - return false; -} - -int CANIface::_write(const AP_HAL::CANFrame& frame) const -{ - if (_fd < 0) { - return -1; - } - errno = 0; - int res = 0; - - if (frame.isCanFDFrame()) { - const canfd_frame sockcan_frame = makeSocketCanFDFrame(frame); - res = write(_fd, &sockcan_frame, sizeof(sockcan_frame)); - if (res > 0 && res != sizeof(sockcan_frame)) { - return -1; - } - } else { - const can_frame sockcan_frame = makeSocketCanFrame(frame); - res = write(_fd, &sockcan_frame, sizeof(sockcan_frame)); - if (res > 0 && res != sizeof(sockcan_frame)) { - return -1; - } - } - if (res <= 0) { - if (errno == ENOBUFS || errno == EAGAIN) { // Writing is not possible atm, not an error - return 0; - } - return res; - } - return 1; -} - - -int CANIface::_read(AP_HAL::CANFrame& frame, uint64_t& timestamp_us, bool& loopback) const -{ - if (_fd < 0) { - return -1; - } - union { - can_frame frame; - canfd_frame frame_fd; - } frames; - - const int res = read(_fd, &frames, sizeof(frames)); - if (res <= 0) { - return (res < 0 && errno == EWOULDBLOCK) ? 0 : res; + if (transport == nullptr) { + return false; } - if (res == sizeof(can_frame)) { - frame = makeCanFrame(frames.frame); - } else { - frame = makeCanFDFrame(frames.frame_fd); + CanRxItem rx {}; + bool ok = transport->receive(rx.frame); + if (!ok) { + return false; } - /* - * Timestamp - */ - timestamp_us = AP_HAL::native_micros64(); - return 1; + rx.timestamp_us = AP_HAL::micros64(); + WITH_SEMAPHORE(sem); + add_to_rx_queue(rx); + stats.rx_received++; + return true; } // Might block forever, only to be used for testing @@ -432,9 +180,8 @@ void CANIface::flush_tx() { WITH_SEMAPHORE(sem); do { - _updateDownStatusFromPollResult(_pollfd); _poll(true, true); - } while(!_tx_queue.empty() && !_down); + } while(!_tx_queue.empty()); } void CANIface::clear_rx() @@ -445,11 +192,6 @@ void CANIface::clear_rx() std::swap( _rx_queue, empty ); } -void CANIface::_incrementNumFramesInSocketTxQueue() -{ - _frames_in_socket_tx_queue++; -} - void CANIface::_confirmSentFrame() { if (_frames_in_socket_tx_queue > 0) { @@ -457,88 +199,51 @@ void CANIface::_confirmSentFrame() } } -bool CANIface::_wasInPendingLoopbackSet(const AP_HAL::CANFrame& frame) +bool CANIface::init(const uint32_t bitrate, const uint32_t fdbitrate, const OperatingMode mode) { - if (_pending_loopback_ids.count(frame.id) > 0) { - _pending_loopback_ids.erase(frame.id); - return true; - } - return false; + return init(bitrate, mode); } -bool CANIface::_checkHWFilters(const can_frame& frame) const +bool CANIface::init(const uint32_t bitrate, const OperatingMode mode) { - if (!_hw_filters_container.empty()) { - for (auto& f : _hw_filters_container) { - if (((frame.can_id & f.can_mask) ^ f.can_id) == 0) { - return true; - } - } + const auto *_sitl = AP::sitl(); + if (_sitl == nullptr) { return false; - } else { - return true; } -} - -bool CANIface::_checkHWFilters(const canfd_frame& frame) const -{ - if (!_hw_filters_container.empty()) { - for (auto& f : _hw_filters_container) { - if (((frame.can_id & f.can_mask) ^ f.can_id) == 0) { - return true; - } - } + if (_self_index >= HAL_NUM_CAN_IFACES) { return false; - } else { - return true; } -} - -void CANIface::_updateDownStatusFromPollResult(const pollfd& pfd) -{ - if (!_down && (pfd.revents & POLLERR)) { - int error = 0; - socklen_t errlen = sizeof(error); - getsockopt(pfd.fd, SOL_SOCKET, SO_ERROR, reinterpret_cast(&error), &errlen); - - _down= error == ENETDOWN || error == ENODEV; - stats.num_downs++; - Debug("Iface %d is dead; error %d", _fd, error); + const SITL::SIM::CANTransport can_type = _sitl->can_transport[_self_index]; + switch (can_type) { + case SITL::SIM::CANTransport::MulticastUDP: + transport = new CAN_Multicast(); + break; + case SITL::SIM::CANTransport::SocketCAN: +#if HAL_CAN_WITH_SOCKETCAN + transport = new CAN_SocketCAN(); +#endif + break; } -} - -bool CANIface::init(const uint32_t bitrate, const uint32_t fdbitrate, const OperatingMode mode) -{ - // we are using vcan, so bitrate is irrelevant - return init(bitrate, mode); -} - -bool CANIface::init(const uint32_t bitrate, const OperatingMode mode) -{ - char iface_name[16]; - sprintf(iface_name, "vcan%u", _self_index); - bitrate_ = bitrate; - mode_ = mode; - if (_initialized) { - return _initialized; + if (transport == nullptr) { + return false; } - - // TODO: Add possibility change bitrate - _fd = _openSocket(iface_name); - if (_fd > 0) { - _bitrate = bitrate; - _initialized = true; - } else { - _initialized = false; + if (!transport->init(_self_index)) { + delete transport; + transport = nullptr; + return false; } - return _initialized; + return true; } bool CANIface::select(bool &read_select, bool &write_select, - const AP_HAL::CANFrame* const pending_tx, uint64_t blocking_deadline) + const AP_HAL::CANFrame* const pending_tx, uint64_t blocking_deadline) { + if (transport == nullptr) { + return false; + } // Detecting whether we need to block at all bool need_block = !write_select; // Write queue is infinite + // call poll here to flush some tx _poll(true, true); @@ -547,39 +252,22 @@ bool CANIface::select(bool &read_select, bool &write_select, } if (need_block) { - if (_down) { - return false; - } else { - _pollfd.fd = _fd; - _pollfd.events |= POLLIN; - stats.num_rx_poll_req++; - if (_hasReadyTx() && write_select) { - _pollfd.events |= POLLOUT; - stats.num_tx_poll_req++; - } - } - if (_evt_handle != nullptr && blocking_deadline > AP_HAL::native_micros64()) { - _evt_handle->wait(blocking_deadline - AP_HAL::native_micros64()); - } + _pollfd.fd = transport->get_read_fd(); + _pollfd.events |= POLLIN; + } + if (_evt_handle != nullptr && blocking_deadline > AP_HAL::micros64()) { + _evt_handle->wait(blocking_deadline - AP_HAL::micros64()); } // Writing the output masks - if (!_down) { - write_select = true; // Always ready to write if not down - } else { - write_select = false; - } - if (_hasReadyRx()) { - read_select = true; // Readability depends only on RX buf, even if down - } else { - read_select = false; - } + write_select = true; + read_select = _hasReadyRx(); - // Return value is irrelevant as long as it's non-negative return true; } -bool CANIface::set_event_handle(AP_HAL::EventHandle* handle) { +bool CANIface::set_event_handle(AP_HAL::EventHandle* handle) +{ _evt_handle = handle; evt_can_socket[_self_index]._ifaces[_self_index] = this; _evt_handle->set_source(&evt_can_socket[_self_index]); @@ -601,37 +289,39 @@ bool CANIface::CANSocketEventSource::wait(uint16_t duration_us, AP_HAL::EventHan if (_ifaces[i] == nullptr) { continue; } - if (_ifaces[i]->_down) { - continue; - } pollfds[num_pollfds] = _ifaces[i]->_pollfd; pollfd_iface_map[num_pollfds] = i; num_pollfds++; - _ifaces[i]->stats.num_poll_waits++; } if (num_pollfds == 0) { return true; } - // Timeout conversion - auto ts = timespec(); - ts.tv_sec = 0; - ts.tv_nsec = duration_us * 1000UL; + const uint32_t start_us = AP_HAL::micros(); + do { + uint16_t wait_us = MIN(100, duration_us); - // Blocking here - const int res = ppoll(pollfds, num_pollfds, &ts, nullptr); + // check FD for input + const int res = poll(pollfds, num_pollfds, wait_us/1000U); + + if (res < 0) { + return false; + } + if (res > 0) { + break; + } + + // ensure simulator runs + hal.scheduler->delay_microseconds(wait_us); + } while (AP_HAL::micros() - start_us < duration_us); - if (res < 0) { - return false; - } // Handling poll output for (unsigned i = 0; i < num_pollfds; i++) { if (_ifaces[pollfd_iface_map[i]] == nullptr) { continue; } - _ifaces[pollfd_iface_map[i]]->_updateDownStatusFromPollResult(pollfds[i]); const bool poll_read = pollfds[i].revents & POLLIN; const bool poll_write = pollfds[i].revents & POLLOUT; @@ -644,32 +334,16 @@ void CANIface::get_stats(ExpandingString &str) { str.printf("tx_requests: %u\n" "tx_rejected: %u\n" - "tx_full: %u\n" - "tx_confirmed: %u\n" "tx_success: %u\n" "tx_timedout: %u\n" "rx_received: %u\n" - "rx_errors: %u\n" - "num_downs: %u\n" - "num_rx_poll_req: %u\n" - "num_tx_poll_req: %u\n" - "num_poll_waits: %u\n" - "num_poll_tx_events: %u\n" - "num_poll_rx_events: %u\n", + "rx_errors: %u\n", stats.tx_requests, stats.tx_rejected, - stats.tx_full, - stats.tx_confirmed, stats.tx_success, stats.tx_timedout, stats.rx_received, - stats.rx_errors, - stats.num_downs, - stats.num_rx_poll_req, - stats.num_tx_poll_req, - stats.num_poll_waits, - stats.num_poll_tx_events, - stats.num_poll_rx_events); + stats.rx_errors); } #endif diff --git a/libraries/AP_HAL_SITL/CANSocketIface.h b/libraries/AP_HAL_SITL/CANSocketIface.h index f65905938f3336..c6f012a38d19da 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.h +++ b/libraries/AP_HAL_SITL/CANSocketIface.h @@ -13,17 +13,6 @@ along with this program. If not, see . */ -/* - * Many thanks to members of the UAVCAN project: - * Pavel Kirienko - * Ilia Sheremet - * - * license info can be found in the uavcan submodule located: - * modules/uavcan/LICENSE - * modules/uavcan/libuavcan_drivers/linux/include/uavcan_linux/socketcan.hpp - */ - - #pragma once #include "AP_HAL_SITL.h" @@ -32,37 +21,26 @@ #include -#include - #include #include #include #include #include #include +#include "CAN_Transport.h" namespace HALSITL { -enum class SocketCanError -{ - SocketReadFailure, - SocketWriteFailure, - TxTimeout -}; - -#define CAN_MAX_POLL_ITERATIONS_COUNT 100 -#define CAN_MAX_INIT_TRIES_COUNT 100 -#define CAN_FILTER_NUMBER 8 - class CANIface: public AP_HAL::CANIface { public: CANIface(int index) : _self_index(index) , _frames_in_socket_tx_queue(0) - { } - - static uint8_t next_interface; - CANIface() : CANIface(next_interface++) {} + { + _num_interfaces++; + } + CANIface() : CANIface(_num_interfaces) {} + static uint8_t _num_interfaces; ~CANIface() { } @@ -70,6 +48,11 @@ class CANIface: public AP_HAL::CANIface { bool init(const uint32_t bitrate, const uint32_t fdbitrate, const OperatingMode mode) override; bool init(const uint32_t bitrate, const OperatingMode mode) override; + // number of enabled interfaces + static uint8_t num_interfaces(void) { + return _num_interfaces; + } + // Put frame into Tx FIFO returns negative on error, 0 on buffer full, // 1 on successfully pushing a frame into FIFO int16_t send(const AP_HAL::CANFrame& frame, uint64_t tx_deadline, @@ -80,10 +63,6 @@ class CANIface: public AP_HAL::CANIface { int16_t receive(AP_HAL::CANFrame& out_frame, uint64_t& out_timestamp_us, CanIOFlags& out_flags) override; - // Set Filters to ignore frames not to be handled by us - bool configureFilters(const CanFilterConfig* filter_configs, - uint16_t num_configs) override; - // Always return false, there's no busoff condition in virtual CAN bool is_busoff() const override { @@ -94,9 +73,6 @@ class CANIface: public AP_HAL::CANIface { void clear_rx() override; - // Get number of Filter configurations - uint16_t getNumFilters() const override; - // Get total number of Errors discovered uint32_t getErrorCount() const override; @@ -140,19 +116,8 @@ class CANIface: public AP_HAL::CANIface { bool _pollRead(); - int _write(const AP_HAL::CANFrame& frame) const; - - int _read(AP_HAL::CANFrame& frame, uint64_t& ts_usec, bool& loopback) const; - - void _incrementNumFramesInSocketTxQueue(); - void _confirmSentFrame(); - bool _wasInPendingLoopbackSet(const AP_HAL::CANFrame& frame); - - bool _checkHWFilters(const can_frame& frame) const; - bool _checkHWFilters(const canfd_frame& frame) const; - bool _hasReadyTx(); bool _hasReadyRx(); @@ -163,12 +128,7 @@ class CANIface: public AP_HAL::CANIface { void _updateDownStatusFromPollResult(const pollfd& pfd); - uint32_t _bitrate; - - bool _down; - bool _initialized; - - int _fd; + CAN_Transport *transport; const uint8_t _self_index; @@ -178,29 +138,16 @@ class CANIface: public AP_HAL::CANIface { static CANSocketEventSource evt_can_socket[HAL_NUM_CAN_IFACES]; pollfd _pollfd; - std::map _errors; std::priority_queue _tx_queue; std::queue _rx_queue; - std::unordered_multiset _pending_loopback_ids; - std::vector _hw_filters_container; /* - additional statistics + bus statistics */ - struct bus_stats : public AP_HAL::CANIface::bus_stats_t { - uint32_t tx_full; - uint32_t tx_confirmed; - uint32_t num_downs; - uint32_t num_rx_poll_req; - uint32_t num_tx_poll_req; - uint32_t num_poll_waits; - uint32_t num_poll_tx_events; - uint32_t num_poll_rx_events; - } stats; + AP_HAL::CANIface::bus_stats_t stats; HAL_Semaphore sem; -protected: bool add_to_rx_queue(const CanRxItem &rx_item) override { _rx_queue.push(rx_item); return true; diff --git a/libraries/AP_HAL_SITL/CAN_Multicast.cpp b/libraries/AP_HAL_SITL/CAN_Multicast.cpp new file mode 100644 index 00000000000000..b83642f7ef73c0 --- /dev/null +++ b/libraries/AP_HAL_SITL/CAN_Multicast.cpp @@ -0,0 +1,178 @@ +/* + multicast UDP transport for SITL CAN + */ +#include "CAN_Multicast.h" + +#if HAL_NUM_CAN_IFACES + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#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]; +}; + +/* + initialise multicast transport + */ +bool CAN_Multicast::init(uint8_t instance) +{ + // setup incoming multicast socket + char address[] = MCAST_ADDRESS_BASE; + struct sockaddr_in sockaddr {}; + struct ip_mreq mreq {}; + int one = 1; + int ret; + +#ifdef HAVE_SOCK_SIN_LEN + sockaddr.sin_len = sizeof(sockaddr); +#endif + address[strlen(address)-1] = '0' + instance; + + sockaddr.sin_port = htons(MCAST_PORT); + sockaddr.sin_family = AF_INET; + sockaddr.sin_addr.s_addr = inet_addr(address); + + fd_in = socket(AF_INET, SOCK_DGRAM, 0); + if (fd_in == -1) { + goto fail; + } + ret = fcntl(fd_in, F_SETFD, FD_CLOEXEC); + if (ret == -1) { + goto fail; + } + if (setsockopt(fd_in, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) == -1) { + goto fail; + } + + // close on exec, to allow reboot + fcntl(fd_in, F_SETFD, FD_CLOEXEC); + +#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD) + /* + on cygwin you need to bind to INADDR_ANY then use the multicast + IP_ADD_MEMBERSHIP to get on the right address + */ + sockaddr.sin_addr.s_addr = htonl(INADDR_ANY); +#endif + + ret = bind(fd_in, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); + if (ret == -1) { + goto fail; + } + + mreq.imr_multiaddr.s_addr = inet_addr(address); + mreq.imr_interface.s_addr = htonl(INADDR_ANY); + + ret = setsockopt(fd_in, IPPROTO_IP, IP_ADD_MEMBERSHIP, &mreq, sizeof(mreq)); + if (ret == -1) { + goto fail; + } + + // setup outgoing socket + fd_out = socket(AF_INET, SOCK_DGRAM, 0); + if (fd_out == -1) { + goto fail; + } + ret = fcntl(fd_out, F_SETFD, FD_CLOEXEC); + if (ret == -1) { + goto fail; + } + + ret = connect(fd_out, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); + if (ret == -1) { + goto fail; + } + + return true; + +fail: + if (fd_in != -1) { + (void)close(fd_in); + fd_in = -1; + } + if (fd_out != -1) { + (void)close(fd_out); + fd_out = -1; + } + return false; +} + +/* + send a CAN frame + */ +bool CAN_Multicast::send(const AP_HAL::CANFrame &frame) +{ + struct mcast_pkt pkt {}; + pkt.magic = MCAST_MAGIC; + pkt.flags = 0; +#if HAL_CANFD_SUPPORTED + if (frame.canfd) { + 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); + pkt.crc = crc16_ccitt((uint8_t*)&pkt.flags, data_length+6, 0xFFFFU); + + return ::send(fd_out, (void*)&pkt, data_length+10, 0) == data_length+10; +} + +/* + receive a CAN frame + */ +bool CAN_Multicast::receive(AP_HAL::CANFrame &frame) +{ + struct mcast_pkt pkt; + struct sockaddr_in src_addr; + socklen_t src_len = sizeof(src_addr); + ssize_t ret = ::recvfrom(fd_in, (void*)&pkt, sizeof(pkt), MSG_DONTWAIT, (struct sockaddr *)&src_addr, &src_len); + if (ret < 10) { + return false; + } + if (pkt.magic != MCAST_MAGIC) { + return false; + } + if (pkt.crc != crc16_ccitt((uint8_t*)&pkt.flags, ret-4, 0xFFFFU)) { + return false; + } + + // ensure it isn't a packet we sent + struct sockaddr_in send_addr; + socklen_t send_len = sizeof(send_addr); + if (getsockname(fd_out, (struct sockaddr *)&send_addr, &send_len) != 0) { + return false; + } + if (src_addr.sin_port == send_addr.sin_port && + src_addr.sin_family == send_addr.sin_family && + src_addr.sin_addr.s_addr == send_addr.sin_addr.s_addr) { + return false; + } + + // run constructor to initialise + new(&frame) AP_HAL::CANFrame(pkt.message_id, pkt.data, ret-10, (pkt.flags & MCAST_FLAG_CANFD) != 0); + + return true; +} + +#endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_HAL_SITL/CAN_Multicast.h b/libraries/AP_HAL_SITL/CAN_Multicast.h new file mode 100644 index 00000000000000..be8144cb65ec9f --- /dev/null +++ b/libraries/AP_HAL_SITL/CAN_Multicast.h @@ -0,0 +1,24 @@ +/* + multicast UDP transport for SITL CAN + */ +#pragma once + +#include "CAN_Transport.h" + +#if HAL_NUM_CAN_IFACES + +class CAN_Multicast : public CAN_Transport { +public: + bool init(uint8_t instance) override; + bool send(const AP_HAL::CANFrame &frame) override; + bool receive(AP_HAL::CANFrame &frame) override; + int get_read_fd(void) const override { + return fd_in; + } + +private: + int fd_in = -1; + int fd_out = -1; +}; + +#endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_HAL_SITL/CAN_SocketCAN.cpp b/libraries/AP_HAL_SITL/CAN_SocketCAN.cpp new file mode 100644 index 00000000000000..09df128ba374be --- /dev/null +++ b/libraries/AP_HAL_SITL/CAN_SocketCAN.cpp @@ -0,0 +1,91 @@ +/* + socketcan transport for SITL CAN + */ +#include "CAN_SocketCAN.h" + +#if HAL_NUM_CAN_IFACES && HAL_CAN_WITH_SOCKETCAN + +#include +#include +#include +#include +#include +#include +#include +#include +#include "CAN_SocketCAN.h" + +/* + initialise socketcan transport + */ +bool CAN_SocketCAN::init(uint8_t instance) +{ + struct sockaddr_can addr {}; + struct ifreq ifr {}; + int ret; + + fd = socket(PF_CAN, SOCK_RAW | SOCK_NONBLOCK, CAN_RAW); + if (fd < 0) { + goto fail; + } + + snprintf(ifr.ifr_name, sizeof(ifr.ifr_name), "vcan%u", instance); + ret = ioctl(fd, SIOCGIFINDEX, &ifr); + if (ret == -1) { + goto fail; + } + + addr.can_family = AF_CAN; + addr.can_ifindex = ifr.ifr_ifindex; + + ret = bind(fd, (struct sockaddr*)&addr, sizeof(addr)); + if (ret == -1) { + goto fail; + } + + return true; + +fail: + if (fd != -1) { + close(fd); + fd = -1; + } + return false; +} + +/* + send a CAN frame + */ +bool CAN_SocketCAN::send(const AP_HAL::CANFrame &frame) +{ + if (frame.canfd) { + // not supported on socketcan + return false; + } + struct can_frame transmit_frame {}; + transmit_frame.can_id = frame.id; + transmit_frame.can_dlc = frame.dlc; + + const uint8_t data_length = AP_HAL::CANFrame::dlcToDataLength(frame.dlc); + memcpy(transmit_frame.data, frame.data, data_length); + + return ::write(fd, &transmit_frame, sizeof(transmit_frame)) == sizeof(transmit_frame); +} + +/* + receive a CAN frame + */ +bool CAN_SocketCAN::receive(AP_HAL::CANFrame &frame) +{ + struct can_frame receive_frame; + const ssize_t ret = ::read(fd, &receive_frame, sizeof(receive_frame)); + if (ret != sizeof(receive_frame)) { + return false; + } + + // run constructor to initialise + new(&frame) AP_HAL::CANFrame(receive_frame.can_id, receive_frame.data, receive_frame.can_dlc, false); + return true; +} + +#endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_HAL_SITL/CAN_SocketCAN.h b/libraries/AP_HAL_SITL/CAN_SocketCAN.h new file mode 100644 index 00000000000000..d82a09a5146397 --- /dev/null +++ b/libraries/AP_HAL_SITL/CAN_SocketCAN.h @@ -0,0 +1,23 @@ +/* + socketcan transport for SITL CAN + */ +#pragma once + +#include "CAN_Transport.h" + +#if HAL_NUM_CAN_IFACES && HAL_CAN_WITH_SOCKETCAN + +class CAN_SocketCAN : public CAN_Transport { +public: + bool init(uint8_t instance) override; + bool send(const AP_HAL::CANFrame &frame) override; + bool receive(AP_HAL::CANFrame &frame) override; + int get_read_fd(void) const override { + return fd; + } + +private: + int fd = -1; +}; + +#endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_HAL_SITL/CAN_Transport.h b/libraries/AP_HAL_SITL/CAN_Transport.h new file mode 100644 index 00000000000000..52307c4c95799f --- /dev/null +++ b/libraries/AP_HAL_SITL/CAN_Transport.h @@ -0,0 +1,21 @@ +/* + parent class for CAN transports in ArduPilot SITL + */ +#pragma once + +#include "AP_HAL_SITL.h" + +#if HAL_NUM_CAN_IFACES + +#include + +class CAN_Transport { +public: + virtual ~CAN_Transport() {} + virtual bool init(uint8_t instance) = 0; + virtual bool send(const AP_HAL::CANFrame &frame) = 0; + virtual bool receive(AP_HAL::CANFrame &frame) = 0; + virtual int get_read_fd(void) const = 0; +}; + +#endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_HAL_SITL/GPIO.cpp b/libraries/AP_HAL_SITL/GPIO.cpp index 9ad575b9082cf7..3fe8db8cc6a102 100644 --- a/libraries/AP_HAL_SITL/GPIO.cpp +++ b/libraries/AP_HAL_SITL/GPIO.cpp @@ -1,7 +1,7 @@ #include "GPIO.h" -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL using namespace HALSITL; diff --git a/libraries/AP_HAL_SITL/GPIO.h b/libraries/AP_HAL_SITL/GPIO.h index fdf571b5265920..1a1fd92823d5d4 100644 --- a/libraries/AP_HAL_SITL/GPIO.h +++ b/libraries/AP_HAL_SITL/GPIO.h @@ -1,7 +1,7 @@ #pragma once #include "AP_HAL_SITL.h" -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL class HALSITL::GPIO : public AP_HAL::GPIO { public: diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index 123a4de11e3ec3..8a7537ab9730f7 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -29,6 +29,7 @@ #include #include #include +#include using namespace HALSITL; @@ -37,15 +38,13 @@ HAL_SITL& hal_sitl = (HAL_SITL&)AP_HAL::get_HAL(); static Storage sitlStorage; static SITL_State sitlState; static Scheduler sitlScheduler(&sitlState); -#if !defined(HAL_BUILD_AP_PERIPH) -static RCInput sitlRCInput(&sitlState); -static RCOutput sitlRCOutput(&sitlState); -static GPIO sitlGPIO(&sitlState); +#if AP_RCPROTOCOL_ENABLED +static RCInput sitlRCInput(&sitlState); #else static Empty::RCInput sitlRCInput; -static Empty::RCOutput sitlRCOutput; -static Empty::GPIO sitlGPIO; #endif +static RCOutput sitlRCOutput(&sitlState); +static GPIO sitlGPIO(&sitlState); static AnalogIn sitlAnalogIn(&sitlState); static DSP dspDriver; @@ -65,11 +64,11 @@ static UARTDriver sitlUart7Driver(7, &sitlState); static UARTDriver sitlUart8Driver(8, &sitlState); static UARTDriver sitlUart9Driver(9, &sitlState); +static I2CDeviceManager i2c_mgr_instance; + #if defined(HAL_BUILD_AP_PERIPH) -static Empty::I2CDeviceManager i2c_mgr_instance; static Empty::SPIDeviceManager spi_mgr_instance; #else -static I2CDeviceManager i2c_mgr_instance; static SPIDeviceManager spi_mgr_instance; #endif static Util utilInstance(&sitlState); diff --git a/libraries/AP_HAL_SITL/I2CDevice.cpp b/libraries/AP_HAL_SITL/I2CDevice.cpp index e4f789ffe0aa8c..7b7b2d5914fb85 100644 --- a/libraries/AP_HAL_SITL/I2CDevice.cpp +++ b/libraries/AP_HAL_SITL/I2CDevice.cpp @@ -17,7 +17,7 @@ #include "I2CDevice.h" #include -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include @@ -217,4 +217,4 @@ bool I2CDevice::adjust_periodic_callback(Device::PeriodicHandle h, uint32_t peri return false; } -#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_SITL/I2CDevice.h b/libraries/AP_HAL_SITL/I2CDevice.h index 2a414bcf6986aa..828fd3efd48a85 100644 --- a/libraries/AP_HAL_SITL/I2CDevice.h +++ b/libraries/AP_HAL_SITL/I2CDevice.h @@ -19,7 +19,7 @@ #include #include -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include #include @@ -128,4 +128,4 @@ class HALSITL::I2CDeviceManager : public AP_HAL::I2CDeviceManager { #define NUM_SITL_I2C_BUSES 4 static I2CBus buses[]; }; -#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#endif //#if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_SITL/RCInput.cpp b/libraries/AP_HAL_SITL/RCInput.cpp index 62242958f158a2..98e28a6db011ff 100644 --- a/libraries/AP_HAL_SITL/RCInput.cpp +++ b/libraries/AP_HAL_SITL/RCInput.cpp @@ -1,5 +1,8 @@ #include -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#include + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_RCPROTOCOL_ENABLED + #include "RCInput.h" #include diff --git a/libraries/AP_HAL_SITL/RCInput.h b/libraries/AP_HAL_SITL/RCInput.h index e991a40132c71a..b327c87d4e691f 100644 --- a/libraries/AP_HAL_SITL/RCInput.h +++ b/libraries/AP_HAL_SITL/RCInput.h @@ -2,7 +2,7 @@ #pragma once #include -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #define SITL_RC_INPUT_CHANNELS 16 #include "AP_HAL_SITL.h" diff --git a/libraries/AP_HAL_SITL/RCOutput.cpp b/libraries/AP_HAL_SITL/RCOutput.cpp index b8dd8634d68faa..3a39d31c2b4b40 100644 --- a/libraries/AP_HAL_SITL/RCOutput.cpp +++ b/libraries/AP_HAL_SITL/RCOutput.cpp @@ -1,7 +1,5 @@ #include -#if !defined(HAL_BUILD_AP_PERIPH) - #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include @@ -52,7 +50,8 @@ void RCOutput::disable_ch(uint8_t ch) void RCOutput::write(uint8_t ch, uint16_t period_us) { if (safety_state == AP_HAL::Util::SAFETY_DISARMED) { - const uint32_t safety_mask = AP_BoardConfig::get_singleton()->get_safety_mask(); + const auto *board_config = AP_BoardConfig::get_singleton(); + const uint32_t safety_mask = board_config != nullptr? board_config->get_safety_mask() : 0; if (!(safety_mask & (1U< -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include "AP_HAL_SITL.h" #include diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp index 3291a3fc30b05e..4d2cb796a01162 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp @@ -19,6 +19,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -35,6 +36,7 @@ using namespace HALSITL; CMDLINE_SERIAL7, CMDLINE_SERIAL8, CMDLINE_SERIAL9, + CMDLINE_DEFAULTS, }; void SITL_State::init(int argc, char * const argv[]) { @@ -53,6 +55,7 @@ void SITL_State::init(int argc, char * const argv[]) { {"serial7", true, 0, CMDLINE_SERIAL7}, {"serial8", true, 0, CMDLINE_SERIAL8}, {"serial9", true, 0, CMDLINE_SERIAL9}, + {"defaults", true, 0, CMDLINE_DEFAULTS}, {0, false, 0, 0} }; @@ -85,11 +88,15 @@ void SITL_State::init(int argc, char * const argv[]) { _uart_path[mapping[opt - CMDLINE_SERIAL0]] = gopt.optarg; break; } + case CMDLINE_DEFAULTS: + defaults_path = strdup(gopt.optarg); + break; default: printf("Options:\n" "\t--help|-h display this help information\n" "\t--instance|-I N set instance of SITL Periph\n" "\t--maintenance|-M run in maintenance mode\n" + "\t--defaults path set param defaults file\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" @@ -106,18 +113,193 @@ void SITL_State::init(int argc, char * const argv[]) { } printf("Running Instance: %d\n", _instance); + + sitl_model = new SimMCast(""); + + _sitl = AP::sitl(); + + _sitl->i2c_sim.init(); + sitl_model->set_i2c(&_sitl->i2c_sim); +} + +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); + sim_update(); + update_voltage_current(input, 0); + usleep(100); + } +} + +/* + open multicast input from main simulator + */ +void SimMCast::multicast_open(void) +{ + struct sockaddr_in sockaddr {}; + int ret; + +#ifdef HAVE_SOCK_SIN_LEN + sockaddr.sin_len = sizeof(sockaddr); +#endif + sockaddr.sin_port = htons(SITL_MCAST_PORT); + sockaddr.sin_family = AF_INET; + sockaddr.sin_addr.s_addr = inet_addr(SITL_MCAST_IP); + + mc_fd = socket(AF_INET, SOCK_DGRAM, 0); + if (mc_fd == -1) { + fprintf(stderr, "socket failed - %s\n", strerror(errno)); + exit(1); + } + ret = fcntl(mc_fd, F_SETFD, FD_CLOEXEC); + if (ret == -1) { + fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno)); + exit(1); + } + int one = 1; + if (setsockopt(mc_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) == -1) { + fprintf(stderr, "setsockopt failed: %s\n", strerror(errno)); + exit(1); + } + +#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD) + /* + on cygwin you need to bind to INADDR_ANY then use the multicast + IP_ADD_MEMBERSHIP to get on the right address + */ + sockaddr.sin_addr.s_addr = htonl(INADDR_ANY); +#endif + + ret = bind(mc_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); + if (ret == -1) { + fprintf(stderr, "multicast bind failed on port %u - %s\n", + (unsigned)ntohs(sockaddr.sin_port), + strerror(errno)); + exit(1); + } + + struct ip_mreq mreq {}; + mreq.imr_multiaddr.s_addr = inet_addr(SITL_MCAST_IP); + mreq.imr_interface.s_addr = htonl(INADDR_ANY); + + ret = setsockopt(mc_fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, &mreq, sizeof(mreq)); + if (ret == -1) { + fprintf(stderr, "multicast membership add failed on port %u - %s\n", + (unsigned)ntohs(sockaddr.sin_port), + strerror(errno)); + exit(1); + } + ::printf("multicast receiver initialised\n"); +} + +/* + open UDP socket back to master for servo output + */ +void SimMCast::servo_fd_open(void) +{ + servo_fd = socket(AF_INET, SOCK_DGRAM, 0); + if (servo_fd == -1) { + fprintf(stderr, "socket failed - %s\n", strerror(errno)); + exit(1); + } + int ret = fcntl(servo_fd, F_SETFD, FD_CLOEXEC); + if (ret == -1) { + fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno)); + exit(1); + } + int one = 1; + if (setsockopt(servo_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) == -1) { + fprintf(stderr, "setsockopt failed: %s\n", strerror(errno)); + exit(1); + } + + in_addr.sin_port = htons(SITL_SERVO_PORT); + + ret = connect(servo_fd, (struct sockaddr *)&in_addr, sizeof(in_addr)); + if (ret == -1) { + fprintf(stderr, "multicast servo connect failed\n"); + exit(1); + } } -void SITL_State::wait_clock(uint64_t wait_time_usec) { - while (AP_HAL::native_micros64() < wait_time_usec) { - usleep(1000); +/* + send servo outputs back to master + */ +void SimMCast::servo_send(void) +{ + const auto *_sitl = AP::sitl(); + if (_sitl == nullptr) { + return; } + uint16_t out[SITL_NUM_CHANNELS] {}; + hal.rcout->read(out, SITL_NUM_CHANNELS); + + float out_float[SITL_NUM_CHANNELS]; + const uint32_t mask = uint32_t(_sitl->can_servo_mask.get()); + for (uint8_t i=0; istate.timestamp_us == 0) { + printf("Waiting for multicast state\n"); + } + struct SITL::sitl_fdm state; + socklen_t len = sizeof(in_addr); + while (recvfrom(mc_fd, (void*)&state, sizeof(state), MSG_WAITALL, (sockaddr *)&in_addr, &len) != sizeof(state)) { + // nop + } + if (_sitl->state.timestamp_us == 0) { + printf("Got multicast state input\n"); + } + if (state.timestamp_us < _sitl->state.timestamp_us) { + printf("multicast state time reset\n"); + // main process has rebooted + base_time_us += (_sitl->state.timestamp_us - state.timestamp_us); + } + _sitl->state = state; + location.lat = state.latitude*1.0e7; + location.lng = state.longitude*1.0e7; + location.alt = state.altitude*1.0e2; + if (home.is_zero()) { + home = location; + } + hal.scheduler->stop_clock(_sitl->state.timestamp_us + base_time_us); + HALSITL::Scheduler::timer_event(); + if (servo_fd == -1) { + servo_fd_open(); + } else { + servo_send(); + } +} -ssize_t SITL::SerialDevice::write_to_device(char const*, size_t) const { return -1; } +SimMCast::SimMCast(const char *frame_str) : + Aircraft(frame_str) +{ + multicast_open(); +} + +void SimMCast::update(const struct sitl_input &input) +{ + multicast_read(); + update_external_payload(input); + + auto *_sitl = AP::sitl(); + if (_sitl != nullptr) { + battery_voltage = _sitl->batt_voltage; + } +} #endif //CONFIG_HAL_BOARD == HAL_BOARD_SITL && defined(HAL_BUILD_AP_PERIPH) diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.h b/libraries/AP_HAL_SITL/SITL_Periph_State.h index fde74a41c547c0..0aca46d29b89fb 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.h +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.h @@ -4,6 +4,8 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_SITL && defined(HAL_BUILD_AP_PERIPH) +#include "SITL_State_common.h" + #include "AP_HAL_SITL.h" #include "AP_HAL_SITL_Namespace.h" #include "HAL_SITL_Class.h" @@ -22,14 +24,34 @@ #include #include +class SimMCast : public SITL::Aircraft { +public: + SimMCast(const char *frame_str); + void update(const struct sitl_input &input) override; + +private: + int mc_fd = -1; + int servo_fd = -1; + struct sockaddr_in in_addr; + + // offset between multicast timestamp and local timestamp + uint64_t base_time_us; + + void multicast_open(); + void multicast_read(); + + void servo_send(void); + void servo_fd_open(void); +}; + class HAL_SITL; -class HALSITL::SITL_State { +class HALSITL::SITL_State : public SITL_State_Common { friend class HALSITL::Scheduler; friend class HALSITL::Util; friend class HALSITL::GPIO; public: - void init(int argc, char * const argv[]); + void init(int argc, char * const argv[]) override; bool use_rtscts(void) const { return _use_rtscts; @@ -39,19 +61,12 @@ class HALSITL::SITL_State { return _base_port; } - // simulated airspeed, sonar and battery monitor - float sonar_pin_voltage; // pin 0 - float airspeed_pin_voltage[AIRSPEED_MAX_SENSORS]; // pin 1 - float voltage_pin_voltage; // pin 13 - float current_pin_voltage; // pin 12 - float voltage2_pin_voltage; // pin 15 - float current2_pin_voltage; // pin 14 // paths for UART devices const char *_uart_path[9] { "none:0", - "fifo:gps", + "GPS1", "none:1", - "none:2", + "sim:adsb", "none:3", "none:4", "none:5", @@ -63,10 +78,6 @@ class HALSITL::SITL_State { bool run_in_maintenance_mode() const { return _maintenance; } - SITL::SerialDevice *create_serial_sim(const char *name, const char *arg) { - return nullptr; - } - private: void wait_clock(uint64_t wait_time_usec); @@ -77,6 +88,9 @@ class HALSITL::SITL_State { uint8_t _instance; bool _maintenance; + + // simulated GPS devices + SITL::GPS *gps[1]; // constrained by # of parameter sets }; #endif diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 0b7b0f21fbfb46..8c3af4c856bd64 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -7,6 +7,7 @@ #include "HAL_SITL_Class.h" #include "UARTDriver.h" #include "Scheduler.h" +#include "CANSocketIface.h" #include #include @@ -222,245 +223,6 @@ void SITL_State::wait_clock(uint64_t wait_time_usec) } } -#define streq(a, b) (!strcmp(a, b)) -SITL::SerialDevice *SITL_State::create_serial_sim(const char *name, const char *arg) -{ - if (streq(name, "vicon")) { - if (vicon != nullptr) { - AP_HAL::panic("Only one vicon system at a time"); - } - vicon = new SITL::Vicon(); - return vicon; -#if HAL_SIM_ADSB_ENABLED - } else if (streq(name, "adsb")) { - // ADSB is a stand-out as it is the only serial device which - // will cope with begin() being called multiple times on a - // serial port - if (adsb == nullptr) { - adsb = new SITL::ADSB(); - } - return adsb; -#endif - } else 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(); - return benewake_tf02; - } 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(); - 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(); - 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(); - 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(); - 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(); - 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(); - 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(); - return lanbao; - } else if (streq(name, "blping")) { - if (blping != nullptr) { - AP_HAL::panic("Only one blping at a time"); - } - blping = new 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(); - return leddarone; - } else if (streq(name, "rds02uf")) { - if (rds02uf != nullptr) { - AP_HAL::panic("Only one rds02uf at a time"); - } - rds02uf = new 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(); - 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(); - 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(); - return maxsonarseriallv; - } else if (streq(name, "wasp")) { - if (wasp != nullptr) { - AP_HAL::panic("Only one wasp at a time"); - } - wasp = new 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(); - return nmea; - - } else if (streq(name, "rf_mavlink")) { - if (rf_mavlink != nullptr) { - AP_HAL::panic("Only one rf_mavlink at a time"); - } - rf_mavlink = new SITL::RF_MAVLink(); - return rf_mavlink; - - } 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(); - 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(); - // 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(); - // 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(); - return crsf; -#endif -#if HAL_SIM_PS_RPLIDARA2_ENABLED - } else if (streq(name, "rplidara2")) { - if (rplidara2 != nullptr) { - AP_HAL::panic("Only one rplidara2 at a time"); - } - rplidara2 = new SITL::PS_RPLidarA2(); - return rplidara2; -#endif -#if HAL_SIM_PS_RPLIDARA1_ENABLED - } else if (streq(name, "rplidara1")) { - if (rplidara1 != nullptr) { - AP_HAL::panic("Only one rplidara1 at a time"); - } - rplidara1 = new SITL::PS_RPLidarA1(); - return rplidara1; -#endif -#if HAL_SIM_PS_TERARANGERTOWER_ENABLED - } else if (streq(name, "terarangertower")) { - if (terarangertower != nullptr) { - AP_HAL::panic("Only one terarangertower at a time"); - } - terarangertower = new SITL::PS_TeraRangerTower(); - return terarangertower; -#endif -#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED - } else if (streq(name, "sf45b")) { - if (sf45b != nullptr) { - AP_HAL::panic("Only one sf45b at a time"); - } - sf45b = new SITL::PS_LightWare_SF45B(); - return sf45b; -#endif - } else if (streq(name, "richenpower")) { - sitl_model->set_richenpower(&_sitl->richenpower_sim); - return &_sitl->richenpower_sim; - } else if (streq(name, "fetteconewireesc")) { - sitl_model->set_fetteconewireesc(&_sitl->fetteconewireesc_sim); - return &_sitl->fetteconewireesc_sim; - } else if (streq(name, "ie24")) { - sitl_model->set_ie24(&_sitl->ie24_sim); - return &_sitl->ie24_sim; - } else if (streq(name, "gyus42v2")) { - if (gyus42v2 != nullptr) { - AP_HAL::panic("Only one gyus42v2 at a time"); - } - gyus42v2 = new 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(); - return efi_ms; - } else if (streq(name, "VectorNav")) { - if (vectornav != nullptr) { - AP_HAL::panic("Only one VectorNav at a time"); - } - vectornav = new SITL::VectorNav(); - return vectornav; - } else if (streq(name, "LORD")) { - if (lord != nullptr) { - AP_HAL::panic("Only one LORD at a time"); - } - lord = new SITL::LORD(); - return lord; -#if HAL_SIM_AIS_ENABLED - } else if (streq(name, "AIS")) { - if (ais != nullptr) { - AP_HAL::panic("Only one AIS at a time"); - } - ais = new 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); - if (x <= 0 || x > ARRAY_SIZE(gps)) { - AP_HAL::panic("Bad GPS number %u", x); - } - gps[x-1] = new SITL::GPS(x-1); - return gps[x-1]; - } - - AP_HAL::panic("unknown simulated device: %s", name); -} - /* check for a SITL RC input packet */ @@ -580,6 +342,9 @@ void SITL_State::_fdm_input_local(void) ride_along.receive(input); #endif + // replace outputs from multicast + multicast_servo_update(input); + // update the model sitl_model->update_model(input); @@ -587,6 +352,12 @@ void SITL_State::_fdm_input_local(void) if (_sitl) { sitl_model->fill_fdm(_sitl->state); +#if HAL_NUM_CAN_IFACES + if (CANIface::num_interfaces() > 0) { + multicast_state_send(); + } +#endif + if (_sitl->rc_fail == SITL::SIM::SITL_RCFail_None) { for (uint8_t i=0; i< _sitl->state.rcin_chan_count; i++) { pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000; @@ -599,137 +370,7 @@ void SITL_State::_fdm_input_local(void) ride_along.send(_sitl->state,sitl_model->get_position_relhome()); #endif - if (gimbal != nullptr) { - gimbal->update(); - } -#if HAL_SIM_ADSB_ENABLED - if (adsb != nullptr) { - adsb->update(*sitl_model); - } -#endif - if (vicon != nullptr) { - Quaternion attitude; - sitl_model->get_attitude(attitude); - vicon->update(sitl_model->get_location(), - sitl_model->get_position_relhome(), - sitl_model->get_velocity_ef(), - attitude); - } - if (benewake_tf02 != nullptr) { - benewake_tf02->update(sitl_model->rangefinder_range()); - } - if (benewake_tf03 != nullptr) { - benewake_tf03->update(sitl_model->rangefinder_range()); - } - if (benewake_tfmini != nullptr) { - benewake_tfmini->update(sitl_model->rangefinder_range()); - } - if (nooploop != nullptr) { - nooploop->update(sitl_model->rangefinder_range()); - } - if (teraranger_serial != nullptr) { - teraranger_serial->update(sitl_model->rangefinder_range()); - } - if (lightwareserial != nullptr) { - lightwareserial->update(sitl_model->rangefinder_range()); - } - if (lightwareserial_binary != nullptr) { - lightwareserial_binary->update(sitl_model->rangefinder_range()); - } - if (lanbao != nullptr) { - lanbao->update(sitl_model->rangefinder_range()); - } - if (blping != nullptr) { - blping->update(sitl_model->rangefinder_range()); - } - if (leddarone != nullptr) { - leddarone->update(sitl_model->rangefinder_range()); - } - if (rds02uf != nullptr) { - rds02uf->update(sitl_model->rangefinder_range()); - } - if (USD1_v0 != nullptr) { - USD1_v0->update(sitl_model->rangefinder_range()); - } - if (USD1_v1 != nullptr) { - USD1_v1->update(sitl_model->rangefinder_range()); - } - if (maxsonarseriallv != nullptr) { - maxsonarseriallv->update(sitl_model->rangefinder_range()); - } - if (wasp != nullptr) { - wasp->update(sitl_model->rangefinder_range()); - } - if (nmea != nullptr) { - nmea->update(sitl_model->rangefinder_range()); - } - if (rf_mavlink != nullptr) { - rf_mavlink->update(sitl_model->rangefinder_range()); - } - if (gyus42v2 != nullptr) { - gyus42v2->update(sitl_model->rangefinder_range()); - } - if (efi_ms != nullptr) { - efi_ms->update(); - } - - if (frsky_d != nullptr) { - frsky_d->update(); - } - // if (frsky_sport != nullptr) { - // frsky_sport->update(); - // } - // if (frsky_sportpassthrough != nullptr) { - // frsky_sportpassthrough->update(); - // } - -#if AP_SIM_CRSF_ENABLED - if (crsf != nullptr) { - crsf->update(); - } -#endif - -#if HAL_SIM_PS_RPLIDARA2_ENABLED - if (rplidara2 != nullptr) { - rplidara2->update(sitl_model->get_location()); - } -#endif - -#if HAL_SIM_PS_RPLIDARA1_ENABLED - if (rplidara1 != nullptr) { - rplidara1->update(sitl_model->get_location()); - } -#endif -#if HAL_SIM_PS_TERARANGERTOWER_ENABLED - if (terarangertower != nullptr) { - terarangertower->update(sitl_model->get_location()); - } -#endif - -#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED - if (sf45b != nullptr) { - sf45b->update(sitl_model->get_location()); - } -#endif - - if (vectornav != nullptr) { - vectornav->update(); - } - - if (lord != nullptr) { - lord->update(); - } - -#if HAL_SIM_AIS_ENABLED - if (ais != nullptr) { - ais->update(); - } -#endif - for (uint8_t i=0; iupdate(); - } - } + sim_update(); if (_sitl && _use_fg_view) { _output_to_flightgear(); @@ -910,44 +551,7 @@ void SITL_State::_simulator_servos(struct sitl_input &input) _sitl->throttle = throttle; } - float voltage = 0; - _current = 0; - - if (_sitl != nullptr) { - if (_sitl->state.battery_voltage <= 0) { - if (_vehicle == ArduSub) { - voltage = _sitl->batt_voltage; - for (uint8_t i=0; i<6; i++) { - float pwm = input.servos[i]; - //printf("i: %d, pwm: %.2f\n", i, pwm); - float fraction = fabsf((pwm - 1500) / 500.0f); - - voltage -= fraction * 0.5f; - - float draw = fraction * 15; - _current += draw; - } - } else { - // simulate simple battery setup - // lose 0.7V at full throttle - voltage = _sitl->batt_voltage - 0.7f * throttle; - - // assume 50A at full throttle - _current = 50.0f * throttle; - } - } else { - // FDM provides voltage and current - voltage = _sitl->state.battery_voltage; - _current = _sitl->state.battery_current; - } - } - - // assume 3DR power brick - voltage_pin_voltage = (voltage / 10.1f); - current_pin_voltage = _current/17.0f; - // fake battery2 as just a 25% gain on the first one - voltage2_pin_voltage = voltage_pin_voltage * .25f; - current2_pin_voltage = current_pin_voltage * .25f; + update_voltage_current(input, throttle); } void SITL_State::init(int argc, char * const argv[]) @@ -1002,4 +606,115 @@ void SITL_State::set_height_agl(void) } } +/* + open multicast UDP + */ +void SITL_State::multicast_state_open(void) +{ + struct sockaddr_in sockaddr {}; + int ret; + +#ifdef HAVE_SOCK_SIN_LEN + sockaddr.sin_len = sizeof(sockaddr); +#endif + sockaddr.sin_port = htons(SITL_MCAST_PORT); + sockaddr.sin_family = AF_INET; + sockaddr.sin_addr.s_addr = inet_addr(SITL_MCAST_IP); + + mc_out_fd = socket(AF_INET, SOCK_DGRAM, 0); + if (mc_out_fd == -1) { + fprintf(stderr, "socket failed - %s\n", strerror(errno)); + exit(1); + } + ret = fcntl(mc_out_fd, F_SETFD, FD_CLOEXEC); + if (ret == -1) { + fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno)); + exit(1); + } + + // try to setup for broadcast, this may fail if insufficient privileges + int one = 1; + setsockopt(mc_out_fd,SOL_SOCKET,SO_BROADCAST,(char *)&one,sizeof(one)); + + ret = connect(mc_out_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); + if (ret == -1) { + fprintf(stderr, "udp connect failed on port %u - %s\n", + (unsigned)ntohs(sockaddr.sin_port), + strerror(errno)); + exit(1); + } + + /* + open servo input socket + */ + servo_in_fd = socket(AF_INET, SOCK_DGRAM, 0); + if (servo_in_fd == -1) { + fprintf(stderr, "socket failed - %s\n", strerror(errno)); + exit(1); + } + ret = fcntl(servo_in_fd, F_SETFD, FD_CLOEXEC); + if (ret == -1) { + fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno)); + exit(1); + } + + sockaddr.sin_addr.s_addr = htonl(INADDR_ANY); + sockaddr.sin_port = htons(SITL_SERVO_PORT); + + ret = bind(servo_in_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); + if (ret == -1) { + fprintf(stderr, "udp servo connect failed\n"); + exit(1); + } + ::printf("multicast initialised\n"); +} + +/* + send out SITL state as multicast UDP + */ +void SITL_State::multicast_state_send(void) +{ + if (_sitl == nullptr) { + return; + } + if (mc_out_fd == -1) { + multicast_state_open(); + } + const auto &sfdm = _sitl->state; + send(mc_out_fd, (void*)&sfdm, sizeof(sfdm), 0); + + check_servo_input(); +} + +/* + check for servo data from peripheral + */ +void SITL_State::check_servo_input(void) +{ + // drain any pending packets + float mc_servo_float[SITL_NUM_CHANNELS]; + // we loop to ensure we drain all packets from all nodes + while (recv(servo_in_fd, (void*)mc_servo_float, sizeof(mc_servo_float), MSG_DONTWAIT) == sizeof(mc_servo_float)) { + for (uint8_t i=0; ican_servo_mask.get()); + if (can_mask & mask) { + input.servos[i] = mc_servo[i]; + } + } +} #endif diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 418216706f41b0..8ca5afd4526af9 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -3,109 +3,31 @@ #include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL + +#include "SITL_State_common.h" + #if defined(HAL_BUILD_AP_PERIPH) #include "SITL_Periph_State.h" #else -#include "AP_HAL_SITL.h" -#include "AP_HAL_SITL_Namespace.h" -#include "HAL_SITL_Class.h" -#include "RCInput.h" - -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -// #include -// #include -#include -#include -#include -#include - -#include -#include -#include - class HAL_SITL; -class HALSITL::SITL_State { +class HALSITL::SITL_State : public SITL_State_Common { friend class HALSITL::Scheduler; friend class HALSITL::Util; friend class HALSITL::GPIO; public: - void init(int argc, char * const argv[]); - - enum vehicle_type { - ArduCopter, - Rover, - ArduPlane, - ArduSub, - Blimp - }; + void init(int argc, char * const argv[]) override; - uint16_t pwm_output[SITL_NUM_CHANNELS]; - uint16_t pwm_input[SITL_RC_INPUT_CHANNELS]; - bool output_ready = false; - bool new_rc_input; void loop_hook(void); uint16_t base_port(void) const { return _base_port; } - // create a simulated serial device; type of device is given by - // name parameter - SITL::SerialDevice *create_serial_sim(const char *name, const char *arg); - bool use_rtscts(void) const { return _use_rtscts; } - // simulated airspeed, sonar and battery monitor - float sonar_pin_voltage; // pin 0 - float airspeed_pin_voltage[AIRSPEED_MAX_SENSORS]; // pin 1 - float voltage_pin_voltage; // pin 13 - float current_pin_voltage; // pin 12 - float voltage2_pin_voltage; // pin 15 - float current2_pin_voltage; // pin 14 - // paths for UART devices const char *_uart_path[9] { "tcp:0:wait", @@ -156,7 +78,6 @@ class HALSITL::SITL_State { void wait_clock(uint64_t wait_time_usec); // internal state - enum vehicle_type _vehicle; uint8_t _instance; uint16_t _base_port; pid_t _parent_pid; @@ -165,11 +86,9 @@ class HALSITL::SITL_State { Scheduler *_scheduler; SocketAPM _sitl_rc_in{true}; - SITL::SIM *_sitl; uint16_t _rcin_port; uint16_t _fg_view_port; uint16_t _irlock_port; - float _current; bool _synthetic_clock_mode; @@ -193,117 +112,6 @@ class HALSITL::SITL_State { uint32_t delayed_time_wind; uint32_t wind_start_delay_micros; - // internal SITL model - SITL::Aircraft *sitl_model; - -#if HAL_SIM_GIMBAL_ENABLED - // simulated gimbal - bool enable_gimbal; - SITL::Gimbal *gimbal; -#endif - -#if HAL_SIM_ADSB_ENABLED - // simulated ADSb - SITL::ADSB *adsb; -#endif - - // simulated vicon system: - SITL::Vicon *vicon; - - // simulated Benewake tf02 rangefinder: - SITL::RF_Benewake_TF02 *benewake_tf02; - // simulated Benewake tf03 rangefinder: - SITL::RF_Benewake_TF03 *benewake_tf03; - // simulated Benewake tfmini rangefinder: - SITL::RF_Benewake_TFmini *benewake_tfmini; - //simulated NoopLoop TOFSense rangefinder: - SITL::RF_Nooploop *nooploop; - // simulated TeraRanger Serial: - SITL::RF_TeraRanger_Serial *teraranger_serial; - - // simulated LightWareSerial rangefinder - legacy protocol:: - SITL::RF_LightWareSerial *lightwareserial; - // simulated LightWareSerial rangefinder - binary protocol: - SITL::RF_LightWareSerialBinary *lightwareserial_binary; - // simulated Lanbao rangefinder: - SITL::RF_Lanbao *lanbao; - // simulated BLping rangefinder: - SITL::RF_BLping *blping; - // simulated LeddarOne rangefinder: - SITL::RF_LeddarOne *leddarone; - // simulated RDS02UF rangefinder: - SITL::RF_RDS02UF *rds02uf; - // simulated USD1 v0 rangefinder: - SITL::RF_USD1_v0 *USD1_v0; - // simulated USD1 v1 rangefinder: - SITL::RF_USD1_v1 *USD1_v1; - // simulated MaxsonarSerialLV rangefinder: - SITL::RF_MaxsonarSerialLV *maxsonarseriallv; - // simulated Wasp rangefinder: - SITL::RF_Wasp *wasp; - // simulated NMEA rangefinder: - SITL::RF_NMEA *nmea; - // simulated MAVLink rangefinder: - SITL::RF_MAVLink *rf_mavlink; - // simulated GYUS42v2 rangefinder: - SITL::RF_GYUS42v2 *gyus42v2; - - // simulated Frsky devices - SITL::Frsky_D *frsky_d; - // SITL::Frsky_SPort *frsky_sport; - // SITL::Frsky_SPortPassthrough *frsky_sportpassthrough; - -#if HAL_SIM_PS_RPLIDARA2_ENABLED - // simulated RPLidarA2: - SITL::PS_RPLidarA2 *rplidara2; -#endif - - // simulated FETtec OneWire ESCs: - SITL::FETtecOneWireESC *fetteconewireesc; - - // simulated RPLidarA1: - SITL::PS_RPLidarA1 *rplidara1; - -#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED - // simulated SF45B proximity sensor: - SITL::PS_LightWare_SF45B *sf45b; -#endif - -#if HAL_SIM_PS_TERARANGERTOWER_ENABLED - SITL::PS_TeraRangerTower *terarangertower; -#endif - -#if AP_SIM_CRSF_ENABLED - // simulated CRSF devices - SITL::CRSF *crsf; -#endif - - // simulated VectorNav system: - SITL::VectorNav *vectornav; - - // simulated LORD Microstrain system - SITL::LORD *lord; - -#if HAL_SIM_JSON_MASTER_ENABLED - // Ride along instances via JSON SITL backend - SITL::JSON_Master ride_along; -#endif - -#if HAL_SIM_AIS_ENABLED - // simulated AIS stream - SITL::AIS *ais; -#endif - - // simulated EFI MegaSquirt device: - SITL::EFI_MegaSquirt *efi_ms; - - // output socket for flightgear viewing - SocketAPM fg_socket{true}; - - const char *defaults_path = HAL_PARAM_DEFAULTS_PATH; - - char *_gps_fifo[2]; - // simulated GPS devices SITL::GPS *gps[2]; // constrained by # of parameter sets @@ -311,6 +119,17 @@ class HALSITL::SITL_State { // voltage from the sensor float _sonar_pin_voltage() const; + // multicast state + int mc_out_fd = -1; + int servo_in_fd = -1; + + // send out SITL state as UDP multicast + void multicast_state_open(void); + void multicast_state_send(void); + void multicast_servo_update(struct sitl_input &input); + + uint16_t mc_servo[SITL_NUM_CHANNELS]; + void check_servo_input(void); }; #endif // defined(HAL_BUILD_AP_PERIPH) diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp new file mode 100644 index 00000000000000..89288310ea2c04 --- /dev/null +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -0,0 +1,459 @@ +#include + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + +#include "AP_HAL_SITL.h" +#include "AP_HAL_SITL_Namespace.h" +#include "HAL_SITL_Class.h" +#include "UARTDriver.h" +#include "Scheduler.h" +#include "CANSocketIface.h" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +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) +{ + 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(); + 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(); + return vicon; +#endif +#if HAL_SIM_ADSB_ENABLED + } else if (streq(name, "adsb")) { + // ADSB is a stand-out as it is the only serial device which + // will cope with begin() being called multiple times on a + // serial port + if (adsb == nullptr) { + adsb = new SITL::ADSB(); + } + return adsb; +#endif + } 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(); + 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(); + 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(); + 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(); + 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(); + 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(); + 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(); + return lanbao; + } else if (streq(name, "blping")) { + if (blping != nullptr) { + AP_HAL::panic("Only one blping at a time"); + } + blping = new 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(); + return leddarone; + } else if (streq(name, "rds02uf")) { + if (rds02uf != nullptr) { + AP_HAL::panic("Only one rds02uf at a time"); + } + rds02uf = new 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(); + 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(); + 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(); + return maxsonarseriallv; + } else if (streq(name, "wasp")) { + if (wasp != nullptr) { + AP_HAL::panic("Only one wasp at a time"); + } + wasp = new 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(); + return nmea; + +#if !defined(HAL_BUILD_AP_PERIPH) + } else if (streq(name, "rf_mavlink")) { + if (rf_mavlink != nullptr) { + AP_HAL::panic("Only one rf_mavlink at a time"); + } + rf_mavlink = new 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(); + 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(); + // 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(); + // 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(); + return crsf; +#endif +#if HAL_SIM_PS_RPLIDARA2_ENABLED + } else if (streq(name, "rplidara2")) { + if (rplidara2 != nullptr) { + AP_HAL::panic("Only one rplidara2 at a time"); + } + rplidara2 = new SITL::PS_RPLidarA2(); + return rplidara2; +#endif +#if HAL_SIM_PS_RPLIDARA1_ENABLED + } else if (streq(name, "rplidara1")) { + if (rplidara1 != nullptr) { + AP_HAL::panic("Only one rplidara1 at a time"); + } + rplidara1 = new SITL::PS_RPLidarA1(); + return rplidara1; +#endif +#if HAL_SIM_PS_TERARANGERTOWER_ENABLED + } else if (streq(name, "terarangertower")) { + if (terarangertower != nullptr) { + AP_HAL::panic("Only one terarangertower at a time"); + } + terarangertower = new SITL::PS_TeraRangerTower(); + return terarangertower; +#endif +#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED + } else if (streq(name, "sf45b")) { + if (sf45b != nullptr) { + AP_HAL::panic("Only one sf45b at a time"); + } + sf45b = new SITL::PS_LightWare_SF45B(); + return sf45b; +#endif +#if !defined(HAL_BUILD_AP_PERIPH) + } else if (streq(name, "richenpower")) { + sitl_model->set_richenpower(&_sitl->richenpower_sim); + return &_sitl->richenpower_sim; + } else if (streq(name, "fetteconewireesc")) { + sitl_model->set_fetteconewireesc(&_sitl->fetteconewireesc_sim); + return &_sitl->fetteconewireesc_sim; + } else if (streq(name, "ie24")) { + sitl_model->set_ie24(&_sitl->ie24_sim); + return &_sitl->ie24_sim; +#endif // HAL_BUILD_AP_PERIPH + } else if (streq(name, "gyus42v2")) { + if (gyus42v2 != nullptr) { + AP_HAL::panic("Only one gyus42v2 at a time"); + } + gyus42v2 = new 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(); + return efi_ms; + } else if (streq(name, "VectorNav")) { + if (vectornav != nullptr) { + AP_HAL::panic("Only one VectorNav at a time"); + } + vectornav = new 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(); + return microstrain5; +#if HAL_SIM_AIS_ENABLED + } else if (streq(name, "AIS")) { + if (ais != nullptr) { + AP_HAL::panic("Only one AIS at a time"); + } + ais = new 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); + if (x <= 0 || x > ARRAY_SIZE(gps)) { + AP_HAL::panic("Bad GPS number %u", x); + } + gps[x-1] = new SITL::GPS(x-1); + return gps[x-1]; + } + + AP_HAL::panic("unknown simulated device: %s", name); +} + +/* + update simulators + */ +void SITL_State_Common::sim_update(void) +{ +#if HAL_SIM_GIMBAL_ENABLED + if (gimbal != nullptr) { + gimbal->update(); + } +#endif +#if HAL_SIM_ADSB_ENABLED + if (adsb != nullptr) { + adsb->update(*sitl_model); + } +#endif +#if !defined(HAL_BUILD_AP_PERIPH) + if (vicon != nullptr) { + Quaternion attitude; + sitl_model->get_attitude(attitude); + vicon->update(sitl_model->get_location(), + sitl_model->get_position_relhome(), + sitl_model->get_velocity_ef(), + attitude); + } +#endif + if (benewake_tf02 != nullptr) { + benewake_tf02->update(sitl_model->rangefinder_range()); + } + if (benewake_tf03 != nullptr) { + benewake_tf03->update(sitl_model->rangefinder_range()); + } + if (benewake_tfmini != nullptr) { + benewake_tfmini->update(sitl_model->rangefinder_range()); + } + if (nooploop != nullptr) { + nooploop->update(sitl_model->rangefinder_range()); + } + if (teraranger_serial != nullptr) { + teraranger_serial->update(sitl_model->rangefinder_range()); + } + if (lightwareserial != nullptr) { + lightwareserial->update(sitl_model->rangefinder_range()); + } + if (lightwareserial_binary != nullptr) { + lightwareserial_binary->update(sitl_model->rangefinder_range()); + } + if (lanbao != nullptr) { + lanbao->update(sitl_model->rangefinder_range()); + } + if (blping != nullptr) { + blping->update(sitl_model->rangefinder_range()); + } + if (leddarone != nullptr) { + leddarone->update(sitl_model->rangefinder_range()); + } + if (rds02uf != nullptr) { + rds02uf->update(sitl_model->rangefinder_range()); + } + if (USD1_v0 != nullptr) { + USD1_v0->update(sitl_model->rangefinder_range()); + } + if (USD1_v1 != nullptr) { + USD1_v1->update(sitl_model->rangefinder_range()); + } + if (maxsonarseriallv != nullptr) { + maxsonarseriallv->update(sitl_model->rangefinder_range()); + } + if (wasp != nullptr) { + wasp->update(sitl_model->rangefinder_range()); + } + if (nmea != nullptr) { + nmea->update(sitl_model->rangefinder_range()); + } + if (rf_mavlink != nullptr) { + rf_mavlink->update(sitl_model->rangefinder_range()); + } + if (gyus42v2 != nullptr) { + gyus42v2->update(sitl_model->rangefinder_range()); + } + if (efi_ms != nullptr) { + efi_ms->update(); + } + + if (frsky_d != nullptr) { + frsky_d->update(); + } + // if (frsky_sport != nullptr) { + // frsky_sport->update(); + // } + // if (frsky_sportpassthrough != nullptr) { + // frsky_sportpassthrough->update(); + // } + +#if AP_SIM_CRSF_ENABLED + if (crsf != nullptr) { + crsf->update(); + } +#endif + +#if HAL_SIM_PS_RPLIDARA2_ENABLED + if (rplidara2 != nullptr) { + rplidara2->update(sitl_model->get_location()); + } +#endif + +#if HAL_SIM_PS_RPLIDARA1_ENABLED + if (rplidara1 != nullptr) { + rplidara1->update(sitl_model->get_location()); + } +#endif +#if HAL_SIM_PS_TERARANGERTOWER_ENABLED + if (terarangertower != nullptr) { + terarangertower->update(sitl_model->get_location()); + } +#endif + +#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED + if (sf45b != nullptr) { + sf45b->update(sitl_model->get_location()); + } +#endif + + if (vectornav != nullptr) { + vectornav->update(); + } + + if (microstrain5 != nullptr) { + microstrain5->update(); + } + +#if HAL_SIM_AIS_ENABLED + if (ais != nullptr) { + ais->update(); + } +#endif + for (uint8_t i=0; iupdate(); + } + } +} + +/* + update voltage and current pins + */ +void SITL_State_Common::update_voltage_current(struct sitl_input &input, float throttle) +{ + float voltage = 0; + float current = 0; + + if (_sitl != nullptr) { + if (_sitl->state.battery_voltage <= 0) { + if (_vehicle == ArduSub) { + voltage = _sitl->batt_voltage; + for (uint8_t i=0; i<6; i++) { + float pwm = input.servos[i]; + //printf("i: %d, pwm: %.2f\n", i, pwm); + float fraction = fabsf((pwm - 1500) / 500.0f); + + voltage -= fraction * 0.5f; + + float draw = fraction * 15; + current += draw; + } + } else { + // simulate simple battery setup + // lose 0.7V at full throttle + voltage = _sitl->batt_voltage - 0.7f * throttle; + + // assume 50A at full throttle + current = 50.0f * throttle; + } + } else { + // FDM provides voltage and current + voltage = _sitl->state.battery_voltage; + current = _sitl->state.battery_current; + } + } + + // assume 3DR power brick + voltage_pin_voltage = (voltage / 10.1f); + current_pin_voltage = current/17.0f; + // fake battery2 as just a 25% gain on the first one + voltage2_pin_voltage = voltage_pin_voltage * .25f; + current2_pin_voltage = current_pin_voltage * .25f; +} + +#endif // HAL_BOARD_SITL + diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h new file mode 100644 index 00000000000000..b1105ecc35ba1c --- /dev/null +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -0,0 +1,239 @@ +#pragma once + +#include + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + +#define SITL_MCAST_IP "239.255.145.51" +#define SITL_MCAST_PORT 20721 +#define SITL_SERVO_PORT 20722 + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +// #include +// #include +#include +#include +#include +#include + +#include +#include + +#include "AP_HAL_SITL.h" +#include "AP_HAL_SITL_Namespace.h" +#include "HAL_SITL_Class.h" +#include "RCInput.h" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +class HAL_SITL; + +class HALSITL::SITL_State_Common { + friend class HALSITL::Scheduler; + friend class HALSITL::Util; + friend class HALSITL::GPIO; +public: + virtual void init(int argc, char * const argv[]) = 0; + + enum vehicle_type { + NONE, + ArduCopter, + Rover, + ArduPlane, + ArduSub, + Blimp + }; + + // create a simulated serial device; type of device is given by + // name parameter + SITL::SerialDevice *create_serial_sim(const char *name, const char *arg); + + // simulated airspeed, sonar and battery monitor + float sonar_pin_voltage; // pin 0 + float airspeed_pin_voltage[AIRSPEED_MAX_SENSORS]; // pin 1 + float voltage_pin_voltage; // pin 13 + float current_pin_voltage; // pin 12 + float voltage2_pin_voltage; // pin 15 + float current2_pin_voltage; // pin 14 + + uint16_t pwm_input[SITL_RC_INPUT_CHANNELS]; + bool new_rc_input; + uint16_t pwm_output[SITL_NUM_CHANNELS]; + bool output_ready = false; + +#if HAL_SIM_GIMBAL_ENABLED + // simulated gimbal + bool enable_gimbal; + SITL::Gimbal *gimbal; +#endif + +#if HAL_SIM_ADSB_ENABLED + // simulated ADSb + SITL::ADSB *adsb; +#endif + +#if !defined(HAL_BUILD_AP_PERIPH) + // simulated vicon system: + SITL::Vicon *vicon; +#endif + + // simulated Benewake tf02 rangefinder: + SITL::RF_Benewake_TF02 *benewake_tf02; + // simulated Benewake tf03 rangefinder: + SITL::RF_Benewake_TF03 *benewake_tf03; + // simulated Benewake tfmini rangefinder: + SITL::RF_Benewake_TFmini *benewake_tfmini; + //simulated NoopLoop TOFSense rangefinder: + SITL::RF_Nooploop *nooploop; + // simulated TeraRanger Serial: + SITL::RF_TeraRanger_Serial *teraranger_serial; + + // simulated LightWareSerial rangefinder - legacy protocol:: + SITL::RF_LightWareSerial *lightwareserial; + // simulated LightWareSerial rangefinder - binary protocol: + SITL::RF_LightWareSerialBinary *lightwareserial_binary; + // simulated Lanbao rangefinder: + SITL::RF_Lanbao *lanbao; + // simulated BLping rangefinder: + SITL::RF_BLping *blping; + // simulated LeddarOne rangefinder: + SITL::RF_LeddarOne *leddarone; + // simulated RDS02UF rangefinder: + SITL::RF_RDS02UF *rds02uf; + // simulated USD1 v0 rangefinder: + SITL::RF_USD1_v0 *USD1_v0; + // simulated USD1 v1 rangefinder: + SITL::RF_USD1_v1 *USD1_v1; + // simulated MaxsonarSerialLV rangefinder: + SITL::RF_MaxsonarSerialLV *maxsonarseriallv; + // simulated Wasp rangefinder: + SITL::RF_Wasp *wasp; + // simulated NMEA rangefinder: + SITL::RF_NMEA *nmea; + // simulated MAVLink rangefinder: + SITL::RF_MAVLink *rf_mavlink; + // simulated GYUS42v2 rangefinder: + SITL::RF_GYUS42v2 *gyus42v2; + + // simulated Frsky devices + SITL::Frsky_D *frsky_d; + // SITL::Frsky_SPort *frsky_sport; + // SITL::Frsky_SPortPassthrough *frsky_sportpassthrough; + +#if HAL_SIM_PS_RPLIDARA2_ENABLED + // simulated RPLidarA2: + SITL::PS_RPLidarA2 *rplidara2; +#endif + + // simulated FETtec OneWire ESCs: + SITL::FETtecOneWireESC *fetteconewireesc; + + // simulated RPLidarA1: + SITL::PS_RPLidarA1 *rplidara1; + +#if HAL_SIM_PS_LIGHTWARE_SF45B_ENABLED + // simulated SF45B proximity sensor: + SITL::PS_LightWare_SF45B *sf45b; +#endif + +#if HAL_SIM_PS_TERARANGERTOWER_ENABLED + SITL::PS_TeraRangerTower *terarangertower; +#endif + +#if AP_SIM_CRSF_ENABLED + // simulated CRSF devices + SITL::CRSF *crsf; +#endif + + // simulated VectorNav system: + SITL::VectorNav *vectornav; + + // simulated LORD MicroStrain system + SITL::MicroStrain5 *microstrain5; + +#if HAL_SIM_JSON_MASTER_ENABLED + // Ride along instances via JSON SITL backend + SITL::JSON_Master ride_along; +#endif + +#if HAL_SIM_AIS_ENABLED + // simulated AIS stream + SITL::AIS *ais; +#endif + + // simulated EFI MegaSquirt device: + SITL::EFI_MegaSquirt *efi_ms; + + // output socket for flightgear viewing + SocketAPM fg_socket{true}; + + const char *defaults_path = HAL_PARAM_DEFAULTS_PATH; + + // simulated GPS devices + SITL::GPS *gps[2]; // constrained by # of parameter sets + + // returns a voltage between 0V to 5V which should appear as the + // voltage from the sensor + float _sonar_pin_voltage() const; + + // multicast state + int mc_out_fd = -1; + + // send out SITL state as UDP multicast + void multicast_state_open(void); + void multicast_state_send(void); + +protected: + enum vehicle_type _vehicle; + + void sim_update(void); + + // internal SITL model + SITL::Aircraft *sitl_model; + + SITL::SIM *_sitl; + + void update_voltage_current(struct sitl_input &input, float throttle); +}; + +#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_SITL/Scheduler.cpp b/libraries/AP_HAL_SITL/Scheduler.cpp index ba04d6af2d2092..2531722d710142 100644 --- a/libraries/AP_HAL_SITL/Scheduler.cpp +++ b/libraries/AP_HAL_SITL/Scheduler.cpp @@ -276,10 +276,8 @@ void Scheduler::_run_io_procs() } hal.storage->_timer_tick(); -#ifndef HAL_BUILD_AP_PERIPH // in lieu of a thread-per-bus: ((HALSITL::I2CDeviceManager*)(hal.i2c_mgr))->_timer_tick(); -#endif #if SITL_STACK_CHECKING_ENABLED check_thread_stacks(); diff --git a/libraries/AP_HAL_SITL/Synth.hpp b/libraries/AP_HAL_SITL/Synth.hpp index d4a2374681acde..cc96cf9f44adf9 100644 --- a/libraries/AP_HAL_SITL/Synth.hpp +++ b/libraries/AP_HAL_SITL/Synth.hpp @@ -7,6 +7,7 @@ // Headers //////////////////////////////////////////////////////////// #include +#include #include namespace Synth @@ -107,7 +108,7 @@ double amplitude(double dTime, sEnvelope env) else if (dTime > env.dAttackTime && dTime <= (env.dAttackTime + env.dDecayTime)) // Decay phase dAmplitude = ((dTime - env.dAttackTime) / env.dDecayTime) * (env.dSustainAmplitude - env.dStartAmplitude) + env.dStartAmplitude; - else if (dTime <= env.dAttackTime) // Attack phase + else if ((env.dAttackTime >= DBL_EPSILON) && dTime <= env.dAttackTime) // Attack phase dAmplitude = (dTime / env.dAttackTime) * env.dStartAmplitude; // Amplitude should not be negative, check just in case diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 64ffbf93776fb7..7b43217e67f1e8 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -120,17 +120,6 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) _uart_path = strdup(args1); _uart_baudrate = baudrate; _uart_start_connection(); - } else if (strcmp(devtype, "fifo") == 0) { - if(strcmp(args1, "gps") == 0) { - UNUSED_RESULT(asprintf(&args1, "/tmp/gps_fifo%d", (int)_sitlState->get_instance())); - } - ::printf("Reading FIFO file @ %s\n", args1); - _fd = ::open(args1, O_RDONLY | O_NONBLOCK); - if (_fd >= 0) { - _connected = true; - } else { - ::printf("Failed Reading FIFO file @ %s\n", args1); - } } else if (strcmp(devtype, "sim") == 0) { if (!_connected) { ::printf("SIM connection %s:%s on port %u\n", args1, args2, _portNumber); @@ -263,18 +252,7 @@ size_t UARTDriver::_write(const uint8_t *buffer, size_t size) if (size <= 0) { return 0; } - if (_unbuffered_writes) { - const ssize_t nwritten = ::write(_fd, buffer, size); - if (nwritten == -1 && errno != EAGAIN && _uart_path) { - close(_fd); - _fd = -1; - _connected = false; - return 0; - } - // these have no effect - tcdrain(_fd); - return nwritten; - } else { + /* simulate byte loss at the link layer */ @@ -288,8 +266,13 @@ size_t UARTDriver::_write(const uint8_t *buffer, size_t size) } } #endif // HAL_BUILD_AP_PERIPH - return _writebuffer.write(buffer, size - lost_byte) + lost_byte; + + + const size_t ret = _writebuffer.write(buffer, size - lost_byte) + lost_byte; + if (_unbuffered_writes) { + handle_writing_from_writebuffer_to_device(); } + return ret; } @@ -796,7 +779,7 @@ uint16_t UARTDriver::read_from_async_csv(uint8_t *buffer, uint16_t space) return i; } -void UARTDriver::_timer_tick(void) +void UARTDriver::handle_writing_from_writebuffer_to_device() { if (!_connected) { _check_reconnect(); @@ -809,12 +792,12 @@ void UARTDriver::_timer_tick(void) 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_tick_us); + float dt = 1.0e-6 * (now - last_write_tick_us); max_bytes = _uart_baudrate * dt / 10; if (max_bytes == 0) { return; } - last_tick_us = now; + last_write_tick_us = now; } #endif if (_packetise) { @@ -856,13 +839,37 @@ void UARTDriver::_timer_tick(void) } } } +} + +void UARTDriver::handle_reading_from_device_to_readbuffer() +{ + if (!_connected) { + _check_reconnect(); + return; + } uint32_t space = _readbuffer.space(); if (space == 0) { return; } + + uint32_t max_bytes = 10000; +#if !defined(HAL_BUILD_AP_PERIPH) + 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; + if (max_bytes == 0) { + return; + } + last_read_tick_us = now; + } +#endif + space = MIN(space, max_bytes); - + char buf[space]; ssize_t nread = 0; if (_mc_fd >= 0) { @@ -929,6 +936,13 @@ void UARTDriver::_timer_tick(void) } } +void UARTDriver::_timer_tick(void) +{ + handle_writing_from_writebuffer_to_device(); + handle_reading_from_device_to_readbuffer(); +} + + /* return timestamp estimate in microseconds for when the start of a nbytes packet arrived on the uart. This should be treated as a diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index 02878d2fd22651..fb0476550bb213 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -106,7 +106,10 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { bool _is_udp; bool _packetise; uint16_t _mc_myport; - uint32_t last_tick_us; + + // for baud-rate limiting: + uint32_t last_read_tick_us; + uint32_t last_write_tick_us; SITL::SerialDevice *_sim_serial_device; @@ -134,6 +137,10 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { void _end() override; void _flush() override; bool _discard_input() override; + +private: + void handle_writing_from_writebuffer_to_device(); + void handle_reading_from_device_to_readbuffer(); }; #endif diff --git a/libraries/AP_HAL_SITL/system.cpp b/libraries/AP_HAL_SITL/system.cpp index 518a2f3e168370..138ee2a7c2bef6 100644 --- a/libraries/AP_HAL_SITL/system.cpp +++ b/libraries/AP_HAL_SITL/system.cpp @@ -193,65 +193,4 @@ uint64_t millis64() return ret; } - -uint32_t native_micros() -{ -#if AP_TEST_DRONECAN_DRIVERS - return micros(); -#else - return native_micros64() & 0xFFFFFFFF; -#endif -} - -uint32_t native_millis() -{ -#if AP_TEST_DRONECAN_DRIVERS - return millis(); -#else - return native_millis64() & 0xFFFFFFFF; -#endif -} - -/* - we define a millis16() here to avoid an issue with sitl builds in cygwin - */ -uint16_t native_millis16() -{ -#if AP_TEST_DRONECAN_DRIVERS - return millis16(); -#else - return native_millis64() & 0xFFFF; -#endif -} - - -uint64_t native_micros64() -{ -#if AP_TEST_DRONECAN_DRIVERS - return micros64(); -#else - struct timeval tp; - gettimeofday(&tp, nullptr); - uint64_t ret = 1.0e6 * ((tp.tv_sec + (tp.tv_usec * 1.0e-6)) - - (state.start_time.tv_sec + - (state.start_time.tv_usec * 1.0e-6))); - return ret; -#endif -} - -uint64_t native_millis64() -{ -#if AP_TEST_DRONECAN_DRIVERS - return millis64(); -#else - struct timeval tp; - gettimeofday(&tp, nullptr); - uint64_t ret = 1.0e3*((tp.tv_sec + (tp.tv_usec*1.0e-6)) - - (state.start_time.tv_sec + - (state.start_time.tv_usec*1.0e-6))); - return ret; -#endif -} - - } // namespace AP_HAL diff --git a/libraries/AP_HAL_SITL/wscript b/libraries/AP_HAL_SITL/wscript new file mode 100644 index 00000000000000..0770f159cbc361 --- /dev/null +++ b/libraries/AP_HAL_SITL/wscript @@ -0,0 +1,2 @@ +def configure(cfg): + cfg.env.DOUBLE_PRECISION_LIBRARIES['AP_HAL_SITL'] = True diff --git a/libraries/AP_Hott_Telem/AP_Hott_Telem.cpp b/libraries/AP_Hott_Telem/AP_Hott_Telem.cpp index 05911a67e4c581..98bff2d86ecbaa 100644 --- a/libraries/AP_Hott_Telem/AP_Hott_Telem.cpp +++ b/libraries/AP_Hott_Telem/AP_Hott_Telem.cpp @@ -289,12 +289,14 @@ void AP_Hott_Telem::send_GPS(void) msg.home_direction = degrees(atan2f(home_vec.y, home_vec.x)) * 0.5 + 0.5; +#if AP_RTC_ENABLED AP_RTC &rtc = AP::rtc(); { WITH_SEMAPHORE(rtc.get_semaphore()); uint16_t ms; rtc.get_system_clock_utc(msg.gps_time_h, msg.gps_time_m, msg.gps_time_s, ms); } +#endif send_packet((const uint8_t *)&msg, sizeof(msg)); } diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index 6d3a9c97a96823..b5b85d38dd4c73 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -24,6 +24,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -141,8 +142,8 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { // @Param: OPTIONS // @DisplayName: ICE options - // @Description: Options for ICE control. The DisableIgnitionRCFailsafe option will cause the ignition to be set off on any R/C failsafe. If ThrottleWhileDisarmed is set then throttle control will be allowed while disarmed for planes when in MANUAL mode. - // @Bitmask: 0:DisableIgnitionRCFailsafe,1:DisableRedineGovernor,2:ThrottleWhileDisarmed + // @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. + // @Bitmask: 0:Disable ignition in RC failsafe,1:Disable redline governor,2:Throttle while disarmed,3:Disable while disarmed AP_GROUPINFO("OPTIONS", 15, AP_ICEngine, options, 0), // @Param: STARTCHN_MIN @@ -246,8 +247,23 @@ void AP_ICEngine::update(void) should_run = false; } + if (option_set(Options::NO_RUNNING_WHILE_DISARMED) && !hal.util->get_soft_armed()) { + // disable the engine if disarmed + should_run = false; + } + +#if HAL_PARACHUTE_ENABLED + // Stop on parachute deployment + AP_Parachute *parachute = AP::parachute(); + if ((parachute != nullptr) && parachute->release_initiated()) { + should_run = false; + } +#endif + // switch on current state to work out new state switch (state) { + case ICE_DISABLED: + return; case ICE_OFF: if (should_run) { state = ICE_START_DELAY; @@ -263,7 +279,7 @@ void AP_ICEngine::update(void) height_pending = false; initial_height = -pos.z; } else if ((-pos.z) >= initial_height + height_required) { - gcs().send_text(MAV_SEVERITY_INFO, "Starting height reached %.1f", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Starting height reached %.1f", (double)(-pos.z - initial_height)); state = ICE_STARTING; } @@ -275,7 +291,7 @@ 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"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Starting engine"); state = ICE_STARTING; } break; @@ -284,7 +300,7 @@ void AP_ICEngine::update(void) if (!should_run) { state = ICE_OFF; } else if (now - starter_start_time_ms >= starter_time*1000) { - gcs().send_text(MAV_SEVERITY_INFO, "Engine running"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine running"); state = ICE_RUNNING; } break; @@ -292,7 +308,7 @@ void AP_ICEngine::update(void) case ICE_RUNNING: if (!should_run) { state = ICE_OFF; - gcs().send_text(MAV_SEVERITY_INFO, "Stopped engine"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Stopped engine"); } #if AP_RPM_ENABLED else if (rpm_instance > 0) { @@ -302,7 +318,7 @@ 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_INFO, "Uncommanded engine stop"); } } #endif @@ -331,7 +347,7 @@ void AP_ICEngine::update(void) filtered_rpm_value = _rpm_filter.apply(rpm_value); if (!redline.flag && filtered_rpm_value > redline_rpm) { // redline governor is off. rpm is too high. enable the governor - gcs().send_text(MAV_SEVERITY_INFO, "Engine: Above redline RPM"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine: Above redline RPM"); redline.flag = true; } else if (redline.flag && filtered_rpm_value < redline_rpm * 0.9f) { // redline governor is on. rpm is safely below. disable the governor @@ -347,6 +363,8 @@ void AP_ICEngine::update(void) /* now set output channels */ switch (state) { + case ICE_DISABLED: + return; case ICE_OFF: SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, pwm_ignition_off); SRV_Channels::set_output_pwm(SRV_Channel::k_starter, pwm_starter_off); @@ -452,12 +470,15 @@ bool AP_ICEngine::throttle_override(float &percentage, const float base_throttle */ bool AP_ICEngine::engine_control(float start_control, float cold_start, float height_delay) { + if (!enable) { + return false; + } if (start_control <= 0) { state = ICE_OFF; return true; } if (state == ICE_RUNNING || state == ICE_START_DELAY || state == ICE_STARTING) { - gcs().send_text(MAV_SEVERITY_INFO, "Engine: already running"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine: already running"); return false; } RC_Channel *c = rc().channel(start_chan-1); @@ -465,7 +486,7 @@ bool AP_ICEngine::engine_control(float start_control, float cold_start, float he // get starter control channel uint16_t cvalue = c->get_radio_in(); if (cvalue >= start_chan_min_pwm && cvalue <= RC_Channel::AUX_PWM_TRIGGER_LOW) { - gcs().send_text(MAV_SEVERITY_INFO, "Engine: start control disabled"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine: start control disabled"); return false; } } @@ -474,7 +495,7 @@ bool AP_ICEngine::engine_control(float start_control, float cold_start, float he initial_height = 0; height_required = height_delay; state = ICE_START_HEIGHT_DELAY; - gcs().send_text(MAV_SEVERITY_INFO, "Takeoff height set to %.1fm", (double)height_delay); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Takeoff height set to %.1fm", (double)height_delay); return true; } state = ICE_STARTING; @@ -542,7 +563,7 @@ void AP_ICEngine::update_idle_governor(int8_t &min_throttle) // Calculate the change per loop to achieve the desired slew rate of 1 percent per second static const float idle_setpoint_step = idle_slew * AP::scheduler().get_loop_period_s(); - // Update Integrator + // Update Integrator if (underspeed) { idle_governor_integrator += idle_setpoint_step; } else { diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 2d73c91f4501d9..1c243dd88fa2c5 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -40,6 +40,7 @@ class AP_ICEngine { bool throttle_override(float &percent, const float base_throttle); enum ICE_State { + ICE_DISABLED = -1, ICE_OFF=0, ICE_START_HEIGHT_DELAY=1, ICE_START_DELAY=2, @@ -48,7 +49,7 @@ class AP_ICEngine { }; // get current engine control state - ICE_State get_state(void) const { return state; } + ICE_State get_state(void) const { return !enable?ICE_DISABLED:state; } // handle DO_ENGINE_CONTROL messages via MAVLink or mission bool engine_control(float start_control, float cold_start, float height_delay); @@ -141,9 +142,10 @@ class AP_ICEngine { float idle_governor_integrator; enum class Options : uint16_t { - DISABLE_IGNITION_RC_FAILSAFE=(1U<<0), - DISABLE_REDLINE_GOVERNOR = (1U << 1), - THROTTLE_WHILE_DISARMED = (1U << 2), + DISABLE_IGNITION_RC_FAILSAFE = (1U << 0), + DISABLE_REDLINE_GOVERNOR = (1U << 1), + THROTTLE_WHILE_DISARMED = (1U << 2), + NO_RUNNING_WHILE_DISARMED = (1U << 3), }; AP_Int16 options; diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index 2d92fd331b1fe9..9045193bb2d3b1 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -38,6 +38,10 @@ enum ioevents { IOEVENT_SET_SAFETY_MASK, IOEVENT_MIXING, IOEVENT_GPIO, + IOEVENT_SET_OUTPUT_MODE, + IOEVENT_SET_DSHOT_PERIOD, + IOEVENT_SET_CHANNEL_MASK, + IOEVENT_DSHOT, }; // max number of consecutve protocol failures we accept before raising @@ -136,6 +140,8 @@ void AP_IOMCU::thread_main(void) is_chibios_backend = (config.protocol_version == IOMCU_PROTOCOL_VERSION && config.protocol_version2 == IOMCU_PROTOCOL_VERSION2); + 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, P_SETUP_ARMING_IO_ARM_OK | @@ -214,6 +220,14 @@ void AP_IOMCU::thread_main(void) } mask &= ~EVENT_MASK(IOEVENT_SET_DEFAULT_RATE); + if (mask & EVENT_MASK(IOEVENT_SET_DSHOT_PERIOD)) { + if (!write_registers(PAGE_SETUP, PAGE_REG_SETUP_DSHOT_PERIOD, sizeof(dshot_rate)/2, (const uint16_t *)&dshot_rate)) { + event_failed(mask); + continue; + } + } + mask &= ~EVENT_MASK(IOEVENT_SET_DSHOT_PERIOD); + if (mask & EVENT_MASK(IOEVENT_SET_ONESHOT_ON)) { if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0, P_SETUP_FEATURES_ONESHOT)) { event_failed(mask); @@ -230,6 +244,22 @@ void AP_IOMCU::thread_main(void) } mask &= ~EVENT_MASK(IOEVENT_SET_BRUSHED_ON); + if (mask & EVENT_MASK(IOEVENT_SET_OUTPUT_MODE)) { + if (!write_registers(PAGE_SETUP, PAGE_REG_SETUP_OUTPUT_MODE, sizeof(mode_out)/2, (const uint16_t *)&mode_out)) { + event_failed(mask); + continue; + } + } + mask &= ~EVENT_MASK(IOEVENT_SET_OUTPUT_MODE); + + if (mask & EVENT_MASK(IOEVENT_SET_CHANNEL_MASK)) { + if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_CHANNEL_MASK, pwm_out.channel_mask)) { + event_failed(mask); + continue; + } + } + mask &= ~EVENT_MASK(IOEVENT_SET_CHANNEL_MASK); + if (mask & EVENT_MASK(IOEVENT_SET_SAFETY_MASK)) { if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_IGNORE_SAFETY, pwm_out.safety_mask)) { event_failed(mask); @@ -248,6 +278,15 @@ void AP_IOMCU::thread_main(void) mask &= ~EVENT_MASK(IOEVENT_GPIO); } + if (mask & EVENT_MASK(IOEVENT_DSHOT)) { + page_dshot dshot; + if (!dshot_command_queue.pop(dshot) || !write_registers(PAGE_DSHOT, 0, sizeof(dshot)/sizeof(uint16_t), (const uint16_t*)&dshot)) { + event_failed(mask); + continue; + } + } + mask &= ~EVENT_MASK(IOEVENT_DSHOT); + // check for regular timed events uint32_t now = AP_HAL::millis(); if (now - last_rc_read_ms > 20) { @@ -306,8 +345,8 @@ void AP_IOMCU::send_servo_out() n = MIN(n, IOMCU_MAX_CHANNELS); } uint32_t now = AP_HAL::micros(); - if (now - last_servo_out_us >= 2000) { - // don't send data at more than 500Hz + if (now - last_servo_out_us >= 2000 || AP_BoardConfig::io_dshot()) { + // don't send data at more than 500Hz except when using dshot which is more timing sensitive if (write_registers(PAGE_DIRECT_PWM, 0, n, pwm_out.pwm)) { last_servo_out_us = now; } @@ -405,10 +444,12 @@ void AP_IOMCU::write_log() static uint32_t last_io_print; if (now - last_io_print >= 5000) { last_io_print = now; - debug("t=%u num=%u mem=%u terr=%u nerr=%u crc=%u opcode=%u rd=%u wr=%u ur=%u ndel=%u\n", + debug("t=%lu num=%lu mem=%u mstack=%u pstack=%u terr=%lu nerr=%lu crc=%u opcode=%u rd=%u wr=%u ur=%u ndel=%lu\n", now, reg_status.total_pkts, reg_status.freemem, + reg_status.freemstack, + reg_status.freepstack, total_errors, reg_status.num_errors, reg_status.err_crc, @@ -508,7 +549,7 @@ 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=%u timeout read page=%u offset=%u count=%u\n", + debug("t=%lu timeout read page=%u offset=%u count=%u\n", AP_HAL::millis(), page, offset, count); protocol_fail_count++; return false; @@ -517,12 +558,12 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1 uint8_t *b = (uint8_t *)&pkt; uint8_t n = uart.available(); if (n < offsetof(struct IOPacket, regs)) { - debug("t=%u small pkt %u\n", AP_HAL::millis(), n); + debug("t=%lu small pkt %u\n", AP_HAL::millis(), n); protocol_fail_count++; return false; } if (pkt.get_size() != n) { - debug("t=%u bad len %u %u\n", AP_HAL::millis(), n, pkt.get_size()); + debug("t=%lu bad len %u %u\n", AP_HAL::millis(), n, pkt.get_size()); protocol_fail_count++; return false; } @@ -532,7 +573,7 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1 pkt.crc = 0; uint8_t expected_crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size()); if (got_crc != expected_crc) { - debug("t=%u bad crc %02x should be %02x n=%u %u/%u/%u\n", + debug("t=%lu bad crc %02x should be %02x n=%u %u/%u/%u\n", AP_HAL::millis(), got_crc, expected_crc, n, page, offset, count); protocol_fail_count++; @@ -789,6 +830,72 @@ void AP_IOMCU::set_brushed_mode(void) rate.brushed_enabled = true; } +#if HAL_DSHOT_ENABLED +// directly set the dshot rate - period_us is the dshot tick period_us and drate is the number +// of dshot ticks per main loop cycle. These values are calculated by RCOutput::set_dshot_rate() +// if the backend is free running then then period_us is fixed at 1000us and drate is 0 +void AP_IOMCU::set_dshot_period(uint16_t period_us, uint8_t drate) +{ + dshot_rate.period_us = period_us; + dshot_rate.rate = drate; + trigger_event(IOEVENT_SET_DSHOT_PERIOD); +} + +// set output mode +void AP_IOMCU::set_telem_request_mask(uint32_t mask) +{ + page_dshot dshot { + .telem_mask = uint16_t(mask) + }; + dshot_command_queue.push(dshot); + trigger_event(IOEVENT_DSHOT); +} + +void AP_IOMCU::send_dshot_command(uint8_t command, uint8_t chan, uint32_t command_timeout_ms, uint16_t repeat_count, bool priority) +{ + page_dshot dshot { + .command = command, + .chan = chan, + .command_timeout_ms = command_timeout_ms, + .repeat_count = uint8_t(repeat_count), + .priority = priority + }; + dshot_command_queue.push(dshot); + trigger_event(IOEVENT_DSHOT); +} +#endif + +// set output mode +void AP_IOMCU::set_output_mode(uint16_t mask, uint16_t mode) +{ + mode_out.mask = mask; + mode_out.mode = mode; + 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); +} + +// setup channels +void AP_IOMCU::enable_ch(uint8_t ch) +{ + if (!(pwm_out.channel_mask & (1U << ch))) { + pwm_out.channel_mask |= (1U << ch); + trigger_event(IOEVENT_SET_CHANNEL_MASK); + } +} + +void AP_IOMCU::disable_ch(uint8_t ch) +{ + if (pwm_out.channel_mask & (1U << ch)) { + pwm_out.channel_mask &= ~(1U << ch); + trigger_event(IOEVENT_SET_CHANNEL_MASK); + } +} + // handling of BRD_SAFETYOPTION parameter void AP_IOMCU::update_safety_options(void) { @@ -836,10 +943,12 @@ bool AP_IOMCU::check_crc(void) { // flash size minus 4k bootloader const uint32_t flash_size = 0x10000 - 0x1000; + const char *path = AP_BoardConfig::io_dshot() ? dshot_fw_name : fw_name; + + fw = AP_ROMFS::find_decompress(path, fw_size); - fw = AP_ROMFS::find_decompress(fw_name, fw_size); if (!fw) { - DEV_PRINTF("failed to find %s\n", fw_name); + DEV_PRINTF("failed to find %s\n", path); return false; } uint32_t crc = crc32_small(0, fw, fw_size); @@ -932,6 +1041,16 @@ void AP_IOMCU::shutdown(void) } } +/* + reboot IOMCU + */ +void AP_IOMCU::soft_reboot(void) +{ + const uint16_t magic = REBOOT_BL_MAGIC; + write_registers(PAGE_SETUP, PAGE_REG_SETUP_REBOOT_BL, 1, &magic); +} + + /* request bind on a DSM radio */ @@ -1048,7 +1167,7 @@ void AP_IOMCU::check_iomcu_reset(void) #endif // when we are in an expected delay allow for a larger time // delta. This copes with flash erase, such as bootloader update - const uint32_t max_delay = hal.scheduler->in_expected_delay()?5000:500; + const uint32_t max_delay = hal.scheduler->in_expected_delay()?8000:500; last_iocmu_timestamp_ms = reg_status.timestamp_ms; if (dt_ms < max_delay) { @@ -1083,6 +1202,9 @@ void AP_IOMCU::check_iomcu_reset(void) } trigger_event(IOEVENT_SET_RATES); trigger_event(IOEVENT_SET_DEFAULT_RATE); + trigger_event(IOEVENT_SET_DSHOT_PERIOD); + trigger_event(IOEVENT_SET_OUTPUT_MODE); + trigger_event(IOEVENT_SET_CHANNEL_MASK); if (rate.oneshot_enabled) { trigger_event(IOEVENT_SET_ONESHOT_ON); } diff --git a/libraries/AP_IOMCU/AP_IOMCU.h b/libraries/AP_IOMCU/AP_IOMCU.h index df9729701798f0..794844a950ab9b 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.h +++ b/libraries/AP_IOMCU/AP_IOMCU.h @@ -12,6 +12,7 @@ #include "iofirmware/ioprotocol.h" #include +#include typedef uint32_t eventmask_t; typedef struct ch_thread thread_t; @@ -98,12 +99,40 @@ class AP_IOMCU { // set to brushed mode void set_brushed_mode(void); + // set output mode + void set_output_mode(uint16_t mask, uint16_t mode); + + // get output mode + AP_HAL::RCOutput::output_mode get_output_mode(uint8_t& mask) const; + + // MCUID + uint32_t get_mcu_id() const { return config.mcuid; } + + // CPUID + uint32_t get_cpu_id() const { return config.cpuid; } + +#if HAL_DSHOT_ENABLED + // set dshot output period + void set_dshot_period(uint16_t period_us, uint8_t drate); + + // set telem request mask + void set_telem_request_mask(uint32_t mask); + + // send a dshot command + void send_dshot_command(uint8_t command, uint8_t chan, uint32_t command_timeout_ms, uint16_t repeat_count, bool priority); +#endif + // setup channels + void enable_ch(uint8_t ch); + void disable_ch(uint8_t ch); + // check if IO is healthy bool healthy(void); // shutdown IO protocol (for reboot) void shutdown(); + void soft_reboot(); + // setup for FMU failsafe mixing bool setup_mixing(RCMapper *rcmap, int8_t override_chan, float mixing_gain, uint16_t manual_rc_mask); @@ -204,6 +233,7 @@ class AP_IOMCU { uint16_t failsafe_pwm[IOMCU_MAX_CHANNELS]; uint8_t failsafe_pwm_set; uint8_t failsafe_pwm_sent; + uint16_t channel_mask; } pwm_out; // read back pwm values @@ -221,7 +251,20 @@ class AP_IOMCU { bool brushed_enabled; } rate; + struct { + uint16_t period_us; + uint16_t rate; + } dshot_rate; + + // queue of dshot commands that need sending + ObjectBuffer dshot_command_queue{8}; + struct page_GPIO GPIO; + // output mode values + struct { + uint16_t mask; + uint16_t mode; + } mode_out; // IMU heater duty cycle uint8_t heater_duty_cycle; @@ -248,6 +291,7 @@ class AP_IOMCU { // firmware upload const char *fw_name = "io_firmware.bin"; + const char *dshot_fw_name = "io_firmware_dshot.bin"; const uint8_t *fw; uint32_t fw_size; diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 70a6aa6aa84dd6..3050a5b8e07cb4 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -20,7 +20,6 @@ #include #include #include "iofirmware.h" -#include "hal.h" #include #include #include "analog.h" @@ -39,6 +38,9 @@ static AP_IOMCU_FW iomcu; void setup(); void loop(); +#undef CH_DBG_ENABLE_STACK_CHECK +#define CH_DBG_ENABLE_STACK_CHECK FALSE + const AP_HAL::HAL& hal = AP_HAL::get_HAL(); /* @@ -49,82 +51,199 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); */ #define IOMCU_ENABLE_RESET_TEST 0 +// enable timing GPIO pings +#ifdef IOMCU_LOOP_TIMING_DEBUG +#undef TOGGLE_PIN_DEBUG +#define TOGGLE_PIN_DEBUG(pin) do { palToggleLine(HAL_GPIO_LINE_GPIO ## pin); } while (0) +#endif + // pending events on the main thread enum ioevents { - IOEVENT_PWM=1, + IOEVENT_PWM = EVENT_MASK(1), + IOEVENT_TX_BEGIN = EVENT_MASK(2), + IOEVENT_TX_END = EVENT_MASK(3), }; -static void dma_rx_end_cb(UARTDriver *uart) +// see https://github.com/MaJerle/stm32-usart-uart-dma-rx-tx for a discussion of how to run +// separate tx and rx streams +static void setup_rx_dma(hal_uart_driver* uart) { - osalSysLockFromISR(); - uart->usart->CR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR); - - (void)uart->usart->SR; - (void)uart->usart->DR; - (void)uart->usart->DR; + uart->usart->CR3 &= ~USART_CR3_DMAR; dmaStreamDisable(uart->dmarx); - dmaStreamDisable(uart->dmatx); - - iomcu.process_io_packet(); - dmaStreamSetMemory0(uart->dmarx, &iomcu.rx_io_packet); dmaStreamSetTransactionSize(uart->dmarx, sizeof(iomcu.rx_io_packet)); + dmaStreamSetPeripheral(uart->dmarx, &(uart->usart->DR)); dmaStreamSetMode(uart->dmarx, uart->dmarxmode | STM32_DMA_CR_DIR_P2M | STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE); dmaStreamEnable(uart->dmarx); uart->usart->CR3 |= USART_CR3_DMAR; +} +static void setup_tx_dma(hal_uart_driver* uart) +{ + uart->usart->CR3 &= ~USART_CR3_DMAT; + dmaStreamDisable(uart->dmatx); dmaStreamSetMemory0(uart->dmatx, &iomcu.tx_io_packet); dmaStreamSetTransactionSize(uart->dmatx, iomcu.tx_io_packet.get_size()); + // starting the UART allocates the peripheral statically, so we need to reinstate it after swapping + dmaStreamSetPeripheral(uart->dmatx, &(uart->usart->DR)); 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->CR1 |= USART_CR1_TCIE; + dmaStreamEnable(uart->dmatx); + uart->usart->CR3 |= USART_CR3_DMAT; - osalSysUnlockFromISR(); } -static void idle_rx_handler(UARTDriver *uart) +static void dma_rx_end_cb(hal_uart_driver *uart) +{ + chSysLockFromISR(); + uart->usart->CR3 &= ~USART_CR3_DMAR; + + (void)uart->usart->SR; // sequence to clear IDLE status + (void)uart->usart->DR; + (void)uart->usart->DR; + dmaStreamDisable(uart->dmarx); + + iomcu.process_io_packet(); + + setup_rx_dma(uart); + +#if AP_HAL_SHARED_DMA_ENABLED + // indicate that a response needs to be sent + uint32_t mask = chEvtGetAndClearEventsI(IOEVENT_TX_BEGIN); + if (mask) { + iomcu.reg_status.err_lock++; + } + // the FMU code waits 10ms for a reply so this should be easily fast enough + chEvtSignalI(iomcu.thread_ctx, IOEVENT_TX_BEGIN); +#else + setup_tx_dma(uart); +#endif + chSysUnlockFromISR(); +} + +static void dma_tx_end_cb(hal_uart_driver *uart) +{ + // DMA stream has already been disabled at this point + uart->usart->CR3 &= ~USART_CR3_DMAT; + + (void)uart->usart->SR; + (void)uart->usart->DR; + (void)uart->usart->DR; + + TOGGLE_PIN_DEBUG(108); + TOGGLE_PIN_DEBUG(108); + + chEvtSignalI(iomcu.thread_ctx, IOEVENT_TX_END); +} + +/* replacement for ChibiOS uart_lld_serve_interrupt() */ +static void idle_rx_handler(hal_uart_driver *uart) { - volatile uint16_t sr = uart->usart->SR; + volatile uint16_t sr; + sr = uart->usart->SR; /* SR reset step 1.*/ + uint32_t cr1 = uart->usart->CR1; if (sr & (USART_SR_LBD | USART_SR_ORE | /* overrun error - packet was too big for DMA or DMA was too slow */ USART_SR_NE | /* noise error - we have lost a byte due to noise */ USART_SR_FE | USART_SR_PE)) { /* framing error - start/stop bit lost or line break */ /* send a line break - this will abort transmission/reception on the other end */ - osalSysLockFromISR(); + chSysLockFromISR(); + uart->usart->SR = ~USART_SR_LBD; - uart->usart->CR1 |= USART_CR1_SBK; + uart->usart->CR1 = cr1 | USART_CR1_SBK; iomcu.reg_status.num_errors++; iomcu.reg_status.err_uart++; - uart->usart->CR3 &= ~(USART_CR3_DMAT | USART_CR3_DMAR); - (void)uart->usart->SR; + + uart->usart->CR3 &= ~USART_CR3_DMAR; + + (void)uart->usart->SR; // clears ORE | FE (void)uart->usart->DR; (void)uart->usart->DR; - dmaStreamDisable(uart->dmarx); - dmaStreamDisable(uart->dmatx); + setup_rx_dma(uart); - dmaStreamSetMemory0(uart->dmarx, &iomcu.rx_io_packet); - dmaStreamSetTransactionSize(uart->dmarx, sizeof(iomcu.rx_io_packet)); - dmaStreamSetMode(uart->dmarx, uart->dmarxmode | STM32_DMA_CR_DIR_P2M | - STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE); - dmaStreamEnable(uart->dmarx); - uart->usart->CR3 |= USART_CR3_DMAR; - osalSysUnlockFromISR(); + chSysUnlockFromISR(); return; } + if ((sr & USART_SR_TC) && (cr1 & USART_CR1_TCIE)) { + chSysLockFromISR(); + + /* TC interrupt cleared and disabled.*/ + uart->usart->SR &= ~USART_SR_TC; + uart->usart->CR1 = cr1 & ~USART_CR1_TCIE; + + /* End of transmission, a callback is generated.*/ + _uart_tx2_isr_code(uart); + + chSysUnlockFromISR(); + } + if (sr & USART_SR_IDLE) { + /* the DMA size is the maximum packet size, but smaller packets are perfectly possible leading to + an IDLE ISR. The data still must be processed. */ dma_rx_end_cb(uart); } } +using namespace ChibiOS; + +#if AP_HAL_SHARED_DMA_ENABLED +/* + copy of uart_lld_serve_tx_end_irq() from ChibiOS hal_uart_lld + that is re-instated upon switching the DMA channel + */ +static void uart_lld_serve_tx_end_irq(hal_uart_driver *uart, uint32_t flags) +{ + dmaStreamDisable(uart->dmatx); + + /* A callback is generated, if enabled, after a completed transfer.*/ + _uart_tx1_isr_code(uart); +} + +void AP_IOMCU_FW::tx_dma_allocate(Shared_DMA *ctx) +{ + hal_uart_driver *uart = &UARTD2; + chSysLock(); + if (uart->dmatx == nullptr) { + uart->dmatx = dmaStreamAllocI(STM32_UART_USART2_TX_DMA_STREAM, + STM32_UART_USART2_IRQ_PRIORITY, + (stm32_dmaisr_t)uart_lld_serve_tx_end_irq, + (void *)uart); + } + chSysUnlock(); +} + +/* + deallocate DMA channel + */ +void AP_IOMCU_FW::tx_dma_deallocate(Shared_DMA *ctx) +{ + hal_uart_driver *uart = &UARTD2; + chSysLock(); + if (uart->dmatx != nullptr) { + // defensively make sure the DMA is fully shutdown before swapping + uart->usart->CR3 &= ~USART_CR3_DMAT; + dmaStreamDisable(uart->dmatx); + dmaStreamSetPeripheral(uart->dmatx, nullptr); + dmaStreamFreeI(uart->dmatx); + uart->dmatx = nullptr; + } + chSysUnlock(); +} +#endif // AP_HAL_SHARED_DMA_ENABLED + /* * UART driver configuration structure. */ static UARTConfig uart_cfg = { nullptr, - nullptr, + dma_tx_end_cb, dma_rx_end_cb, nullptr, nullptr, @@ -140,16 +259,19 @@ void setup(void) { hal.rcin->init(); hal.rcout->init(); - - for (uint8_t i = 0; i< 14; i++) { - hal.rcout->enable_ch(i); - } - iomcu.init(); iomcu.calculate_fw_crc(); + uartStart(&UARTD2, &uart_cfg); uartStartReceive(&UARTD2, sizeof(iomcu.rx_io_packet), &iomcu.rx_io_packet); +#if AP_HAL_SHARED_DMA_ENABLED + iomcu.tx_dma_handle->unlock(); +#endif + // disable the pieces from the UART which will get enabled later + chSysLock(); + UARTD2.usart->CR3 &= ~USART_CR3_DMAT; + chSysUnlock(); } void loop(void) @@ -163,9 +285,26 @@ void AP_IOMCU_FW::init() // old NuttX based firmwares config.protocol_version = IOMCU_PROTOCOL_VERSION; config.protocol_version2 = IOMCU_PROTOCOL_VERSION2; + config.mcuid = (*(uint32_t *)DBGMCU_BASE); +#if defined(STM32F103xB) || defined(STM32F103x8) + if (config.mcuid == 0) { + // Errata 2.2.2 - Debug registers cannot be read by user software + config.mcuid = 0x20036410; // STM32F10x (Medium Density) rev Y + } +#endif + config.cpuid = SCB->CPUID; 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, + 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(); + // deallocate so that the uart initializes correctly + tx_dma_deallocate(tx_dma_handle); +#endif + if (palReadLine(HAL_GPIO_PIN_IO_HW_DETECT1) == 1 && palReadLine(HAL_GPIO_PIN_IO_HW_DETECT2) == 0) { has_heater = true; } @@ -184,7 +323,7 @@ void AP_IOMCU_FW::init() palSetLineMode(HAL_GPIO_PIN_SPEKTRUM_PWR_EN, PAL_MODE_OUTPUT_PUSHPULL); SPEKTRUM_POWER(1); - // we do no allocations after setup completes + // we generally do no allocations after setup completes reg_status.freemem = hal.util->available_memory(); if (hal.util->was_watchdog_safety_off()) { @@ -194,11 +333,112 @@ void AP_IOMCU_FW::init() } +#if CH_DBG_ENABLE_STACK_CHECK == TRUE +static void stackCheck(uint16_t& mstack, uint16_t& pstack) { + extern uint32_t __main_stack_base__[]; + extern uint32_t __main_stack_end__[]; + uint32_t stklimit = (uint32_t)__main_stack_end__; + uint32_t stkbase = (uint32_t)__main_stack_base__; + uint32_t *crawl = (uint32_t *)stkbase; + + while (*crawl == 0x55555555 && crawl < (uint32_t *)stklimit) { + crawl++; + } + uint32_t free = (uint32_t)crawl - stkbase; + chDbgAssert(free > 0, "mstack exhausted"); + mstack = (uint16_t)free; + + extern uint32_t __main_thread_stack_base__[]; + extern uint32_t __main_thread_stack_end__[]; + stklimit = (uint32_t)__main_thread_stack_end__; + stkbase = (uint32_t)__main_thread_stack_base__; + crawl = (uint32_t *)stkbase; + + while (*crawl == 0x55555555 && crawl < (uint32_t *)stklimit) { + crawl++; + } + free = (uint32_t)crawl - stkbase; + chDbgAssert(free > 0, "pstack exhausted"); + pstack = (uint16_t)free; +} +#endif /* CH_DBG_ENABLE_STACK_CHECK == TRUE */ + +/* + Update loop design. + + Considerations - the F100 is quite slow and so processing time needs to be used effectively. + The CPU time slices required by dshot are generally faster than those required for other processing. + Dshot requires even updates at at least 1Khz and generally faster if SERVO_DSHOT_RATE is used. + The two most time sensitive regular functions are (1) PWM updates which run at loop rate triggered from the FMU + (and thus require efficient code page write) and (2) rcin updates which run at a fixed 1Khz cycle (a speed + which is assumed by the rcin protocol handlers) and require efficient code read. The FMU sends code page + requests which require a response within 10ms in order to prevent the IOMCU being considered to have failed, + however code page requests are always initiated by the FMU and so the IOMCU only ever needs to be ready + to read requests - writing responses are always in response to a request. Finally, PWM channels 3-4 share a DMA + channel with UART TX and so access needs to be mediated. + + Design - + 1. requests are read using circular DMA. In other words the RX side of the UART is always ready. Once + a request has been processed DMA is immediately set up for a new request. + 2. responses are only ever sent in response to a request. As soon as a request is received the ISR only + ever requests that a response be sent - it never actually sends a response. + 3. The update loop waits for four different events: + 3a - a request has been received and should be processed. This does not require the TX DMA lock. + 3b - a response needs to be sent. This requires the TX DMA lock. + 3c - a response has been sent. This allows the TX DMA lock to be released. + 3d - an out of band PWM request, usually triggered by a failsafe needs to be processed. + Since requests are processed continuously it is possible for 3b and 3c to occur simultaneously. Since the + TX lock is already held to send the previous response, there is no need to do anything with the lock in order + to process the next response. + + Profiling shows that sending a response takes very little time - 10s of microseconds - and so a response is sent + if required at the beginning of the update. This means that by the end of the update there is a very high chance + that the response will have already been sent and this is therefore checked. If the response has been sent the + lock is released. If for some reason the response has not gone out, as soon as it does an event will be posted + and the update loop will run again. + + This design means that on average the update loop is idle with the TX DMA channel unlocked. This maximises the + time that dshot can run uninterrupted leading to very efficient and even output. + + Finally the update loop has a timeout which forces updates to progress even in the absence of requests from the + FMU. Since responses will always be triggered in a timely fashion, regardlesss of the timeout, this can be + set relatively long. + + If compiled without sharing, DMA - and thus dshot - is not used on channels 3-4, there are no locks and responses + are always setup in the request ISR handler. +*/ void AP_IOMCU_FW::update() { +#if CH_CFG_ST_FREQUENCY == 1000000 + eventmask_t mask = chEvtWaitAnyTimeout(IOEVENT_PWM | IOEVENT_TX_END | IOEVENT_TX_BEGIN, TIME_US2I(1000)); +#else // we are not running any other threads, so we can use an // immediate timeout here for lowest latency - eventmask_t mask = chEvtWaitAnyTimeout(~0, TIME_IMMEDIATE); + eventmask_t mask = chEvtWaitAnyTimeout(IOEVENT_PWM | IOEVENT_TX_END, TIME_IMMEDIATE); +#endif + + TOGGLE_PIN_DEBUG(107); + + iomcu.reg_status.total_ticks++; + if (mask) { + iomcu.reg_status.total_events++; + } + +#if AP_HAL_SHARED_DMA_ENABLED + // See discussion above + if ((mask & IOEVENT_TX_BEGIN) && !(mask & IOEVENT_TX_END)) { // 3b - lock required to send response + tx_dma_handle->lock(); + } else if (!(mask & IOEVENT_TX_BEGIN) && (mask & IOEVENT_TX_END)) { // 3c - response sent, lock can be released + tx_dma_handle->unlock(); + } // else 3b and 3c - current lock required for new response + + // send a response if required + if (mask & IOEVENT_TX_BEGIN) { + chSysLock(); + setup_tx_dma(&UARTD2); + chSysUnlock(); + } +#endif // we get the timestamp once here, and avoid fetching it // within the DMA callbacks @@ -209,16 +449,16 @@ void AP_IOMCU_FW::update() hal.scheduler->reboot(true); while (true) {} } - - if ((mask & EVENT_MASK(IOEVENT_PWM)) || + if ((mask & IOEVENT_PWM) || (last_safety_off != reg_status.flag_safety_off)) { last_safety_off = reg_status.flag_safety_off; pwm_out_update(); } uint32_t now = last_ms; - reg_status.timestamp_ms = last_ms; + uint32_t now_us = AP_HAL::micros(); + reg_status.timestamp_ms = last_ms; // output SBUS if enabled if ((reg_setup.features & P_SETUP_FEATURES_SBUS1_OUT) && reg_status.flag_safety_off && @@ -227,13 +467,12 @@ void AP_IOMCU_FW::update() sbus_last_ms = now; sbus_out_write(reg_servo.pwm, IOMCU_MAX_CHANNELS); } - // handle FMU failsafe if (now - fmu_data_received_time > 200) { // we are not getting input from the FMU. Fill in failsafe values at 100Hz if (now - last_failsafe_ms > 10) { fill_failsafe_pwm(); - chEvtSignal(thread_ctx, EVENT_MASK(IOEVENT_PWM)); + chEvtSignal(thread_ctx, IOEVENT_PWM); last_failsafe_ms = now; } // turn amber on @@ -243,27 +482,46 @@ void AP_IOMCU_FW::update() // turn amber off AMBER_SET(0); } - // update status page at 20Hz if (now - last_status_ms > 50) { last_status_ms = now; page_status_update(); } - // run remaining functions at 1kHz - if (now != last_loop_ms) { - last_loop_ms = now; + // run fast loop functions at 1Khz + if (now_us - last_fast_loop_us >= 1000) + { + last_fast_loop_us = now_us; heater_update(); rcin_update(); - safety_update(); - rcout_mode_update(); rcin_serial_update(); + } + + // run remaining functions at 100Hz + // these are all relatively expensive and take ~10ms to complete + // so there is no way they can effectively be run faster than 100Hz + if (now - last_slow_loop_ms > 10) { + last_slow_loop_ms = now; + safety_update(); + rcout_config_update(); hal.rcout->timer_tick(); if (dsm_bind_state) { dsm_bind_step(); } GPIO_write(); +#if CH_DBG_ENABLE_STACK_CHECK == TRUE + stackCheck(reg_status.freemstack, reg_status.freepstack); +#endif + } +#if AP_HAL_SHARED_DMA_ENABLED + // check whether a response has now been sent + mask = chEvtGetAndClearEvents(IOEVENT_TX_END); + + if (mask) { + tx_dma_handle->unlock(); } +#endif + TOGGLE_PIN_DEBUG(107); } void AP_IOMCU_FW::pwm_out_update() @@ -341,7 +599,7 @@ void AP_IOMCU_FW::rcin_update() if (override_active) { fill_failsafe_pwm(); } - chEvtSignal(thread_ctx, EVENT_MASK(IOEVENT_PWM)); + chEvtSignal(thread_ctx, IOEVENT_PWM); } } @@ -513,6 +771,14 @@ bool AP_IOMCU_FW::handle_code_write() reg_setup.pwm_defaultrate = rx_io_packet.regs[0]; update_default_rate = true; break; + case PAGE_REG_SETUP_DSHOT_PERIOD: + reg_setup.dshot_period_us = rx_io_packet.regs[0]; + reg_setup.dshot_rate = rx_io_packet.regs[1]; + hal.rcout->set_dshot_period(reg_setup.dshot_period_us, reg_setup.dshot_rate); + break; + case PAGE_REG_SETUP_CHANNEL_MASK: + reg_setup.channel_mask = rx_io_packet.regs[0]; + break; case PAGE_REG_SETUP_SBUS_RATE: reg_setup.sbus_rate = rx_io_packet.regs[0]; sbus_interval_ms = MAX(1000U / reg_setup.sbus_rate,3); @@ -541,6 +807,11 @@ bool AP_IOMCU_FW::handle_code_write() } break; + case PAGE_REG_SETUP_OUTPUT_MODE: + mode_out.mask = rx_io_packet.regs[0]; + mode_out.mode = rx_io_packet.regs[1]; + break; + case PAGE_REG_SETUP_HEATER_DUTY_CYCLE: reg_setup.heater_duty_cycle = rx_io_packet.regs[0]; last_heater_ms = last_ms; @@ -605,7 +876,7 @@ bool AP_IOMCU_FW::handle_code_write() i++; } fmu_data_received_time = last_ms; - chEvtSignalI(thread_ctx, EVENT_MASK(IOEVENT_PWM)); + chEvtSignalI(thread_ctx, IOEVENT_PWM); break; } @@ -632,18 +903,23 @@ bool AP_IOMCU_FW::handle_code_write() return false; } memcpy(&GPIO, &rx_io_packet.regs[0] + rx_io_packet.offset, sizeof(GPIO)); - if (GPIO.channel_mask != last_GPIO_channel_mask) { - for (uint8_t i=0; i<8; i++) { - if ((GPIO.channel_mask & (1U << i)) != 0) { - hal.rcout->disable_ch(i); - hal.gpio->pinMode(101+i, HAL_GPIO_OUTPUT); - } else { - hal.rcout->enable_ch(i); - } - } - last_GPIO_channel_mask = GPIO.channel_mask; + break; + + case PAGE_DSHOT: { + uint16_t offset = rx_io_packet.offset, num_values = rx_io_packet.count; + if (offset + num_values > sizeof(dshot)/2) { + return false; + } + memcpy(((uint16_t *)&dshot)+offset, &rx_io_packet.regs[0], num_values*2); + if(dshot.telem_mask) { + hal.rcout->set_telem_request_mask(dshot.telem_mask); } + if (dshot.command) { + hal.rcout->send_dshot_command(dshot.command, dshot.chan, dshot.command_timeout_ms, dshot.repeat_count, dshot.priority); + } + break; + } default: break; @@ -758,26 +1034,71 @@ void AP_IOMCU_FW::safety_update(void) /* update hal.rcout mode if needed */ -void AP_IOMCU_FW::rcout_mode_update(void) +void AP_IOMCU_FW::rcout_config_update(void) { - bool use_oneshot = (reg_setup.features & P_SETUP_FEATURES_ONESHOT) != 0; - if (use_oneshot && !oneshot_enabled) { - oneshot_enabled = true; - hal.rcout->set_output_mode(reg_setup.pwm_rates, AP_HAL::RCOutput::MODE_PWM_ONESHOT); - } - bool use_brushed = (reg_setup.features & P_SETUP_FEATURES_BRUSHED) != 0; - if (use_brushed && !brushed_enabled) { - brushed_enabled = true; - if (reg_setup.pwm_rates == 0) { - // default to 2kHz for all channels for brushed output - reg_setup.pwm_rates = 0xFF; - reg_setup.pwm_altrate = 2000; - hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate); + // channels cannot be changed from within a lock zone + // so needs to be done here + if (GPIO.channel_mask != last_GPIO_channel_mask) { + for (uint8_t i=0; i<8; i++) { + if ((GPIO.channel_mask & (1U << i)) != 0) { + hal.rcout->disable_ch(i); + hal.gpio->pinMode(101+i, HAL_GPIO_OUTPUT); + } else { + hal.rcout->enable_ch(i); + } + } + last_GPIO_channel_mask = GPIO.channel_mask; + } + + if (last_channel_mask != reg_setup.channel_mask) { + for (uint8_t i=0; ienable_ch(i); + } else { + hal.rcout->disable_ch(i); + } } + last_channel_mask = reg_setup.channel_mask; + } + + // 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) { + return; + } + + switch (mode_out.mode) { + case AP_HAL::RCOutput::MODE_PWM_DSHOT150: + case AP_HAL::RCOutput::MODE_PWM_DSHOT300: +#if defined(STM32F103xB) || defined(STM32F103x8) + case AP_HAL::RCOutput::MODE_PWM_DSHOT600: +#endif + 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; + break; + case AP_HAL::RCOutput::MODE_PWM_ONESHOT: + case AP_HAL::RCOutput::MODE_PWM_ONESHOT125: + // setup to use a 1Hz frequency, so we only get output when we trigger + hal.rcout->set_freq(mode_out.mask, 1); + hal.rcout->set_output_mode(mode_out.mask, (AP_HAL::RCOutput::output_mode)mode_out.mode); + last_output_mode_mask |= mode_out.mask; + break; + case AP_HAL::RCOutput::MODE_PWM_BRUSHED: + // default to 2kHz for all channels for brushed output + hal.rcout->set_freq(mode_out.mask, 2000); hal.rcout->set_esc_scaling(1000, 2000); - hal.rcout->set_output_mode(reg_setup.pwm_rates, AP_HAL::RCOutput::MODE_PWM_BRUSHED); - hal.rcout->set_freq(reg_setup.pwm_rates, reg_setup.pwm_altrate); + hal.rcout->set_output_mode(mode_out.mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED); + hal.rcout->set_freq(mode_out.mask, reg_setup.pwm_altrate); + last_output_mode_mask |= mode_out.mask; + break; + default: + break; } + + uint32_t output_mask = 0; + reg_status.rcout_mode = hal.rcout->get_output_mode(output_mask); + reg_status.rcout_mask = uint8_t(0xFF & output_mask); } /* diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.h b/libraries/AP_IOMCU/iofirmware/iofirmware.h index 8aef68165db7ae..62c8b12565b6e8 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.h +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.h @@ -5,10 +5,14 @@ #include #include - +#include "hal.h" #include "ch.h" #include "ioprotocol.h" +#if AP_HAL_SHARED_DMA_ENABLED +#include +#endif + #define PWM_IGNORE_THIS_CHANNEL UINT16_MAX #define SERVO_COUNT 8 @@ -30,7 +34,7 @@ class AP_IOMCU_FW { bool handle_code_read(); void schedule_reboot(uint32_t time_ms); void safety_update(); - void rcout_mode_update(); + void rcout_config_update(); void rcin_serial_init(); void rcin_serial_update(); void page_status_update(void); @@ -67,8 +71,13 @@ class AP_IOMCU_FW { uint16_t ignore_safety; uint16_t heater_duty_cycle = 0xFFFFU; uint16_t pwm_altclock = 1; + uint16_t dshot_period_us; + uint16_t dshot_rate; + uint16_t channel_mask; } reg_setup; + uint16_t last_channel_mask; + // CONFIG values struct page_config config; @@ -102,6 +111,14 @@ class AP_IOMCU_FW { uint16_t sbus_rate_hz; } rate; + // output mode values + struct { + uint16_t mask; + uint16_t mode; + } mode_out; + + uint16_t last_output_mode_mask; + // MIXER values struct page_mixing mixing; @@ -110,6 +127,16 @@ class AP_IOMCU_FW { uint8_t last_GPIO_channel_mask; void GPIO_write(); + // DSHOT runtime + struct page_dshot dshot; + +#if AP_HAL_SHARED_DMA_ENABLED + void tx_dma_allocate(ChibiOS::Shared_DMA *ctx); + void tx_dma_deallocate(ChibiOS::Shared_DMA *ctx); + + ChibiOS::Shared_DMA* tx_dma_handle; +#endif + // true when override channel active bool override_active; @@ -118,6 +145,8 @@ class AP_IOMCU_FW { uint32_t sbus_interval_ms; uint32_t fmu_data_received_time; + + bool pwm_update_pending; uint32_t last_heater_ms; uint32_t reboot_time; bool do_reboot; @@ -129,9 +158,8 @@ class AP_IOMCU_FW { uint32_t safety_update_ms; uint32_t safety_button_counter; uint8_t led_counter; - uint32_t last_loop_ms; - bool oneshot_enabled; - bool brushed_enabled; + uint32_t last_slow_loop_ms; + uint32_t last_fast_loop_us; thread_t *thread_ctx; bool last_safety_off; uint32_t last_status_ms; diff --git a/libraries/AP_IOMCU/iofirmware/ioprotocol.h b/libraries/AP_IOMCU/iofirmware/ioprotocol.h index 85d4b9c4bcaa24..21b0a4263a07c9 100644 --- a/libraries/AP_IOMCU/iofirmware/ioprotocol.h +++ b/libraries/AP_IOMCU/iofirmware/ioprotocol.h @@ -2,6 +2,7 @@ #include #include + /* common protocol definitions between AP_IOMCU and iofirmware */ @@ -56,6 +57,7 @@ enum iopage { PAGE_FAILSAFE_PWM = 55, PAGE_MIXING = 200, PAGE_GPIO = 201, + PAGE_DSHOT = 202, }; // setup page registers @@ -78,6 +80,7 @@ enum iopage { #define PAGE_REG_SETUP_PWM_RATE_MASK 2 #define PAGE_REG_SETUP_DEFAULTRATE 3 #define PAGE_REG_SETUP_ALTRATE 4 +#define PAGE_REG_SETUP_OUTPUT_MODE 5 #define PAGE_REG_SETUP_REBOOT_BL 10 #define PAGE_REG_SETUP_CRC 11 #define PAGE_REG_SETUP_SBUS_RATE 19 @@ -85,6 +88,8 @@ enum iopage { #define PAGE_REG_SETUP_HEATER_DUTY_CYCLE 21 #define PAGE_REG_SETUP_DSM_BIND 22 #define PAGE_REG_SETUP_RC_PROTOCOLS 23 // uses 2 slots, 23 and 24 +#define PAGE_REG_SETUP_DSHOT_PERIOD 25 +#define PAGE_REG_SETUP_CHANNEL_MASK 27 // config page registers #define PAGE_CONFIG_PROTOCOL_VERSION 0 @@ -102,21 +107,30 @@ enum iopage { struct page_config { uint16_t protocol_version; uint16_t protocol_version2; + uint32_t mcuid; + uint32_t cpuid; }; struct page_reg_status { uint16_t freemem; + uint16_t freemstack; + uint16_t freepstack; uint32_t timestamp_ms; uint16_t vservo; uint16_t vrssi; uint32_t num_errors; uint32_t total_pkts; + uint32_t total_ticks; + uint32_t total_events; uint8_t flag_safety_off; + uint8_t rcout_mask; + uint8_t rcout_mode; uint8_t err_crc; uint8_t err_bad_opcode; uint8_t err_read; uint8_t err_write; uint8_t err_uart; + uint8_t err_lock; }; struct page_rc_input { @@ -169,3 +183,12 @@ struct __attribute__((packed, aligned(2))) page_GPIO { uint8_t channel_mask; uint8_t output_mask; }; + +struct __attribute__((packed, aligned(2))) page_dshot { + uint16_t telem_mask; + uint8_t command; + uint8_t chan; + uint32_t command_timeout_ms; + uint8_t repeat_count; + uint8_t priority; +}; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 7c80d92066024a..c83bd987d3fb79 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -674,6 +674,13 @@ const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { AP_SUBGROUPINFO(params[1], "5_", 55, AP_InertialSensor, AP_InertialSensor_Params), #endif + // @Param: _RAW_LOG_OPT + // @DisplayName: Raw logging options + // @Description: Raw logging options bitmask + // @Bitmask: 0:Log primary gyro only, 1:Log all gyros, 2:Post filter, 3: Pre and post filter + // @User: Advanced + AP_GROUPINFO("_RAW_LOG_OPT", 56, AP_InertialSensor, raw_logging_options, 0), + /* NOTE: parameter indexes have gaps above. When adding new parameters check for conflicts carefully @@ -888,6 +895,11 @@ AP_InertialSensor::init(uint16_t loop_rate) // cause divergence of state estimators _loop_delta_t_max = 10 * _loop_delta_t; + // Initialize notch params + for (auto ¬ch : harmonic_notches) { + notch.params.init(); + } + if (_gyro_count == 0 && _accel_count == 0) { _start_backends(); } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 1f00247aba8b2f..27d21e1137d164 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -766,6 +766,18 @@ class AP_InertialSensor : AP_AccelCal_Client AP_Int32 tcal_options; bool tcal_learning; #endif + + // Raw logging options bitmask and parameter + enum class RAW_LOGGING_OPTION { + PRIMARY_GYRO_ONLY = (1U<<0), + ALL_GYROS = (1U<<1), + POST_FILTER = (1U<<2), + PRE_AND_POST_FILTER = (1U<<3), + }; + AP_Int16 raw_logging_options; + bool raw_logging_option_set(RAW_LOGGING_OPTION option) const { + return (raw_logging_options.get() & int32_t(option)) != 0; + } }; namespace AP { diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp index dcbbf22046e237..aa839b6b4e6bbc 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_BMI088.cpp @@ -400,7 +400,7 @@ void AP_InertialSensor_BMI088::read_fifo_gyro(void) } const float scale = radians(2000.0f) / 32767.0f; const uint8_t max_frames = 8; - const Vector3i bad_frame{int16_t(0xffff), int16_t(0xffff), int16_t(0xffff)}; + const Vector3i bad_frame{INT16_MIN,INT16_MIN,INT16_MIN}; Vector3i data[max_frames]; if (num_frames & 0x80) { diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp index 88b780964e7911..9b2954ef86a493 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp @@ -343,17 +343,7 @@ void AP_InertialSensor_Backend::_notify_new_gyro_raw_sample(uint8_t instance, } // 5us -#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED - if (!_imu.batchsampler.doing_post_filter_logging()) { - log_gyro_raw(instance, sample_us, gyro); - } - else { - log_gyro_raw(instance, sample_us, _imu._gyro_filtered[instance]); - } -#else - // assume pre-filter logging if batchsampler is not enabled - log_gyro_raw(instance, sample_us, gyro); -#endif + log_gyro_raw(instance, sample_us, gyro, _imu._gyro_filtered[instance]); } /* @@ -440,20 +430,10 @@ void AP_InertialSensor_Backend::_notify_new_delta_angle(uint8_t instance, const _imu._new_gyro_data[instance] = true; } -#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED - if (!_imu.batchsampler.doing_post_filter_logging()) { - log_gyro_raw(instance, sample_us, gyro); - } - else { - log_gyro_raw(instance, sample_us, _imu._gyro_filtered[instance]); - } -#else - // assume we're doing pre-filter logging: - log_gyro_raw(instance, sample_us, gyro); -#endif + log_gyro_raw(instance, sample_us, gyro, _imu._gyro_filtered[instance]); } -void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &gyro) +void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &raw_gyro, const Vector3f &filtered_gyro) { #if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); @@ -461,12 +441,30 @@ void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sa // should not have been called return; } - if (should_log_imu_raw()) { - Write_GYR(instance, sample_us, gyro); + + if (_imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::ALL_GYROS) || + (_imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::PRIMARY_GYRO_ONLY) && (instance == AP::ahrs().get_primary_gyro_index())) || + should_log_imu_raw()) { + + if (_imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::PRE_AND_POST_FILTER)) { + // Both pre and post, offset post instance as batch sampler does + Write_GYR(instance, sample_us, raw_gyro); + Write_GYR(instance + _imu._gyro_count, sample_us, filtered_gyro); + + } else if (_imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::POST_FILTER)) { + // Just post + Write_GYR(instance, sample_us, filtered_gyro); + + } else { + // Just pre + Write_GYR(instance, sample_us, raw_gyro); + + } } else { #if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED if (!_imu.batchsampler.doing_sensor_rate_logging()) { - _imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_GYRO, sample_us, gyro); + _imu.batchsampler.sample(instance, AP_InertialSensor::IMU_SENSOR_TYPE_GYRO, sample_us, + !_imu.batchsampler.doing_post_filter_logging() ? raw_gyro : filtered_gyro); } #endif } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h index c49356a85ffc9a..a9bd7bb4118081 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h @@ -315,7 +315,7 @@ class AP_InertialSensor_Backend bool should_log_imu_raw() const ; void log_accel_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &accel) __RAMFUNC__; - void log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &gryo) __RAMFUNC__; + void log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &raw_gyro, const Vector3f &filtered_gyro) __RAMFUNC__; // logging void Write_ACC(const uint8_t instance, const uint64_t sample_us, const Vector3f &accel) const __RAMFUNC__; // 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 e51a97d618e447..b64a06b9358f59 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp @@ -255,17 +255,10 @@ void AP_InertialSensor_NONE::generate_gyro() void AP_InertialSensor_NONE::timer_update(void) { - uint64_t now = AP_HAL::micros64(); - static uint64_t last_msg_sent = 0; - if (now > last_msg_sent + 2000000) { //2sec= 2000ms = 2000000us - //gcs().send_text(MAV_SEVERITY_WARNING, "NO IMU FOUND"); - DEV_PRINTF("INS: NO IMU FOUND\n"); - last_msg_sent = now; - } if (now >= next_accel_sample) { - if (((1U << accel_instance) ) == 0) { + { generate_accel(); if (next_accel_sample == 0) { next_accel_sample = now + 1000000UL / accel_sample_hz; @@ -277,7 +270,7 @@ void AP_InertialSensor_NONE::timer_update(void) } } if (now >= next_gyro_sample) { - if (((1U << gyro_instance) ) == 0) { + { generate_gyro(); if (next_gyro_sample == 0) { next_gyro_sample = now + 1000000UL / gyro_sample_hz; diff --git a/libraries/AP_InternalError/AP_InternalError.cpp b/libraries/AP_InternalError/AP_InternalError.cpp index 2bb3b3170e126b..bc505804a8179c 100644 --- a/libraries/AP_InternalError/AP_InternalError.cpp +++ b/libraries/AP_InternalError/AP_InternalError.cpp @@ -1,6 +1,12 @@ +#include "AP_InternalError_config.h" + +#if AP_INTERNALERROR_ENABLED + #include "AP_InternalError.h" -#include +#include +#include + #include extern const AP_HAL::HAL &hal; @@ -137,3 +143,5 @@ void AP_memory_guard_error(uint32_t size) AP_HAL::panic("memory guard size=%u\n", unsigned(size)); } } + +#endif // AP_INTERNALERROR_ENABLED diff --git a/libraries/AP_InternalError/AP_InternalError.h b/libraries/AP_InternalError/AP_InternalError.h index 4cbbb29043d4fe..d6936d978cbf43 100644 --- a/libraries/AP_InternalError/AP_InternalError.h +++ b/libraries/AP_InternalError/AP_InternalError.h @@ -22,6 +22,10 @@ #pragma once +#include "AP_InternalError_config.h" + +#if AP_INTERNALERROR_ENABLED + #include class AP_InternalError { @@ -113,3 +117,7 @@ extern "C" { #define INTERNAL_ERROR(error_number) \ AP::internalerror().error(error_number, __AP_LINE__); + +#else // AP_INTERNALERROR_ENABLED is false +#define INTERNAL_ERROR(error_number) +#endif // AP_INTERNALERROR_ENABLED diff --git a/libraries/AP_InternalError/AP_InternalError_config.h b/libraries/AP_InternalError/AP_InternalError_config.h new file mode 100644 index 00000000000000..64bbb03f69076d --- /dev/null +++ b/libraries/AP_InternalError/AP_InternalError_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef AP_INTERNALERROR_ENABLED +#define AP_INTERNALERROR_ENABLED 1 +#endif diff --git a/libraries/AP_JSButton/AP_JSButton.cpp b/libraries/AP_JSButton/AP_JSButton.cpp index a25ae0af3f60c6..95ee43f4221443 100644 --- a/libraries/AP_JSButton/AP_JSButton.cpp +++ b/libraries/AP_JSButton/AP_JSButton.cpp @@ -5,14 +5,14 @@ const AP_Param::GroupInfo JSButton::var_info[] = { // @Param: FUNCTION // @DisplayName: Function for button // @Description: Set to 0 to disable or choose a function - // @Values: 0:Disabled,1:shift,2:arm_toggle,3:arm,4:disarm,5:mode_manual,6:mode_stabilize,7:mode_depth_hold,8:mode_poshold,9:mode_auto,10:mode_circle,11:mode_guided,12:mode_acro,21:mount_center,22:mount_tilt_up,23:mount_tilt_down,24:camera_trigger,25:camera_source_toggle,26:mount_pan_right,27:mount_pan_left,31:lights1_cycle,32:lights1_brighter,33:lights1_dimmer,34:lights2_cycle,35:lights2_brighter,36:lights2_dimmer,41:gain_toggle,42:gain_inc,43:gain_dec,44:trim_roll_inc,45:trim_roll_dec,46:trim_pitch_inc,47:trim_pitch_dec,48:input_hold_set,49:roll_pitch_toggle,51:relay_1_on,52:relay_1_off,53:relay_1_toggle,54:relay_2_on,55:relay_2_off,56:relay_2_toggle,57:relay_3_on,58:relay_3_off,59:relay_3_toggle,61:servo_1_inc,62:servo_1_dec,63:servo_1_min,64:servo_1_max,65:servo_1_center,66:servo_2_inc,67:servo_2_dec,68:servo_2_min,69:servo_2_max,70:servo_2_center,71:servo_3_inc,72:servo_3_dec,73:servo_3_min,74:servo_3_max,75:servo_3_center,76:servo_1_min_momentary,77:servo_1_max_momentary,78:servo_1_min_toggle,79:servo_1_max_toggle,80:servo_2_min_momentary,81:servo_2_max_momentary,82:servo_2_min_toggle,83:servo_2_max_toggle,84:servo_3_min_momentary,85:servo_3_max_momentary,86:servo_3_min_toggle,87:servo_3_max_toggle,91:custom_1,92:custom_2,93:custom_3,94:custom_4,95:custom_5,96:custom_6,101:relay_4_on,102:relay_4_off,103:relay_4_toggle,104:relay_1_momentary,105:relay_2_momentary,106:relay_3_momentary,107:relay_4_momentary + // @Values: 0:Disabled,1:shift,2:arm_toggle,3:arm,4:disarm,5:mode_manual,6:mode_stabilize,7:mode_depth_hold,8:mode_poshold,9:mode_auto,10:mode_circle,11:mode_guided,12:mode_acro,21:mount_center,22:mount_tilt_up,23:mount_tilt_down,24:camera_trigger,25:camera_source_toggle,26:mount_pan_right,27:mount_pan_left,31:lights1_cycle,32:lights1_brighter,33:lights1_dimmer,34:lights2_cycle,35:lights2_brighter,36:lights2_dimmer,41:gain_toggle,42:gain_inc,43:gain_dec,44:trim_roll_inc,45:trim_roll_dec,46:trim_pitch_inc,47:trim_pitch_dec,48:input_hold_set,49:roll_pitch_toggle,51:relay_1_on,52:relay_1_off,53:relay_1_toggle,54:relay_2_on,55:relay_2_off,56:relay_2_toggle,57:relay_3_on,58:relay_3_off,59:relay_3_toggle,61:servo_1_inc,62:servo_1_dec,63:servo_1_min,64:servo_1_max,65:servo_1_center,66:servo_2_inc,67:servo_2_dec,68:servo_2_min,69:servo_2_max,70:servo_2_center,71:servo_3_inc,72:servo_3_dec,73:servo_3_min,74:servo_3_max,75:servo_3_center,76:servo_1_min_momentary,77:servo_1_max_momentary,78:servo_1_min_toggle,79:servo_1_max_toggle,80:servo_2_min_momentary,81:servo_2_max_momentary,82:servo_2_min_toggle,83:servo_2_max_toggle,84:servo_3_min_momentary,85:servo_3_max_momentary,86:servo_3_min_toggle,87:servo_3_max_toggle,91:custom_1,92:custom_2,93:custom_3,94:custom_4,95:custom_5,96:custom_6,101:relay_4_on,102:relay_4_off,103:relay_4_toggle,104:relay_1_momentary,105:relay_2_momentary,106:relay_3_momentary,107:relay_4_momentary,108:script_1,109:script_2,110:script_3,111:script_4 // @User: Standard AP_GROUPINFO("FUNCTION", 1, JSButton, _function, 0), // @Param: SFUNCTION // @DisplayName: Function for button when the shift mode is toggled on // @Description: Set to 0 to disable or choose a function - // @Values: 0:Disabled,1:shift,2:arm_toggle,3:arm,4:disarm,5:mode_manual,6:mode_stabilize,7:mode_depth_hold,8:mode_poshold,9:mode_auto,10:mode_circle,11:mode_guided,12:mode_acro,21:mount_center,22:mount_tilt_up,23:mount_tilt_down,24:camera_trigger,25:camera_source_toggle,26:mount_pan_right,27:mount_pan_left,31:lights1_cycle,32:lights1_brighter,33:lights1_dimmer,34:lights2_cycle,35:lights2_brighter,36:lights2_dimmer,41:gain_toggle,42:gain_inc,43:gain_dec,44:trim_roll_inc,45:trim_roll_dec,46:trim_pitch_inc,47:trim_pitch_dec,48:input_hold_set,49:roll_pitch_toggle,51:relay_1_on,52:relay_1_off,53:relay_1_toggle,54:relay_2_on,55:relay_2_off,56:relay_2_toggle,57:relay_3_on,58:relay_3_off,59:relay_3_toggle,61:servo_1_inc,62:servo_1_dec,63:servo_1_min,64:servo_1_max,65:servo_1_center,66:servo_2_inc,67:servo_2_dec,68:servo_2_min,69:servo_2_max,70:servo_2_center,71:servo_3_inc,72:servo_3_dec,73:servo_3_min,74:servo_3_max,75:servo_3_center,76:servo_1_min_momentary,77:servo_1_max_momentary,78:servo_1_min_toggle,79:servo_1_max_toggle,80:servo_2_min_momentary,81:servo_2_max_momentary,82:servo_2_min_toggle,83:servo_2_max_toggle,84:servo_3_min_momentary,85:servo_3_max_momentary,86:servo_3_min_toggle,87:servo_3_max_toggle,91:custom_1,92:custom_2,93:custom_3,94:custom_4,95:custom_5,96:custom_6,101:relay_4_on,102:relay_4_off,103:relay_4_toggle,104:relay_1_momentary,105:relay_2_momentary,106:relay_3_momentary,107:relay_4_momentary + // @Values: 0:Disabled,1:shift,2:arm_toggle,3:arm,4:disarm,5:mode_manual,6:mode_stabilize,7:mode_depth_hold,8:mode_poshold,9:mode_auto,10:mode_circle,11:mode_guided,12:mode_acro,21:mount_center,22:mount_tilt_up,23:mount_tilt_down,24:camera_trigger,25:camera_source_toggle,26:mount_pan_right,27:mount_pan_left,31:lights1_cycle,32:lights1_brighter,33:lights1_dimmer,34:lights2_cycle,35:lights2_brighter,36:lights2_dimmer,41:gain_toggle,42:gain_inc,43:gain_dec,44:trim_roll_inc,45:trim_roll_dec,46:trim_pitch_inc,47:trim_pitch_dec,48:input_hold_set,49:roll_pitch_toggle,51:relay_1_on,52:relay_1_off,53:relay_1_toggle,54:relay_2_on,55:relay_2_off,56:relay_2_toggle,57:relay_3_on,58:relay_3_off,59:relay_3_toggle,61:servo_1_inc,62:servo_1_dec,63:servo_1_min,64:servo_1_max,65:servo_1_center,66:servo_2_inc,67:servo_2_dec,68:servo_2_min,69:servo_2_max,70:servo_2_center,71:servo_3_inc,72:servo_3_dec,73:servo_3_min,74:servo_3_max,75:servo_3_center,76:servo_1_min_momentary,77:servo_1_max_momentary,78:servo_1_min_toggle,79:servo_1_max_toggle,80:servo_2_min_momentary,81:servo_2_max_momentary,82:servo_2_min_toggle,83:servo_2_max_toggle,84:servo_3_min_momentary,85:servo_3_max_momentary,86:servo_3_min_toggle,87:servo_3_max_toggle,91:custom_1,92:custom_2,93:custom_3,94:custom_4,95:custom_5,96:custom_6,101:relay_4_on,102:relay_4_off,103:relay_4_toggle,104:relay_1_momentary,105:relay_2_momentary,106:relay_3_momentary,107:relay_4_momentary,108:script_1,109:script_2,110:script_3,111:script_4 // @User: Standard AP_GROUPINFO("SFUNCTION", 2, JSButton, _sfunction, 0), diff --git a/libraries/AP_JSButton/AP_JSButton.h b/libraries/AP_JSButton/AP_JSButton.h index 3f13f1f07af34f..f5005fcf6b7d54 100644 --- a/libraries/AP_JSButton/AP_JSButton.h +++ b/libraries/AP_JSButton/AP_JSButton.h @@ -112,7 +112,12 @@ class JSButton { k_relay_3_momentary = 106, k_relay_4_momentary = 107, - // 108+ reserved for future functions + k_script_1 = 108, + k_script_2 = 109, + k_script_3 = 110, + k_script_4 = 111, + + // 112+ reserved for future functions k_nr_btn_functions ///< This must be the last enum value (only add new values _before_ this one) } button_function_t; diff --git a/libraries/AP_L1_Control/AP_L1_Control.cpp b/libraries/AP_L1_Control/AP_L1_Control.cpp index 3b9bbcab187137..816637af457c6f 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.cpp +++ b/libraries/AP_L1_Control/AP_L1_Control.cpp @@ -79,7 +79,17 @@ int32_t AP_L1_Control::get_yaw_sensor() const int32_t AP_L1_Control::nav_roll_cd(void) const { float ret; - ret = cosf(_ahrs.pitch)*degrees(atanf(_latAccDem * (1.0f/GRAVITY_MSS)) * 100.0f); + /* + formula can be obtained through equations of balanced spiral: + liftForce * cos(roll) = gravityForce * cos(pitch); + liftForce * sin(roll) = gravityForce * lateralAcceleration / gravityAcceleration; // as mass = gravityForce/gravityAcceleration + see issue 24319 [https://github.com/ArduPilot/ardupilot/issues/24319] + Multiplier 100.0f is for converting degrees to centidegrees + Made changes to avoid zero division as proposed by Andrew Tridgell: https://github.com/ArduPilot/ardupilot/pull/24331#discussion_r1267798397 + */ + float pitchLimL1 = radians(60); // Suggestion: constraint may be modified to pitch limits if their absolute values are less than 90 degree and more than 60 degrees. + float pitchL1 = constrain_float(_ahrs.pitch,-pitchLimL1,pitchLimL1); + ret = degrees(atanf(_latAccDem * (1.0f/(GRAVITY_MSS * cosf(pitchL1))))) * 100.0f; ret = constrain_float(ret, -9000, 9000); return ret; } @@ -230,7 +240,11 @@ void AP_L1_Control::update_waypoint(const Location &prev_WP, const Location &nex //Calculate groundspeed float groundSpeed = _groundspeed_vector.length(); - if (groundSpeed < 0.1f) { + + // check if we are moving in the direction of the front of the vehicle + const bool moving_forwards = fabsf(wrap_PI(_groundspeed_vector.angle() - get_yaw())) < M_PI_2; + + if (groundSpeed < 0.1f || !moving_forwards) { // use a small ground speed vector in the right direction, // allowing us to use the compass heading at zero GPS velocity groundSpeed = 0.1f; diff --git a/libraries/AP_Landing/AP_Landing.h b/libraries/AP_Landing/AP_Landing.h index 554a883a277e4d..b9cfc80e888a9e 100644 --- a/libraries/AP_Landing/AP_Landing.h +++ b/libraries/AP_Landing/AP_Landing.h @@ -110,7 +110,7 @@ class AP_Landing { void set_initial_slope(void) { initial_slope = slope; } bool is_expecting_impact(void) const; void Log(void) const; - const AP_PIDInfo * get_pid_info(void) const; + const class AP_PIDInfo * get_pid_info(void) const; // landing altitude offset (meters) float alt_offset; diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.cpp b/libraries/AP_Landing/AP_Landing_Deepstall.cpp index a0c04c75354367..550fa92ecc6c3d 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.cpp +++ b/libraries/AP_Landing/AP_Landing_Deepstall.cpp @@ -17,10 +17,12 @@ * AP_Landing_Deepstall.cpp - Landing logic handler for ArduPlane for deepstall landings */ -#include "AP_Landing.h" +#include "AP_Landing_config.h" #if HAL_LANDING_DEEPSTALL_ENABLED +#include "AP_Landing.h" + #include #include #include diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.h b/libraries/AP_Landing/AP_Landing_Deepstall.h index b668054855d1d4..50099861defe8b 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.h +++ b/libraries/AP_Landing/AP_Landing_Deepstall.h @@ -15,16 +15,16 @@ #pragma once +#include "AP_Landing_config.h" + +#if HAL_LANDING_DEEPSTALL_ENABLED + #include #include #include #include #include -#ifndef HAL_LANDING_DEEPSTALL_ENABLED -#define HAL_LANDING_DEEPSTALL_ENABLED (BOARD_FLASH_SIZE > 1024) -#endif - class AP_Landing; /// @class AP_Landing_Deepstall @@ -110,3 +110,5 @@ class AP_Landing_Deepstall #define DEEPSTALL_LOITER_ALT_TOLERANCE 5.0f }; + +#endif // HAL_LANDING_DEEPSTALL_ENABLED diff --git a/libraries/AP_Landing/AP_Landing_config.h b/libraries/AP_Landing/AP_Landing_config.h new file mode 100644 index 00000000000000..3b1aac2acb5810 --- /dev/null +++ b/libraries/AP_Landing/AP_Landing_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef HAL_LANDING_DEEPSTALL_ENABLED +#define HAL_LANDING_DEEPSTALL_ENABLED (BOARD_FLASH_SIZE > 1024) +#endif diff --git a/libraries/AP_Landing/LogStructure.h b/libraries/AP_Landing/LogStructure.h new file mode 100644 index 00000000000000..aabeb98fc13fab --- /dev/null +++ b/libraries/AP_Landing/LogStructure.h @@ -0,0 +1,51 @@ +#pragma once + +#include +#include "AP_Landing_config.h" + +#define LOG_IDS_FROM_LANDING \ + LOG_DSTL_MSG + +#if HAL_LANDING_DEEPSTALL_ENABLED + +// @LoggerMessage: DSTL +// @Description: Deepstall Landing data +// @Field: TimeUS: Time since system startup +// @Field: Stg: Deepstall landing stage +// @Field: THdg: Target heading +// @Field: Lat: Landing point latitude +// @Field: Lng: Landing point longitude +// @Field: Alt: Landing point altitude +// @Field: XT: Crosstrack error +// @Field: Travel: Expected travel distance vehicle will travel from this point +// @Field: L1I: L1 controller crosstrack integrator value +// @Field: Loiter: wind estimate loiter angle flown +// @Field: Des: Deepstall steering PID desired value +// @Field: P: Deepstall steering PID Proportional response component +// @Field: I: Deepstall steering PID Integral response component +// @Field: D: Deepstall steering PID Derivative response component + +struct PACKED log_DSTL { + LOG_PACKET_HEADER; + uint64_t time_us; + uint8_t stage; + float target_heading; + int32_t target_lat; + int32_t target_lng; + int32_t target_alt; + int16_t crosstrack_error; + int16_t travel_distance; + float l1_i; + int32_t loiter_sum_cd; + float desired; + float P; + float I; + float D; +}; + +#define LOG_STRUCTURE_FROM_LANDING \ + { LOG_DSTL_MSG, sizeof(log_DSTL), \ + "DSTL", "QBfLLeccfeffff", "TimeUS,Stg,THdg,Lat,Lng,Alt,XT,Travel,L1I,Loiter,Des,P,I,D", "s??DUm--------", "F??000--------" , true }, +#else +#define LOG_STRUCTURE_FROM_LANDING +#endif diff --git a/libraries/AP_LandingGear/AP_LandingGear_config.h b/libraries/AP_LandingGear/AP_LandingGear_config.h index e6e1015ffe0624..668c03b074a7b7 100644 --- a/libraries/AP_LandingGear/AP_LandingGear_config.h +++ b/libraries/AP_LandingGear/AP_LandingGear_config.h @@ -3,8 +3,6 @@ #include #include -// historical compatability; only Copters get it - and Plane on -// non-minimized boards. #ifndef AP_LANDINGGEAR_ENABLED -#define AP_LANDINGGEAR_ENABLED (APM_BUILD_COPTER_OR_HELI || (!HAL_MINIMIZE_FEATURES && APM_BUILD_TYPE(APM_BUILD_ArduPlane))) +#define AP_LANDINGGEAR_ENABLED APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) #endif diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index 84b1d252185cd6..d5b35cddfe1ba9 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -161,7 +161,7 @@ enum class LogErrorCode : uint8_t { FAILED_CIRCLE_INIT = 4, DEST_OUTSIDE_FENCE = 5, RTL_MISSING_RNGFND = 6, - // subsystem specific error codes -- internal_error +// subsystem specific error codes -- internal_error INTERNAL_ERRORS_DETECTED = 1, // parachute failed to deploy because of low altitude or landed @@ -173,7 +173,7 @@ enum class LogErrorCode : uint8_t { // Baro specific error codes BARO_GLITCH = 2, BAD_DEPTH = 3, // sub-only -// GPS specific error coces +// GPS specific error codes GPS_GLITCH = 2, }; @@ -431,6 +431,11 @@ class AP_Logger BLOCK = (1<<2), }; + enum class RCLoggingFlags : uint8_t { + HAS_VALID_INPUT = 1U<<0, // true if the system is receiving good RC values + IN_RC_FAILSAFE = 1U<<1, // true if the system is current in RC failsafe + }; + /* * support for dynamic Write; user-supplies name, format, * labels and values in a single function call. diff --git a/libraries/AP_Logger/AP_Logger_Backend.cpp b/libraries/AP_Logger/AP_Logger_Backend.cpp index 313747a20cf202..f432328a160490 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.cpp +++ b/libraries/AP_Logger/AP_Logger_Backend.cpp @@ -1,3 +1,7 @@ +#include "AP_Logger_config.h" + +#if HAL_LOGGING_ENABLED + #include "AP_Logger_Backend.h" #include "LoggerMessageWriter.h" @@ -7,6 +11,7 @@ #include #include #include +#include "AP_Logger.h" #if HAL_LOGGER_FENCE_ENABLED #include @@ -381,6 +386,7 @@ void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer, } 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); if (s == nullptr) { const struct AP_Logger::log_write_fmt *t = _front.log_write_fmt_for_msg_type(type); @@ -388,13 +394,15 @@ void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer, AP_HAL::panic("No structure for msg_type=%u", type); } type_len = t->msg_len; + name_src = t->name; } else { type_len = s->msg_len; + name_src = s->name; } if (type_len != size) { char name[5] = {}; // get a null-terminated string - if (s->name != nullptr) { - memcpy(name, s->name, 4); + if (name_src != nullptr) { + memcpy(name, name_src, 4); } else { strncpy(name, "?NM?", ARRAY_SIZE(name)); } @@ -565,6 +573,7 @@ bool AP_Logger_Backend::Write_VER() patch: fwver.patch, fw_type: fwver.fw_type, git_hash: fwver.fw_hash, + build_type: fwver.vehicle_type, }; strncpy(pkt.fw_string, fwver.fw_string, ARRAY_SIZE(pkt.fw_string)-1); @@ -749,3 +758,5 @@ bool AP_Logger_RateLimiter::should_log(uint8_t msgid, bool writev_streaming) } return ret; } + +#endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_Logger/AP_Logger_Backend.h b/libraries/AP_Logger/AP_Logger_Backend.h index 65ed643dcef86d..4864f6802a215a 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.h +++ b/libraries/AP_Logger/AP_Logger_Backend.h @@ -1,8 +1,14 @@ #pragma once -#include "AP_Logger.h" +#include "AP_Logger_config.h" + +#if HAL_LOGGING_ENABLED #include +#include +#include +#include +#include class LoggerMessageWriter_DFLogStart; @@ -12,7 +18,7 @@ class LoggerMessageWriter_DFLogStart; class AP_Logger_RateLimiter { public: - AP_Logger_RateLimiter(const AP_Logger &_front, const AP_Float &_limit_hz, const AP_Float &_disarm_limit_hz); + AP_Logger_RateLimiter(const class AP_Logger &_front, const AP_Float &_limit_hz, const AP_Float &_disarm_limit_hz); // return true if message passes the rate limit test bool should_log(uint8_t msgid, bool writev_streaming); @@ -103,7 +109,7 @@ class AP_Logger_Backend #endif // for Logger_MAVlink - virtual void remote_log_block_status_msg(const GCS_MAVLINK &link, + virtual void remote_log_block_status_msg(const class GCS_MAVLINK &link, const mavlink_message_t &msg) { } // end for Logger_MAVlink @@ -259,3 +265,5 @@ class AP_Logger_Backend void Write_AP_Logger_Stats_File(const struct df_stats &_stats); void validate_WritePrioritisedBlock(const void *pBuffer, uint16_t size); }; + +#endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_Logger/AP_Logger_Block.cpp b/libraries/AP_Logger/AP_Logger_Block.cpp index e056aef46e0f6b..c0966f7ec6ef3c 100644 --- a/libraries/AP_Logger/AP_Logger_Block.cpp +++ b/libraries/AP_Logger/AP_Logger_Block.cpp @@ -2,10 +2,12 @@ block based logging, for boards with flash logging */ -#include "AP_Logger_Block.h" +#include "AP_Logger_config.h" #if HAL_LOGGING_BLOCK_ENABLED +#include "AP_Logger_Block.h" +#include "AP_Logger.h" #include #include #include diff --git a/libraries/AP_Logger/AP_Logger_DataFlash.cpp b/libraries/AP_Logger/AP_Logger_DataFlash.cpp index b846f63cd97fe3..338ef88c910eeb 100644 --- a/libraries/AP_Logger/AP_Logger_DataFlash.cpp +++ b/libraries/AP_Logger/AP_Logger_DataFlash.cpp @@ -2,13 +2,14 @@ logging to a DataFlash block based storage device on SPI */ +#include "AP_Logger_config.h" + +#if HAL_LOGGING_DATAFLASH_ENABLED #include #include "AP_Logger_DataFlash.h" -#if HAL_LOGGING_DATAFLASH_ENABLED - #include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 5cdd386c64c190..99e76bb97a2299 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -10,17 +10,21 @@ - readdir loop of 511 entry directory ~62,000 microseconds */ +#include "AP_Logger_config.h" + +#if HAL_LOGGING_FILESYSTEM_ENABLED + #include #include +#include "AP_Logger.h" #include "AP_Logger_File.h" -#if HAL_LOGGING_FILESYSTEM_ENABLED - #include #include #include #include +#include #include #include @@ -579,11 +583,15 @@ uint32_t AP_Logger_File::_get_log_time(const uint16_t log_num) // it is the file we are currently writing free(fname); write_fd_semaphore.give(); +#if AP_RTC_ENABLED uint64_t utc_usec; if (!AP::rtc().get_utc_usec(utc_usec)) { return 0; } return utc_usec / 1000000U; +#else + return 0; +#endif } write_fd_semaphore.give(); } @@ -836,8 +844,10 @@ void AP_Logger_File::start_new_log(void) #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS // remember if we had utc time when we opened the file +#if AP_RTC_ENABLED uint64_t utc_usec; _need_rtc_update = !AP::rtc().get_utc_usec(utc_usec); +#endif #endif // create the log directory if need be @@ -1030,7 +1040,7 @@ void AP_Logger_File::io_timer(void) last_io_operation = ""; #endif -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#if AP_RTC_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS // ChibiOS does not update mtime on writes, so if we opened // without knowing the time we should update it later if (_need_rtc_update) { diff --git a/libraries/AP_Logger/AP_Logger_File.h b/libraries/AP_Logger/AP_Logger_File.h index dbfe61f807a9eb..07709d3e9350c8 100644 --- a/libraries/AP_Logger/AP_Logger_File.h +++ b/libraries/AP_Logger/AP_Logger_File.h @@ -72,7 +72,7 @@ class AP_Logger_File : public AP_Logger_Backend char *_write_filename; bool last_log_is_marked_discard; uint32_t _last_write_ms; -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#if AP_RTC_ENABLED bool _need_rtc_update; #endif diff --git a/libraries/AP_Logger/AP_Logger_MAVLink.cpp b/libraries/AP_Logger/AP_Logger_MAVLink.cpp index 7184d848031c21..cb5ee787f9426d 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLink.cpp +++ b/libraries/AP_Logger/AP_Logger_MAVLink.cpp @@ -2,11 +2,14 @@ AP_Logger Remote(via MAVLink) logging */ -#include "AP_Logger_MAVLink.h" +#include "AP_Logger_config.h" #if HAL_LOGGING_MAVLINK_ENABLED +#include "AP_Logger_MAVLink.h" + #include "LogStructure.h" +#include #define REMOTE_LOG_DEBUGGING 0 @@ -22,6 +25,13 @@ extern const AP_HAL::HAL& hal; +AP_Logger_MAVLink::AP_Logger_MAVLink(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) : + AP_Logger_Backend(front, writer), + _max_blocks_per_send_blocks(8) +{ + _blockcount = 1024*((uint8_t)_front._params.mav_bufsize) / sizeof(struct dm_block); + // ::fprintf(stderr, "DM: Using %u blocks\n", _blockcount); +} // initialisation void AP_Logger_MAVLink::Init() diff --git a/libraries/AP_Logger/AP_Logger_MAVLink.h b/libraries/AP_Logger/AP_Logger_MAVLink.h index 3011dcd718df10..4ae7202ff4f5d7 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLink.h +++ b/libraries/AP_Logger/AP_Logger_MAVLink.h @@ -17,13 +17,7 @@ class AP_Logger_MAVLink : public AP_Logger_Backend { public: // constructor - AP_Logger_MAVLink(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) : - AP_Logger_Backend(front, writer), - _max_blocks_per_send_blocks(8) - { - _blockcount = 1024*((uint8_t)_front._params.mav_bufsize) / sizeof(struct dm_block); - // ::fprintf(stderr, "DM: Using %u blocks\n", _blockcount); - } + AP_Logger_MAVLink(class AP_Logger &front, LoggerMessageWriter_DFLogStart *writer); static AP_Logger_Backend *probe(AP_Logger &front, LoggerMessageWriter_DFLogStart *ls) { diff --git a/libraries/AP_Logger/AP_Logger_config.h b/libraries/AP_Logger/AP_Logger_config.h index 92f25cc3ca32d6..afbbc52e150aa4 100644 --- a/libraries/AP_Logger/AP_Logger_config.h +++ b/libraries/AP_Logger/AP_Logger_config.h @@ -7,17 +7,21 @@ #define HAL_LOGGING_ENABLED 1 #endif +#ifndef HAL_LOGGING_BACKEND_DEFAULT_ENABLED +#define HAL_LOGGING_BACKEND_DEFAULT_ENABLED HAL_LOGGING_ENABLED +#endif + // set default for HAL_LOGGING_DATAFLASH_ENABLED #ifndef HAL_LOGGING_DATAFLASH_ENABLED -#define HAL_LOGGING_DATAFLASH_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#define HAL_LOGGING_DATAFLASH_ENABLED HAL_LOGGING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL) #endif #ifndef HAL_LOGGING_MAVLINK_ENABLED - #define HAL_LOGGING_MAVLINK_ENABLED HAL_LOGGING_ENABLED + #define HAL_LOGGING_MAVLINK_ENABLED HAL_LOGGING_BACKEND_DEFAULT_ENABLED #endif #ifndef HAL_LOGGING_FILESYSTEM_ENABLED -#define HAL_LOGGING_FILESYSTEM_ENABLED HAL_LOGGING_ENABLED && AP_FILESYSTEM_FILE_WRITING_ENABLED +#define HAL_LOGGING_FILESYSTEM_ENABLED HAL_LOGGING_BACKEND_DEFAULT_ENABLED && AP_FILESYSTEM_FILE_WRITING_ENABLED #endif #if HAL_LOGGING_DATAFLASH_ENABLED @@ -45,4 +49,7 @@ #define REPLAY_LOG_NEW_MSG_MIN 220 #include -#define HAL_LOGGER_FENCE_ENABLED AP_FENCE_ENABLED +#define HAL_LOGGER_FENCE_ENABLED HAL_LOGGING_ENABLED && AP_FENCE_ENABLED + +#include +#define HAL_LOGGER_RALLY_ENABLED HAL_LOGGING_ENABLED && HAL_RALLY_ENABLED diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index d393ebd7d7c380..26717af38cf4b2 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -1,3 +1,7 @@ +#include "AP_Logger_config.h" + +#if HAL_LOGGING_ENABLED + #include #include @@ -155,28 +159,21 @@ void AP_Logger::Write_RCIN(void) }; WriteBlock(&pkt, sizeof(pkt)); - const uint16_t override_mask = rc().get_override_mask(); - - // don't waste logging bandwidth if we haven't seen non-zero - // channels 15/16: - if (!should_log_rcin2) { - if (values[14] || values[15]) { - should_log_rcin2 = true; - } else if (override_mask != 0) { - should_log_rcin2 = true; - } + uint8_t flags = 0; + if (rc().has_valid_input()) { + flags |= (uint8_t)AP_Logger::RCLoggingFlags::HAS_VALID_INPUT; } - - if (!should_log_rcin2) { - return; + if (rc().in_rc_failsafe()) { + flags |= (uint8_t)AP_Logger::RCLoggingFlags::IN_RC_FAILSAFE; } - const struct log_RCIN2 pkt2{ - LOG_PACKET_HEADER_INIT(LOG_RCIN2_MSG), + const struct log_RCI2 pkt2{ + LOG_PACKET_HEADER_INIT(LOG_RCI2_MSG), time_us : AP_HAL::micros64(), chan15 : values[14], chan16 : values[15], - override_mask : override_mask, + override_mask : rc().get_override_mask(), + flags : flags, }; WriteBlock(&pkt2, sizeof(pkt2)); } @@ -476,6 +473,19 @@ void AP_Logger::Write_ServoStatus(uint64_t time_us, uint8_t id, float position, // Write a Yaw PID packet void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info) { + enum class log_PID_Flags : uint8_t { + LIMIT = 1U<<0, // true if the output is saturated, I term anti windup is active + PD_SUM_LIMIT = 1U<<1, // true if the PD sum limit is active + }; + + uint8_t flags = 0; + if (info.limit) { + flags |= (uint8_t)log_PID_Flags::LIMIT; + } + if (info.PD_limit) { + flags |= (uint8_t)log_PID_Flags::PD_SUM_LIMIT; + } + const struct log_PID pkt{ LOG_PACKET_HEADER_INIT(msg_type), time_us : AP_HAL::micros64(), @@ -488,7 +498,7 @@ void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info) FF : info.FF, Dmod : info.Dmod, slew_rate : info.slew_rate, - limit : info.limit + flags : flags }; WriteBlock(&pkt, sizeof(pkt)); } @@ -561,3 +571,5 @@ void AP_Logger::Write_PSCD(float pos_target, float pos, float vel_desired, float { Write_PSCx(LOG_PSCD_MSG, pos_target, pos, vel_desired, vel_target, vel, accel_desired, accel_target, accel); } + +#endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index 9ec9e5c15aa1f8..cfbfbbb1780314 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -131,6 +131,7 @@ const struct MultiplierStructure log_Multipliers[] = { #include #include #include +#include #include #include #include @@ -141,6 +142,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 @@ -260,12 +262,13 @@ struct PACKED log_RCIN { uint16_t chan14; }; -struct PACKED log_RCIN2 { +struct PACKED log_RCI2 { LOG_PACKET_HEADER; uint64_t time_us; uint16_t chan15; uint16_t chan16; uint16_t override_mask; + uint8_t flags; }; struct PACKED log_RCOUT { @@ -404,7 +407,7 @@ struct PACKED log_PID { float FF; float Dmod; float slew_rate; - uint8_t limit; + uint8_t flags; }; struct PACKED log_WheelEncoder { @@ -464,6 +467,7 @@ struct PACKED log_RFND { uint16_t dist; uint8_t status; uint8_t orient; + int8_t quality; }; /* @@ -576,24 +580,6 @@ struct PACKED log_SRTL { float D; }; -struct PACKED log_DSTL { - LOG_PACKET_HEADER; - uint64_t time_us; - uint8_t stage; - float target_heading; - int32_t target_lat; - int32_t target_lng; - int32_t target_alt; - int16_t crosstrack_error; - int16_t travel_distance; - float l1_i; - int32_t loiter_sum_cd; - float desired; - float P; - float I; - float D; -}; - struct PACKED log_Arm_Disarm { LOG_PACKET_HEADER; uint64_t time_us; @@ -684,6 +670,7 @@ struct PACKED log_VER { uint32_t git_hash; char fw_string[64]; uint16_t _APJ_BOARD_ID; + uint8_t build_type; }; @@ -691,7 +678,7 @@ struct PACKED log_VER { // UNIT messages define units which can be referenced by FMTU messages // FMTU messages associate types (e.g. centimeters/second/second) to FMT message fields -#define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF,Dmod,SRate,Limit" +#define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF,Dmod,SRate,Flags" #define PID_FMT "QfffffffffB" #define PID_UNITS "s----------" #define PID_MULTS "F----------" @@ -794,23 +781,6 @@ struct PACKED log_VER { // @Field: FMx: Maximum free space in write buffer in last time period // @Field: FAv: Average free space in write buffer in last time period -// @LoggerMessage: DSTL -// @Description: Deepstall Landing data -// @Field: TimeUS: Time since system startup -// @Field: Stg: Deepstall landing stage -// @Field: THdg: Target heading -// @Field: Lat: Landing point latitude -// @Field: Lng: Landing point longitude -// @Field: Alt: Landing point altitude -// @Field: XT: Crosstrack error -// @Field: Travel: Expected travel distance vehicle will travel from this point -// @Field: L1I: L1 controller crosstrack integrator value -// @Field: Loiter: wind estimate loiter angle flown -// @Field: Des: Deepstall steering PID desired value -// @Field: P: Deepstall steering PID Proportional response component -// @Field: I: Deepstall steering PID Integral response component -// @Field: D: Deepstall steering PID Derivative response component - // @LoggerMessage: ERR // @Description: Specifically coded error messages // @Field: TimeUS: Time since system startup @@ -941,7 +911,8 @@ struct PACKED log_VER { // @Field: FF: controller feed-forward portion of response // @Field: Dmod: scaler applied to D gain to reduce limit cycling // @Field: SRate: slew rate used in slew limiter -// @Field: Limit: 1 if I term is limited due to output saturation +// @Field: Flags: bitmask of PID state flags +// @FieldBitmaskEnum: Flags: log_PID_Flags // @LoggerMessage: PM // @Description: autopilot system performance and general data dumping ground @@ -1004,6 +975,8 @@ struct PACKED log_VER { // @Field: C15: channel 15 input // @Field: C16: channel 16 input // @Field: OMask: bitmask of RC channels being overridden by mavlink input +// @Field: Flags: bitmask of RC state flags +// @FieldBitmaskEnum: Flags: AP_Logger::RCLoggingFlags // @LoggerMessage: RCIN // @Description: RC input channels to vehicle @@ -1075,6 +1048,7 @@ struct PACKED log_VER { // @Field: Stat: Sensor state // @FieldValueEnum: Stat: RangeFinder::Status // @Field: Orient: Sensor orientation +// @Field: Quality: Signal quality. -1 means invalid, 0 is no signal, 100 is perfect signal // @LoggerMessage: RSSI // @Description: Received Signal Strength Indicator for RC receiver @@ -1237,8 +1211,8 @@ LOG_STRUCTURE_FROM_GPS \ "MSG", "QZ", "TimeUS,Message", "s-", "F-"}, \ { LOG_RCIN_MSG, sizeof(log_RCIN), \ "RCIN", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------", true }, \ - { LOG_RCIN2_MSG, sizeof(log_RCIN2), \ - "RCI2", "QHHH", "TimeUS,C15,C16,OMask", "sYY-", "F---", true }, \ + { LOG_RCI2_MSG, sizeof(log_RCI2), \ + "RCI2", "QHHHB", "TimeUS,C15,C16,OMask,Flags", "sYY--", "F----", true }, \ { LOG_RCOUT_MSG, sizeof(log_RCOUT), \ "RCOU", "QHHHHHHHHHHHHHH", "TimeUS,C1,C2,C3,C4,C5,C6,C7,C8,C9,C10,C11,C12,C13,C14", "sYYYYYYYYYYYYYY", "F--------------", true }, \ { LOG_RCOUT2_MSG, sizeof(log_RCOUT2), \ @@ -1260,6 +1234,7 @@ LOG_STRUCTURE_FROM_PRECLAND \ { LOG_RADIO_MSG, sizeof(log_Radio), \ "RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed", "s-------", "F-------", true }, \ LOG_STRUCTURE_FROM_CAMERA \ +LOG_STRUCTURE_FROM_MOUNT \ { LOG_ARSP_MSG, sizeof(log_ARSP), "ARSP", "QBffcffBBffB", "TimeUS,I,Airspeed,DiffPress,Temp,RawPress,Offset,U,H,Hp,TR,Pri", "s#nPOPP-----", "F-00B00-----", true }, \ LOG_STRUCTURE_FROM_BATTMONITOR \ { LOG_MAG_MSG, sizeof(log_MAG), \ @@ -1267,7 +1242,7 @@ LOG_STRUCTURE_FROM_CAMERA \ { LOG_MODE_MSG, sizeof(log_Mode), \ "MODE", "QMBB", "TimeUS,Mode,ModeNum,Rsn", "s---", "F---" }, \ { LOG_RFND_MSG, sizeof(log_RFND), \ - "RFND", "QBCBB", "TimeUS,Instance,Dist,Stat,Orient", "s#m--", "F-B--", true }, \ + "RFND", "QBCBBb", "TimeUS,Instance,Dist,Stat,Orient,Quality", "s#m--%", "F-B---", true }, \ { LOG_MAV_STATS, sizeof(log_MAV_Stats), \ "DMS", "QIIIIBBBBBBBBB", "TimeUS,N,Dp,RT,RS,Fa,Fmn,Fmx,Pa,Pmn,Pmx,Sa,Smn,Smx", "s-------------", "F-------------" }, \ LOG_STRUCTURE_FROM_BEACON \ @@ -1298,8 +1273,7 @@ LOG_STRUCTURE_FROM_ESC_TELEM \ "PIDN", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, \ { LOG_PIDE_MSG, sizeof(log_PID), \ "PIDE", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, \ - { LOG_DSTL_MSG, sizeof(log_DSTL), \ - "DSTL", "QBfLLeccfeffff", "TimeUS,Stg,THdg,Lat,Lng,Alt,XT,Travel,L1I,Loiter,Des,P,I,D", "s??DUm--------", "F??000--------" , true }, \ +LOG_STRUCTURE_FROM_LANDING \ LOG_STRUCTURE_FROM_INERTIALSENSOR \ LOG_STRUCTURE_FROM_DAL \ LOG_STRUCTURE_FROM_NAVEKF2 \ @@ -1344,7 +1318,7 @@ LOG_STRUCTURE_FROM_AIS \ { LOG_SCRIPTING_MSG, sizeof(log_Scripting), \ "SCR", "QNIii", "TimeUS,Name,Runtime,Total_mem,Run_mem", "s#sbb", "F-F--", true }, \ { LOG_VER_MSG, sizeof(log_VER), \ - "VER", "QBHBBBBIZH", "TimeUS,BT,BST,Maj,Min,Pat,FWT,GH,FWS,APJ", "s---------", "F---------", false }, \ + "VER", "QBHBBBBIZHB", "TimeUS,BT,BST,Maj,Min,Pat,FWT,GH,FWS,APJ,BU", "s----------", "F----------", false }, \ { LOG_MOTBATT_MSG, sizeof(log_MotBatt), \ "MOTB", "QfffffB", "TimeUS,LiftMax,BatVolt,ThLimit,ThrAvMx,ThrOut,FailFlags", "s------", "F------" , true } @@ -1357,7 +1331,7 @@ enum LogMessages : uint8_t { LOG_IDS_FROM_NAVEKF3, LOG_MESSAGE_MSG, LOG_RCIN_MSG, - LOG_RCIN2_MSG, + LOG_RCI2_MSG, LOG_RCOUT_MSG, LOG_RSSI_MSG, LOG_IDS_FROM_BARO, @@ -1370,6 +1344,7 @@ enum LogMessages : uint8_t { LOG_RADIO_MSG, LOG_ATRP_MSG, LOG_IDS_FROM_CAMERA, + LOG_IDS_FROM_MOUNT, LOG_TERRAIN_MSG, LOG_CSRV_MSG, LOG_IDS_FROM_ESC_TELEM, @@ -1385,7 +1360,7 @@ enum LogMessages : uint8_t { LOG_PIDS_MSG, LOG_PIDN_MSG, LOG_PIDE_MSG, - LOG_DSTL_MSG, + LOG_IDS_FROM_LANDING, LOG_MAG_MSG, LOG_ARSP_MSG, LOG_IDS_FROM_RPM, diff --git a/libraries/AP_Logger/LoggerMessageWriter.cpp b/libraries/AP_Logger/LoggerMessageWriter.cpp index 76d11f5524248c..3918fc6226c6b3 100644 --- a/libraries/AP_Logger/LoggerMessageWriter.cpp +++ b/libraries/AP_Logger/LoggerMessageWriter.cpp @@ -1,12 +1,21 @@ +#include "AP_Logger_config.h" + +#if HAL_LOGGING_ENABLED + #include "AP_Common/AP_FWVersion.h" #include "LoggerMessageWriter.h" #include #include +#include "AP_Logger.h" #if HAL_LOGGER_FENCE_ENABLED #include #endif +#if HAL_LOGGER_RALLY_ENABLED +#include +#endif + #define FORCE_VERSION_H_INCLUDE #include "ap_version.h" #undef FORCE_VERSION_H_INCLUDE @@ -46,7 +55,7 @@ void LoggerMessageWriter_DFLogStart::reset() #if AP_MISSION_ENABLED _writeentiremission.reset(); #endif -#if HAL_RALLY_ENABLED +#if HAL_LOGGER_RALLY_ENABLED _writeallrallypoints.reset(); #endif #if HAL_LOGGER_FENCE_ENABLED @@ -62,7 +71,7 @@ void LoggerMessageWriter_DFLogStart::reset() ap = AP_Param::first(&token, &type, ¶m_default); } -bool LoggerMessageWriter_DFLogStart::out_of_time_for_writing_messages() const +bool LoggerMessageWriter_DFLogStart::out_of_time_for_writing_messages_df() const { if (stage == Stage::FORMATS) { // write out the FMT messages as fast as we can @@ -90,7 +99,7 @@ bool LoggerMessageWriter_DFLogStart::check_process_limit(uint32_t start_us) void LoggerMessageWriter_DFLogStart::process() { - if (out_of_time_for_writing_messages()) { + if (out_of_time_for_writing_messages_df()) { return; } // allow any stage to run for max 1ms, to prevent a long loop on arming @@ -183,7 +192,7 @@ void LoggerMessageWriter_DFLogStart::process() } } #endif -#if HAL_RALLY_ENABLED +#if HAL_LOGGER_RALLY_ENABLED if (!_writeallrallypoints.finished()) { _writeallrallypoints.process(); if (!_writeallrallypoints.finished()) { @@ -235,7 +244,7 @@ bool LoggerMessageWriter_DFLogStart::writeentiremission() } #endif -#if HAL_RALLY_ENABLED +#if HAL_LOGGER_RALLY_ENABLED bool LoggerMessageWriter_DFLogStart::writeallrallypoints() { if (stage != Stage::DONE) { @@ -356,6 +365,7 @@ void LoggerMessageWriter_WriteSysInfo::process() { _finished = true; // all done! } +#if HAL_LOGGER_RALLY_ENABLED void LoggerMessageWriter_WriteAllRallyPoints::process() { const AP_Rally *_rally = AP::rally(); @@ -405,6 +415,7 @@ void LoggerMessageWriter_WriteAllRallyPoints::reset() stage = Stage::WRITE_NEW_RALLY_MESSAGE; _rally_number_to_send = 0; } +#endif // HAL_LOGGER_RALLY_ENABLED void LoggerMessageWriter_WriteEntireMission::process() { const AP_Mission *_mission = AP::mission(); @@ -513,3 +524,5 @@ void LoggerMessageWriter_Write_Polyfence::reset() } #endif // !APM_BUILD_TYPE(APM_BUILD_Replay) #endif // AP_FENCE_ENABLED + +#endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_Logger/LoggerMessageWriter.h b/libraries/AP_Logger/LoggerMessageWriter.h index bc1417a8b4e1d1..2e28503676faf5 100644 --- a/libraries/AP_Logger/LoggerMessageWriter.h +++ b/libraries/AP_Logger/LoggerMessageWriter.h @@ -110,7 +110,7 @@ class LoggerMessageWriter_DFLogStart : public LoggerMessageWriter { { } - virtual void set_logger_backend(class AP_Logger_Backend *backend) override { + void set_logger_backend(class AP_Logger_Backend *backend) override final { LoggerMessageWriter::set_logger_backend(backend); _writesysinfo.set_logger_backend(backend); #if AP_MISSION_ENABLED @@ -124,7 +124,7 @@ class LoggerMessageWriter_DFLogStart : public LoggerMessageWriter { #endif } - bool out_of_time_for_writing_messages() const; + bool out_of_time_for_writing_messages_df() const; void reset() override; void process() override; diff --git a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp index db694f82824aca..ee01834cb19d6f 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp +++ b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp @@ -989,10 +989,12 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_rtc(sbuf_t *dst) { tm localtime_tm {}; // year is relative to 1900 uint64_t time_usec = 0; +#if AP_RTC_ENABLED if (AP::rtc().get_utc_usec(time_usec)) { // may fail, leaving time_unix at 0 const time_t time_sec = time_usec / 1000000; localtime_tm = *gmtime(&time_sec); } +#endif const struct PACKED { uint16_t year; uint8_t mon; @@ -1150,10 +1152,14 @@ void AP_MSP_Telem_Backend::hide_osd_items(void) BIT_SET(osd_hidden_items_bitmask, OSD_MAIN_BATT_VOLTAGE); } // flash rtc if no time available +#if AP_RTC_ENABLED uint64_t time_usec; if (!AP::rtc().get_utc_usec(time_usec)) { BIT_SET(osd_hidden_items_bitmask, OSD_RTC_DATETIME); } +#else + BIT_SET(osd_hidden_items_bitmask, OSD_RTC_DATETIME); +#endif // flash rssi if disabled float rssi; if (!get_rssi(rssi)) { diff --git a/libraries/AP_MSP/AP_MSP_config.h b/libraries/AP_MSP/AP_MSP_config.h index 1f486e07ccdb56..9265def7bebebc 100644 --- a/libraries/AP_MSP/AP_MSP_config.h +++ b/libraries/AP_MSP/AP_MSP_config.h @@ -8,10 +8,10 @@ // define for enabling MSP sensor drivers #ifndef HAL_MSP_SENSORS_ENABLED -#define HAL_MSP_SENSORS_ENABLED HAL_MSP_ENABLED && !defined(HAL_BUILD_AP_PERIPH) +#define HAL_MSP_SENSORS_ENABLED HAL_MSP_ENABLED #endif // define for enabling MSP DisplayPort #ifndef HAL_WITH_MSP_DISPLAYPORT -#define HAL_WITH_MSP_DISPLAYPORT HAL_MSP_ENABLED && !defined(HAL_BUILD_AP_PERIPH) +#define HAL_WITH_MSP_DISPLAYPORT HAL_MSP_ENABLED #endif diff --git a/libraries/AP_Math/AP_Math.cpp b/libraries/AP_Math/AP_Math.cpp index e784486e929c70..2e4d6ba9b5b404 100644 --- a/libraries/AP_Math/AP_Math.cpp +++ b/libraries/AP_Math/AP_Math.cpp @@ -270,7 +270,9 @@ T constrain_value_line(const T amt, const T low, const T high, uint32_t line) // errors through any function that uses constrain_value(). The normal // float semantics already handle -Inf and +Inf if (isnan(amt)) { +#if AP_INTERNALERROR_ENABLED AP::internalerror().error(AP_InternalError::error_t::constraining_nan, line); +#endif return (low + high) / 2; } diff --git a/libraries/AP_Math/crc.cpp b/libraries/AP_Math/crc.cpp index bfc9b1dedfc5c4..e538d243758ff5 100644 --- a/libraries/AP_Math/crc.cpp +++ b/libraries/AP_Math/crc.cpp @@ -92,6 +92,16 @@ uint8_t crc_crc8(const uint8_t *p, uint8_t len) return crc & 0xFF; } +// CRC8 that does not use a lookup table: for generic polynomials +uint8_t crc8_generic(const uint8_t *buf, const uint16_t buf_len, const uint8_t polynomial) +{ + uint8_t crc = 0; + for (uint16_t i = 0; i < buf_len; i++) { + crc = crc8_dvb(buf[i], crc, polynomial); + } + return crc; +} + // crc8 from betaflight uint8_t crc8_dvb_s2(uint8_t crc, uint8_t a) { diff --git a/libraries/AP_Math/crc.h b/libraries/AP_Math/crc.h index 7c7b908c7bc372..cf994a5c23c8b2 100644 --- a/libraries/AP_Math/crc.h +++ b/libraries/AP_Math/crc.h @@ -21,6 +21,7 @@ uint16_t crc_crc4(uint16_t *data); uint8_t crc_crc8(const uint8_t *p, uint8_t len); +uint8_t crc8_generic(const uint8_t *buf, const uint16_t buf_len, const uint8_t polynomial); // CRC8 that does not use a lookup table for generic polynomials uint8_t crc8_dvb_s2(uint8_t crc, uint8_t a); uint8_t crc8_dvb(uint8_t crc, uint8_t a, uint8_t seed); uint8_t crc8_dvb_s2_update(uint8_t crc, const void *data, uint32_t length); diff --git a/libraries/AP_Math/definitions.h b/libraries/AP_Math/definitions.h index 3194dc607d79d5..88199349d51556 100644 --- a/libraries/AP_Math/definitions.h +++ b/libraries/AP_Math/definitions.h @@ -110,6 +110,7 @@ static const double WGS84_E = (sqrt(2 * WGS84_F - WGS84_F * WGS84_F)); // speed and distance conversions #define KNOTS_TO_METERS_PER_SECOND 0.51444 #define FEET_TO_METERS 0.3048 +#define METRES_TO_FEET 3.280839895013123 // Convert amps milliseconds to milliamp hours // Amp.millisec to milliAmp.hour = 1/1E3(ms->s) * 1/3600(s->hr) * 1000(A->mA) diff --git a/libraries/AP_Math/tests/test_math_double.cpp b/libraries/AP_Math/tests/test_math_double.cpp index e6667650d92019..0f84b6fe3c0774 100644 --- a/libraries/AP_Math/tests/test_math_double.cpp +++ b/libraries/AP_Math/tests/test_math_double.cpp @@ -3,7 +3,6 @@ // you're doing when directly comparing floats: #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wfloat-equal" -#define ALLOW_DOUBLE_MATH_FUNCTIONS #include #include @@ -187,8 +186,8 @@ TEST(MathWrapTest, Angle2PIDouble) const double accuracy = 1.0e-5; EXPECT_NEAR(M_PI, wrap_2PI((double)M_PI), accuracy); - EXPECT_NEAR(0.0, wrap_2PI((double)M_2PI), accuracy); - EXPECT_NEAR(0.0, wrap_2PI((double)M_PI * 10.0), accuracy); + EXPECT_NEAR(0.0, wrap_PI((double)M_2PI), accuracy); + EXPECT_NEAR(0.0, wrap_PI((double)M_PI * 10.0), accuracy); EXPECT_NEAR(0.0, wrap_2PI(0.0), accuracy); EXPECT_NEAR(M_PI, wrap_2PI((double)-M_PI), accuracy); EXPECT_NEAR(0, wrap_2PI((double)-M_2PI), accuracy); diff --git a/libraries/AP_Math/tests/test_vector2.cpp b/libraries/AP_Math/tests/test_vector2.cpp index 2125aabaca1550..e3b835f10963fe 100644 --- a/libraries/AP_Math/tests/test_vector2.cpp +++ b/libraries/AP_Math/tests/test_vector2.cpp @@ -111,7 +111,7 @@ TEST(Vector2Test, angle) { EXPECT_FLOAT_EQ(M_PI/2, Vector2f(0, 1).angle()); EXPECT_FLOAT_EQ(M_PI/4, Vector2f(1, 1).angle()); - EXPECT_FLOAT_EQ(0.0f, Vector2d(1, 0).angle()); + EXPECT_TRUE(is_zero(Vector2d(1, 0).angle())); EXPECT_FLOAT_EQ(M_PI*5/4, Vector2f(-1, -1).angle()); EXPECT_FLOAT_EQ(M_PI*5/4, Vector2f(-5, -5).angle()); diff --git a/libraries/AP_Math/tests/test_vector3.cpp b/libraries/AP_Math/tests/test_vector3.cpp index dac9662f4a4577..f242af26deed12 100644 --- a/libraries/AP_Math/tests/test_vector3.cpp +++ b/libraries/AP_Math/tests/test_vector3.cpp @@ -1,5 +1,4 @@ #include -#define ALLOW_DOUBLE_MATH_FUNCTIONS #include const AP_HAL::HAL& hal = AP_HAL::get_HAL(); diff --git a/libraries/AP_Math/tests/wscript b/libraries/AP_Math/tests/wscript index cd3e5e3ce7c9d9..05adee01a560f4 100644 --- a/libraries/AP_Math/tests/wscript +++ b/libraries/AP_Math/tests/wscript @@ -4,4 +4,5 @@ def build(bld): bld.ap_find_tests( use='ap', + DOUBLE_PRECISION_SOURCES = ['test_math_double.cpp', 'test_vector3.cpp'] ) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 67de677799b6d9..2dba86c24eb19c 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -89,7 +89,7 @@ void AP_Mission::init() // If Mission Clear bit is set then it should clear the mission, otherwise retain the mission. if (AP_MISSION_MASK_MISSION_CLEAR & _options) { - gcs().send_text(MAV_SEVERITY_INFO, "Clearing Mission"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Clearing Mission"); clear(); } @@ -378,6 +378,7 @@ bool AP_Mission::verify_command(const Mission_Command& cmd) case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: case MAV_CMD_JUMP_TAG: case MAV_CMD_IMAGE_START_CAPTURE: + case MAV_CMD_IMAGE_STOP_CAPTURE: case MAV_CMD_SET_CAMERA_ZOOM: case MAV_CMD_SET_CAMERA_FOCUS: case MAV_CMD_VIDEO_START_CAPTURE: @@ -397,7 +398,12 @@ bool AP_Mission::start_command(const Mission_Command& cmd) set_in_landing_sequence_flag(false); } - gcs().send_text(MAV_SEVERITY_INFO, "Mission: %u %s", cmd.index, cmd.type()); + if (cmd.id == MAV_CMD_DO_JUMP || cmd.id == MAV_CMD_JUMP_TAG || cmd.id == MAV_CMD_DO_JUMP_TAG) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u %s %u", cmd.index, cmd.type(), (unsigned)cmd.p1); + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u %s", cmd.index, cmd.type()); + } + switch (cmd.id) { case MAV_CMD_DO_AUX_FUNCTION: return start_command_do_aux_function(cmd); @@ -417,6 +423,7 @@ bool AP_Mission::start_command(const Mission_Command& cmd) case MAV_CMD_DO_DIGICAM_CONTROL: case MAV_CMD_DO_SET_CAM_TRIGG_DIST: case MAV_CMD_IMAGE_START_CAPTURE: + case MAV_CMD_IMAGE_STOP_CAPTURE: case MAV_CMD_SET_CAMERA_ZOOM: case MAV_CMD_SET_CAMERA_FOCUS: case MAV_CMD_VIDEO_START_CAPTURE: @@ -1307,11 +1314,16 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_ break; case MAV_CMD_IMAGE_START_CAPTURE: + cmd.content.image_start_capture.instance = packet.param1; cmd.content.image_start_capture.interval_s = packet.param2; cmd.content.image_start_capture.total_num_images = packet.param3; cmd.content.image_start_capture.start_seq_number = packet.param4; break; + case MAV_CMD_IMAGE_STOP_CAPTURE: + cmd.p1 = packet.param1; + break; + case MAV_CMD_SET_CAMERA_ZOOM: cmd.content.set_camera_zoom.zoom_type = packet.param1; cmd.content.set_camera_zoom.zoom_value = packet.param2; @@ -1470,24 +1482,6 @@ MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_INT_to_MISSION_ITEM(const ma return MAV_MISSION_ACCEPTED; } -// mavlink_cmd_long_to_mission_cmd - converts a mavlink cmd long to an AP_Mission::Mission_Command object which can be stored to eeprom -// return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure -MAV_MISSION_RESULT AP_Mission::mavlink_cmd_long_to_mission_cmd(const mavlink_command_long_t& packet, AP_Mission::Mission_Command& cmd) -{ - mavlink_mission_item_int_t miss_item = {0}; - - miss_item.param1 = packet.param1; - miss_item.param2 = packet.param2; - miss_item.param3 = packet.param3; - miss_item.param4 = packet.param4; - - miss_item.command = packet.command; - miss_item.target_system = packet.target_system; - miss_item.target_component = packet.target_component; - - return mavlink_int_to_mission_cmd(miss_item, cmd); -} - // mission_cmd_to_mavlink_int - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS // return true on success, false on failure // NOTE: callers to this method current fill parts of "packet" in before calling this method, so do NOT attempt to zero the entire packet in here @@ -1820,11 +1814,16 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c break; case MAV_CMD_IMAGE_START_CAPTURE: + packet.param1 = cmd.content.image_start_capture.instance; packet.param2 = cmd.content.image_start_capture.interval_s; packet.param3 = cmd.content.image_start_capture.total_num_images; packet.param4 = cmd.content.image_start_capture.start_seq_number; break; + case MAV_CMD_IMAGE_STOP_CAPTURE: + packet.param1 = cmd.p1; + break; + case MAV_CMD_SET_CAMERA_ZOOM: packet.param1 = cmd.content.set_camera_zoom.zoom_type; packet.param2 = cmd.content.set_camera_zoom.zoom_value; @@ -1973,7 +1972,7 @@ bool AP_Mission::advance_current_nav_cmd(uint16_t starting_index) // check if the vehicle is resuming and has returned to where it was interrupted if (_flags.resuming_mission && _nav_cmd.index == _wp_index_history[AP_MISSION_MAX_WP_HISTORY-1]) { // vehicle has resumed previous position - gcs().send_text(MAV_SEVERITY_INFO, "Mission: Returned to interrupted WP"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: Returned to interrupted WP"); _flags.resuming_mission = false; } @@ -2240,7 +2239,7 @@ 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); + 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) { @@ -2335,12 +2334,12 @@ bool AP_Mission::jump_to_landing_sequence(void) resume(); } - gcs().send_text(MAV_SEVERITY_INFO, "Landing sequence start"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Landing sequence start"); _flags.in_landing_sequence = true; return true; } - gcs().send_text(MAV_SEVERITY_WARNING, "Unable to start landing sequence"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Unable to start landing sequence"); return false; } @@ -2381,11 +2380,11 @@ bool AP_Mission::jump_to_abort_landing_sequence(void) _flags.in_landing_sequence = false; - gcs().send_text(MAV_SEVERITY_INFO, "Landing abort sequence start"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Landing abort sequence start"); return true; } - gcs().send_text(MAV_SEVERITY_WARNING, "Unable to start find a landing abort sequence"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Unable to start find a landing abort sequence"); return false; } @@ -2443,7 +2442,7 @@ bool AP_Mission::is_best_land_sequence(void) // compare distances if (dist_via_do_land >= dist_continue_to_land) { // then the mission should carry on uninterrupted as that is the shorter distance - gcs().send_text(MAV_SEVERITY_NOTICE, "Rejecting RTL: closer land if mis continued"); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Rejecting RTL: closer land if mis continued"); return true; } else { // allow failsafes to interrupt the current mission @@ -2648,6 +2647,8 @@ const char *AP_Mission::Mission_Command::type() const return "GimbalPitchYaw"; case MAV_CMD_IMAGE_START_CAPTURE: return "ImageStartCapture"; + case MAV_CMD_IMAGE_STOP_CAPTURE: + return "ImageStopCapture"; case MAV_CMD_SET_CAMERA_ZOOM: return "SetCameraZoom"; case MAV_CMD_SET_CAMERA_FOCUS: diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index c8608e657c8374..c6b35b8fb09e82 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -269,6 +269,7 @@ class AP_Mission // MAV_CMD_IMAGE_START_CAPTURE support struct PACKED image_start_capture_Command { + uint8_t instance; float interval_s; uint16_t total_num_images; uint16_t start_seq_number; @@ -627,10 +628,6 @@ class AP_Mission // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure static MAV_MISSION_RESULT mavlink_int_to_mission_cmd(const mavlink_mission_item_int_t& packet, AP_Mission::Mission_Command& cmd); - // mavlink_cmd_long_to_mission_cmd - converts a mavlink cmd long to an AP_Mission::Mission_Command object which can be stored to eeprom - // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure - static MAV_MISSION_RESULT mavlink_cmd_long_to_mission_cmd(const mavlink_command_long_t& packet, AP_Mission::Mission_Command& cmd); - // mission_cmd_to_mavlink_int - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS // return true on success, false on failure static bool mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& cmd, mavlink_mission_item_int_t& packet); diff --git a/libraries/AP_Mission/AP_Mission_Commands.cpp b/libraries/AP_Mission/AP_Mission_Commands.cpp index fac9973c5c0139..83716ec71849cd 100644 --- a/libraries/AP_Mission/AP_Mission_Commands.cpp +++ b/libraries/AP_Mission/AP_Mission_Commands.cpp @@ -43,12 +43,12 @@ bool AP_Mission::start_command_do_gripper(const AP_Mission::Mission_Command& cmd case GRIPPER_ACTION_RELEASE: gripper->release(); // Log_Write_Event(DATA_GRIPPER_RELEASE); - gcs().send_text(MAV_SEVERITY_INFO, "Gripper Released"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper Released"); return true; case GRIPPER_ACTION_GRAB: gripper->grab(); // Log_Write_Event(DATA_GRIPPER_GRAB); - gcs().send_text(MAV_SEVERITY_INFO, "Gripper Grabbed"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper Grabbed"); return true; default: #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -163,8 +163,35 @@ bool AP_Mission::start_command_camera(const AP_Mission::Mission_Command& cmd) return false; case MAV_CMD_IMAGE_START_CAPTURE: - camera->take_picture(); - return true; + // check if this is a single picture request (e.g. total images is 1 or interval and total images are zero) + if ((cmd.content.image_start_capture.total_num_images == 1) || + (cmd.content.image_start_capture.total_num_images == 0 && is_zero(cmd.content.image_start_capture.interval_s))) { + if (cmd.content.image_start_capture.instance == 0) { + // take pictures for every backend + return camera->take_picture(); + } + return camera->take_picture(cmd.content.image_start_capture.instance-1); + } else if (cmd.content.image_start_capture.total_num_images == 0) { + // multiple picture request, take pictures forever + if (cmd.content.image_start_capture.instance == 0) { + // take pictures for every backend + return camera->take_multiple_pictures(cmd.content.image_start_capture.interval_s*1000, -1); + } + return camera->take_multiple_pictures(cmd.content.image_start_capture.instance-1, cmd.content.image_start_capture.interval_s*1000, -1); + } else { + if (cmd.content.image_start_capture.instance == 0) { + // take pictures for every backend + return camera->take_multiple_pictures(cmd.content.image_start_capture.interval_s*1000, cmd.content.image_start_capture.total_num_images); + } + return camera->take_multiple_pictures(cmd.content.image_start_capture.instance-1, cmd.content.image_start_capture.interval_s*1000, cmd.content.image_start_capture.total_num_images); + } + case MAV_CMD_IMAGE_STOP_CAPTURE: + if (cmd.p1 == 0) { + // stop capture for each backend + camera->stop_capture(); + return true; + } + return camera->stop_capture(cmd.p1 - 1); case MAV_CMD_VIDEO_START_CAPTURE: case MAV_CMD_VIDEO_STOP_CAPTURE: @@ -220,7 +247,7 @@ bool AP_Mission::start_command_parachute(const AP_Mission::Mission_Command& cmd) bool AP_Mission::command_do_set_repeat_dist(const AP_Mission::Mission_Command& cmd) { _repeat_dist = cmd.p1; - gcs().send_text(MAV_SEVERITY_INFO, "Resume repeat dist set to %u m",_repeat_dist); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Resume repeat dist set to %u m",_repeat_dist); return true; } diff --git a/libraries/AP_Motors/AP_Motors6DOF.cpp b/libraries/AP_Motors/AP_Motors6DOF.cpp index f64e0a5aae61a9..951ecabbcbb7bd 100644 --- a/libraries/AP_Motors/AP_Motors6DOF.cpp +++ b/libraries/AP_Motors/AP_Motors6DOF.cpp @@ -232,7 +232,9 @@ void AP_Motors6DOF::output_min() int16_t AP_Motors6DOF::calc_thrust_to_pwm(float thrust_in) const { - return constrain_int16(1500 + thrust_in * 400, get_pwm_output_min(), get_pwm_output_max()); + int16_t range_up = get_pwm_output_max() - 1500; + int16_t range_down = 1500 - get_pwm_output_min(); + return 1500 + thrust_in * (thrust_in > 0 ? range_up : range_down); } void AP_Motors6DOF::output_to_motors() diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index 6c24ca2d389987..52176330bac8b3 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -440,69 +440,6 @@ void AP_MotorsHeli::output_logic() } } -// parameter_check - check if helicopter specific parameters are sensible -bool AP_MotorsHeli::parameter_check(bool display_msg) const -{ - // returns false if RSC Mode is not set to a valid control mode - if (_main_rotor._rsc_mode.get() <= (int8_t)ROTOR_CONTROL_MODE_DISABLED || _main_rotor._rsc_mode.get() > (int8_t)ROTOR_CONTROL_MODE_AUTOTHROTTLE) { - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_MODE invalid"); - } - return false; - } - - // returns false if rsc_setpoint is out of range - if ( _main_rotor._rsc_setpoint.get() > 100 || _main_rotor._rsc_setpoint.get() < 10){ - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_SETPOINT out of range"); - } - return false; - } - - // returns false if idle output is out of range - if ( _main_rotor._idle_output.get() > 100 || _main_rotor._idle_output.get() < 0){ - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_IDLE out of range"); - } - return false; - } - - // returns false if _rsc_critical is not between 0 and 100 - if (_main_rotor._critical_speed.get() > 100 || _main_rotor._critical_speed.get() < 0) { - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RSC_CRITICAL out of range"); - } - return false; - } - - // returns false if RSC Runup Time is less than Ramp time as this could cause undesired behaviour of rotor speed estimate - if (_main_rotor._runup_time.get() <= _main_rotor._ramp_time.get()){ - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_RUNUP_TIME too small"); - } - return false; - } - - // returns false if _collective_min_deg is not default value which indicates users set parameter - if (is_equal((float)_collective_min_deg, (float)AP_MOTORS_HELI_COLLECTIVE_MIN_DEG)) { - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Set H_COL_ANG_MIN to measured min blade pitch in deg"); - } - return false; - } - - // returns false if _collective_max_deg is not default value which indicates users set parameter - if (is_equal((float)_collective_max_deg, (float)AP_MOTORS_HELI_COLLECTIVE_MAX_DEG)) { - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Set H_COL_ANG_MAX to measured max blade pitch in deg"); - } - return false; - } - - // all other cases parameters are OK - return true; -} - // update the throttle input filter void AP_MotorsHeli::update_throttle_filter() { @@ -576,6 +513,7 @@ void AP_MotorsHeli::update_turbine_start() } } +// Run arming checks bool AP_MotorsHeli::arming_checks(size_t buflen, char *buffer) const { // run base class checks @@ -588,6 +526,48 @@ bool AP_MotorsHeli::arming_checks(size_t buflen, char *buffer) const return false; } + // returns false if RSC Mode is not set to a valid control mode + if (_main_rotor._rsc_mode.get() <= (int8_t)ROTOR_CONTROL_MODE_DISABLED || _main_rotor._rsc_mode.get() > (int8_t)ROTOR_CONTROL_MODE_AUTOTHROTTLE) { + hal.util->snprintf(buffer, buflen, "H_RSC_MODE invalid"); + return false; + } + + // returns false if rsc_setpoint is out of range + if ( _main_rotor._rsc_setpoint.get() > 100 || _main_rotor._rsc_setpoint.get() < 10){ + hal.util->snprintf(buffer, buflen, "H_RSC_SETPOINT out of range"); + return false; + } + + // returns false if idle output is out of range + if ( _main_rotor._idle_output.get() > 100 || _main_rotor._idle_output.get() < 0){ + hal.util->snprintf(buffer, buflen, "H_RSC_IDLE out of range"); + return false; + } + + // returns false if _rsc_critical is not between 0 and 100 + if (_main_rotor._critical_speed.get() > 100 || _main_rotor._critical_speed.get() < 0) { + hal.util->snprintf(buffer, buflen, "H_RSC_CRITICAL out of range"); + return false; + } + + // returns false if RSC Runup Time is less than Ramp time as this could cause undesired behaviour of rotor speed estimate + if (_main_rotor._runup_time.get() <= _main_rotor._ramp_time.get()){ + hal.util->snprintf(buffer, buflen, "H_RUNUP_TIME too small"); + return false; + } + + // returns false if _collective_min_deg is not default value which indicates users set parameter + if (is_equal((float)_collective_min_deg, (float)AP_MOTORS_HELI_COLLECTIVE_MIN_DEG)) { + hal.util->snprintf(buffer, buflen, "Set H_COL_ANG_MIN to measured min blade pitch in deg"); + return false; + } + + // returns false if _collective_max_deg is not default value which indicates users set parameter + if (is_equal((float)_collective_max_deg, (float)AP_MOTORS_HELI_COLLECTIVE_MAX_DEG)) { + hal.util->snprintf(buffer, buflen, "Set H_COL_ANG_MAX to measured max blade pitch in deg"); + return false; + } + return true; } diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index c5e27114c1f19a..c32ed28f1cff40 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -66,9 +66,6 @@ class AP_MotorsHeli : public AP_Motors { // heli specific methods // - // parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check - virtual bool parameter_check(bool display_msg) const; - //set turbine start flag on to initiaize starting sequence void set_turb_start(bool turb_start) { _heliflags.start_engine = turb_start; } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index e629ffb0e4ada2..290a3f9a2e1ee2 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -242,7 +242,6 @@ void AP_MotorsHeli_Dual::calculate_armed_scalars() if (_main_rotor._rsc_mode.get() != _main_rotor.get_control_mode()) { _main_rotor.reset_rsc_mode_param(); _heliflags.save_rsc_mode = true; - gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed"); } // saves rsc mode parameter when disarmed if it had been reset while armed if (_heliflags.save_rsc_mode && !armed()) { @@ -608,25 +607,25 @@ void AP_MotorsHeli_Dual::servo_test() _pitch_in = constrain_float(_pitch_test, -1.0f, 1.0f); } -// parameter_check - check if helicopter specific parameters are sensible -bool AP_MotorsHeli_Dual::parameter_check(bool display_msg) const +// Run arming checks +bool AP_MotorsHeli_Dual::arming_checks(size_t buflen, char *buffer) const { + // run base class checks + if (!AP_MotorsHeli::arming_checks(buflen, buffer)) { + return false; + } + // returns false if Phase Angle is outside of range for H3 swashplate 1 if (_swashplate1.get_swash_type() == SWASHPLATE_TYPE_H3 && (_swashplate1.get_phase_angle() > 30 || _swashplate1.get_phase_angle() < -30)){ - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_SW1_H3_PHANG out of range"); - } + hal.util->snprintf(buffer, buflen, "H_SW1_H3_PHANG out of range"); return false; } // returns false if Phase Angle is outside of range for H3 swashplate 2 if (_swashplate2.get_swash_type() == SWASHPLATE_TYPE_H3 && (_swashplate2.get_phase_angle() > 30 || _swashplate2.get_phase_angle() < -30)){ - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_SW2_H3_PHANG out of range"); - } + hal.util->snprintf(buffer, buflen, "H_SW2_H3_PHANG out of range"); return false; } - // check parent class parameters - return AP_MotorsHeli::parameter_check(display_msg); + return true; } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.h b/libraries/AP_Motors/AP_MotorsHeli_Dual.h index d9f592399f9fbb..5fefd3201bdd1d 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.h @@ -64,8 +64,8 @@ class AP_MotorsHeli_Dual : public AP_MotorsHeli { // servo_test - move servos through full range of movement void servo_test() override; - // parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check - bool parameter_check(bool display_msg) const override; + // Run arming checks + bool arming_checks(size_t buflen, char *buffer) const override; // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp index f545b4c3e8c4eb..2b0fd53083c23b 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp @@ -73,7 +73,6 @@ void AP_MotorsHeli_Quad::calculate_armed_scalars() // keeps user from changing RSC mode while armed if (_main_rotor._rsc_mode.get() != _main_rotor.get_control_mode()) { _main_rotor.reset_rsc_mode_param(); - gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed"); _heliflags.save_rsc_mode = true; } // saves rsc mode parameter when disarmed if it had been reset while armed diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index eacb0b923c42f5..5cdb3a58b527f4 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -145,7 +145,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = { // @Param: DDFP_SPIN_MIN // @DisplayName: DDFP Tail Rotor Motor Spin minimum - // @Description: Point at which the thrust starts expressed as a number from 0 to 1 in the entire output range. Should be higher than MOT_SPIN_ARM. + // @Description: Point at which the thrust starts expressed as a number from 0 to 1 in the entire output range. // @Values: 0.0:Low, 0.15:Default, 0.3:High // @User: Standard @@ -243,7 +243,6 @@ void AP_MotorsHeli_Single::calculate_armed_scalars() // keeps user from changing RSC mode while armed if (_main_rotor._rsc_mode.get() != _main_rotor.get_control_mode()) { _main_rotor.reset_rsc_mode_param(); - gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed"); _heliflags.save_rsc_mode = true; } // saves rsc mode parameter when disarmed if it had been reset while armed @@ -602,41 +601,37 @@ void AP_MotorsHeli_Single::servo_test() _yaw_in = constrain_float(_yaw_test, -1.0f, 1.0f); } -// parameter_check - check if helicopter specific parameters are sensible -bool AP_MotorsHeli_Single::parameter_check(bool display_msg) const +// Run arming checks +bool AP_MotorsHeli_Single::arming_checks(size_t buflen, char *buffer) const { + // run base class checks + if (!AP_MotorsHeli::arming_checks(buflen, buffer)) { + return false; + } + // returns false if direct drive tailspeed is outside of range - if ((_direct_drive_tailspeed < 0) || (_direct_drive_tailspeed > 100)){ - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_TAIL_SPEED out of range"); - } + if ((_direct_drive_tailspeed < 0) || (_direct_drive_tailspeed > 100)) { + hal.util->snprintf(buffer, buflen, "H_TAIL_SPEED out of range"); return false; } // returns false if Phase Angle is outside of range for H3 swashplate if (_swashplate.get_swash_type() == SWASHPLATE_TYPE_H3 && (_swashplate.get_phase_angle() > 30 || _swashplate.get_phase_angle() < -30)){ - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_H3_PHANG out of range"); - } + hal.util->snprintf(buffer, buflen, "H_SW_H3_PHANG out of range"); return false; } // returns false if Acro External Gyro Gain is outside of range - if ((_ext_gyro_gain_acro < 0) || (_ext_gyro_gain_acro > 1000)){ - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_GYR_GAIN_ACRO out of range"); - } + if ((_ext_gyro_gain_acro < 0) || (_ext_gyro_gain_acro > 1000)) { + hal.util->snprintf(buffer, buflen, "H_GYR_GAIN_ACRO out of range"); return false; } // returns false if Standard External Gyro Gain is outside of range - if ((_ext_gyro_gain_std < 0) || (_ext_gyro_gain_std > 1000)){ - if (display_msg) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: H_GYR_GAIN out of range"); - } + if ((_ext_gyro_gain_std < 0) || (_ext_gyro_gain_std > 1000)) { + hal.util->snprintf(buffer, buflen, "H_GYR_GAIN out of range"); return false; } - // check parent class parameters - return AP_MotorsHeli::parameter_check(display_msg); + return true; } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index 0ab86299e3f159..ec67fa0ba11f47 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -77,8 +77,8 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { void set_acro_tail(bool set) override { _acro_tail = set; } - // parameter_check - returns true if helicopter specific parameters are sensible, used for pre-arm check - bool parameter_check(bool display_msg) const override; + // Run arming checks + bool arming_checks(size_t buflen, char *buffer) const override; // Thrust Linearization handling Thrust_Linearization thr_lin {*this}; diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 675e7fd566786c..5359ad16e70409 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -165,7 +165,7 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = { // @Param: SPOOL_TIME // @DisplayName: Spool up time // @Description: Time in seconds to spool up the motors from zero to min throttle. - // @Range: 0 2 + // @Range: 0.05 2 // @Units: s // @Increment: 0.1 // @User: Advanced @@ -222,6 +222,15 @@ const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = { // @User: Advanced AP_GROUPINFO("OPTIONS", 43, AP_MotorsMulticopter, _options, 0), + // @Param: SPOOL_TIM_DN + // @DisplayName: Spool down time + // @Description: Time taken to spool down the motors from min to zero throttle. If set to 0 then SPOOL_TIME is used instead. + // @Range: 0 2 + // @Units: s + // @Increment: 0.001 + // @User: Advanced + AP_GROUPINFO("SPOOL_TIM_DN", 44, AP_MotorsMulticopter, _spool_down_time, 0), + AP_GROUPEND }; @@ -477,6 +486,7 @@ void AP_MotorsMulticopter::update_throttle_hover(float dt) // run spool logic void AP_MotorsMulticopter::output_logic() { + const constexpr float minimum_spool_time = 0.05f; if (armed()) { if (_disarm_disable_pwm && (_disarm_safe_timer < _safe_time)) { _disarm_safe_timer += _dt; @@ -493,12 +503,11 @@ void AP_MotorsMulticopter::output_logic() _spool_state = SpoolState::SHUT_DOWN; } - if (_spool_up_time < 0.05) { + if (_spool_up_time < minimum_spool_time) { // prevent float exception - _spool_up_time.set(0.05); + _spool_up_time.set(minimum_spool_time); } - const float spool_step = _dt / _spool_up_time; switch (_spool_state) { case SpoolState::SHUT_DOWN: // Motors should be stationary. @@ -539,7 +548,9 @@ void AP_MotorsMulticopter::output_logic() // set and increment ramp variables switch (_spool_desired) { - case DesiredSpoolState::SHUT_DOWN: + case DesiredSpoolState::SHUT_DOWN: { + const float spool_time = _spool_down_time > minimum_spool_time ? _spool_down_time : _spool_up_time; + const float spool_step = _dt / spool_time; _spin_up_ratio -= spool_step; // constrain ramp value and update mode if (_spin_up_ratio <= 0.0f) { @@ -547,8 +558,10 @@ void AP_MotorsMulticopter::output_logic() _spool_state = SpoolState::SHUT_DOWN; } break; + } - case DesiredSpoolState::THROTTLE_UNLIMITED: + case DesiredSpoolState::THROTTLE_UNLIMITED: { + const float spool_step = _dt / _spool_up_time; _spin_up_ratio += spool_step; // constrain ramp value and update mode if (_spin_up_ratio >= 1.0f) { @@ -559,15 +572,19 @@ void AP_MotorsMulticopter::output_logic() } } break; - - case DesiredSpoolState::GROUND_IDLE: + } + case DesiredSpoolState::GROUND_IDLE: { + const float spool_up_step = _dt / _spool_up_time; + const float spool_down_time = _spool_down_time > minimum_spool_time ? _spool_down_time : _spool_up_time; + const float spool_down_step = _dt / spool_down_time; float spin_up_armed_ratio = 0.0f; if (thr_lin.get_spin_min() > 0.0f) { spin_up_armed_ratio = _spin_arm / thr_lin.get_spin_min(); } - _spin_up_ratio += constrain_float(spin_up_armed_ratio - _spin_up_ratio, -spool_step, spool_step); + _spin_up_ratio += constrain_float(spin_up_armed_ratio - _spin_up_ratio, -spool_down_step, spool_up_step); break; } + } _throttle_thrust_max = 0.0f; // initialise motor failure variables @@ -575,7 +592,8 @@ void AP_MotorsMulticopter::output_logic() _thrust_boost_ratio = 0.0f; break; } - case SpoolState::SPOOLING_UP: + case SpoolState::SPOOLING_UP: { + const float spool_step = _dt / _spool_up_time; // Maximum throttle should move from minimum to maximum. // Servos should exhibit normal flight behavior. @@ -608,8 +626,10 @@ void AP_MotorsMulticopter::output_logic() _thrust_boost = false; _thrust_boost_ratio = MAX(0.0, _thrust_boost_ratio - spool_step); break; + } - case SpoolState::THROTTLE_UNLIMITED: + case SpoolState::THROTTLE_UNLIMITED: { + const float spool_step = _dt / _spool_up_time; // Throttle should exhibit normal flight behavior. // Servos should exhibit normal flight behavior. @@ -636,6 +656,7 @@ void AP_MotorsMulticopter::output_logic() _thrust_boost_ratio = MAX(0.0, _thrust_boost_ratio - spool_step); } break; + } case SpoolState::SPOOLING_DOWN: // Maximum throttle should move from maximum to minimum. @@ -656,6 +677,8 @@ void AP_MotorsMulticopter::output_logic() // set and increment ramp variables _spin_up_ratio = 1.0f; + const float spool_time = _spool_down_time > minimum_spool_time ? _spool_down_time : _spool_up_time; + const float spool_step = _dt / spool_time; _throttle_thrust_max -= spool_step; // constrain ramp value and update mode diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index f2b8b1dc036ab2..f6e07e204a74c4 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -169,6 +169,7 @@ class AP_MotorsMulticopter : public AP_Motors { // time to spool motors to min throttle AP_Float _spool_up_time; + AP_Float _spool_down_time; // scaling for booster motor throttle AP_Float _boost_scale; diff --git a/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh b/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh index a2f68b435f04fa..9aa45495411d26 100755 --- a/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh +++ b/libraries/AP_Motors/examples/AP_Motors_test/MotorTestSweep.sh @@ -1,3 +1,4 @@ +#!/bin/bash # Build and run the motors example stability test at a range of yaw headroom and throttle average max values # Output results to files for comparison diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 3e1ac030fc96fe..5f582ffdbbc004 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -287,7 +287,7 @@ void AP_Mount::set_rate_target(uint8_t instance, float roll_degs, float pitch_de backend->set_rate_target(roll_degs, pitch_degs, yaw_degs, yaw_lock); } -MAV_RESULT AP_Mount::handle_command_do_mount_configure(const mavlink_command_long_t &packet) +MAV_RESULT AP_Mount::handle_command_do_mount_configure(const mavlink_command_int_t &packet) { auto *backend = get_primary(); if (backend == nullptr) { @@ -300,7 +300,7 @@ MAV_RESULT AP_Mount::handle_command_do_mount_configure(const mavlink_command_lon } -MAV_RESULT AP_Mount::handle_command_do_mount_control(const mavlink_command_long_t &packet) +MAV_RESULT AP_Mount::handle_command_do_mount_control(const mavlink_command_int_t &packet) { auto *backend = get_primary(); if (backend == nullptr) { @@ -310,13 +310,13 @@ MAV_RESULT AP_Mount::handle_command_do_mount_control(const mavlink_command_long_ return backend->handle_command_do_mount_control(packet); } -MAV_RESULT AP_Mount::handle_command_do_gimbal_manager_pitchyaw(const mavlink_command_long_t &packet) +MAV_RESULT AP_Mount::handle_command_do_gimbal_manager_pitchyaw(const mavlink_command_int_t &packet) { AP_Mount_Backend *backend; // check gimbal device id. 0 is primary, 1 is 1st gimbal, 2 is // 2nd gimbal, etc - const uint8_t instance = packet.param7; + const uint8_t instance = packet.z; if (instance == 0) { backend = get_primary(); } else { @@ -328,7 +328,7 @@ MAV_RESULT AP_Mount::handle_command_do_gimbal_manager_pitchyaw(const mavlink_com } // check flags for change to RETRACT - uint32_t flags = (uint32_t)packet.param5; + const uint32_t flags = packet.x; if ((flags & GIMBAL_MANAGER_FLAGS_RETRACT) > 0) { backend->set_mode(MAV_MOUNT_MODE_RETRACT); return MAV_RESULT_ACCEPTED; @@ -361,12 +361,12 @@ MAV_RESULT AP_Mount::handle_command_do_gimbal_manager_pitchyaw(const mavlink_com } // handle mav_cmd_do_gimbal_manager_configure for deconflicting different mavlink message senders -MAV_RESULT AP_Mount::handle_command_do_gimbal_manager_configure(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT AP_Mount::handle_command_do_gimbal_manager_configure(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { AP_Mount_Backend *backend; // check gimbal device id. 0 is primary, 1 is 1st gimbal, 2 is 2nd gimbal, etc - const uint8_t instance = packet.param7; + const uint8_t instance = packet.z; if (instance == 0) { backend = get_primary(); } else { @@ -486,7 +486,7 @@ void AP_Mount::handle_command_gimbal_manager_set_pitchyaw(const mavlink_message_ if (!isnan(packet.pitch) && !isnan(packet.yaw)) { const float pitch_angle_deg = degrees(packet.pitch); const float yaw_angle_deg = degrees(packet.yaw); - set_angle_target(instance, 0, pitch_angle_deg, yaw_angle_deg, flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); + backend->set_angle_target(0, pitch_angle_deg, yaw_angle_deg, flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); return; } @@ -494,12 +494,24 @@ void AP_Mount::handle_command_gimbal_manager_set_pitchyaw(const mavlink_message_ if (!isnan(packet.pitch_rate) && !isnan(packet.yaw_rate)) { const float pitch_rate_degs = degrees(packet.pitch_rate); const float yaw_rate_degs = degrees(packet.yaw_rate); - set_rate_target(instance, 0, pitch_rate_degs, yaw_rate_degs, flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); + backend->set_rate_target(0, pitch_rate_degs, yaw_rate_degs, flags & GIMBAL_MANAGER_FLAGS_YAW_LOCK); return; } } -MAV_RESULT AP_Mount::handle_command_long(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT AP_Mount::handle_command_do_set_roi_sysid(const mavlink_command_int_t &packet) +{ + set_target_sysid((uint8_t)packet.param1); + return MAV_RESULT_ACCEPTED; +} + +MAV_RESULT AP_Mount::handle_command_do_set_roi_none() +{ + set_mode_to_default(); + return MAV_RESULT_ACCEPTED; +} + +MAV_RESULT AP_Mount::handle_command(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch (packet.command) { case MAV_CMD_DO_MOUNT_CONFIGURE: @@ -510,6 +522,10 @@ MAV_RESULT AP_Mount::handle_command_long(const mavlink_command_long_t &packet, c return handle_command_do_gimbal_manager_pitchyaw(packet); case MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE: return handle_command_do_gimbal_manager_configure(packet, msg); + case MAV_CMD_DO_SET_ROI_SYSID: + return handle_command_do_set_roi_sysid(packet); + case MAV_CMD_DO_SET_ROI_NONE: + return handle_command_do_set_roi_none(); default: return MAV_RESULT_UNSUPPORTED; } @@ -532,6 +548,7 @@ void AP_Mount::handle_global_position_int(const mavlink_message_t &msg) } } +#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED /// Change the configuration of the mount void AP_Mount::handle_mount_configure(const mavlink_message_t &msg) { @@ -546,7 +563,9 @@ void AP_Mount::handle_mount_configure(const mavlink_message_t &msg) // send message to backend backend->handle_mount_configure(packet); } +#endif +#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED /// Control the mount (depends on the previously set mount configuration) void AP_Mount::handle_mount_control(const mavlink_message_t &msg) { @@ -561,7 +580,9 @@ void AP_Mount::handle_mount_control(const mavlink_message_t &msg) // send message to backend backend->handle_mount_control(packet); } +#endif +#if HAL_GCS_ENABLED // send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS void AP_Mount::send_gimbal_device_attitude_status(mavlink_channel_t chan) { @@ -594,6 +615,7 @@ void AP_Mount::send_gimbal_manager_status(mavlink_channel_t chan) } } } +#endif // HAL_GCS_ENABLED // get mount's current attitude in euler angles in degrees. yaw angle is in body-frame // returns true on success @@ -646,7 +668,7 @@ bool AP_Mount::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) return true; } -// accessors for scripting backends +// get target rate in deg/sec. returns true on success bool AP_Mount::get_rate_target(uint8_t instance, float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame) { auto *backend = get_instance(instance); @@ -656,6 +678,7 @@ bool AP_Mount::get_rate_target(uint8_t instance, float& roll_degs, float& pitch_ return backend->get_rate_target(roll_degs, pitch_degs, yaw_degs, yaw_is_earth_frame); } +// get target angle in deg. returns true on success bool AP_Mount::get_angle_target(uint8_t instance, float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) { auto *backend = get_instance(instance); @@ -665,6 +688,7 @@ bool AP_Mount::get_angle_target(uint8_t instance, float& roll_deg, float& pitch_ return backend->get_angle_target(roll_deg, pitch_deg, yaw_deg, yaw_is_earth_frame); } +// accessors for scripting backends and logging bool AP_Mount::get_location_target(uint8_t instance, Location& target_loc) { auto *backend = get_instance(instance); @@ -683,6 +707,26 @@ void AP_Mount::set_attitude_euler(uint8_t instance, float roll_deg, float pitch_ backend->set_attitude_euler(roll_deg, pitch_deg, yaw_bf_deg); } +// write mount log packet for all backends +void AP_Mount::write_log() +{ + // each instance writes log + for (uint8_t instance=0; instancewrite_log(0); + } + } +} + +void AP_Mount::write_log(uint8_t instance, uint64_t timestamp_us) +{ + auto *backend = get_instance(instance); + if (backend == nullptr) { + return; + } + backend->write_log(timestamp_us); +} + // point at system ID sysid void AP_Mount::set_target_sysid(uint8_t instance, uint8_t sysid) { @@ -772,26 +816,44 @@ bool AP_Mount::set_tracking(uint8_t instance, TrackingType tracking_type, const return backend->set_tracking(tracking_type, p1, p2); } +// set camera lens as a value from 0 to 5 +bool AP_Mount::set_lens(uint8_t instance, uint8_t lens) +{ + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + return backend->set_lens(lens); +} + // send camera information message to GCS -void AP_Mount::send_camera_information(mavlink_channel_t chan) const +void AP_Mount::send_camera_information(uint8_t instance, mavlink_channel_t chan) const { - // call send_camera_information for each instance - for (uint8_t instance=0; instancesend_camera_information(chan); - } + auto *backend = get_instance(instance); + if (backend == nullptr) { + return; } + backend->send_camera_information(chan); } // send camera settings message to GCS -void AP_Mount::send_camera_settings(mavlink_channel_t chan) const +void AP_Mount::send_camera_settings(uint8_t instance, mavlink_channel_t chan) const { - // call send_camera_settings for each instance - for (uint8_t instance=0; instancesend_camera_settings(chan); - } + auto *backend = get_instance(instance); + if (backend == nullptr) { + return; } + backend->send_camera_settings(chan); +} + +// get rangefinder distance. Returns true on success +bool AP_Mount::get_rangefinder_distance(uint8_t instance, float& distance_m) const +{ + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + return backend->get_rangefinder_distance(distance_m); } AP_Mount_Backend *AP_Mount::get_primary() const @@ -823,12 +885,16 @@ void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t &m case MAVLINK_MSG_ID_GIMBAL_REPORT: handle_gimbal_report(chan, msg); break; +#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED case MAVLINK_MSG_ID_MOUNT_CONFIGURE: handle_mount_configure(msg); break; +#endif +#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED case MAVLINK_MSG_ID_MOUNT_CONTROL: handle_mount_control(msg); break; +#endif case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: handle_global_position_int(msg); break; diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index b4187eabe46deb..d349da56b77b5a 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -23,6 +23,7 @@ #if HAL_MOUNT_ENABLED +#include #include #include #include @@ -177,8 +178,14 @@ class AP_Mount void set_target_sysid(uint8_t sysid) { set_target_sysid(_primary, sysid); } void set_target_sysid(uint8_t instance, uint8_t sysid); + // handling of set_roi_sysid message + MAV_RESULT handle_command_do_set_roi_sysid(const mavlink_command_int_t &packet); + + // handling of set_roi_none message + MAV_RESULT handle_command_do_set_roi_none(); + // mavlink message handling: - MAV_RESULT handle_command_long(const mavlink_command_long_t &packet, const mavlink_message_t &msg); + MAV_RESULT handle_command(const mavlink_command_int_t &packet, const mavlink_message_t &msg); void handle_param_value(const mavlink_message_t &msg); void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg); @@ -199,12 +206,22 @@ class AP_Mount // any failure_msg returned will not include a prefix bool pre_arm_checks(char *failure_msg, uint8_t failure_msg_len); - // accessors for scripting backends + // get target rate in deg/sec. returns true on success bool get_rate_target(uint8_t instance, float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame); + + // get target angle in deg. returns true on success bool get_angle_target(uint8_t instance, float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame); + + // accessors for scripting backends and logging bool get_location_target(uint8_t instance, Location& target_loc); void set_attitude_euler(uint8_t instance, float roll_deg, float pitch_deg, float yaw_bf_deg); + // write mount log packet for all backends + void write_log(); + + // write mount log packet for a single backend (called by camera library) + void write_log(uint8_t instance, uint64_t timestamp_us); + // // camera controls for gimbals that include a camera // @@ -228,11 +245,21 @@ class AP_Mount // p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom bool set_tracking(uint8_t instance, TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2); + // set camera lens as a value from 0 to 5 + bool set_lens(uint8_t instance, uint8_t lens); + // send camera information message to GCS - void send_camera_information(mavlink_channel_t chan) const; + void send_camera_information(uint8_t instance, mavlink_channel_t chan) const; // send camera settings message to GCS - void send_camera_settings(mavlink_channel_t chan) const; + void send_camera_settings(uint8_t instance, mavlink_channel_t chan) const; + + // + // rangefinder + // + + // get rangefinder distance. Returns true on success + bool get_rangefinder_distance(uint8_t instance, float& distance_m) const; // parameter var table static const struct AP_Param::GroupInfo var_info[]; @@ -255,13 +282,17 @@ class AP_Mount AP_Mount_Backend *get_instance(uint8_t instance) const; void handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg); +#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED void handle_mount_configure(const mavlink_message_t &msg); +#endif +#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED void handle_mount_control(const mavlink_message_t &msg); +#endif - MAV_RESULT handle_command_do_mount_configure(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_do_mount_control(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_do_gimbal_manager_pitchyaw(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_do_gimbal_manager_configure(const mavlink_command_long_t &packet, const mavlink_message_t &msg); + MAV_RESULT handle_command_do_mount_configure(const mavlink_command_int_t &packet); + MAV_RESULT handle_command_do_mount_control(const mavlink_command_int_t &packet); + MAV_RESULT handle_command_do_gimbal_manager_pitchyaw(const mavlink_command_int_t &packet); + MAV_RESULT handle_command_do_gimbal_manager_configure(const mavlink_command_int_t &packet, const mavlink_message_t &msg); void handle_gimbal_manager_set_attitude(const mavlink_message_t &msg); void handle_command_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg); void handle_global_position_int(const mavlink_message_t &msg); diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.cpp b/libraries/AP_Mount/AP_Mount_Alexmos.cpp index 1b831edc01c3de..f7f39f6119be40 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.cpp +++ b/libraries/AP_Mount/AP_Mount_Alexmos.cpp @@ -30,58 +30,59 @@ void AP_Mount_Alexmos::update() // move mount to a "retracted" position. we do not implement a separate servo based retract mechanism case MAV_MOUNT_MODE_RETRACT: { const Vector3f &target = _params.retract_angles.get(); - _angle_rad.roll = radians(target.x); - _angle_rad.pitch = radians(target.y); - _angle_rad.yaw = radians(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); break; } // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &target = _params.neutral_angles.get(); - _angle_rad.roll = radians(target.x); - _angle_rad.pitch = radians(target.y); - _angle_rad.yaw = radians(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - _angle_rad = mavt_target.angle_rad; - break; - case MountTargetType::RATE: - update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); - break; - } + // 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 targets using pilot's RC inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - update_angle_target_from_rate(rc_target, _angle_rad); - } else if (get_rc_angle_target(rc_target)) { - _angle_rad = rc_target; + 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; } break; } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: - IGNORE_RETURN(get_angle_target_to_roi(_angle_rad)); + 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: - IGNORE_RETURN(get_angle_target_to_home(_angle_rad)); + 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: - IGNORE_RETURN(get_angle_target_to_sysid(_angle_rad)); + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + } break; default: @@ -89,8 +90,16 @@ void AP_Mount_Alexmos::update() break; } - // send latest targets to gimbal - control_axis(_angle_rad); + // send target angles or rates depending on the target type + switch (mnt_target.target_type) { + case MountTargetType::RATE: + update_angle_target_from_rate(mnt_target.rate_rads, mnt_target.angle_rad); + FALLTHROUGH; + case MountTargetType::ANGLE: + // send latest angle targets to gimbal + control_axis(mnt_target.angle_rad); + break; + } } // has_pan_control - returns true if this mount can control its pan (required for multicopters) diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.h b/libraries/AP_Mount/AP_Mount_Alexmos.h index 1547d4a2fa8840..6485073dd4f5cb 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.h +++ b/libraries/AP_Mount/AP_Mount_Alexmos.h @@ -112,8 +112,6 @@ class AP_Mount_Alexmos : public AP_Mount_Backend // read_incoming - detect and read the header of the incoming message from the gimbal void read_incoming(); - MountTarget _angle_rad; // latest angle target - // structure for the Serial Protocol // CMD_BOARD_INFO diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index d4bc9b3a15085c..c50ab5a5d5e7b5 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -2,6 +2,7 @@ #if HAL_MOUNT_ENABLED #include #include +#include extern const AP_HAL::HAL& hal; @@ -49,11 +50,11 @@ void AP_Mount_Backend::set_angle_target(float roll_deg, float pitch_deg, float y } // set angle targets - mavt_target.target_type = MountTargetType::ANGLE; - mavt_target.angle_rad.roll = radians(roll_deg); - mavt_target.angle_rad.pitch = radians(pitch_deg); - mavt_target.angle_rad.yaw = radians(yaw_deg); - mavt_target.angle_rad.yaw_is_ef = yaw_is_earth_frame; + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.roll = radians(roll_deg); + mnt_target.angle_rad.pitch = radians(pitch_deg); + mnt_target.angle_rad.yaw = radians(yaw_deg); + mnt_target.angle_rad.yaw_is_ef = yaw_is_earth_frame; // set the mode to mavlink targeting set_mode(MAV_MOUNT_MODE_MAVLINK_TARGETING); @@ -64,11 +65,11 @@ void AP_Mount_Backend::set_angle_target(float roll_deg, float pitch_deg, float y void AP_Mount_Backend::set_rate_target(float roll_degs, float pitch_degs, float yaw_degs, bool yaw_is_earth_frame) { // set rate targets - mavt_target.target_type = MountTargetType::RATE; - mavt_target.rate_rads.roll = radians(roll_degs); - mavt_target.rate_rads.pitch = radians(pitch_degs); - mavt_target.rate_rads.yaw = radians(yaw_degs); - mavt_target.rate_rads.yaw_is_ef = yaw_is_earth_frame; + mnt_target.target_type = MountTargetType::RATE; + mnt_target.rate_rads.roll = radians(roll_degs); + mnt_target.rate_rads.pitch = radians(pitch_degs); + mnt_target.rate_rads.yaw = radians(yaw_degs); + mnt_target.rate_rads.yaw_is_ef = yaw_is_earth_frame; // set the mode to mavlink targeting set_mode(MAV_MOUNT_MODE_MAVLINK_TARGETING); @@ -107,12 +108,15 @@ void AP_Mount_Backend::set_target_sysid(uint8_t sysid) set_mode(MAV_MOUNT_MODE_SYSID_TARGET); } +#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED // process MOUNT_CONFIGURE messages received from GCS. deprecated. void AP_Mount_Backend::handle_mount_configure(const mavlink_mount_configure_t &packet) { set_mode((MAV_MOUNT_MODE)packet.mount_mode); } +#endif +#if HAL_GCS_ENABLED // send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan) { @@ -138,8 +142,12 @@ void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan std::numeric_limits::quiet_NaN(), // roll axis angular velocity (NaN for unknown) std::numeric_limits::quiet_NaN(), // pitch axis angular velocity (NaN for unknown) std::numeric_limits::quiet_NaN(), // yaw axis angular velocity (NaN for unknown) - 0); // failure flags (not supported) + 0, // failure flags (not supported) + std::numeric_limits::quiet_NaN(), // delta_yaw (NaN for unknonw) + std::numeric_limits::quiet_NaN(), // delta_yaw_velocity (NaN for unknonw) + _instance + 1); // gimbal_device_id } +#endif // return gimbal manager capability flags used by GIMBAL_MANAGER_INFORMATION message uint32_t AP_Mount_Backend::get_gimbal_manager_capability_flags() const @@ -208,6 +216,7 @@ void AP_Mount_Backend::send_gimbal_manager_status(mavlink_channel_t chan) 0); // secondary control component id } +#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED // process MOUNT_CONTROL messages received from GCS. deprecated. void AP_Mount_Backend::handle_mount_control(const mavlink_mount_control_t &packet) { @@ -243,11 +252,12 @@ void AP_Mount_Backend::handle_mount_control(const mavlink_mount_control_t &packe break; } } +#endif // handle do_mount_control command. Returns MAV_RESULT_ACCEPTED on success -MAV_RESULT AP_Mount_Backend::handle_command_do_mount_control(const mavlink_command_long_t &packet) +MAV_RESULT AP_Mount_Backend::handle_command_do_mount_control(const mavlink_command_int_t &packet) { - const MAV_MOUNT_MODE new_mode = (MAV_MOUNT_MODE)packet.param7; + const MAV_MOUNT_MODE new_mode = (MAV_MOUNT_MODE)packet.z; // interpret message fields based on mode switch (new_mode) { @@ -278,19 +288,19 @@ MAV_RESULT AP_Mount_Backend::handle_command_do_mount_control(const mavlink_comma case MAV_MOUNT_MODE_GPS_POINT: { // set lat, lon, alt position targets from mavlink message - // warn if lat, lon appear to be in param1,2 instead of param5,6 as this indicates + // warn if lat, lon appear to be in param1,2 instead of param x,y as this indicates // sender is relying on a bug in AP-4.2's (and earlier) handling of MAV_CMD_DO_MOUNT_CONTROL - if (!is_zero(packet.param1) && !is_zero(packet.param2) && is_zero(packet.param5) && is_zero(packet.param6)) { + if (!is_zero(packet.param1) && !is_zero(packet.param2) && packet.x == 0 && packet.y == 0) { send_warning_to_GCS("GPS_POINT target invalid"); return MAV_RESULT_FAILED; } // param4: altitude in meters - // param5: latitude in degrees * 1E7 - // param6: longitude in degrees * 1E7 + // x: latitude in degrees * 1E7 + // y: longitude in degrees * 1E7 const Location target_location { - (int32_t)packet.param5, // latitude in degrees * 1E7 - (int32_t)packet.param6, // longitude in degrees * 1E7 + packet.x, // latitude in degrees * 1E7 + packet.y, // longitude in degrees * 1E7 (int32_t)packet.param4 * 100, // alt converted from meters to cm Location::AltFrame::ABOVE_HOME }; @@ -306,7 +316,7 @@ MAV_RESULT AP_Mount_Backend::handle_command_do_mount_control(const mavlink_comma // handle do_gimbal_manager_configure. Returns MAV_RESULT_ACCEPTED on success // requires original message in order to extract caller's sysid and compid -MAV_RESULT AP_Mount_Backend::handle_command_do_gimbal_manager_configure(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT AP_Mount_Backend::handle_command_do_gimbal_manager_configure(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { // sanity check param1 and param2 values if ((packet.param1 < -3) || (packet.param1 > UINT8_MAX) || (packet.param2 < -3) || (packet.param2 > UINT8_MAX)) { @@ -356,6 +366,54 @@ bool AP_Mount_Backend::handle_global_position_int(uint8_t msg_sysid, const mavli return true; } +// write mount log packet +void AP_Mount_Backend::write_log(uint64_t timestamp_us) +{ + // return immediately if no yaw estimate + float ahrs_yaw = AP::ahrs().yaw; + if (isnan(ahrs_yaw)) { + return; + } + + const auto nanf = AP::logger().quiet_nanf(); + + // get_attitude_quaternion and convert to Euler angles + float roll = nanf; + float pitch = nanf; + float yaw_bf = nanf; + float yaw_ef = nanf; + if (_frontend.get_attitude_euler(_instance, roll, pitch, yaw_bf)) { + yaw_ef = wrap_180(yaw_bf + degrees(ahrs_yaw)); + } + + // get mount's target (desired) angles and convert yaw to earth frame + float target_roll = nanf; + float target_pitch = nanf; + float target_yaw = nanf; + bool target_yaw_is_ef = false; + IGNORE_RETURN(get_angle_target(target_roll, target_pitch, target_yaw, target_yaw_is_ef)); + + // get rangefinder distance + float rangefinder_dist = nanf; + IGNORE_RETURN(get_rangefinder_distance(rangefinder_dist)); + + const struct log_Mount pkt { + LOG_PACKET_HEADER_INIT(static_cast(LOG_MOUNT_MSG)), + time_us : (timestamp_us > 0) ? timestamp_us : AP_HAL::micros64(), + instance : _instance, + desired_roll : target_roll, + actual_roll : roll, + desired_pitch : target_pitch, + actual_pitch : pitch, + desired_yaw_bf: target_yaw_is_ef ? nanf : target_yaw, + actual_yaw_bf : yaw_bf, + desired_yaw_ef: target_yaw_is_ef ? target_yaw : nanf, + actual_yaw_ef : yaw_ef, + rangefinder_dist : rangefinder_dist, + }; + AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt)); +} + // get pilot input (in the range -1 to +1) received through RC void AP_Mount_Backend::get_rc_input(float& roll_in, float& pitch_in, float& yaw_in) const { @@ -379,61 +437,44 @@ void AP_Mount_Backend::get_rc_input(float& roll_in, float& pitch_in, float& yaw_ } } -// get rate targets (in rad/s) from pilot RC -// returns true on success (RC is providing rate targets), false on failure (RC is providing angle targets) -bool AP_Mount_Backend::get_rc_rate_target(MountTarget& rate_rads) const +// get angle or rate targets from pilot RC +// target_type will be either ANGLE or RATE, rpy will be the target angle in deg or rate in deg/s +void AP_Mount_Backend::get_rc_target(MountTargetType& target_type, MountTarget& target_rpy) const { - // exit immediately if RC is not providing rate targets - if (_params.rc_rate_max <= 0) { - return false; - } - // get RC input from pilot float roll_in, pitch_in, yaw_in; get_rc_input(roll_in, pitch_in, yaw_in); - // calculate rates - const float rc_rate_max_rads = radians(_params.rc_rate_max.get()); - rate_rads.roll = roll_in * rc_rate_max_rads; - rate_rads.pitch = pitch_in * rc_rate_max_rads; - rate_rads.yaw = yaw_in * rc_rate_max_rads; - // yaw frame - rate_rads.yaw_is_ef = _yaw_lock; - - return true; -} + target_rpy.yaw_is_ef = _yaw_lock; -// get angle targets (in radians) from pilot RC -// returns true on success (RC is providing angle targets), false on failure (RC is providing rate targets) -bool AP_Mount_Backend::get_rc_angle_target(MountTarget& angle_rad) const -{ - // exit immediately if RC is not providing angle targets - if (_params.rc_rate_max > 0) { - return false; - } - - // get RC input from pilot - float roll_in, pitch_in, yaw_in; - get_rc_input(roll_in, pitch_in, yaw_in); + // if RC_RATE is zero, targets are angle + if (_params.rc_rate_max <= 0) { + target_type = MountTargetType::ANGLE; - // roll angle - angle_rad.roll = radians(((roll_in + 1.0f) * 0.5f * (_params.roll_angle_max - _params.roll_angle_min) + _params.roll_angle_min)); + // roll angle + target_rpy.roll = radians(((roll_in + 1.0f) * 0.5f * (_params.roll_angle_max - _params.roll_angle_min) + _params.roll_angle_min)); - // pitch angle - angle_rad.pitch = radians(((pitch_in + 1.0f) * 0.5f * (_params.pitch_angle_max - _params.pitch_angle_min) + _params.pitch_angle_min)); + // pitch angle + target_rpy.pitch = radians(((pitch_in + 1.0f) * 0.5f * (_params.pitch_angle_max - _params.pitch_angle_min) + _params.pitch_angle_min)); - // yaw angle - angle_rad.yaw_is_ef = _yaw_lock; - if (angle_rad.yaw_is_ef) { - // if yaw is earth-frame pilot yaw input control angle from -180 to +180 deg - angle_rad.yaw = yaw_in * M_PI; - } else { - // yaw target in body frame so apply body frame limits - angle_rad.yaw = radians(((yaw_in + 1.0f) * 0.5f * (_params.yaw_angle_max - _params.yaw_angle_min) + _params.yaw_angle_min)); + // yaw angle + if (target_rpy.yaw_is_ef) { + // if yaw is earth-frame pilot yaw input control angle from -180 to +180 deg + target_rpy.yaw = yaw_in * M_PI; + } else { + // yaw target in body frame so apply body frame limits + target_rpy.yaw = radians(((yaw_in + 1.0f) * 0.5f * (_params.yaw_angle_max - _params.yaw_angle_min) + _params.yaw_angle_min)); + } + return; } - return true; + // calculate rate targets + target_type = MountTargetType::RATE; + const float rc_rate_max_rads = radians(_params.rc_rate_max.get()); + target_rpy.roll = roll_in * rc_rate_max_rads; + target_rpy.pitch = pitch_in * rc_rate_max_rads; + target_rpy.yaw = yaw_in * rc_rate_max_rads; } // get angle targets (in radians) to a Location @@ -507,6 +548,15 @@ float AP_Mount_Backend::MountTarget::get_ef_yaw() const return wrap_PI(yaw + AP::ahrs().yaw); } +// sets roll, pitch, yaw and yaw_is_ef +void AP_Mount_Backend::MountTarget::set(const Vector3f& rpy, bool yaw_is_ef_in) +{ + roll = rpy.x; + pitch = rpy.y; + yaw = rpy.z; + yaw_is_ef = yaw_is_ef_in; +} + // update angle targets using a given rate target // the resulting angle_rad yaw frame will match the rate_rad yaw frame // assumes a 50hz update rate @@ -572,6 +622,32 @@ bool AP_Mount_Backend::get_angle_target_to_sysid(MountTarget& angle_rad) const return get_angle_target_to_location(_target_sysid_location, angle_rad); } +// get target rate in deg/sec. returns true on success +bool AP_Mount_Backend::get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame) +{ + if (mnt_target.target_type == MountTargetType::RATE) { + roll_degs = degrees(mnt_target.rate_rads.roll); + pitch_degs = degrees(mnt_target.rate_rads.pitch); + yaw_degs = degrees(mnt_target.rate_rads.yaw); + yaw_is_earth_frame = mnt_target.rate_rads.yaw_is_ef; + return true; + } + return false; +} + +// get target angle in deg. returns true on success +bool AP_Mount_Backend::get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) +{ + if (mnt_target.target_type == MountTargetType::ANGLE) { + roll_deg = degrees(mnt_target.angle_rad.roll); + pitch_deg = degrees(mnt_target.angle_rad.pitch); + yaw_deg = degrees(mnt_target.angle_rad.yaw); + yaw_is_earth_frame = mnt_target.angle_rad.yaw_is_ef; + return true; + } + return false; +} + // sent warning to GCS. Warnings are throttled to at most once every 30 seconds void AP_Mount_Backend::send_warning_to_GCS(const char* warning_str) { @@ -580,7 +656,7 @@ void AP_Mount_Backend::send_warning_to_GCS(const char* warning_str) return; } - gcs().send_text(MAV_SEVERITY_WARNING, "Mount: %s", warning_str); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Mount: %s", warning_str); _last_warning_ms = now_ms; } diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 827c7db133f4cc..7e5563f44e210b 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -28,7 +28,7 @@ #include #include #include -#include "AP_Mount_Params.h" +#include "AP_Mount.h" class AP_Mount_Backend { @@ -94,17 +94,21 @@ class AP_Mount_Backend void set_target_sysid(uint8_t sysid); // handle do_mount_control command. Returns MAV_RESULT_ACCEPTED on success - MAV_RESULT handle_command_do_mount_control(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_do_mount_control(const mavlink_command_int_t &packet); // handle do_gimbal_manager_configure. Returns MAV_RESULT_ACCEPTED on success // requires original message in order to extract caller's sysid and compid - MAV_RESULT handle_command_do_gimbal_manager_configure(const mavlink_command_long_t &packet, const mavlink_message_t &msg); - + MAV_RESULT handle_command_do_gimbal_manager_configure(const mavlink_command_int_t &packet, const mavlink_message_t &msg); + +#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED // process MOUNT_CONFIGURE messages received from GCS. deprecated. void handle_mount_configure(const mavlink_mount_configure_t &msg); +#endif +#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED // process MOUNT_CONTROL messages received from GCS. deprecated. void handle_mount_control(const mavlink_mount_control_t &packet); +#endif // send a GIMBAL_DEVICE_ATTITUDE_STATUS message to GCS void send_gimbal_device_attitude_status(mavlink_channel_t chan); @@ -133,12 +137,19 @@ class AP_Mount_Backend // handle GIMBAL_DEVICE_ATTITUDE_STATUS message virtual void handle_gimbal_device_attitude_status(const mavlink_message_t &msg) {} + // get target rate in deg/sec. returns true on success + bool get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame); + + // get target angle in deg. returns true on success + bool get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame); + // accessors for scripting backends - virtual bool get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame) { return false; } - virtual bool get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) { return false; } virtual bool get_location_target(Location &target_loc) { return false; } virtual void set_attitude_euler(float roll_deg, float pitch_deg, float yaw_bf_deg) {}; + // write mount log packet + void write_log(uint64_t timestamp_us); + // // camera controls for gimbals that include a camera // @@ -162,12 +173,22 @@ class AP_Mount_Backend // p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom virtual bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) { return false; } + // set camera lens as a value from 0 to 5 + virtual bool set_lens(uint8_t lens) { return false; } + // send camera information message to GCS virtual void send_camera_information(mavlink_channel_t chan) const {} // send camera settings message to GCS virtual void send_camera_settings(mavlink_channel_t chan) const {} + // + // rangefinder + // + + // get rangefinder distance. Returns true on success + virtual bool get_rangefinder_distance(float& distance_m) const { return false; } + protected: enum class MountTargetType { @@ -175,8 +196,9 @@ class AP_Mount_Backend RATE, }; - // structure for a single angle or rate target - struct MountTarget { + // class for a single angle or rate target + class MountTarget { + public: float roll; float pitch; float yaw; @@ -187,6 +209,9 @@ class AP_Mount_Backend // return earth-frame yaw angle from a mount target (in radians) float get_ef_yaw() const; + + // set roll, pitch, yaw and yaw_is_ef from Vector3f + void set(const Vector3f& rpy, bool yaw_is_ef_in); }; // returns true if user has configured a valid yaw angle range @@ -199,13 +224,9 @@ class AP_Mount_Backend // get pilot input (in the range -1 to +1) received through RC void get_rc_input(float& roll_in, float& pitch_in, float& yaw_in) const; - // get rate targets (in rad/s) from pilot RC - // returns true on success (RC is providing rate targets), false on failure (RC is providing angle targets) - bool get_rc_rate_target(MountTarget& rate_rads) const WARN_IF_UNUSED; - - // get angle targets (in radians) from pilot RC - // returns true on success (RC is providing angle targets), false on failure (RC is providing rate targets) - bool get_rc_angle_target(MountTarget& angle_rad) const WARN_IF_UNUSED; + // get angle or rate targets from pilot RC + // target_type will be either ANGLE or RATE, rpy will be the target angle in deg or rate in deg/s + void get_rc_target(MountTargetType& target_type, MountTarget& rpy) const; // get angle targets (in radians) to a Location // returns true on success, false on failure @@ -246,7 +267,7 @@ class AP_Mount_Backend MountTargetType target_type;// MAVLink targeting mode's current target type (e.g. angle or rate) MountTarget angle_rad; // angle target in radians MountTarget rate_rads; // rate target in rad/s - } mavt_target; + } mnt_target; Location _roi_target; // roi target location bool _roi_target_set; // true if the roi target has been set diff --git a/libraries/AP_Mount/AP_Mount_Gremsy.cpp b/libraries/AP_Mount/AP_Mount_Gremsy.cpp index 43e2bbb3817559..b9bf372a680646 100644 --- a/libraries/AP_Mount/AP_Mount_Gremsy.cpp +++ b/libraries/AP_Mount/AP_Mount_Gremsy.cpp @@ -26,70 +26,75 @@ void AP_Mount_Gremsy::update() // move mount to a "retracted" position. We disable motors case MAV_MOUNT_MODE_RETRACT: // handled below + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(Vector3f{0,0,0}, false); send_gimbal_device_retract(); break; // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &angle_bf_target = _params.neutral_angles.get(); - send_gimbal_device_set_attitude(ToRad(angle_bf_target.x), ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); - } + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); break; + } - // use angle or rate targets provided by a mavlink message or mission command - case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - send_gimbal_device_set_attitude(mavt_target.angle_rad.roll, mavt_target.angle_rad.pitch, mavt_target.angle_rad.yaw, mavt_target.angle_rad.yaw_is_ef); - break; - case MountTargetType::RATE: - send_gimbal_device_set_rate(mavt_target.rate_rads.roll, mavt_target.rate_rads.pitch, mavt_target.rate_rads.yaw, mavt_target.rate_rads.yaw_is_ef); - break; - } + case MAV_MOUNT_MODE_MAVLINK_TARGETING: { + // mavlink targets are stored while handling the incoming message set_angle_target() or set_rate_target() break; + } // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { - // update targets using pilot's rc inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - send_gimbal_device_set_rate(rc_target.roll, rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } else if (get_rc_angle_target(rc_target)) { - send_gimbal_device_set_attitude(rc_target.roll, rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); + // 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; } break; } // point mount to a GPS point given by the mission planner - case MAV_MOUNT_MODE_GPS_POINT: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_roi(angle_target_rad)) { - send_gimbal_device_set_attitude(angle_target_rad.roll, angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + 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 - case MAV_MOUNT_MODE_HOME_LOCATION: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_home(angle_target_rad)) { - send_gimbal_device_set_attitude(angle_target_rad.roll, angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // 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; - } - case MAV_MOUNT_MODE_SYSID_TARGET: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_sysid(angle_target_rad)) { - send_gimbal_device_set_attitude(angle_target_rad.roll, angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // 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: // unknown mode so do nothing break; } + + // send target angles or rates depending on the target type + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + send_gimbal_device_set_attitude(mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, mnt_target.angle_rad.yaw, mnt_target.angle_rad.yaw_is_ef); + break; + case MountTargetType::RATE: + send_gimbal_device_set_rate(mnt_target.rate_rads.roll, mnt_target.rate_rads.pitch, mnt_target.rate_rads.yaw, mnt_target.rate_rads.yaw_is_ef); + break; + } } // return true if healthy @@ -123,12 +128,6 @@ bool AP_Mount_Gremsy::healthy() const // get attitude as a quaternion. returns true on success bool AP_Mount_Gremsy::get_attitude_quaternion(Quaternion& att_quat) { - // check we have received an updated message - if (_gimbal_device_attitude_status.time_boot_ms == _sent_gimbal_device_attitude_status_ms) { - return false; - } - _sent_gimbal_device_attitude_status_ms = _gimbal_device_attitude_status.time_boot_ms; - att_quat = _gimbal_device_attitude_status.q; return true; } diff --git a/libraries/AP_Mount/AP_Mount_Gremsy.h b/libraries/AP_Mount/AP_Mount_Gremsy.h index 84670366e55e96..79bd42af77670a 100644 --- a/libraries/AP_Mount/AP_Mount_Gremsy.h +++ b/libraries/AP_Mount/AP_Mount_Gremsy.h @@ -70,6 +70,5 @@ class AP_Mount_Gremsy : public AP_Mount_Backend uint8_t _compid; // component id of gimbal mavlink_gimbal_device_attitude_status_t _gimbal_device_attitude_status; // copy of most recently received gimbal status uint32_t _last_attitude_status_ms; // system time last attitude status was received (used for health reporting) - uint32_t _sent_gimbal_device_attitude_status_ms; // time_boot_ms field of gimbal_device_status message last forwarded to the GCS (used to prevent sending duplicates) }; #endif // HAL_MOUNT_GREMSY_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Params.cpp b/libraries/AP_Mount/AP_Mount_Params.cpp index a481aa49eff8ce..c811afde8418db 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 + // @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 // @RebootRequired: True // @User: Standard AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Mount_Params, type, 0, AP_PARAM_FLAG_ENABLE), @@ -162,7 +162,6 @@ const AP_Param::GroupInfo AP_Mount_Params::var_info[] = { // @Param: _DEVID // @DisplayName: Mount Device ID // @Description: Mount device ID, taking into account its type, bus and instance - // @ReadOnly: True // @User: Advanced AP_GROUPINFO_FLAGS("_DEVID", 15, AP_Mount_Params, dev_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY), diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.cpp b/libraries/AP_Mount/AP_Mount_SToRM32.cpp index bdea46bf1491cb..1c1e5da3eadc1e 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32.cpp @@ -26,32 +26,24 @@ void AP_Mount_SToRM32::update() // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? case MAV_MOUNT_MODE_RETRACT: { const Vector3f &target = _params.retract_angles.get(); - _angle_rad.roll = radians(target.x); - _angle_rad.pitch = radians(target.y); - _angle_rad.yaw = radians(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &target = _params.neutral_angles.get(); - _angle_rad.roll = radians(target.x); - _angle_rad.pitch = radians(target.y); - _angle_rad.yaw = radians(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - _angle_rad = mavt_target.angle_rad; - break; - case MountTargetType::RATE: - update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); - break; + // mnt_target should have already been populated by set_angle_target() or set_rate_target(). Update target angle from rate if necessary + if (mnt_target.target_type == MountTargetType::RATE) { + update_angle_target_from_rate(mnt_target.rate_rads, mnt_target.angle_rad); } resend_now = true; break; @@ -59,31 +51,40 @@ void AP_Mount_SToRM32::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 {}; - if (get_rc_rate_target(rc_target)) { - update_angle_target_from_rate(rc_target, _angle_rad); - } else if (get_rc_angle_target(rc_target)) { - _angle_rad = rc_target; + 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; } resend_now = true; break; } - // point mount to a GPS location + // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: - if (get_angle_target_to_roi(_angle_rad)) { + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; + // point mount to Home location case MAV_MOUNT_MODE_HOME_LOCATION: - if (get_angle_target_to_home(_angle_rad)) { + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; + // point mount to another vehicle case MAV_MOUNT_MODE_SYSID_TARGET: - if (get_angle_target_to_sysid(_angle_rad)) { + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; @@ -95,14 +96,14 @@ void AP_Mount_SToRM32::update() // resend target angles at least once per second if (resend_now || ((AP_HAL::millis() - _last_send) > AP_MOUNT_STORM32_RESEND_MS)) { - send_do_mount_control(_angle_rad); + send_do_mount_control(mnt_target.angle_rad); } } // get attitude as a quaternion. returns true on success bool AP_Mount_SToRM32::get_attitude_quaternion(Quaternion& att_quat) { - att_quat.from_euler(_angle_rad.roll, _angle_rad.pitch, _angle_rad.get_bf_yaw()); + att_quat.from_euler(mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, mnt_target.angle_rad.get_bf_yaw()); return true; } diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.h b/libraries/AP_Mount/AP_Mount_SToRM32.h index d850869f9fd15d..33aef375c410f4 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32.h @@ -42,6 +42,5 @@ class AP_Mount_SToRM32 : public AP_Mount_Backend uint8_t _compid; // component id of gimbal mavlink_channel_t _chan = MAVLINK_COMM_0; // mavlink channel used to communicate with gimbal uint32_t _last_send; // system time of last do_mount_control sent to gimbal - MountTarget _angle_rad; // latest angle target }; #endif // HAL_MOUNT_STORM32MAVLINK_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index 9f94ab0a7078ee..0fdcdd53c70fbf 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -37,32 +37,24 @@ void AP_Mount_SToRM32_serial::update() // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? case MAV_MOUNT_MODE_RETRACT: { const Vector3f &target = _params.retract_angles.get(); - _angle_rad.roll = ToRad(target.x); - _angle_rad.pitch = ToRad(target.y); - _angle_rad.yaw = ToRad(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &target = _params.neutral_angles.get(); - _angle_rad.roll = ToRad(target.x); - _angle_rad.pitch = ToRad(target.y); - _angle_rad.yaw = ToRad(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - _angle_rad = mavt_target.angle_rad; - break; - case MountTargetType::RATE: - update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); - break; + // mnt_target should have already been filled in by set_angle_target() or set_rate_target() + if (mnt_target.target_type == MountTargetType::RATE) { + update_angle_target_from_rate(mnt_target.rate_rads, mnt_target.angle_rad); } resend_now = true; break; @@ -70,11 +62,15 @@ void AP_Mount_SToRM32_serial::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 {}; - if (get_rc_rate_target(rc_target)) { - update_angle_target_from_rate(rc_target, _angle_rad); - } else if (get_rc_angle_target(rc_target)) { - _angle_rad = rc_target; + 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; } resend_now = true; break; @@ -82,19 +78,24 @@ void AP_Mount_SToRM32_serial::update() // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: - if (get_angle_target_to_roi(_angle_rad)) { + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; + // point mount to Home location case MAV_MOUNT_MODE_HOME_LOCATION: - if (get_angle_target_to_home(_angle_rad)) { + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; + // point mount to another vehicle case MAV_MOUNT_MODE_SYSID_TARGET: - if (get_angle_target_to_sysid(_angle_rad)) { + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; @@ -112,7 +113,7 @@ void AP_Mount_SToRM32_serial::update() } if (can_send(resend_now)) { if (resend_now) { - send_target_angles(_angle_rad); + send_target_angles(mnt_target.angle_rad); get_angles(); _reply_type = ReplyType_ACK; _reply_counter = 0; diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h index 5ae4fe773aa1f2..e6632ca10eb8bc 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h @@ -130,7 +130,6 @@ class AP_Mount_SToRM32_serial : public AP_Mount_Backend AP_HAL::UARTDriver *_port; bool _initialised; // true once the driver has been initialised - MountTarget _angle_rad; // latest angle target uint32_t _last_send; // system time of last do_mount_control sent to gimbal uint8_t _reply_length; diff --git a/libraries/AP_Mount/AP_Mount_Scripting.cpp b/libraries/AP_Mount/AP_Mount_Scripting.cpp index e1809c4a844cf6..9eb738503919bc 100644 --- a/libraries/AP_Mount/AP_Mount_Scripting.cpp +++ b/libraries/AP_Mount/AP_Mount_Scripting.cpp @@ -20,14 +20,8 @@ void AP_Mount_Scripting::update() // 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(); - target_angle_rad.roll = ToRad(angle_bf_target.x); - target_angle_rad.pitch = ToRad(angle_bf_target.y); - target_angle_rad.yaw = ToRad(angle_bf_target.z); - target_angle_rad.yaw_is_ef = false; - target_angle_rad_valid = true; - - // mark other targets as invalid - target_rate_rads_valid = false; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; target_loc_valid = false; break; } @@ -35,92 +29,55 @@ void AP_Mount_Scripting::update() // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &angle_bf_target = _params.neutral_angles.get(); - target_angle_rad.roll = ToRad(angle_bf_target.x); - target_angle_rad.pitch = ToRad(angle_bf_target.y); - target_angle_rad.yaw = ToRad(angle_bf_target.z); - target_angle_rad.yaw_is_ef = false; - target_angle_rad_valid = true; - - // mark other targets as invalid - target_rate_rads_valid = false; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; target_loc_valid = false; break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - target_angle_rad = mavt_target.angle_rad; - target_angle_rad_valid = true; - target_rate_rads_valid = false; - target_loc_valid = false; - break; - case MountTargetType::RATE: - target_rate_rads = mavt_target.rate_rads; - target_rate_rads_valid = true; - target_angle_rad_valid = false; - target_loc_valid = false; - break; - } + // mavlink targets should have been already stored while handling the message + target_loc_valid = false; break; // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { - // update targets using pilot's rc inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - target_rate_rads = rc_target; - target_rate_rads_valid = true; - target_angle_rad_valid = false; - target_loc_valid = false; - } else if (get_rc_angle_target(rc_target)) { - target_angle_rad = rc_target; - target_angle_rad_valid = true; - target_rate_rads_valid = false; - target_loc_valid = false; + // 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; } + target_loc_valid = false; break; } - // point mount towards a GPS point - case MAV_MOUNT_MODE_GPS_POINT: { - target_loc_valid = _roi_target_set; - if (target_loc_valid) { - target_loc = _roi_target; - target_angle_rad_valid = get_angle_target_to_location(target_loc, target_angle_rad); - } else { - target_angle_rad_valid = false; + // 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; } - target_rate_rads_valid = false; break; - } - // point mount towards home - case MAV_MOUNT_MODE_HOME_LOCATION: { - target_loc_valid = AP::ahrs().home_is_set(); - if (target_loc_valid) { - target_loc = AP::ahrs().get_home(); - target_angle_rad_valid = get_angle_target_to_home(target_angle_rad); - } else { - target_angle_rad_valid = false; + // 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; } - target_rate_rads_valid = false; break; - } - // point mount towards another vehicle - case MAV_MOUNT_MODE_SYSID_TARGET: { - target_loc_valid = _target_sysid_location_set; - if (target_loc_valid) { - target_loc = _target_sysid_location; - target_angle_rad_valid = get_angle_target_to_location(target_loc, target_angle_rad); - } else { - target_angle_rad_valid = false; + // 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; } - target_rate_rads_valid = false; break; - } default: // we do not know this mode so raise internal error @@ -136,31 +93,6 @@ bool AP_Mount_Scripting::healthy() const return (AP_HAL::millis() - last_update_ms <= AP_MOUNT_SCRIPTING_TIMEOUT_MS); } -// accessors for scripting backends -bool AP_Mount_Scripting::get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame) -{ - if (target_rate_rads_valid) { - roll_degs = degrees(target_rate_rads.roll); - pitch_degs = degrees(target_rate_rads.pitch); - yaw_degs = degrees(target_rate_rads.yaw); - yaw_is_earth_frame = target_rate_rads.yaw_is_ef; - return true; - } - return false; -} - -bool AP_Mount_Scripting::get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) -{ - if (target_angle_rad_valid) { - roll_deg = degrees(target_angle_rad.roll); - pitch_deg = degrees(target_angle_rad.pitch); - yaw_deg = degrees(target_angle_rad.yaw); - yaw_is_earth_frame = target_angle_rad.yaw_is_ef; - return true; - } - return false; -} - // return target location if available // returns true if a target location is available and fills in target_loc argument bool AP_Mount_Scripting::get_location_target(Location &_target_loc) diff --git a/libraries/AP_Mount/AP_Mount_Scripting.h b/libraries/AP_Mount/AP_Mount_Scripting.h index d5f945fa120f29..ecf1f7cbd89c72 100644 --- a/libraries/AP_Mount/AP_Mount_Scripting.h +++ b/libraries/AP_Mount/AP_Mount_Scripting.h @@ -32,8 +32,6 @@ class AP_Mount_Scripting : public AP_Mount_Backend bool has_pan_control() const override { return yaw_range_valid(); }; // accessors for scripting backends - bool get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame) override; - bool get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) override; bool get_location_target(Location& _target_loc) override; void set_attitude_euler(float roll_deg, float pitch_deg, float yaw_bf_deg) override; @@ -48,12 +46,6 @@ class AP_Mount_Scripting : public AP_Mount_Backend uint32_t last_update_ms; // system time of last call to one of the get_ methods. Used for health reporting Vector3f current_angle_deg; // current gimbal angles in degrees (x=roll, y=pitch, z=yaw) - MountTarget target_rate_rads; // rate target in rad/s - bool target_rate_rads_valid; // true if _target_rate_degs holds a valid rate target - - MountTarget target_angle_rad; // angle target in radians - bool target_angle_rad_valid; // true if _target_rate_degs holds a valid rate target - Location target_loc; // target location bool target_loc_valid; // true if target_loc holds a valid target location }; diff --git a/libraries/AP_Mount/AP_Mount_Servo.cpp b/libraries/AP_Mount/AP_Mount_Servo.cpp index 840d19803e0c4e..6d1d45a7668a0f 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.cpp +++ b/libraries/AP_Mount/AP_Mount_Servo.cpp @@ -27,89 +27,87 @@ void AP_Mount_Servo::init() // update mount position - should be called periodically void AP_Mount_Servo::update() { - switch (get_mode()) { + auto mount_mode = get_mode(); + switch (mount_mode) { // move mount to a "retracted position" or to a position where a fourth servo can retract the entire mount into the fuselage case MAV_MOUNT_MODE_RETRACT: { _angle_bf_output_rad = _params.retract_angles.get() * DEG_TO_RAD; - - // initialise _angle_rad to smooth transition if user changes to RC_TARGETTING - _angle_rad.roll = _angle_bf_output_rad.x; - _angle_rad.pitch = _angle_bf_output_rad.y; - _angle_rad.yaw = _angle_bf_output_rad.z; - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(_angle_bf_output_rad, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { _angle_bf_output_rad = _params.neutral_angles.get() * DEG_TO_RAD; - - // initialise _angle_rad to smooth transition if user changes to RC_TARGETTING - _angle_rad.roll = _angle_bf_output_rad.x; - _angle_rad.pitch = _angle_bf_output_rad.y; - _angle_rad.yaw = _angle_bf_output_rad.z; - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(_angle_bf_output_rad, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: { - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - _angle_rad = mavt_target.angle_rad; - break; - case MountTargetType::RATE: - update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); - break; - } - // update _angle_bf_output_rad based on angle target - update_angle_outputs(_angle_rad); + // mavlink targets are stored while handling the incoming message and considered valid break; } // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { // update targets using pilot's RC inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - update_angle_target_from_rate(rc_target, _angle_rad); - } else if (get_rc_angle_target(rc_target)) { - _angle_rad = rc_target; + 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 _angle_bf_output_rad based on angle target - update_angle_outputs(_angle_rad); break; } - // point mount to a GPS location - case MAV_MOUNT_MODE_GPS_POINT: { - if (get_angle_target_to_roi(_angle_rad)) { - update_angle_outputs(_angle_rad); + // 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; - } - case MAV_MOUNT_MODE_HOME_LOCATION: { - if (get_angle_target_to_home(_angle_rad)) { - update_angle_outputs(_angle_rad); + // 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; - } - case MAV_MOUNT_MODE_SYSID_TARGET: { - if (get_angle_target_to_sysid(_angle_rad)) { - update_angle_outputs(_angle_rad); + // 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: //do nothing break; } + // send target angles or rates depending on the target type + switch (mnt_target.target_type) { + case MountTargetType::RATE: + update_angle_target_from_rate(mnt_target.rate_rads, mnt_target.angle_rad); + FALLTHROUGH; + case MountTargetType::ANGLE: + // update _angle_bf_output_rad based on angle target + if ((mount_mode != MAV_MOUNT_MODE_RETRACT) & (mount_mode != MAV_MOUNT_MODE_NEUTRAL)) { + update_angle_outputs(mnt_target.angle_rad); + } + break; + } + // move mount to a "retracted position" into the fuselage with a fourth servo - const bool mount_open = (get_mode() == MAV_MOUNT_MODE_RETRACT) ? 0 : 1; + const bool mount_open = (mount_mode == MAV_MOUNT_MODE_RETRACT) ? 0 : 1; move_servo(_open_idx, mount_open, 0, 1); // write the results to the servos diff --git a/libraries/AP_Mount/AP_Mount_Servo.h b/libraries/AP_Mount/AP_Mount_Servo.h index 9016fd2af6d962..529a97bd7341c1 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.h +++ b/libraries/AP_Mount/AP_Mount_Servo.h @@ -56,7 +56,6 @@ class AP_Mount_Servo : public AP_Mount_Backend SRV_Channel::Aux_servo_function_t _pan_idx; // SRV_Channel mount pan function index SRV_Channel::Aux_servo_function_t _open_idx; // SRV_Channel mount open function index - MountTarget _angle_rad; // angle target Vector3f _angle_bf_output_rad; // final body frame output angle in radians }; #endif // HAL_MOUNT_SERVO_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index ee60bbf00cd76f..714a9cadd694e8 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -13,16 +13,24 @@ extern const AP_HAL::HAL& hal; #define AP_MOUNT_SIYI_HEADER2 0x66 // second header byte #define AP_MOUNT_SIYI_PACKETLEN_MIN 10 // minimum number of bytes in a packet. this is a packet with no data bytes #define AP_MOUNT_SIYI_DATALEN_MAX (AP_MOUNT_SIYI_PACKETLEN_MAX-AP_MOUNT_SIYI_PACKETLEN_MIN) // max bytes for data portion of packet -#define AP_MOUNT_SIYI_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second -#define AP_MOUNT_SIYI_MSG_BUF_DATA_START 8 // data starts at this byte in _msg_buf #define AP_MOUNT_SIYI_RATE_MAX_RADS radians(90) // maximum physical rotation rate of gimbal in radans/sec #define AP_MOUNT_SIYI_PITCH_P 1.50 // pitch controller P gain (converts pitch angle error to target rate) #define AP_MOUNT_SIYI_YAW_P 1.50 // yaw controller P gain (converts yaw angle error to target rate) -#define AP_MOUNT_SIYI_LOCK_RESEND_COUNT 5 // lock value is resent to gimbal every 5 iterations +#define AP_MOUNT_SIYI_TIMEOUT_MS 1000 // timeout for health and rangefinder 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) +// hardware lookup table indexed by HardwareModel enum values +const AP_Mount_Siyi::HWInfo AP_Mount_Siyi::hardware_lookup_table[] { + {{'0','0'}, "Unknown"}, + {{'7','5'}, "A2"}, + {{'7','3'}, "A8"}, + {{'6','B'}, "ZR10"}, + {{'7','8'}, "ZR30"}, + {{'7','A'}, "ZT30"}, +}; + // init - performs any required initialisation for this instance void AP_Mount_Siyi::init() { @@ -51,7 +59,10 @@ void AP_Mount_Siyi::update() uint32_t now_ms = AP_HAL::millis(); if ((now_ms - _last_send_ms) >= 1000) { _last_send_ms = now_ms; - if (!_got_firmware_version) { + if (!_got_hardware_id) { + request_hardware_id(); + return; + } else if (!_fw_version.received) { request_firmware_version(); return; } else { @@ -65,92 +76,100 @@ void AP_Mount_Siyi::update() _last_req_current_angle_rad_ms = now_ms; } + // request rangefinder distance from ZT30 at 10hz + if ((_hardware_model == HardwareModel::ZT30) && (now_ms - _last_rangefinder_req_ms > 100)) { + request_rangefinder_distance(); + _last_rangefinder_req_ms = now_ms; + } + // run zoom control update_zoom_control(); - // update based on mount mode + // Get the target angles or rates first depending on the current mount mode switch (get_mode()) { - // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? case MAV_MOUNT_MODE_RETRACT: { const Vector3f &angle_bf_target = _params.retract_angles.get(); - send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + 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(); - send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + 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: - switch (mavt_target.target_type) { + case MAV_MOUNT_MODE_MAVLINK_TARGETING: { + // mavlink targets are stored while handling the incoming message + 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: - send_target_angles(mavt_target.angle_rad.pitch, mavt_target.angle_rad.yaw, mavt_target.angle_rad.yaw_is_ef); + mnt_target.angle_rad = rc_target; break; case MountTargetType::RATE: - send_target_rates(mavt_target.rate_rads.pitch, mavt_target.rate_rads.yaw, mavt_target.rate_rads.yaw_is_ef); + mnt_target.rate_rads = rc_target; break; } break; - - // RC radio manual angle control, but with stabilization from the AHRS - case MAV_MOUNT_MODE_RC_TARGETING: { - // update targets using pilot's rc inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - send_target_rates(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } else if (get_rc_angle_target(rc_target)) { - send_target_angles(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } - break; } // point mount to a GPS point given by the mission planner - case MAV_MOUNT_MODE_GPS_POINT: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_roi(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + case MAV_MOUNT_MODE_GPS_POINT: + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_HOME_LOCATION: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_home(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // 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; - } - case MAV_MOUNT_MODE_SYSID_TARGET:{ - MountTarget angle_target_rad {}; - if (get_angle_target_to_sysid(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // 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_target_angles(mnt_target.angle_rad.pitch, mnt_target.angle_rad.yaw, mnt_target.angle_rad.yaw_is_ef); + break; + case MountTargetType::RATE: + send_target_rates(mnt_target.rate_rads.pitch, mnt_target.rate_rads.yaw, mnt_target.rate_rads.yaw_is_ef); + break; + } } // return true if healthy bool AP_Mount_Siyi::healthy() const { // unhealthy until gimbal has been found and replied with firmware version info - if (!_initialised || !_got_firmware_version) { + if (!_initialised || !_fw_version.received) { return false; } // unhealthy if attitude information NOT received recently const uint32_t now_ms = AP_HAL::millis(); - if (now_ms - _last_current_angle_rad_ms > 1000) { + if (now_ms - _last_current_angle_rad_ms > AP_MOUNT_SIYI_TIMEOUT_MS) { return false; } @@ -161,7 +180,8 @@ bool AP_Mount_Siyi::healthy() const // get attitude as a quaternion. returns true on success bool AP_Mount_Siyi::get_attitude_quaternion(Quaternion& att_quat) { - att_quat.from_euler(_current_angle_rad.x, _current_angle_rad.y, _current_angle_rad.z); + // Order of rotation for Siyi gimbals is (yaw, roll, pitch), which is 312 order + att_quat.from_vector312(_current_angle_rad.x, _current_angle_rad.y, _current_angle_rad.z); return true; } @@ -305,44 +325,61 @@ void AP_Mount_Siyi::process_packet() #endif break; } - _got_firmware_version = true; - - // set hardware version based on message length - _hardware_model = (_parsed_msg.data_bytes_received <= 8) ? HardwareModel::A8 : HardwareModel::ZR10; // consume and display camera firmware version - _cam_firmware_version = { - _msg_buff[_msg_buff_data_start+2], // firmware major version - _msg_buff[_msg_buff_data_start+1], // firmware minor version - _msg_buff[_msg_buff_data_start+0] // firmware revision (aka patch) - }; - - gcs().send_text(MAV_SEVERITY_INFO, "Mount: SiyiCam fw:%u.%u.%u", - (unsigned)_cam_firmware_version.major, // firmware major version - (unsigned)_cam_firmware_version.minor, // firmware minor version - (unsigned)_cam_firmware_version.patch); // firmware revision + _fw_version = {}; + _fw_version.camera.major = _msg_buff[_msg_buff_data_start+2]; // firmware major version + _fw_version.camera.minor = _msg_buff[_msg_buff_data_start+1]; // firmware minor version + _fw_version.camera.patch = _msg_buff[_msg_buff_data_start+0]; // firmware revision (aka patch) + + _fw_version.gimbal.major = _msg_buff[_msg_buff_data_start+6]; // firmware major version + _fw_version.gimbal.minor = _msg_buff[_msg_buff_data_start+5]; // firmware minor version + _fw_version.gimbal.patch = _msg_buff[_msg_buff_data_start+4]; // firmware revision (aka patch) + + _fw_version.received = true; + + // display camera info to user + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mount: Siyi camera fw v%u.%u.%u", + _fw_version.camera.major, + _fw_version.camera.minor, + _fw_version.camera.patch); // display gimbal info to user - gcs().send_text(MAV_SEVERITY_INFO, "Mount: Siyi fw:%u.%u.%u", - (unsigned)_msg_buff[_msg_buff_data_start+6], // firmware major version - (unsigned)_msg_buff[_msg_buff_data_start+5], // firmware minor version - (unsigned)_msg_buff[_msg_buff_data_start+4]); // firmware revision + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mount: Siyi gimbal fw v%u.%u.%u", + _fw_version.gimbal.major, + _fw_version.gimbal.minor, + _fw_version.gimbal.patch); - // display zoom firmware version -#if AP_MOUNT_SIYI_DEBUG + // display zoom firmware version for those that have it if (_parsed_msg.data_bytes_received >= 12) { - debug("Mount: SiyiZoom fw:%u.%u.%u", - (unsigned)_msg_buff[_msg_buff_data_start+10], // firmware major version - (unsigned)_msg_buff[_msg_buff_data_start+9], // firmware minor version - (unsigned)_msg_buff[_msg_buff_data_start+8]); // firmware revision + _fw_version.zoom.major = _msg_buff[_msg_buff_data_start+10]; + _fw_version.zoom.minor = _msg_buff[_msg_buff_data_start+ 9]; + _fw_version.zoom.patch = _msg_buff[_msg_buff_data_start+ 8]; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mount: Siyi zoom fw v%u.%u.%u", + _fw_version.zoom.major, + _fw_version.zoom.minor, + _fw_version.zoom.patch); } -#endif + + // report to the user if gimbal firmware is not up-to-date + check_firmware_version(); + break; } - case SiyiCommandId::HARDWARE_ID: - // unsupported + case SiyiCommandId::HARDWARE_ID: { + // lookup first two digits of hardware id + const uint8_t hwid0 = _msg_buff[_msg_buff_data_start]; + const uint8_t hwid1 = _msg_buff[_msg_buff_data_start+1]; + for (uint8_t i=1; i 5) { - _gimbal_mounting_dir = (_msg_buff[_msg_buff_data_start+5] == 2) ? GimbalMountingDirection::UPSIDE_DOWN : GimbalMountingDirection::NORMAL; + const RecordingStatus prev_record_status = _config_info.record_status; + + // Update Gimbal Config Information + size_t config_sz = MIN(_parsed_msg.data_bytes_received, sizeof(_config_info)); + memcpy(&_config_info, &_msg_buff[_msg_buff_data_start], config_sz); + + // Alert user if recording status changed + if (prev_record_status != _config_info.record_status) { + const char * msg = "?"; + MAV_SEVERITY sev = MAV_SEVERITY_INFO; + switch (_config_info.record_status) { + case RecordingStatus::OFF: + msg = "OFF"; + break; + case RecordingStatus::ON: + msg = "ON"; + break; + case RecordingStatus::NO_CARD: + msg = "NO CARD!"; + sev = MAV_SEVERITY_WARNING; + break; + case RecordingStatus::DATA_LOSS: + msg = "DATA LOSS!"; + sev = MAV_SEVERITY_WARNING; + break; + } + GCS_SEND_TEXT(sev, "Siyi: recording %s", msg); } - // update recording state and warn user of mismatch - const bool recording = _msg_buff[_msg_buff_data_start+3] > 0; - if (recording != _last_record_video) { - gcs().send_text(MAV_SEVERITY_INFO, "Siyi: recording %s", recording ? "ON" : "OFF"); - } - _last_record_video = recording; - debug("GimConf hdr:%u rec:%u foll:%u mntdir:%u", (unsigned)_msg_buff[_msg_buff_data_start+1], - (unsigned)_msg_buff[_msg_buff_data_start+3], - (unsigned)_msg_buff[_msg_buff_data_start+4], - (unsigned)_msg_buff[_msg_buff_data_start+5]); + debug( + "GimConf hdr:%u rec:%u foll:%u mntdir:%u vid:%u", + (uint8_t)_config_info.hdr_status, + (uint8_t)_config_info.record_status, + (uint8_t)_config_info.motion_mode, + (uint8_t)_config_info.mounting_dir, + (uint8_t)_config_info.video_mode + ); break; } @@ -424,12 +483,13 @@ void AP_Mount_Siyi::process_packet() } const uint8_t func_feedback_info = _msg_buff[_msg_buff_data_start]; const char* err_prefix = "Mount: Siyi"; + (void)err_prefix; // in case !HAL_GCS_ENABLED switch ((FunctionFeedbackInfo)func_feedback_info) { case FunctionFeedbackInfo::SUCCESS: debug("FnFeedB success"); break; case FunctionFeedbackInfo::FAILED_TO_TAKE_PHOTO: - gcs().send_text(MAV_SEVERITY_ERROR, "%s failed to take picture", err_prefix); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s failed to take picture", err_prefix); break; case FunctionFeedbackInfo::HDR_ON: debug("HDR on"); @@ -438,7 +498,7 @@ void AP_Mount_Siyi::process_packet() debug("HDR off"); break; case FunctionFeedbackInfo::FAILED_TO_RECORD_VIDEO: - gcs().send_text(MAV_SEVERITY_ERROR, "%s failed to record video", err_prefix); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s failed to record video", err_prefix); break; default: debug("FnFeedB unexpected val:%u", (unsigned)func_feedback_info); @@ -467,6 +527,12 @@ void AP_Mount_Siyi::process_packet() break; } + 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(); + break; + } + default: debug("Unhandled CmdId:%u", (unsigned)_parsed_msg.command_id); break; @@ -549,25 +615,42 @@ bool AP_Mount_Siyi::send_1byte_packet(SiyiCommandId cmd_id, uint8_t data_byte) // yaw_is_ef should be true if gimbal should maintain an earth-frame target (aka lock) void AP_Mount_Siyi::rotate_gimbal(int8_t pitch_scalar, int8_t yaw_scalar, bool yaw_is_ef) { - // send lock/follow value if it has changed - if ((yaw_is_ef != _last_lock) || (_lock_send_counter >= AP_MOUNT_SIYI_LOCK_RESEND_COUNT)) { - set_lock(yaw_is_ef); - _lock_send_counter = 0; - _last_lock = yaw_is_ef; - } else { - _lock_send_counter++; + // send lock/follow value + const GimbalMotionMode mode = yaw_is_ef ? GimbalMotionMode::LOCK : GimbalMotionMode::FOLLOW; + if (!set_motion_mode(mode)) { + // couldn't set mode, so don't send rotation + return; } const uint8_t yaw_and_pitch_rates[] {(uint8_t)yaw_scalar, (uint8_t)pitch_scalar}; send_packet(SiyiCommandId::GIMBAL_ROTATION, yaw_and_pitch_rates, ARRAY_SIZE(yaw_and_pitch_rates)); } -// set gimbal's lock vs follow mode -// lock should be true if gimbal should maintain an earth-frame target -// lock is false to follow / maintain a body-frame target -void AP_Mount_Siyi::set_lock(bool lock) +// Set gimbal's motion mode if it has changed. Use force=true to always send. +// FOLLOW: roll and pitch are in earth-frame, yaw is in body-frame +// LOCK: roll, pitch and yaw are all in earth-frame +// FPV: roll, pitch and yaw are all in body-frame +// Returns true if mode successfully sent to Gimbal +bool AP_Mount_Siyi::set_motion_mode(const GimbalMotionMode mode, const bool force) { - send_1byte_packet(SiyiCommandId::PHOTO, lock ? (uint8_t)PhotoFunction::LOCK_MODE : (uint8_t)PhotoFunction::FOLLOW_MODE); + if (!force && (mode == _config_info.motion_mode)) { + // we're already in the right mode... + return true; + } + + PhotoFunction data = PhotoFunction::LOCK_MODE; + switch (mode) { + case GimbalMotionMode::LOCK: data = PhotoFunction::LOCK_MODE; break; + case GimbalMotionMode::FOLLOW: data = PhotoFunction::FOLLOW_MODE; break; + case GimbalMotionMode::FPV: data = PhotoFunction::FPV_MODE; break; + } + bool sent = send_1byte_packet(SiyiCommandId::PHOTO, (uint8_t)data); + if (sent) { + // assume the mode is set correctly until told otherwise + _config_info.motion_mode = mode; + request_configuration(); + } + return sent; } // send target pitch and yaw rates to gimbal @@ -592,7 +675,7 @@ void AP_Mount_Siyi::send_target_angles(float pitch_rad, float yaw_rad, bool yaw_ // if gimbal mounting direction is 2 i.e. upside down, then transform the angles Vector3f current_angle_transformed = _current_angle_rad; - if (_gimbal_mounting_dir == GimbalMountingDirection::UPSIDE_DOWN) { + if (_config_info.mounting_dir == GimbalMountingDirection::UPSIDE_DOWN) { current_angle_transformed.y = -wrap_PI(_current_angle_rad.y + M_PI); current_angle_transformed.z = -_current_angle_rad.z; } @@ -636,18 +719,45 @@ bool AP_Mount_Siyi::record_video(bool start_recording) return false; } - // check desired recording state has changed - bool ret = true; - if (_last_record_video != start_recording) { - // request recording start or stop (sadly the same message is used) - const uint8_t func_type = (uint8_t)PhotoFunction::RECORD_VIDEO_TOGGLE; - ret = send_packet(SiyiCommandId::PHOTO, &func_type, 1); + bool success = true; + bool send_toggle = false; + if (start_recording) { + switch (_config_info.record_status) { + case RecordingStatus::ON: + // already recording... + break; + // assume that DATA_LOSS is the same as OFF + case RecordingStatus::DATA_LOSS: + case RecordingStatus::OFF: + send_toggle = true; + break; + case RecordingStatus::NO_CARD: + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Siyi: can't start recording: No Card"); + success = false; + break; + } + } else { + switch (_config_info.record_status) { + case RecordingStatus::ON: + send_toggle = true; + break; + // assume that DATA_LOSS is the same as OFF + case RecordingStatus::DATA_LOSS: + case RecordingStatus::OFF: + case RecordingStatus::NO_CARD: + // already off... + break; + } + } + + if (send_toggle) { + success = send_1byte_packet(SiyiCommandId::PHOTO, (uint8_t)PhotoFunction::RECORD_VIDEO_TOGGLE); } // request recording state update from gimbal request_configuration(); - return ret; + return success; } // send zoom rate command to camera. zoom out = -1, hold = 0, zoom in = 1 @@ -684,11 +794,14 @@ float AP_Mount_Siyi::get_zoom_mult_max() const switch (_hardware_model) { case HardwareModel::UNKNOWN: return 0; + case HardwareModel::A2: case HardwareModel::A8: // a8 has 6x digital zoom return 6; case HardwareModel::ZR10: - // zr10 has 30x hybrid zoom (optical + digital) + case HardwareModel::ZR30: + case HardwareModel::ZT30: + // 30x hybrid zoom (optical + digital) return 30; } return 0; @@ -697,63 +810,51 @@ float AP_Mount_Siyi::get_zoom_mult_max() const // set zoom specified as a rate or percentage bool AP_Mount_Siyi::set_zoom(ZoomType zoom_type, float zoom_value) { - if (zoom_type == ZoomType::RATE) { - // disable absolute zoom target - _zoom_mult_target = 0; - return send_zoom_rate(zoom_value); - } - - // absolute zoom - if (zoom_type == ZoomType::PCT) { + switch (zoom_type) { + case ZoomType::RATE: + if (send_zoom_rate(zoom_value)) { + _zoom_type = zoom_type; + _zoom_rate_target = zoom_value; + return true; + } + return false; + case ZoomType::PCT: { + // absolute zoom float zoom_mult_max = get_zoom_mult_max(); if (is_positive(zoom_mult_max)) { // convert zoom percentage (0~100) to target zoom multiple (e.g. 0~6x or 0~30x) const float zoom_mult = linear_interpolate(1, zoom_mult_max, zoom_value, 0, 100); - switch (_hardware_model) { - case HardwareModel::UNKNOWN: - // unknown model - return false; - case HardwareModel::A8: - // set internal zoom control target - _zoom_mult_target = zoom_mult; + if (send_zoom_mult(zoom_mult)) { + _zoom_type = zoom_type; return true; - case HardwareModel::ZR10: - return send_zoom_mult(zoom_mult); } + return false; } + return false; + } } // unsupported zoom type return false; } -// update absolute zoom controller -// only used for A8 that does not support abs zoom control +// update zoom controller void AP_Mount_Siyi::update_zoom_control() { - // exit immediately if no target - if (!is_positive(_zoom_mult_target)) { - return; - } - - // limit update rate to 20hz - const uint32_t now_ms = AP_HAL::millis(); - if ((now_ms - _last_zoom_control_ms) <= 50) { - return; - } - _last_zoom_control_ms = now_ms; + if (_zoom_type == ZoomType::RATE) { + // limit updates to 1hz + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _last_zoom_control_ms < 1000) { + return; + } + _last_zoom_control_ms = now_ms; - // zoom towards target zoom multiple - if (_zoom_mult_target > _zoom_mult + 0.1f) { - send_zoom_rate(1); - } else if (_zoom_mult_target < _zoom_mult - 0.1f) { - send_zoom_rate(-1); - } else { - send_zoom_rate(0); - _zoom_mult_target = 0; + // only send zoom rate target if it's non-zero because if zero it has already been sent + // and sending zero rate also triggers autofocus + if (!is_zero(_zoom_rate_target)) { + send_zoom_rate(_zoom_rate_target); + } } - - debug("Siyi zoom targ:%f act:%f", (double)_zoom_mult_target, (double)_zoom_mult); } // set focus specified as rate, percentage or auto @@ -788,30 +889,78 @@ SetFocusResult AP_Mount_Siyi::set_focus(FocusType focus_type, float focus_value) return SetFocusResult::INVALID_PARAMETERS; } +// 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; + } + + // 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; + } + + // send desired image type to camera + return send_1byte_packet(SiyiCommandId::SET_CAMERA_IMAGE_TYPE, (uint8_t)cam_image_type); +} + // send camera information message to GCS void AP_Mount_Siyi::send_camera_information(mavlink_channel_t chan) const { // exit immediately if not initialised - if (!_initialised || !_got_firmware_version) { + if (!_initialised || !_fw_version.received) { return; } static const uint8_t vendor_name[32] = "Siyi"; - static uint8_t model_name[32] = "Unknown"; - const uint32_t fw_version = _cam_firmware_version.major | (_cam_firmware_version.minor << 8) | (_cam_firmware_version.patch << 16); + static uint8_t model_name[32] {}; + const uint32_t fw_version = _fw_version.camera.major | (_fw_version.camera.minor << 8) | (_fw_version.camera.patch << 16); const char cam_definition_uri[140] {}; + // copy model name + strncpy((char *)model_name, get_model_name(), sizeof(model_name)-1); + // focal length + // To-Do: check these values are correct for A2, ZR30, ZT30 float focal_length_mm = 0; switch (_hardware_model) { case HardwareModel::UNKNOWN: - break; + case HardwareModel::A2: case HardwareModel::A8: - strncpy((char *)model_name, "A8", sizeof(model_name)); focal_length_mm = 21; break; case HardwareModel::ZR10: - strncpy((char *)model_name, "ZR10", sizeof(model_name)); + case HardwareModel::ZR30: + case HardwareModel::ZT30: // focal length range from 5.15 ~ 47.38 focal_length_mm = 5.15; break; @@ -838,23 +987,103 @@ void AP_Mount_Siyi::send_camera_information(mavlink_channel_t chan) const 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] + cam_definition_uri, // cam_definition_uri char[140] + _instance + 1); // gimbal_device_id uint8_t } // send camera settings message to GCS 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(); - const float zoom_pct = is_positive(zoom_mult_max) ? (_zoom_mult / zoom_mult_max * 100) : 0; + float zoom_pct = 0.0; + if (is_positive(zoom_mult_max)) { + zoom_pct = linear_interpolate(0, 100, _zoom_mult, 1.0, zoom_mult_max); + } // send CAMERA_SETTINGS message mavlink_msg_camera_settings_send( chan, AP_HAL::millis(), // time_boot_ms - _last_record_video ? CAMERA_MODE_VIDEO : CAMERA_MODE_IMAGE, // camera mode (0:image, 1:video, 2:image survey) + 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 } +// get model name string. returns "Unknown" if hardware model is not yet known +const char* AP_Mount_Siyi::get_model_name() const +{ + uint8_t model_idx = (uint8_t)_hardware_model; + if (model_idx < ARRAY_SIZE(hardware_lookup_table)) { + return hardware_lookup_table[model_idx].model_name; + } + return hardware_lookup_table[0].model_name; +} + +// get rangefinder distance. Returns true on success +bool AP_Mount_Siyi::get_rangefinder_distance(float& distance_m) const +{ + // only supported on ZT30 + if (_hardware_model != HardwareModel::ZT30) { + return false; + } + + // unhealthy if distance not received recently + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - _last_rangefinder_dist_ms > AP_MOUNT_SIYI_TIMEOUT_MS) { + return false; + } + + distance_m = _rangefinder_dist_m; + return true; +} + +// Checks that the firmware version on the Gimbal meets the minimum supported version. +void AP_Mount_Siyi::check_firmware_version() const +{ + if (!_fw_version.received) { + debug("Can't check firmware if we haven't received it..."); + return; + } + + if (!_got_hardware_id) { + debug("Can't check firmware without Hardware ID!"); + return; + } + + FirmwareVersion minimum_ver {}; + switch (_hardware_model) { + case HardwareModel::A8: + minimum_ver.camera.major = 0; + minimum_ver.camera.minor = 2; + minimum_ver.camera.patch = 1; + break; + + case HardwareModel::A2: + case HardwareModel::ZR10: + case HardwareModel::ZR30: + case HardwareModel::ZT30: + // TBD + break; + + case HardwareModel::UNKNOWN: + debug("Can't check FW on unknown hardware model!"); + return; + } + + const uint32_t minimum_camera_val = (minimum_ver.camera.major << 16) + (minimum_ver.camera.minor << 8) + minimum_ver.camera.patch; + const uint32_t firmware_camera_val = (_fw_version.camera.major << 16) + (_fw_version.camera.minor << 8) + _fw_version.camera.patch; + + const bool is_camera_supported = firmware_camera_val >= minimum_camera_val; + + if (!is_camera_supported) { + GCS_SEND_TEXT( + MAV_SEVERITY_WARNING, + "Mount: Siyi running old camera fw (need v%u.%u.%u)", + minimum_ver.camera.major, minimum_ver.camera.minor, minimum_ver.camera.patch + ); + } +} + #endif // HAL_MOUNT_SIYI_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h index c774134094626d..fd929558a7d3e8 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.h +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -72,12 +72,22 @@ class AP_Mount_Siyi : public AP_Mount_Backend // focus in = -1, focus hold = 0, focus out = 1 SetFocusResult set_focus(FocusType focus_type, float focus_value) override; + // set camera lens as a value from 0 to 8. ZT30 only + bool set_lens(uint8_t lens) override; + // 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; + protected: // get attitude as a quaternion. returns true on success @@ -98,7 +108,9 @@ class AP_Mount_Siyi : public AP_Mount_Backend FUNCTION_FEEDBACK_INFO = 0x0B, PHOTO = 0x0C, ACQUIRE_GIMBAL_ATTITUDE = 0x0D, - ABSOLUTE_ZOOM = 0x0F + ABSOLUTE_ZOOM = 0x0F, + SET_CAMERA_IMAGE_TYPE = 0x11, + READ_RANGEFINDER = 0x15, }; // Function Feedback Info packet info_type values @@ -137,17 +149,79 @@ class AP_Mount_Siyi : public AP_Mount_Backend // hardware model enum enum class HardwareModel : uint8_t { - UNKNOWN, + UNKNOWN = 0, + A2, A8, - ZR10 + ZR10, + ZR30, + ZT30 } _hardware_model; - // gimbal mounting method/direction + enum class HdrStatus : uint8_t { + OFF = 0, + ON = 1, + }; + + enum class RecordingStatus : uint8_t { + OFF = 0, + ON = 1, + NO_CARD = 2, + DATA_LOSS = 3, + }; + + enum class GimbalMotionMode : uint8_t { + LOCK = 0, + FOLLOW = 1, + FPV = 2, + }; + enum class GimbalMountingDirection : uint8_t { UNDEFINED = 0, NORMAL = 1, UPSIDE_DOWN = 2, - } _gimbal_mounting_dir; + }; + + enum class VideoOutputStatus : uint8_t { + HDMI = 0, + CVBS = 1, + }; + + // Response message for "Acquire Gimbal Confuguration Information" (0x0A) + typedef struct { + uint8_t _reserved1; + HdrStatus hdr_status; + uint8_t _reserved3; + RecordingStatus record_status; + GimbalMotionMode motion_mode; + GimbalMountingDirection mounting_dir; + VideoOutputStatus video_mode; + } GimbalConfigInfo; + static_assert(sizeof(GimbalConfigInfo) == 7); + + // camera image types (aka lens) + enum class CameraImageType : uint8_t { + MAIN_PIP_ZOOM_THERMAL_SUB_WIDEANGLE = 0, + MAIN_PIP_WIDEANGLE_THERMAL_SUB_ZOOM = 1, + MAIN_PIP_ZOOM_WIDEANGLE_SUB_THERMAL = 2, + MAIN_ZOOM_SUB_THERMAL = 3, + MAIN_ZOOM_SUB_WIDEANGLE = 4, + MAIN_WIDEANGLE_SUB_THERMAL = 5, + MAIN_WIDEANGLE_SUB_ZOOM = 6, + MAIN_THERMAL_SUB_ZOOM = 7, + MAIN_THERMAL_SUB_WIDEANGLE = 8 + }; + + typedef struct { + uint8_t major; + uint8_t minor; + uint8_t patch; + } Version; + typedef struct { + Version camera; + Version gimbal; + Version zoom; + bool received; // true once version information has been received + } FirmwareVersion; // reading incoming packets from gimbal and confirm they are of the correct format // results are held in the _parsed_msg structure @@ -167,15 +241,18 @@ class AP_Mount_Siyi : public AP_Mount_Backend void request_configuration() { send_packet(SiyiCommandId::ACQUIRE_GIMBAL_CONFIG_INFO, nullptr, 0); } void request_function_feedback_info() { send_packet(SiyiCommandId::FUNCTION_FEEDBACK_INFO, nullptr, 0); } void request_gimbal_attitude() { send_packet(SiyiCommandId::ACQUIRE_GIMBAL_ATTITUDE, nullptr, 0); } + void request_rangefinder_distance() { send_packet(SiyiCommandId::READ_RANGEFINDER, nullptr, 0); } // rotate gimbal. pitch_rate and yaw_rate are scalars in the range -100 ~ +100 // yaw_is_ef should be true if gimbal should maintain an earth-frame target (aka lock) void rotate_gimbal(int8_t pitch_scalar, int8_t yaw_scalar, bool yaw_is_ef); - // set gimbal's lock vs follow mode - // lock should be true if gimbal should maintain an earth-frame target - // lock is false to follow / maintain a body-frame target - void set_lock(bool lock); + // Set gimbal's motion mode if it has changed. Use force=true to always send. + // FOLLOW: roll and pitch are in earth-frame, yaw is in body-frame + // LOCK: roll, pitch and yaw are all in earth-frame + // FPV: roll, pitch and yaw are all in body-frame + // Returns true if message successfully sent to Gimbal + bool set_motion_mode(const GimbalMotionMode mode, const bool force=false); // send target pitch and yaw rates to gimbal // yaw_is_ef should be true if yaw_rads target is an earth frame rate, false if body_frame @@ -189,25 +266,26 @@ class AP_Mount_Siyi : public AP_Mount_Backend bool send_zoom_rate(float zoom_value); // send zoom multiple command to camera. e.g. 1x, 10x, 30x - // only supported by ZR10 and ZR30 bool send_zoom_mult(float zoom_mult); // get zoom multiple max float get_zoom_mult_max() const; - // update absolute zoom controller - // only used for A8 that does not support abs zoom control + // update zoom controller void update_zoom_control(); + // get model name string, returns nullptr if hardware id is unknown + const char* get_model_name() const; + + // Checks that the firmware version on the Gimbal meets the minimum supported version. + void check_firmware_version() const; + // internal variables AP_HAL::UARTDriver *_uart; // uart connected to gimbal bool _initialised; // true once the driver has been initialised - bool _got_firmware_version; // true once gimbal firmware version has been received - struct { - uint8_t major; - uint8_t minor; - uint8_t patch; - } _cam_firmware_version; // camera firmware version (for reporting for GCS) + bool _got_hardware_id; // true once hardware id ha been received + + FirmwareVersion _fw_version; // firmware version (for reporting for GCS) // buffer holding bytes from latest packet. This is only used to calculate the crc uint8_t _msg_buff[AP_MOUNT_SIYI_PACKETLEN_MAX]; @@ -226,21 +304,32 @@ class AP_Mount_Siyi : public AP_Mount_Backend // variables for sending packets to gimbal uint32_t _last_send_ms; // system time (in milliseconds) of last packet sent to gimbal uint16_t _last_seq; // last sequence number used (should be increment for each send) - bool _last_lock; // last lock value sent to gimbal - uint8_t _lock_send_counter; // counter used to resend lock status to gimbal at regular intervals // actual attitude received from gimbal Vector3f _current_angle_rad; // current angles in radians received from gimbal (x=roll, y=pitch, z=yaw) uint32_t _last_current_angle_rad_ms; // system time _current_angle_rad was updated uint32_t _last_req_current_angle_rad_ms; // system time that this driver last requested current angle - // variables for camera state - bool _last_record_video; // last record_video state sent to gimbal - // absolute zoom control. only used for A8 that does not support abs zoom control - float _zoom_mult_target; // current zoom multiple target. 0 if no target + ZoomType _zoom_type; // current zoom type + float _zoom_rate_target; // current zoom rate target float _zoom_mult; // most recent actual zoom multiple received from camera uint32_t _last_zoom_control_ms; // system time that zoom control was last run + + // Configuration info received from gimbal + GimbalConfigInfo _config_info; + + // rangefinder variables + uint32_t _last_rangefinder_req_ms; // system time of last request for rangefinder distance + uint32_t _last_rangefinder_dist_ms; // system time of last successful read of rangefinder distance + float _rangefinder_dist_m; // distance received from rangefinder + + // hardware lookup table indexed by HardwareModel enum values (see above) + struct HWInfo { + uint8_t hwid[2]; + const char* model_name; + }; + static const HWInfo hardware_lookup_table[]; }; #endif // HAL_MOUNT_SIYISERIAL_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index 2643eb36947a25..907b09a0d4574c 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -36,61 +36,66 @@ void AP_Mount_SoloGimbal::update() // move mount to a "retracted" position. we do not implement a separate servo based retract mechanism case MAV_MOUNT_MODE_RETRACT: _gimbal.set_lockedToBody(true); - // initialise _angle_rad to smooth transition if user changes to RC_TARGETTINg - _angle_rad = {0, 0, 0, false}; + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(Vector3f{0,0,0}, false); break; // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { _gimbal.set_lockedToBody(false); const Vector3f &target = _params.neutral_angles.get(); - _angle_rad.roll = radians(target.x); - _angle_rad.pitch = radians(target.y); - _angle_rad.yaw = radians(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: + // targets are stored while handling the incoming mavlink message _gimbal.set_lockedToBody(false); - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - _angle_rad = mavt_target.angle_rad; - break; - case MountTargetType::RATE: - update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); - break; + if (mnt_target.target_type == MountTargetType::RATE) { + update_angle_target_from_rate(mnt_target.rate_rads, mnt_target.angle_rad); } break; // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { _gimbal.set_lockedToBody(false); - // update targets using pilot's RC inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - update_angle_target_from_rate(rc_target, _angle_rad); - } else if (get_rc_angle_target(rc_target)) { - _angle_rad = rc_target; + 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; } break; } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: - _gimbal.set_lockedToBody(false); - IGNORE_RETURN(get_angle_target_to_roi(_angle_rad)); + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + _gimbal.set_lockedToBody(false); + } break; + // point mount to Home location case MAV_MOUNT_MODE_HOME_LOCATION: - _gimbal.set_lockedToBody(false); - IGNORE_RETURN(get_angle_target_to_home(_angle_rad)); + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + _gimbal.set_lockedToBody(false); + } break; + // point mount to another vehicle case MAV_MOUNT_MODE_SYSID_TARGET: - _gimbal.set_lockedToBody(false); - IGNORE_RETURN(get_angle_target_to_sysid(_angle_rad)); + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + _gimbal.set_lockedToBody(false); + } break; default: @@ -105,7 +110,7 @@ bool AP_Mount_SoloGimbal::get_attitude_quaternion(Quaternion& att_quat) if (!_gimbal.aligned()) { return false; } - att_quat.from_euler(_angle_rad.roll, _angle_rad.pitch, _angle_rad.get_bf_yaw()); + att_quat.from_euler(mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, mnt_target.angle_rad.get_bf_yaw()); return true; } @@ -114,7 +119,7 @@ bool AP_Mount_SoloGimbal::get_attitude_quaternion(Quaternion& att_quat) */ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg) { - _gimbal.update_target(Vector3f{_angle_rad.roll, _angle_rad.pitch, _angle_rad.get_bf_yaw()}); + _gimbal.update_target(Vector3f{mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, mnt_target.angle_rad.get_bf_yaw()}); _gimbal.receive_feedback(chan,msg); AP_Logger *logger = AP_Logger::get_singleton(); diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.h b/libraries/AP_Mount/AP_Mount_SoloGimbal.h index 87503e5f39d8d2..4e64233284a9fd 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.h +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.h @@ -54,7 +54,6 @@ class AP_Mount_SoloGimbal : public AP_Mount_Backend void Log_Write_Gimbal(SoloGimbal &gimbal); bool _params_saved; - MountTarget _angle_rad; // angle target SoloGimbal _gimbal; }; diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.cpp b/libraries/AP_Mount/AP_Mount_Viewpro.cpp index 5b199d7af3e93c..07608d689bfff1 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.cpp +++ b/libraries/AP_Mount/AP_Mount_Viewpro.cpp @@ -19,7 +19,7 @@ extern const AP_HAL::HAL& hal; #define AP_MOUNT_VIEWPRO_HEALTH_TIMEOUT_MS 1000 // state will become unhealthy if no attitude is received within this timeout #define AP_MOUNT_VIEWPRO_UPDATE_INTERVAL_MS 100 // resend angle or rate targets to gimbal at this interval #define AP_MOUNT_VIEWPRO_ZOOM_SPEED 0x07 // hard-coded zoom speed (fast) -#define AP_MOUNT_VIEWPRO_ZOOM_MAX 20 // hard-coded absolute zoom times max +#define AP_MOUNT_VIEWPRO_ZOOM_MAX 10 // hard-coded absolute zoom times max #define AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT (65536.0 / 360.0) // scalar to convert degrees to the viewpro angle scaling #define AP_MOUNT_VIEWPRO_OUTPUT_TO_DEG (360.0 / 65536.0) // scalar to convert viewpro angle scaling to degrees @@ -60,6 +60,16 @@ void AP_Mount_Viewpro::update() // reading incoming packets from gimbal read_incoming_packets(); + // request model name + if (!_got_model_name) { + send_comm_config_cmd(CommConfigCmd::QUERY_MODEL); + } + + // request firmware version + if (!_got_firmware_version) { + send_comm_config_cmd(CommConfigCmd::QUERY_FIRMWARE_VER); + } + // send handshake send_handshake(); @@ -76,71 +86,76 @@ void AP_Mount_Viewpro::update() // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? case MAV_MOUNT_MODE_RETRACT: { const Vector3f &angle_bf_target = _params.retract_angles.get(); - send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + 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(); - send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + 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: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - send_target_angles(mavt_target.angle_rad.pitch, mavt_target.angle_rad.yaw, mavt_target.angle_rad.yaw_is_ef); - break; - case MountTargetType::RATE: - send_target_rates(mavt_target.rate_rads.pitch, mavt_target.rate_rads.yaw, mavt_target.rate_rads.yaw_is_ef); - break; - } + // 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 targets using pilot's rc inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - send_target_rates(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } else if (get_rc_angle_target(rc_target)) { - send_target_angles(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); + // 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; } break; } // point mount to a GPS point given by the mission planner - case MAV_MOUNT_MODE_GPS_POINT: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_roi(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + case MAV_MOUNT_MODE_GPS_POINT: + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_HOME_LOCATION: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_home(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // 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; - } - case MAV_MOUNT_MODE_SYSID_TARGET:{ - MountTarget angle_target_rad {}; - if (get_angle_target_to_sysid(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // 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_target_angles(mnt_target.angle_rad.pitch, mnt_target.angle_rad.yaw, mnt_target.angle_rad.yaw_is_ef); + break; + case MountTargetType::RATE: + send_target_rates(mnt_target.rate_rads.pitch, mnt_target.rate_rads.yaw, mnt_target.rate_rads.yaw_is_ef); + break; + } } // return true if healthy @@ -282,6 +297,35 @@ void AP_Mount_Viewpro::process_packet() case FrameId::HANDSHAKE: break; + case FrameId::V: { + const CommConfigCmd control_cmd = (CommConfigCmd)_msg_buff[_msg_buff_data_start]; + switch (control_cmd) { + case CommConfigCmd::QUERY_FIRMWARE_VER: { + // firmware version, length is 20 bytes but we expect format of "S" + yyyymmdd + const uint8_t fw_major_str[3] {_msg_buff[_msg_buff_data_start+4], _msg_buff[_msg_buff_data_start+5], 0x0}; + const uint8_t fw_minor_str[3] {_msg_buff[_msg_buff_data_start+6], _msg_buff[_msg_buff_data_start+7], 0x0}; + const uint8_t fw_patch_str[3] {_msg_buff[_msg_buff_data_start+8], _msg_buff[_msg_buff_data_start+9], 0x0}; + const uint8_t major_ver = atoi((const char*)fw_major_str) & 0xFF; + const uint8_t minor_ver = atoi((const char*)fw_minor_str) & 0xFF; + const uint8_t patch_ver = atoi((const char*)fw_patch_str) & 0xFF; + _firmware_version = (patch_ver << 16) | (minor_ver << 8) | major_ver; + _got_firmware_version = true; + gcs().send_text(MAV_SEVERITY_INFO, "%s fw:%u.%u.%u", send_text_prefix, (unsigned)major_ver, (unsigned)minor_ver, (unsigned)patch_ver); + break; + } + case CommConfigCmd::QUERY_MODEL: + // gimbal model, length is 10 bytes + strncpy((char *)_model_name, (const char *)&_msg_buff[_msg_buff_data_start+1], sizeof(_model_name)-1); + _got_model_name = true; + gcs().send_text(MAV_SEVERITY_INFO, "%s %s", send_text_prefix, (const char*)_model_name); + break; + default: + // unsupported control command + break; + } + break; + } + case FrameId::T1_F1_B1_D1: { // T1 holds target info including target lean angles // F1 holds tracker sensor status (which camera, tracking vs lost) @@ -310,8 +354,25 @@ void AP_Mount_Viewpro::process_packet() _last_current_angle_rad_ms = AP_HAL::millis(); _current_angle_rad.x = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+23] & 0x0F, _msg_buff[_msg_buff_data_start+24]) * (180.0/4095.0) - 90.0); // roll angle _current_angle_rad.z = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+25], _msg_buff[_msg_buff_data_start+26]) * AP_MOUNT_VIEWPRO_OUTPUT_TO_DEG); // yaw angle - _current_angle_rad.y = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+27], _msg_buff[_msg_buff_data_start+28]) * AP_MOUNT_VIEWPRO_OUTPUT_TO_DEG); // pitch angle + _current_angle_rad.y = -radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+27], _msg_buff[_msg_buff_data_start+28]) * AP_MOUNT_VIEWPRO_OUTPUT_TO_DEG); // pitch angle debug("r:%4.1f p:%4.1f y:%4.1f", (double)degrees(_current_angle_rad.x), (double)degrees(_current_angle_rad.y), (double)degrees(_current_angle_rad.z)); + + // get active image sensor. D1's image sensor values are one value lower than C1's + _image_sensor = ImageSensor((_msg_buff[_msg_buff_data_start+29] & 0x07) + 1); + + // get recording status + const RecordingStatus recording_status = (RecordingStatus)(_msg_buff[_msg_buff_data_start+32] & 0x07); + const bool recording = (recording_status == RecordingStatus::RECORDING); + if (recording != _recording) { + _recording = recording; + gcs().send_text(MAV_SEVERITY_INFO, "%s recording %s", send_text_prefix, _recording ? "ON" : "OFF"); + } + + // get optical zoom times + _zoom_times = UINT16_VALUE(_msg_buff[_msg_buff_data_start+39], _msg_buff[_msg_buff_data_start+40]) * 0.1; + + // get laser rangefinder distance + _rangefinder_dist_m = UINT16_VALUE(_msg_buff[_msg_buff_data_start+33], _msg_buff[_msg_buff_data_start+34]) * 0.1; break; } @@ -393,7 +454,12 @@ bool AP_Mount_Viewpro::send_packet(const uint8_t* databuff, uint8_t databuff_len // send handshake, gimbal will respond with T1_F1_B1_D1 paket that includes current angles void AP_Mount_Viewpro::send_handshake() { - HandshakePacket hs_packet {FrameId::HANDSHAKE, 0}; + const HandshakePacket hs_packet { + .content = { + frame_id: FrameId::HANDSHAKE, + unused: 0 + } + }; send_packet(hs_packet.bytes, sizeof(hs_packet.bytes)); } @@ -408,9 +474,12 @@ bool AP_Mount_Viewpro::set_lock(bool lock) } // fill in packet - A1Packet a1_packet {}; - a1_packet.content.frame_id = FrameId::A1; - a1_packet.content.servo_status = lock ? ServoStatus::follow_yaw_disable : ServoStatus::follow_yaw; + const A1Packet a1_packet { + .content = { + frame_id: FrameId::A1, + servo_status: lock ? ServoStatus::FOLLOW_YAW_DISABLE : ServoStatus::FOLLOW_YAW + } + }; // send targets to gimbal if (send_packet(a1_packet.bytes, sizeof(a1_packet.bytes))) { @@ -420,6 +489,21 @@ bool AP_Mount_Viewpro::set_lock(bool lock) return false; } +// send communication configuration command (aka U packet), gimbal will respond with a V packet +bool AP_Mount_Viewpro::send_comm_config_cmd(CommConfigCmd cmd) +{ + // fill in packet + const UPacket u_packet { + .content = { + frame_id: FrameId::U, + control_cmd: cmd + } + }; + + // send targets to gimbal + return send_packet(u_packet.bytes, sizeof(u_packet.bytes)); +} + // send target pitch and yaw rates to gimbal // yaw_is_ef should be true if yaw_rads target is an earth frame rate, false if body_frame bool AP_Mount_Viewpro::send_target_rates(float pitch_rads, float yaw_rads, bool yaw_is_ef) @@ -434,11 +518,14 @@ bool AP_Mount_Viewpro::send_target_rates(float pitch_rads, float yaw_rads, bool const int16_t yaw_rate_output = degrees(yaw_rads) * 100.0; // fill in packet - A1Packet a1_packet {}; - a1_packet.content.frame_id = FrameId::A1; - a1_packet.content.servo_status = ServoStatus::manual_speed_mode; - a1_packet.content.yaw_be = htobe16(yaw_rate_output); - a1_packet.content.pitch_be = htobe16(pitch_rate_output); + const A1Packet a1_packet { + .content = { + frame_id: FrameId::A1, + servo_status: ServoStatus::MANUAL_SPEED_MODE, + yaw_be: htobe16(yaw_rate_output), + pitch_be: htobe16(pitch_rate_output) + } + }; // send targets to gimbal return send_packet(a1_packet.bytes, sizeof(a1_packet.bytes)); @@ -469,32 +556,38 @@ bool AP_Mount_Viewpro::send_target_angles(float pitch_rad, float yaw_rad, bool y const int16_t yaw_angle_output = degrees(yaw_bf_rad) * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT; // fill in packet - A1Packet a1_packet {}; - a1_packet.content.frame_id = FrameId::A1; - a1_packet.content.servo_status = ServoStatus::manual_absolute_angle_mode; - a1_packet.content.yaw_be = htobe16(yaw_angle_output); - a1_packet.content.pitch_be = htobe16(pitch_angle_output); + const A1Packet a1_packet { + .content = { + frame_id: FrameId::A1, + servo_status: ServoStatus::MANUAL_ABSOLUTE_ANGLE_MODE, + yaw_be: htobe16(yaw_angle_output), + pitch_be: htobe16(pitch_angle_output) + } + }; // send targets to gimbal return send_packet(a1_packet.bytes, sizeof(a1_packet.bytes)); } -// send camera command and corresponding value (e.g. zoom speed) -bool AP_Mount_Viewpro::send_camera_command(CameraCommand cmd, uint8_t value) +// send camera command, affected image sensor and value (e.g. zoom speed) +bool AP_Mount_Viewpro::send_camera_command(ImageSensor img_sensor, CameraCommand cmd, uint8_t value) { - // fill in packet - C1Packet c1_packet {}; - c1_packet.content.frame_id = FrameId::C1; - // fill in 2 bytes containing sensor, zoom speed, operation command and LRF // bit0~2: sensor // bit3~5: zoom speed // bit6~12: operation command no // bit13~15: LRF command (unused) - const uint16_t sensor_id = (uint16_t)ImageSensor::EO1; + const uint16_t sensor_id = (uint16_t)img_sensor; const uint16_t zoom_speed = ((uint16_t)value & 0x07) << 3; const uint16_t operation_cmd = ((uint16_t)cmd & 0x7F) << 6; - c1_packet.content.sensor_zoom_cmd_be = htobe16(sensor_id | zoom_speed | operation_cmd); + + // fill in packet + const C1Packet c1_packet { + .content = { + frame_id: FrameId::C1, + sensor_zoom_cmd_be: htobe16(sensor_id | zoom_speed | operation_cmd) + } + }; // send packet to gimbal return send_packet(c1_packet.bytes, sizeof(c1_packet.bytes)); @@ -504,10 +597,13 @@ bool AP_Mount_Viewpro::send_camera_command(CameraCommand cmd, uint8_t value) bool AP_Mount_Viewpro::send_camera_command2(CameraCommand2 cmd, uint16_t value) { // fill in packet - C2Packet c2_packet {}; - c2_packet.content.frame_id = FrameId::C2; - c2_packet.content.cmd = cmd; - c2_packet.content.value_be = htobe16(value); + const C2Packet c2_packet { + .content = { + frame_id: FrameId::C2, + cmd: cmd, + value_be: htobe16(value) + } + }; // send packet to gimbal return send_packet(c2_packet.bytes, sizeof(c2_packet.bytes)); @@ -516,12 +612,30 @@ bool AP_Mount_Viewpro::send_camera_command2(CameraCommand2 cmd, uint16_t value) // send tracking command and corresponding value (normally zero) bool AP_Mount_Viewpro::send_tracking_command(TrackingCommand cmd, uint8_t value) { + // convert image sensor to tracking source + TrackingSource tracking_source = TrackingSource::EO1; + switch (_image_sensor) { + case ImageSensor::NO_ACTION: + case ImageSensor::EO1: + case ImageSensor::EO1_IR_PIP: + case ImageSensor::FUSION: + tracking_source = TrackingSource::EO1; + break; + case ImageSensor::IR: + case ImageSensor::IR_EO1_PIP: + case ImageSensor::IR1_13MM: + case ImageSensor::IR2_52MM: + tracking_source = TrackingSource::IR; + break; + } + // fill in packet + // Packet creation is done long-hand here to support g++-7.5.0 E1Packet e1_packet {}; e1_packet.content.frame_id = FrameId::E1; - e1_packet.content.source = TrackingSource::EO1; // hard-coded to only affect RGB sensor for now + e1_packet.content.source = tracking_source; e1_packet.content.cmd = cmd; - e1_packet.content.param2 = value; // normally zero + e1_packet.content.param2 = value; // normally zero // send packet to gimbal return send_packet(e1_packet.bytes, sizeof(e1_packet.bytes)); @@ -531,11 +645,14 @@ bool AP_Mount_Viewpro::send_tracking_command(TrackingCommand cmd, uint8_t value) bool AP_Mount_Viewpro::send_tracking_command2(TrackingCommand2 cmd, uint16_t param1, uint16_t param2) { // fill in packet - E2Packet e2_packet {}; - e2_packet.content.frame_id = FrameId::E2; - e2_packet.content.cmd = cmd; - e2_packet.content.param1_be = htobe16(param1); - e2_packet.content.param2_be = htobe16(param2); + const E2Packet e2_packet { + .content = { + frame_id: FrameId::E2, + cmd: cmd, + param1_be: htobe16(param1), + param2_be: htobe16(param2), + } + }; // send packet to gimbal return send_packet(e2_packet.bytes, sizeof(e2_packet.bytes)); @@ -551,43 +668,55 @@ bool AP_Mount_Viewpro::send_m_ahrs() return false; } +#if AP_RTC_ENABLED // get date and time 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)) { - year = month = day = hour = min = sec = 0; + year = month = day = hour = min = sec = ms = 0; } - uint16_t date = ((year-2000) & 0x7f) | (((month+1) & 0x0F) << 7) | ((day & 0x0F) << 11); + uint16_t date = ((year-2000) & 0x7f) | (((month+1) & 0x0F) << 7) | ((day & 0x1F) << 11); uint64_t second_hundredths = (((hour * 60 * 60) + (min * 60) + sec) * 100) + (ms * 0.1); +#else + const uint16_t date = 0; + const uint64_t second_hundredths = 0; +#endif // get vehicle velocity in m/s in NED Frame Vector3f vel_NED; IGNORE_RETURN(AP::ahrs().get_velocity_NED(vel_NED)); - float vel_yaw_deg = degrees(vel_NED.xy().angle()); + float vel_yaw_deg = wrap_360(degrees(vel_NED.xy().angle())); // get GPS vdop uint16_t gps_vdop = AP::gps().get_vdop(); + // get vehicle yaw in the range 0 to 360 + const uint16_t veh_yaw_deg = wrap_360(degrees(AP::ahrs().get_yaw())); + // fill in packet - M_AHRSPacket mahrs_packet{}; - mahrs_packet.content.frame_id = FrameId::M_AHRS; - mahrs_packet.content.data_type = 0x07; // Bit0: Attitude, Bit1: GPS, Bit2 Gyro - mahrs_packet.content.pitch_be = htobe16(-degrees(AP::ahrs().get_pitch()) * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT); // vehicle pitch angle. 1bit=360deg/65536 - mahrs_packet.content.roll_be = htobe16(degrees(AP::ahrs().get_roll()) * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT); // vehicle roll angle. 1bit=360deg/65536 - mahrs_packet.content.yaw_be = htobe16(degrees(AP::ahrs().get_yaw()) * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT); // vehicle yaw angle. 1bit=360deg/65536 - mahrs_packet.content.date_be = htobe16(date); // bit0~6:year, bit7~10:month, bit11~15:day - mahrs_packet.content.seconds_utc[0] = uint8_t((second_hundredths & 0xFF0000ULL) >> 16); // seconds * 100 MSB. 1bit = 0.01sec - mahrs_packet.content.seconds_utc[1] = uint8_t((second_hundredths & 0xFF00ULL) >> 8); // seconds * 100 next MSB. 1bit = 0.01sec - mahrs_packet.content.seconds_utc[2] = uint8_t(second_hundredths & 0xFFULL); // seconds * 100 LSB. 1bit = 0.01sec - mahrs_packet.content.gps_yaw_be = htobe16(vel_yaw_deg * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT); // GPS yaw - mahrs_packet.content.position_mark_bitmask = 0x0F; // bit0:new position, bit1:clock fix calced, bit2:horiz calced, bit3:alt calced - mahrs_packet.content.latitude_be = htobe32(loc.lat); // latitude. 1bit = 10e-7 - mahrs_packet.content.longitude_be = htobe32(loc.lng); // longitude. 1bit = 10e-7 - mahrs_packet.content.height_be = htobe32(alt_amsl_cm * 10); // height. 1bit = 1mm - mahrs_packet.content.ground_speed_N_be = htobe16(vel_NED.x * 100); // ground speed in North direction. 1bit = 0.01m/s - mahrs_packet.content.ground_speed_E_be = htobe16(vel_NED.y * 100); // ground speed in East direction. 1bit = 0.01m/s - mahrs_packet.content.vdop_be = htobe16(gps_vdop); // GPS vdop. 1bit = 0.01 - mahrs_packet.content.ground_speed_D_be = htobe16(vel_NED.z * 100); // speed downwards. 1bit = 0.01m/s + const M_AHRSPacket mahrs_packet { + .content = { + frame_id: FrameId::M_AHRS, + data_type: 0x07, // Bit0: Attitude, Bit1: GPS, Bit2 Gyro + unused2to8 : {0, 0, 0, 0, 0, 0, 0}, + pitch_be: htobe16(-degrees(AP::ahrs().get_pitch()) * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT), // vehicle pitch angle. 1bit=360deg/65536 + roll_be: htobe16(degrees(AP::ahrs().get_roll()) * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT), // vehicle roll angle. 1bit=360deg/65536 + yaw_be: htobe16(veh_yaw_deg * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT), // vehicle yaw angle. 1bit=360deg/65536 + date_be: htobe16(date), // bit0~6:year, bit7~10:month, bit11~15:day + seconds_utc: {uint8_t((second_hundredths & 0xFF0000ULL) >> 16), // seconds * 100 MSB. 1bit = 0.01sec + uint8_t((second_hundredths & 0xFF00ULL) >> 8), // seconds * 100 next MSB. 1bit = 0.01sec + uint8_t(second_hundredths & 0xFFULL)}, // seconds * 100 LSB. 1bit = 0.01sec + gps_yaw_be: htobe16(vel_yaw_deg * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT), // GPS yaw + position_mark_bitmask: 0x0F, // bit0:new position, bit1:clock fix calced, bit2:horiz calced, bit3:alt calced + latitude_be: htobe32(loc.lat), // latitude. 1bit = 10e-7 + longitude_be: htobe32(loc.lng), // longitude. 1bit = 10e-7 + height_be: htobe32(alt_amsl_cm * 10), // height. 1bit = 1mm + ground_speed_N_be: htobe16(vel_NED.x * 100), // ground speed in North direction. 1bit = 0.01m/s + ground_speed_E_be: htobe16(vel_NED.y * 100), // ground speed in East direction. 1bit = 0.01m/s + vdop_be: htobe16(gps_vdop), // GPS vdop. 1bit = 0.01 + ground_speed_D_be: htobe16(vel_NED.z * 100) // speed downwards. 1bit = 0.01m/s + } + }; // send packet to gimbal return send_packet(mahrs_packet.bytes, sizeof(mahrs_packet.bytes)); @@ -601,7 +730,7 @@ bool AP_Mount_Viewpro::take_picture() return false; } - return send_camera_command(CameraCommand::TAKE_PICTURE, 0); + return send_camera_command(_image_sensor, CameraCommand::TAKE_PICTURE, 0); } // start or stop video recording. returns true on success @@ -613,13 +742,7 @@ bool AP_Mount_Viewpro::record_video(bool start_recording) return false; } - if (!send_camera_command(start_recording ? CameraCommand::START_RECORD : CameraCommand::STOP_RECORD, 0)) { - return false; - } - - gcs().send_text(MAV_SEVERITY_INFO, "%s recording %s", send_text_prefix, start_recording ? "ON": "OFF"); - _last_record_video = start_recording; - return true; + return send_camera_command(_image_sensor, start_recording ? CameraCommand::START_RECORD : CameraCommand::STOP_RECORD, 0); } // set zoom specified as a rate or percentage @@ -638,7 +761,7 @@ bool AP_Mount_Viewpro::set_zoom(ZoomType zoom_type, float zoom_value) } else if (zoom_value > 0) { zoom_cmd = CameraCommand::ZOOM_IN; } - return send_camera_command(zoom_cmd, AP_MOUNT_VIEWPRO_ZOOM_SPEED); + return send_camera_command(_image_sensor, zoom_cmd, AP_MOUNT_VIEWPRO_ZOOM_SPEED); } // zoom percentage @@ -668,7 +791,7 @@ SetFocusResult AP_Mount_Viewpro::set_focus(FocusType focus_type, float focus_val } else if (focus_value > 0) { focus_cmd = CameraCommand::FOCUS_PLUS; } - if (!send_camera_command(focus_cmd, 0)) { + if (!send_camera_command(_image_sensor, focus_cmd, 0)) { return SetFocusResult::FAILED; } return SetFocusResult::ACCEPTED; @@ -677,7 +800,7 @@ SetFocusResult AP_Mount_Viewpro::set_focus(FocusType focus_type, float focus_val // not supported return SetFocusResult::INVALID_PARAMETERS; case FocusType::AUTO: - if (!send_camera_command(CameraCommand::AUTO_FOCUS, 0)) { + if (!send_camera_command(_image_sensor, CameraCommand::AUTO_FOCUS, 0)) { return SetFocusResult::FAILED; } return SetFocusResult::ACCEPTED; @@ -717,6 +840,25 @@ bool AP_Mount_Viewpro::set_tracking(TrackingType tracking_type, const Vector2f& return false; } +// set camera lens as a value from 0 to 5 +bool AP_Mount_Viewpro::set_lens(uint8_t lens) +{ + // exit immediately if not initialised + if (!_initialised) { + return false; + } + + // match lens to ImageSensor enum values and sanity check + lens++; + if (lens > (uint8_t)ImageSensor::IR2_52MM) { + return false; + } + + // if lens is zero use default lens + ImageSensor new_image_sensor = ImageSensor(lens); + return send_camera_command(new_image_sensor, CameraCommand::NO_ACTION, 0); +} + // send camera information message to GCS void AP_Mount_Viewpro::send_camera_information(mavlink_channel_t chan) const { @@ -726,7 +868,10 @@ void AP_Mount_Viewpro::send_camera_information(mavlink_channel_t chan) const } static const uint8_t vendor_name[32] = "Viewpro"; - static uint8_t model_name[32] = "Unknown"; + uint8_t model_name[32] {}; + if (_got_model_name) { + strncpy((char *)model_name, (const char*)_model_name, MIN(sizeof(model_name), sizeof(_model_name))); + } const char cam_definition_uri[140] {}; // capability flags @@ -742,8 +887,8 @@ void AP_Mount_Viewpro::send_camera_information(mavlink_channel_t chan) const 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 + _model_name, // model_name uint8_t[32] + _firmware_version, // firmware version uint32_t 0, // focal_length float (mm) 0, // sensor_size_h float (mm) 0, // sensor_size_v float (mm) @@ -752,7 +897,8 @@ void AP_Mount_Viewpro::send_camera_information(mavlink_channel_t chan) const 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] + cam_definition_uri, // cam_definition_uri char[140] + _instance + 1); // gimbal_device_id uint8_t } // send camera settings message to GCS @@ -765,13 +911,29 @@ void AP_Mount_Viewpro::send_camera_settings(mavlink_channel_t chan) const 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); + // send CAMERA_SETTINGS message mavlink_msg_camera_settings_send( chan, AP_HAL::millis(), // time_boot_ms - _last_record_video ? CAMERA_MODE_VIDEO : CAMERA_MODE_IMAGE, // camera mode (0:image, 1:video, 2:image survey) - NaN, // zoomLevel float, percentage from 0 to 100, NaN if unknown + _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 } +// get rangefinder distance. Returns true on success +bool AP_Mount_Viewpro::get_rangefinder_distance(float& distance_m) const +{ + // if not healthy or zero distance return false + // healthy() checks attitude timeout which is in same message as rangefinder distance + if (!healthy()) { + return false; + } + + distance_m = _rangefinder_dist_m; + return true; +} + #endif // HAL_MOUNT_VIEWPRO_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.h b/libraries/AP_Mount/AP_Mount_Viewpro.h index 49489d2da7a476..2e9fc3cdb9c317 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.h +++ b/libraries/AP_Mount/AP_Mount_Viewpro.h @@ -75,12 +75,22 @@ class AP_Mount_Viewpro : public AP_Mount_Backend // 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; + // set camera lens as a value from 0 to 5 + bool set_lens(uint8_t lens) override; + // 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; + protected: // get attitude as a quaternion. returns true on success @@ -94,8 +104,10 @@ class AP_Mount_Viewpro : public AP_Mount_Backend // packet frame ids enum class FrameId : uint8_t { HANDSHAKE = 0x00, // handshake sent to gimbal + U = 0x01, // communication configuration control (this packet is sent to gimbal) + V = 0x02, // communication configuration status (this is the reply to U) HEARTBEAT = 0x10, // heartbeat received from gimbal - A1 = 0x1A, // target angles (this packet is sent) + A1 = 0x1A, // target angles (sent) C1 = 0x1C, // camera controls commonly used (sent) E1 = 0x1E, // tracking controls commonly used (sent) C2 = 0x2C, // camera controls infrequently used (sent) @@ -104,12 +116,18 @@ class AP_Mount_Viewpro : public AP_Mount_Backend M_AHRS = 0xB1, // vehicle attitude and position (sent) }; + // U communication configuration control commands + enum class CommConfigCmd : uint8_t { + QUERY_FIRMWARE_VER = 0xD0, + QUERY_MODEL = 0xE4, + }; + // A1 servo status enum (used in A1, B1 packets) enum class ServoStatus : uint8_t { - manual_speed_mode = 0x01, - follow_yaw = 0x03, - manual_absolute_angle_mode = 0x0B, - follow_yaw_disable = 0x0A, + MANUAL_SPEED_MODE = 0x01, + FOLLOW_YAW = 0x03, + MANUAL_ABSOLUTE_ANGLE_MODE = 0x0B, + FOLLOW_YAW_DISABLE = 0x0A, }; // C1 image sensor choice @@ -126,7 +144,7 @@ class AP_Mount_Viewpro : public AP_Mount_Backend // C1 camera commands enum class CameraCommand : uint8_t { - NO_ACTION = 0, + NO_ACTION = 0x00, STOP_FOCUS_AND_ZOOM = 0x01, ZOOM_OUT = 0x08, ZOOM_IN = 0x09, @@ -144,6 +162,13 @@ class AP_Mount_Viewpro : public AP_Mount_Backend SET_EO_ZOOM = 0x53 }; + // D1 recording status (received from gimbal) + enum class RecordingStatus : uint8_t { + RECORDING_STOPPED = 0x00, + RECORDING = 0x01, + PICTURE_MODE = 0x02 + }; + // E1 tracking commands enum class TrackingCommand : uint8_t { STOP = 0x01, @@ -195,6 +220,17 @@ class AP_Mount_Viewpro : public AP_Mount_Backend uint8_t bytes[sizeof(content)]; }; + // U packed used to send communication configuration control commands + // gimbal replies with V packet + union UPacket { + struct { + FrameId frame_id; // always 0x01 + CommConfigCmd control_cmd; // see CommConfigCmd enum above + uint8_t params[9]; // parameters (unused) + } content; + uint8_t bytes[sizeof(content)]; + }; + // A1 used to send target angles and rates union A1Packet { struct { @@ -291,7 +327,7 @@ class AP_Mount_Viewpro : public AP_Mount_Backend // returns true on success, false if outgoing serial buffer is full bool send_packet(const uint8_t* databuff, uint8_t databuff_len); - // send handshake, gimbal will respond with T1_F1_B1_D1 paket that includes current angles + // send handshake, gimbal will respond with T1_F1_B1_D1 packet that includes current angles void send_handshake(); // set gimbal's lock vs follow mode @@ -299,6 +335,9 @@ class AP_Mount_Viewpro : public AP_Mount_Backend // lock is false to follow / maintain a body-frame target bool set_lock(bool lock); + // send communication configuration command (aka U packet), gimbal will respond with a V packet + bool send_comm_config_cmd(CommConfigCmd cmd); + // send target pitch and yaw rates to gimbal // yaw_is_ef should be true if yaw_rads target is an earth frame rate, false if body_frame bool send_target_rates(float pitch_rads, float yaw_rads, bool yaw_is_ef); @@ -307,8 +346,8 @@ class AP_Mount_Viewpro : public AP_Mount_Backend // yaw_is_ef should be true if yaw_rad target is an earth frame angle, false if body_frame bool send_target_angles(float pitch_rad, float yaw_rad, bool yaw_is_ef); - // send camera command and corresponding value (e.g. zoom speed) - bool send_camera_command(CameraCommand cmd, uint8_t value); + // send camera command, affected image sensor and value (e.g. zoom speed) + bool send_camera_command(ImageSensor img_sensor, CameraCommand cmd, uint8_t value); // send camera command2 and corresponding value (e.g. zoom as absolute value) bool send_camera_command2(CameraCommand2 cmd, uint16_t value); @@ -343,9 +382,16 @@ class AP_Mount_Viewpro : public AP_Mount_Backend uint32_t _last_update_ms; // system time (in milliseconds) that angle or rate targets were last sent Vector3f _current_angle_rad; // current angles in radians received from gimbal (x=roll, y=pitch, z=yaw) uint32_t _last_current_angle_rad_ms; // system time _current_angle_rad was updated (used for health reporting) - bool _last_record_video; // last record_video state sent to gimbal + bool _recording; // recording status received from gimbal bool _last_lock; // last lock mode sent to gimbal TrackingStatus _last_tracking_status; // last tracking status received from gimbal (used to notify users) + ImageSensor _image_sensor; // user selected image sensor (aka camera lens) + float _zoom_times; // zoom times received from gimbal + uint32_t _firmware_version; // firmware version from gimbal + bool _got_firmware_version; // true once we have received the firmware version + uint8_t _model_name[11] {}; // model name received from gimbal + bool _got_model_name; // true once we have received model name + float _rangefinder_dist_m; // latest rangefinder distance (in meters) }; #endif // HAL_MOUNT_VIEWPRO_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Xacti.cpp b/libraries/AP_Mount/AP_Mount_Xacti.cpp index cb08a54fb4cff2..9f210993d4350d 100644 --- a/libraries/AP_Mount/AP_Mount_Xacti.cpp +++ b/libraries/AP_Mount/AP_Mount_Xacti.cpp @@ -7,13 +7,16 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; #define LOG_TAG "Mount" -#define XACTI_PARAM_SINGLESHOT "SingleShot" -#define XACTI_PARAM_RECORDING "Recording" -#define XACTI_PARAM_FOCUSMODE "FocusMode" +#define XACTI_MSG_SEND_MIN_MS 20 // messages should not be sent to camera more often than 20ms +#define XACTI_DIGITAL_ZOOM_RATE_UPDATE_INTERVAL_MS 500 // digital zoom rate control updates 11% up or down every 0.5sec +#define XACTI_OPTICAL_ZOOM_RATE_UPDATE_INTERVAL_MS 250 // optical zoom rate control updates 6.6% up or down every 0.25sec +#define XACTI_STATUS_REQ_INTERVAL_MS 3000 // request status every 3 seconds +#define XACTI_SET_PARAM_QUEUE_SIZE 3 // three set-param requests may be queued #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) @@ -21,6 +24,12 @@ extern const AP_HAL::HAL& hal; 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:"; +const char* AP_Mount_Xacti::sensor_mode_str[] = { "RGB", "IR", "PIP", "NDVI" }; +const char* AP_Mount_Xacti::_param_names[] = {"SingleShot", "Recording", "FocusMode", + "SensorMode", "DigitalZoomMagnification", + "FirmwareVersion", "Status", "DateTime", + "OpticalZoomMagnification"}; // Constructor AP_Mount_Xacti::AP_Mount_Xacti(class AP_Mount &frontend, class AP_Mount_Params ¶ms, uint8_t instance) : @@ -29,12 +38,22 @@ AP_Mount_Xacti::AP_Mount_Xacti(class AP_Mount &frontend, class AP_Mount_Params & register_backend(); param_int_cb = FUNCTOR_BIND_MEMBER(&AP_Mount_Xacti::handle_param_get_set_response_int, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); + param_string_cb = FUNCTOR_BIND_MEMBER(&AP_Mount_Xacti::handle_param_get_set_response_string, bool, AP_DroneCAN*, const uint8_t, const char*, AP_DroneCAN::string &); param_save_cb = FUNCTOR_BIND_MEMBER(&AP_Mount_Xacti::handle_param_save_response, void, AP_DroneCAN*, const uint8_t, bool); + + // static assert that Param enum matches parameter names array + static_assert((uint8_t)AP_Mount_Xacti::Param::LAST+1 == ARRAY_SIZE(AP_Mount_Xacti::_param_names), "AP_Mount_Xacti::_param_names array must match Param enum"); } // init - performs any required initialisation for this instance 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); + if (_set_param_int32_queue == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s init failed", send_text_prefix); + return; + } _initialised = true; } @@ -46,86 +65,131 @@ void AP_Mount_Xacti::update() return; } + // return immediately if any message sent is unlikely to be processed + const uint32_t now_ms = AP_HAL::millis(); + if (!is_safe_to_send(now_ms)) { + return; + } + + // get firmware version + if (request_firmware_version(now_ms)) { + return; + } + + // additional initial setup + if (_firmware_version.received) { + // set date and time + if (set_datetime(now_ms)) { + return; + } + // request camera capabilities + if (request_capabilities(now_ms)) { + return; + } + } + + // request status + if (request_status(now_ms)) { + return; + } + + // process queue of set parameter items + if (process_set_param_int32_queue()) { + return; + } + // periodically send copter attitude and GPS status - send_copter_att_status(); + if (send_copter_att_status(now_ms)) { + // if message sent avoid sending other messages + return; + } + + // update zoom rate control + if (update_zoom_rate_control(now_ms)) { + // if message sent avoid sending other messages + return; + } // update based on mount mode switch (get_mode()) { // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? case MAV_MOUNT_MODE_RETRACT: { const Vector3f &angle_bf_target = _params.retract_angles.get(); - send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + 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(); - send_target_rates(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + 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: - switch (mavt_target.target_type) { + case MAV_MOUNT_MODE_MAVLINK_TARGETING: { + // mavlink targets are set while handling the incoming message + 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: - send_target_angles(mavt_target.angle_rad.pitch, mavt_target.angle_rad.yaw, mavt_target.angle_rad.yaw_is_ef); + mnt_target.angle_rad = rc_target; break; case MountTargetType::RATE: - send_target_rates(mavt_target.rate_rads.pitch, mavt_target.rate_rads.yaw, mavt_target.rate_rads.yaw_is_ef); + mnt_target.rate_rads = rc_target; break; } break; - - // RC radio manual angle control, but with stabilization from the AHRS - case MAV_MOUNT_MODE_RC_TARGETING: { - // update targets using pilot's rc inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - send_target_rates(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } else if (get_rc_angle_target(rc_target)) { - send_target_angles(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } - break; } // point mount to a GPS point given by the mission planner - case MAV_MOUNT_MODE_GPS_POINT: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_roi(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + case MAV_MOUNT_MODE_GPS_POINT: + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_HOME_LOCATION: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_home(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // 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; - } - case MAV_MOUNT_MODE_SYSID_TARGET:{ - MountTarget angle_target_rad {}; - if (get_angle_target_to_sysid(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // 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_target_angles(mnt_target.angle_rad.pitch, mnt_target.angle_rad.yaw, mnt_target.angle_rad.yaw_is_ef); + break; + case MountTargetType::RATE: + send_target_rates(mnt_target.rate_rads.pitch, mnt_target.rate_rads.yaw, mnt_target.rate_rads.yaw_is_ef); + break; + } } // return true if healthy bool AP_Mount_Xacti::healthy() const { - // unhealthy until gimbal has been found and replied with firmware version info - if (!_initialised) { + // unhealthy until gimbal has been found and replied with firmware version and no motor errors + if (!_initialised || !_firmware_version.received || _motor_error) { return false; } @@ -142,34 +206,72 @@ bool AP_Mount_Xacti::healthy() const // take a picture. returns true on success bool AP_Mount_Xacti::take_picture() { - if (_detected_modules[_instance].ap_dronecan == nullptr) { + // fail if camera errored + if (_camera_error) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s unable to take pic", send_text_prefix); return false; } - // set SingleShot parameter - return _detected_modules[_instance].ap_dronecan->set_parameter_on_node(_detected_modules[_instance].node_id, XACTI_PARAM_SINGLESHOT, 0, ¶m_int_cb); + return set_param_int32(Param::SingleShot, 0); } // start or stop video recording. returns true on success // set start_recording = true to start record, false to stop recording bool AP_Mount_Xacti::record_video(bool start_recording) { - if (_detected_modules[_instance].ap_dronecan == nullptr) { - return false; + return set_param_int32(Param::Recording, start_recording ? 1 : 0); +} + +// set zoom specified as a rate or percentage +bool AP_Mount_Xacti::set_zoom(ZoomType zoom_type, float zoom_value) +{ + // zoom rate + if (zoom_type == ZoomType::RATE) { + if (is_zero(zoom_value)) { + // stop zooming + _zoom_rate_control.enabled = false; + } else { + // zoom in or out + _zoom_rate_control.enabled = true; + _zoom_rate_control.dir = (zoom_value < 0) ? -1 : 1; + } + return true; + } + + // zoom percentage + if (zoom_type == ZoomType::PCT) { + if (capabilities.optical_zoom == Capability::True) { + // optical zoom capable cameras use combination of optical and digital zoom + // convert zoom percentage (0 ~ 100) to zoom times using linear interpolation + // optical zoom covers 1x to 2.5x, param values are in 100 to 250 + // digital zoom covers 2.5x to 25x, param values are 100 to 1000 + const float zoom_times = linear_interpolate(1, 25, zoom_value, 0, 100); + const uint16_t optical_zoom_param = constrain_uint16(uint16_t(zoom_times * 10) * 10, 100, 250); + const uint16_t digital_zoom_param = constrain_uint16(uint16_t(zoom_times * 0.4) * 100, 100, 1000); + bool ret = true; + if (optical_zoom_param != _last_optical_zoom_param_value) { + ret = set_param_int32(Param::OpticalZoomMagnification, optical_zoom_param); + } + if (digital_zoom_param != _last_digital_zoom_param_value) { + ret &= set_param_int32(Param::DigitalZoomMagnification, digital_zoom_param); + } + return ret; + } + // digital only zoom + // convert zoom percentage (0 ~ 100) to zoom parameter value (100, 200, 300, ... 1000) + // 0~11pct:100, 12~22pct:200, 23~33pct:300, 34~44pct:400, 45~55pct:500, 56~66pct:600, 67~77pct:700, 78~88pct:800, 89~99pct:900, 100:1000 + const uint16_t zoom_param_value = uint16_t(linear_interpolate(1, 10, zoom_value, 0, 100)) * 100; + return set_param_int32(Param::DigitalZoomMagnification, zoom_param_value); } - // set Recording parameter - return _detected_modules[_instance].ap_dronecan->set_parameter_on_node(_detected_modules[_instance].node_id, XACTI_PARAM_RECORDING, start_recording ? 1 : 0, ¶m_int_cb); + // 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_Xacti::set_focus(FocusType focus_type, float focus_value) { - if (_detected_modules[_instance].ap_dronecan == nullptr) { - return SetFocusResult::FAILED; - } - // convert focus type and value to parameter value uint8_t focus_param_value; switch (focus_type) { @@ -189,10 +291,18 @@ SetFocusResult AP_Mount_Xacti::set_focus(FocusType focus_type, float focus_value } // set FocusMode parameter - if (!_detected_modules[_instance].ap_dronecan->set_parameter_on_node(_detected_modules[_instance].node_id, XACTI_PARAM_FOCUSMODE, focus_param_value, ¶m_int_cb)) { - return SetFocusResult::FAILED; + return set_param_int32(Param::FocusMode, focus_param_value) ? SetFocusResult::ACCEPTED : SetFocusResult::FAILED; +} + +// set camera lens as a value from 0 to 5 +bool AP_Mount_Xacti::set_lens(uint8_t lens) +{ + // sanity check + if (lens > (uint8_t)SensorsMode::NDVI) { + return false; } - return SetFocusResult::ACCEPTED; + + return set_param_int32(Param::SensorMode, lens); } // send camera information message to GCS @@ -219,7 +329,7 @@ void AP_Mount_Xacti::send_camera_information(mavlink_channel_t chan) const 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 + _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) @@ -228,7 +338,8 @@ void AP_Mount_Xacti::send_camera_information(mavlink_channel_t chan) const 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] + cam_definition_uri, // cam_definition_uri char[140] + _instance + 1); // gimbal_device_id uint8_t } // send camera settings message to GCS @@ -276,7 +387,7 @@ void 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, "Xacti: DroneCAN subscribe failed"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s DroneCAN subscribe failed", send_text_prefix); return; } @@ -391,9 +502,14 @@ void AP_Mount_Xacti::handle_gnss_status_req(AP_DroneCAN* ap_dronecan, const Cana // get date and time uint16_t year, ms; uint8_t month, day, hour, min, sec; +#if AP_RTC_ENABLED if (!AP::rtc().get_date_and_time_utc(year, month, day, hour, min, sec, ms)) { year = month = day = hour = min = sec = 0; } +#else + year = month = day = hour = min = sec = 0; + (void)ms; +#endif // send xacti specific gnss status message com_xacti_GnssStatus xacti_gnss_status_msg {}; @@ -415,34 +531,155 @@ void AP_Mount_Xacti::handle_gnss_status_req(AP_DroneCAN* ap_dronecan, const Cana // handle param get/set response bool AP_Mount_Xacti::handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, int32_t &value) { - // display errors + // error string prefix to save on flash const char* err_prefix_str = "Xacti: failed to"; - if (strcmp(name, XACTI_PARAM_SINGLESHOT) == 0) { + + // take picture + if (strcmp(name, get_param_name_str(Param::SingleShot)) == 0) { if (value < 0) { - gcs().send_text(MAV_SEVERITY_ERROR, "%s take pic", err_prefix_str); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s take pic", err_prefix_str); } return false; } - if (strcmp(name, XACTI_PARAM_RECORDING) == 0) { + + // recording + if (strcmp(name, get_param_name_str(Param::Recording)) == 0) { if (value < 0) { _recording_video = false; - gcs().send_text(MAV_SEVERITY_ERROR, "%s record", err_prefix_str); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s record", err_prefix_str); } else { _recording_video = (value == 1); - gcs().send_text(MAV_SEVERITY_INFO, "Xacti: recording %s", _recording_video ? "ON" : "OFF"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s recording %s", send_text_prefix, _recording_video ? "ON" : "OFF"); } return false; } - if (strcmp(name, XACTI_PARAM_FOCUSMODE) == 0) { + + // focus + if (strcmp(name, get_param_name_str(Param::FocusMode)) == 0) { if (value < 0) { - gcs().send_text(MAV_SEVERITY_ERROR, "%s change focus", err_prefix_str); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s change focus", err_prefix_str); } else { - gcs().send_text(MAV_SEVERITY_INFO, "Xacti: %s focus", value == 0 ? "manual" : "auto"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %s focus", send_text_prefix, value == 0 ? "manual" : "auto"); } return false; } + + // camera lens (aka sensor mode) + if (strcmp(name, get_param_name_str(Param::SensorMode)) == 0) { + if (value < 0) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s change lens", err_prefix_str); + } else if ((uint32_t)value < ARRAY_SIZE(sensor_mode_str)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %s", send_text_prefix, sensor_mode_str[(uint8_t)value]); + } + return false; + } + + // digital zoom + if (strcmp(name, get_param_name_str(Param::DigitalZoomMagnification)) == 0) { + if (value < 0) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s change zoom", err_prefix_str); + // disable zoom rate control (if active) to avoid repeated failures + _zoom_rate_control.enabled = false; + } else if (value >= 100 && value <= 1000) { + _last_digital_zoom_param_value = value; + } + return false; + } + + // optical zoom + if (strcmp(name, get_param_name_str(Param::OpticalZoomMagnification)) == 0) { + if (value < 0) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s change optical zoom", err_prefix_str); + // disable zoom rate control (if active) to avoid repeated failures + _zoom_rate_control.enabled = false; + } else if (value >= 100 && value <= 250) { + capabilities.optical_zoom = Capability::True; + capabilities.received = true; + _last_optical_zoom_param_value = value; + } + return false; + } + // unhandled parameter get or set - gcs().send_text(MAV_SEVERITY_INFO, "Xacti: get/set %s res:%ld", name, (long int)value); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s get/set %s res:%ld", send_text_prefix, name, (long int)value); + return false; +} + +// handle param get/set response +bool AP_Mount_Xacti::handle_param_get_set_response_string(AP_DroneCAN* ap_dronecan, uint8_t node_id, const char* name, AP_DroneCAN::string &value) +{ + if (strcmp(name, get_param_name_str(Param::FirmwareVersion)) == 0) { + _firmware_version.received = true; + const uint8_t len = MIN(value.len, ARRAY_SIZE(_firmware_version.str)-1); + memcpy(_firmware_version.str, (const char*)value.data, len); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mount: Xacti fw:%s", _firmware_version.str); + + // firmware str from gimbal is of the format YYMMDD[b]xx. Convert to uint32 for reporting to GCS + if (len >= 9) { + const char major_str[3] = {_firmware_version.str[0], _firmware_version.str[1], 0}; + const char minor_str[3] = {_firmware_version.str[2], _firmware_version.str[3], 0}; + const char patch_str[3] = {_firmware_version.str[4], _firmware_version.str[5], 0}; + const char dev_str[3] = {_firmware_version.str[7], _firmware_version.str[8], 0}; + const uint8_t major_ver_num = atoi(major_str) & 0xFF; + const uint8_t minor_ver_num = atoi(minor_str) & 0xFF; + const uint8_t patch_ver_num = atoi(patch_str) & 0xFF; + const uint8_t dev_ver_num = atoi(dev_str) & 0xFF; + _firmware_version.mav_ver = UINT32_VALUE(dev_ver_num, patch_ver_num, minor_ver_num, major_ver_num); + } + return false; + } else if (strcmp(name, get_param_name_str(Param::DateTime)) == 0) { + // display when time and date have been set + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s datetime set %s", send_text_prefix, (const char*)value.data); + return false; + } else if (strcmp(name, get_param_name_str(Param::Status)) == 0) { + // check for expected length + const char* error_str = "error"; + if (value.len != sizeof(_status)) { + INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); + return false; + } + + // backup error status and copy to structure + const uint32_t last_error_status = _status.error_status; + memcpy(&_status, value.data, value.len); + + // report change in status + uint32_t changed_bits = last_error_status ^ _status.error_status; + const char* ok_str = "OK"; + if (changed_bits & (uint32_t)ErrorStatus::TIME_NOT_SET) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s time %sset", send_text_prefix, _status.error_status & (uint32_t)ErrorStatus::TIME_NOT_SET ? "not " : ""); + if (_status.error_status & (uint32_t)ErrorStatus::TIME_NOT_SET) { + // try to set time again + _datetime.set = false; + } + } + if (changed_bits & (uint32_t)ErrorStatus::MEDIA_ERROR) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s media %s", send_text_prefix, _status.error_status & (uint32_t)ErrorStatus::MEDIA_ERROR ? error_str : ok_str); + } + if (changed_bits & (uint32_t)ErrorStatus::LENS_ERROR) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s lens %s", send_text_prefix, _status.error_status & (uint32_t)ErrorStatus::LENS_ERROR ? error_str : ok_str); + } + if (changed_bits & (uint32_t)ErrorStatus::MOTOR_INIT_ERROR) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s motor %s", send_text_prefix, _status.error_status & (uint32_t)ErrorStatus::MOTOR_INIT_ERROR ? "init error" : ok_str); + } + if (changed_bits & (uint32_t)ErrorStatus::MOTOR_OPERATION_ERROR) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s motor op %s", send_text_prefix, _status.error_status & (uint32_t)ErrorStatus::MOTOR_OPERATION_ERROR ? error_str : ok_str); + } + if (changed_bits & (uint32_t)ErrorStatus::GIMBAL_CONTROL_ERROR) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s control %s", send_text_prefix, _status.error_status & (uint32_t)ErrorStatus::GIMBAL_CONTROL_ERROR ? error_str : ok_str); + } + if (changed_bits & (uint32_t)ErrorStatus::TEMP_WARNING) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s temp %s", send_text_prefix, _status.error_status & (uint32_t)ErrorStatus::TEMP_WARNING ? "warning" : ok_str); + } + + // set motor error for health reporting + _motor_error = _status.error_status & ((uint32_t)ErrorStatus::MOTOR_INIT_ERROR | (uint32_t)ErrorStatus::MOTOR_OPERATION_ERROR | (uint32_t)ErrorStatus::GIMBAL_CONTROL_ERROR); + _camera_error = _status.error_status & ((uint32_t)ErrorStatus::LENS_ERROR | (uint32_t)ErrorStatus::MEDIA_ERROR); + return false; + } + + // unhandled parameter get or set + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s get/set string %s res:%s", send_text_prefix, name, (const char*)value.data); return false; } @@ -450,8 +687,87 @@ void AP_Mount_Xacti::handle_param_save_response(AP_DroneCAN* ap_dronecan, const { // display failure to save parameter if (!success) { - gcs().send_text(MAV_SEVERITY_ERROR, "Xacti: CAM%u failed to set param", (int)_instance+1); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s CAM%u failed to set param", send_text_prefix, (int)_instance+1); + } +} + +// get parameter name for a particular param enum value +// returns an empty string if not found (which should never happen) +const char* AP_Mount_Xacti::get_param_name_str(Param param) const +{ + // check to avoid reading beyond end of array. This should never happen + if ((uint8_t)param > ARRAY_SIZE(_param_names)) { + INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); + return ""; + } + return _param_names[(uint8_t)param]; +} + +// helper function to set integer parameters +bool AP_Mount_Xacti::set_param_int32(Param param, int32_t param_value) +{ + if (_set_param_int32_queue == nullptr) { + return false; + } + + // set param request added to queue to be sent. throttling requests improves reliability + return _set_param_int32_queue->push(SetParamQueueItem{param, param_value}); +} + +// helper function to set string parameters +bool AP_Mount_Xacti::set_param_string(Param param, const AP_DroneCAN::string& param_value) +{ + if (_detected_modules[_instance].ap_dronecan == nullptr) { + return false; + } + + // convert param to string + const char* param_name_str = get_param_name_str(param); + if (param_name_str == nullptr) { + return false; + } + + if (_detected_modules[_instance].ap_dronecan->set_parameter_on_node(_detected_modules[_instance].node_id, param_name_str, param_value, ¶m_string_cb)) { + last_send_getset_param_ms = AP_HAL::millis(); + return true; + } + return false; +} + +// helper function to get string parameters +bool AP_Mount_Xacti::get_param_string(Param param) +{ + if (_detected_modules[_instance].ap_dronecan == nullptr) { + return false; + } + + // convert param to string + const char* param_name_str = get_param_name_str(param); + if (_detected_modules[_instance].ap_dronecan->get_parameter_on_node(_detected_modules[_instance].node_id, param_name_str, ¶m_string_cb)) { + last_send_getset_param_ms = AP_HAL::millis(); + return true; + } + return false; +} + +// process queue of set parameter items +bool AP_Mount_Xacti::process_set_param_int32_queue() +{ + if ((_set_param_int32_queue == nullptr) || (_detected_modules[_instance].ap_dronecan == nullptr)) { + return false; + } + + SetParamQueueItem param_to_set; + if (_set_param_int32_queue->pop(param_to_set)) { + // convert param to string + const char* param_name_str = get_param_name_str(param_to_set.param); + if (_detected_modules[_instance].ap_dronecan->set_parameter_on_node(_detected_modules[_instance].node_id, param_name_str, param_to_set.value, ¶m_int_cb)) { + last_send_getset_param_ms = AP_HAL::millis(); + return true; + } + return false; } + return false; } // send gimbal control message via DroneCAN @@ -466,7 +782,7 @@ void AP_Mount_Xacti::send_gimbal_control(uint8_t mode, int16_t pitch_cd, int16_t } // send at no faster than 5hz - const uint32_t now_ms = AP_HAL::native_millis(); + const uint32_t now_ms = AP_HAL::millis(); if (now_ms - last_send_gimbal_control_ms < 200) { return; } @@ -481,24 +797,24 @@ void AP_Mount_Xacti::send_gimbal_control(uint8_t mode, int16_t pitch_cd, int16_t _detected_modules[_instance].ap_dronecan->xacti_gimbal_control_data.broadcast(gimbal_control_data_msg); } -// send copter attitude status message to gimbal -void AP_Mount_Xacti::send_copter_att_status() +// send copter attitude status message to gimbal. now_ms is current system time +// returns true if sent so that we avoid immediately trying to also send other messages +bool AP_Mount_Xacti::send_copter_att_status(uint32_t now_ms) { // exit immediately if no DroneCAN port if (_detected_modules[_instance].ap_dronecan == nullptr) { - return; + return false; } // send at no faster than 5hz - const uint32_t now_ms = AP_HAL::native_millis(); if (now_ms - last_send_copter_att_status_ms < 100) { - return; + return false; } // send xacti specific vehicle attitude message Quaternion veh_att; if (!AP::ahrs().get_quaternion(veh_att)) { - return; + return false; } last_send_copter_att_status_ms = now_ms; @@ -511,6 +827,183 @@ void AP_Mount_Xacti::send_copter_att_status() copter_att_status_msg.reserved.data[0] = 0; copter_att_status_msg.reserved.data[1] = 0; _detected_modules[_instance].ap_dronecan->xacti_copter_att_status.broadcast(copter_att_status_msg); + return true; +} + +// update zoom rate controller. now_ms is current system time +// returns true if sent so that we avoid immediately trying to also send other messages +bool AP_Mount_Xacti::update_zoom_rate_control(uint32_t now_ms) +{ + // return immediately if zoom rate control is not enabled + if (!_zoom_rate_control.enabled) { + return false; + } + + // we are controlling optical zoom if the camera has it and we are below the optical zoom upper limit + // or at the optical zoom upper limit, the lower digital zoom limit and are zooming out + bool optical_zoom_control = (capabilities.optical_zoom == Capability::True) && + ((_last_optical_zoom_param_value < 250) || + ((_last_optical_zoom_param_value == 250) && (_last_digital_zoom_param_value == 100) && (_zoom_rate_control.dir < 0))); + + // update every 0.25 or 0.5 sec + const uint32_t update_interval_ms = optical_zoom_control ? XACTI_OPTICAL_ZOOM_RATE_UPDATE_INTERVAL_MS : XACTI_DIGITAL_ZOOM_RATE_UPDATE_INTERVAL_MS; + if (now_ms - _zoom_rate_control.last_update_ms < update_interval_ms) { + return false; + } + _zoom_rate_control.last_update_ms = now_ms; + + // optical zoom + if (optical_zoom_control) { + const uint16_t optical_zoom_value = _last_optical_zoom_param_value + _zoom_rate_control.dir * 10; + // if reached lower limit of optical zoom, disable zoom control + if (optical_zoom_value < 100) { + _zoom_rate_control.enabled = false; + return false; + } + + // send desired optical zoom to camera + return set_param_int32(Param::OpticalZoomMagnification, MIN(optical_zoom_value, 250)); + } + + // digital zoom + const uint16_t digital_zoom_value = _last_digital_zoom_param_value + _zoom_rate_control.dir * 100; + // if reached limit then disable zoom + if (((capabilities.optical_zoom != Capability::True) && (digital_zoom_value < 100)) || (digital_zoom_value > 1000)) { + _zoom_rate_control.enabled = false; + return false; + } + + // send desired digital zoom to camera + return set_param_int32(Param::DigitalZoomMagnification, digital_zoom_value); +} + +// request firmware version. now_ms should be current system time (reduces calls to AP_HAL::millis) +// returns true if sent so that we avoid immediately trying to also send other messages +bool AP_Mount_Xacti::request_firmware_version(uint32_t now_ms) +{ + // return immediately if already have version or no dronecan + if (_firmware_version.received) { + return false; + } + + // send request once per second until received + if (now_ms - _firmware_version.last_request_ms < 1000) { + return false; + } + _firmware_version.last_request_ms = now_ms; + return get_param_string(Param::FirmwareVersion); +} + +// request parameters used to determine camera capabilities. now_ms is current system time +// returns true if a param get/set was sent so that we avoid sending other messages +bool AP_Mount_Xacti::request_capabilities(uint32_t now_ms) +{ + // return immediately if we have already determined this models capabilities + if (capabilities.received) { + return false; + } + + // send requests once per second until received + if (now_ms - capabilities.last_request_ms < 1000) { + return false; + } + capabilities.last_request_ms = now_ms; + + // record start time + if (capabilities.first_request_ms == 0) { + capabilities.first_request_ms = now_ms; + } + + // timeout after 10 seconds + if (now_ms - capabilities.first_request_ms > 10000) { + capabilities.optical_zoom = Capability::False; + capabilities.received = true; + return false; + } + + // optical zoom: try setting optical zoom to 1x + // return is handled in handle_param_get_set_response_int + return set_param_int32(Param::OpticalZoomMagnification, 100); +} + +// set date and time. now_ms is current system time +bool AP_Mount_Xacti::set_datetime(uint32_t now_ms) +{ + // return immediately if gimbal's date/time has been set + if (_datetime.set) { + return false; + } + + // attempt to set datetime once per second until received + if (now_ms - _datetime.last_request_ms < 1000) { + return false; + } + _datetime.last_request_ms = now_ms; + + // get date and time + uint16_t year, ms; + uint8_t month, day, hour, min, sec; +#if AP_RTC_ENABLED + if (!AP::rtc().get_date_and_time_utc(year, month, day, hour, min, sec, ms)) { + return false; + } +#else + (void)ms; + return false; +#endif + + // date time is of the format YYYYMMDDHHMMSS (14 bytes) + // convert month from 0~11 to 1~12 range + AP_DroneCAN::string datetime_string {}; + const int num_bytes = snprintf((char *)datetime_string.data, sizeof(AP_DroneCAN::string::data), "%04u%02u%02u%02u%02u%02u", + (unsigned)year, (unsigned)month+1, (unsigned)day, (unsigned)hour, (unsigned)min, (unsigned)sec); + // sanity check bytes to be sent + if (num_bytes != 14) { + INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result); + return false; + } + datetime_string.len = num_bytes; + _datetime.set = set_param_string(Param::DateTime, datetime_string); + if (!_datetime.set) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s failed to set date/time", send_text_prefix); + } + + return _datetime.set; +} + +// request status. now_ms should be current system time (reduces calls to AP_HAL::millis) +// returns true if sent so that we avoid immediately trying to also send other messages +bool AP_Mount_Xacti::request_status(uint32_t now_ms) +{ + // return immediately if 3 seconds has not passed + if (now_ms - _status_report.last_request_ms < XACTI_STATUS_REQ_INTERVAL_MS) { + return false; + } + + _status_report.last_request_ms = now_ms; + return get_param_string(Param::Status); +} + +// check if safe to send message (if messages sent too often camera will not respond) +// now_ms should be current system time (reduces calls to AP_HAL::millis) +bool AP_Mount_Xacti::is_safe_to_send(uint32_t now_ms) const +{ + // check time since last attitude sent + if (now_ms - last_send_copter_att_status_ms < XACTI_MSG_SEND_MIN_MS) { + return false; + } + + // check time since last angle target sent + if (now_ms - last_send_gimbal_control_ms < XACTI_MSG_SEND_MIN_MS) { + return false; + } + + // check time since last set param message sent + if (now_ms - last_send_getset_param_ms < XACTI_MSG_SEND_MIN_MS) { + return false; + } + + return true; } #endif // HAL_MOUNT_XACTI_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Xacti.h b/libraries/AP_Mount/AP_Mount_Xacti.h index 50aee42d8a6728..247a66bac1cbb3 100644 --- a/libraries/AP_Mount/AP_Mount_Xacti.h +++ b/libraries/AP_Mount/AP_Mount_Xacti.h @@ -16,6 +16,7 @@ #include #include #include +#include #include "AP_Mount.h" class AP_Mount_Xacti : public AP_Mount_Backend @@ -51,10 +52,16 @@ class AP_Mount_Xacti : public AP_Mount_Backend // set start_recording = true to start record, false to stop recording bool record_video(bool start_recording) override; + // set zoom specified as a rate or percentage + bool set_zoom(ZoomType zoom_type, float zoom_value) override; + // set focus specified as rate, percentage or auto // focus in = -1, focus hold = 0, focus out = 1 SetFocusResult set_focus(FocusType focus_type, float focus_value) override; + // set camera lens as a value from 0 to 5 + bool set_lens(uint8_t lens) override; + // send camera information message to GCS void send_camera_information(mavlink_channel_t chan) const override; @@ -75,6 +82,20 @@ class AP_Mount_Xacti : public AP_Mount_Backend private: + // send text prefix string to reduce flash cost + static const char* send_text_prefix; + + // Sensor mode enumeration (aka lens) + enum class SensorsMode : uint8_t { + RGB = 0, // RGB (aka "visible)") + IR = 1, // Infrared, aka thermal + PIP = 2, // RGB with IR PIP + NDVI = 3, // NDVI (vegetation greenness) + }; + // array of sensor mode enumeration strings for display to user + // if enum above is updated, also update sensor_mode_str definition in cpp + static const char* sensor_mode_str[]; + // send target pitch and yaw rates to gimbal // yaw_is_ef should be true if yaw_rads target is an earth frame rate, false if body_frame void send_target_rates(float pitch_rads, float yaw_rads, bool yaw_is_ef); @@ -92,18 +113,71 @@ class AP_Mount_Xacti : public AP_Mount_Backend // DroneCAN parameter handling methods FUNCTOR_DECLARE(param_int_cb, bool, AP_DroneCAN*, const uint8_t, const char*, int32_t &); + FUNCTOR_DECLARE(param_string_cb, bool, AP_DroneCAN*, const uint8_t, const char*, AP_DroneCAN::string &); FUNCTOR_DECLARE(param_save_cb, void, AP_DroneCAN*, const uint8_t, bool); bool handle_param_get_set_response_int(AP_DroneCAN* ap_dronecan, const uint8_t node_id, const char* name, int32_t &value); + bool handle_param_get_set_response_string(AP_DroneCAN* ap_dronecan, const uint8_t node_id, const char* name, AP_DroneCAN::string &value); void handle_param_save_response(AP_DroneCAN* ap_dronecan, const uint8_t node_id, bool success); + // param enum. If enum is updated also update _param_names definition in cpp + enum class Param : uint8_t { + SingleShot = 0, + Recording, + FocusMode, + SensorMode, + DigitalZoomMagnification, + FirmwareVersion, + Status, + DateTime, + OpticalZoomMagnification, + LAST = OpticalZoomMagnification, // this should be equal to the final parameter enum + }; + static const char* _param_names[]; // array of Xacti parameter strings + + // get parameter name for a particular param enum value + // returns an empty string if not found (which should never happen) + const char* get_param_name_str(Param param) const; + + // helper function to get and set parameters + bool set_param_int32(Param param, int32_t param_value); + bool set_param_string(Param param, const AP_DroneCAN::string& param_value); + bool get_param_string(Param param); + + // process queue of set parameter items. returns true if set-parameter message was sent + bool process_set_param_int32_queue(); + // send gimbal control message via DroneCAN // mode is 2:angle control or 3:rate control // pitch_cd is pitch angle in centi-degrees or pitch rate in cds // yaw_cd is angle in centi-degrees or yaw rate in cds void send_gimbal_control(uint8_t mode, int16_t pitch_cd, int16_t yaw_cd); - // send vehicle attitude to gimbal via DroneCAN - void send_copter_att_status(); + // send vehicle attitude to gimbal via DroneCAN. now_ms is current system time + // returns true if sent so that we avoid immediately trying to also send other messages + bool send_copter_att_status(uint32_t now_ms); + + // update zoom rate controller. now_ms is current system time + // returns true if sent so that we avoid immediately trying to also send other messages + bool update_zoom_rate_control(uint32_t now_ms); + + // request firmware version. now_ms is current system time + // returns true if sent so that we avoid immediately trying to also send other messages + bool request_firmware_version(uint32_t now_ms); + + // request parameters used to determine camera capabilities. now_ms is current system time + // returns true if a param get/set was sent so that we avoid sending other messages + bool request_capabilities(uint32_t now_ms); + + // set date and time. now_ms is current system time + bool set_datetime(uint32_t now_ms); + + // request status. now_ms is current system time + // returns true if sent so that we avoid immediately trying to also send other messages + bool request_status(uint32_t now_ms); + + // check if safe to send message (if messages sent too often camera will not respond) + // now_ms is current system time + bool is_safe_to_send(uint32_t now_ms) const; // internal variables bool _initialised; // true once the driver has been initialised @@ -112,6 +186,79 @@ class AP_Mount_Xacti : public AP_Mount_Backend Quaternion _current_attitude_quat; // current attitude as a quaternion uint32_t _last_current_attitude_quat_ms; // system time _current_angle_rad was updated bool _recording_video; // true if recording video + uint16_t _last_digital_zoom_param_value = 100; // last digital zoom parameter value sent to camera. 100 ~ 1000 (interval 100) + uint16_t _last_optical_zoom_param_value = 100; // last optical zoom parameter value sent to camera. 100 ~ 250 (interval 10) + struct { + bool enabled; // true if zoom rate control is enabled + int8_t dir; // zoom direction (-1 to zoom out, +1 to zoom in) + uint32_t last_update_ms; // system time that zoom rate control last updated zoom + } _zoom_rate_control; + + // firmware version received from gimbal + struct { + uint32_t last_request_ms; // system time of last request for firmware version + bool received; // true once firmware version has been received + char str[12] {}; // firmware version string (11 bytes + 1 null byte) + uint32_t mav_ver; // version formatted for reporting to GCS via CAMERA_INFORMATION message + } _firmware_version; + + // date and time handling + struct { + uint32_t last_request_ms; // system time that date/time was last requested + bool set; // true once date/time has been set + } _datetime; + + // capability handling + enum class Capability : uint8_t { + False = 0, + True = 1, + Unknown = 2, + }; + struct { + bool received; // true if we have determined cameras capabilities + uint32_t first_request_ms; // system time of first request for capabilities (used to timeout) + uint32_t last_request_ms; // system time of last capability related parameter check + Capability optical_zoom; // Yes if camera has optical zoom + } capabilities = {false, 0, 0, Capability::Unknown}; + + // gimbal status handling + enum class ErrorStatus : uint32_t { + TAKING_PICTURE = 0x04, // currently taking a picture + RECORDING_VIDEO = 0x08, // currently recording video + CANNOT_TAKE_PIC = 0x20, + TIME_NOT_SET = 0x10000, + MEDIA_ERROR = 0x20000, + LENS_ERROR = 0x40000, + MOTOR_INIT_ERROR = 0x100000, + MOTOR_OPERATION_ERROR = 0x200000, + GIMBAL_CONTROL_ERROR = 0x400000, + TEMP_WARNING = 0x1000000 + }; + struct { + uint32_t error_status; // see ErrorStatus enum + uint32_t video_remain_time; // max seconds of video that may be recorded before SD card is full + uint32_t photo_remain_count; // max number of pics before SD card is full + uint32_t sd_card_size_mb; // SD card size in MB + uint32_t sd_card_free_mb; // SD card remaining size in MB + uint16_t body; // body type + uint16_t cmos; // cmos type + uint16_t gimbal_pitch; // gimbal pitch angle + uint16_t gimbal_roll; // gimbal roll angle + uint16_t gimbal_yaw; // gimbal yaw angle + uint16_t reserved1; + uint8_t date_time[7]; // camera's date and time + uint8_t reserved2; + uint32_t exposure_time_us; // camera's exposure time in us + uint16_t apeture; // cameras' aperture * 100 + uint16_t iso_sensitivity; // camera's iso sensitivity + } _status; // latest status received + static_assert(sizeof(_status) == 48); // status should be 48 bytes + struct { + uint32_t last_request_ms; // system time that status was last requested + uint32_t last_error_status; // last error status reported to user + } _status_report; + bool _motor_error; // true if status reports motor or control error (used for health reporting) + bool _camera_error; // true if status reports camera error // DroneCAN related variables static bool _subscribed; // true once subscribed to receive DroneCAN messages @@ -123,6 +270,14 @@ class AP_Mount_Xacti : public AP_Mount_Backend static HAL_Semaphore _sem_registry; // semaphore protecting access to _detected_modules table uint32_t last_send_gimbal_control_ms; // system time that send_gimbal_control was last called (used to slow down sends to 5hz) uint32_t last_send_copter_att_status_ms; // system time that send_copter_att_status was last called (used to slow down sends to 10hz) + uint32_t last_send_getset_param_ms; // system time that a get or set parameter message was sent + + // queue of set parameter int32 items. set-parameter requests to camera are throttled to improve reliability + struct SetParamQueueItem { + Param param; // parameter (name) + int32_t value; // parameter value + }; + ObjectArray *_set_param_int32_queue; // queue of set-parameter items }; #endif // HAL_MOUNT_XACTI_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_config.h b/libraries/AP_Mount/AP_Mount_config.h index 9967ad312a2065..3195a5ce387d47 100644 --- a/libraries/AP_Mount/AP_Mount_config.h +++ b/libraries/AP_Mount/AP_Mount_config.h @@ -34,7 +34,7 @@ #endif #ifndef HAL_MOUNT_STORM32MAVLINK_ENABLED -#define HAL_MOUNT_STORM32MAVLINK_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED +#define HAL_MOUNT_STORM32MAVLINK_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED #endif #ifndef HAL_MOUNT_STORM32SERIAL_ENABLED diff --git a/libraries/AP_Mount/LogStructure.h b/libraries/AP_Mount/LogStructure.h new file mode 100644 index 00000000000000..369128bb216f10 --- /dev/null +++ b/libraries/AP_Mount/LogStructure.h @@ -0,0 +1,40 @@ +#pragma once + +#include + +#define LOG_IDS_FROM_MOUNT \ + LOG_MOUNT_MSG + +// @LoggerMessage: MNT +// @Description: Mount's desired and actual roll, pitch and yaw angles +// @Field: TimeUS: Time since system startup +// @Field: I: Instance number +// @Field: DRoll: Desired roll +// @Field: Roll: Actual roll +// @Field: DPitch: Desired pitch +// @Field: Pitch: Actual pitch +// @Field: DYawB: Desired yaw in body frame +// @Field: YawB: Actual yaw in body frame +// @Field: DYawE: Desired yaw in earth frame +// @Field: YawE: Actual yaw in earth frame +// @Field: Dist: Rangefinder distance + +struct PACKED log_Mount { + LOG_PACKET_HEADER; + uint64_t time_us; + uint8_t instance; + float desired_roll; + float actual_roll; + float desired_pitch; + float actual_pitch; + float desired_yaw_bf; + float actual_yaw_bf; + float desired_yaw_ef; + float actual_yaw_ef; + float rangefinder_dist; +}; + +#define LOG_STRUCTURE_FROM_MOUNT \ + { LOG_MOUNT_MSG, sizeof(log_Mount), \ + "MNT", "QBfffffffff","TimeUS,I,DRoll,Roll,DPitch,Pitch,DYawB,YawB,DYawE,YawE,Dist", "s#ddddddddm", "F---------0" }, + diff --git a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp index b50e4d96e7a9f8..bc7d0ff2ef898d 100644 --- a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp +++ b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp @@ -96,9 +96,13 @@ void AP_NMEA_Output::update() // get time and date uint64_t time_usec; +#if AP_RTC_ENABLED if (!AP::rtc().get_utc_usec(time_usec)) { return; } +#else + time_usec = 0; +#endif uint32_t space_required = 0; diff --git a/libraries/AP_NMEA_Output/AP_NMEA_Output_config.h b/libraries/AP_NMEA_Output/AP_NMEA_Output_config.h index d3164bb1a5f832..f8e44934de2631 100644 --- a/libraries/AP_NMEA_Output/AP_NMEA_Output_config.h +++ b/libraries/AP_NMEA_Output/AP_NMEA_Output_config.h @@ -5,5 +5,5 @@ // Needs SerialManager + (AHRS or GPS) #ifndef HAL_NMEA_OUTPUT_ENABLED -#define HAL_NMEA_OUTPUT_ENABLED HAL_GCS_ENABLED +#define HAL_NMEA_OUTPUT_ENABLED BOARD_FLASH_SIZE>1024 && HAL_GCS_ENABLED #endif diff --git a/libraries/AP_NavEKF/AP_NavEKF_Source.cpp b/libraries/AP_NavEKF/AP_NavEKF_Source.cpp index c4992dd0a7261d..0f80af9f69e37f 100644 --- a/libraries/AP_NavEKF/AP_NavEKF_Source.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF_Source.cpp @@ -17,6 +17,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -231,6 +232,18 @@ AP_NavEKF_Source::SourceYaw AP_NavEKF_Source::getYawSource() const return _source_set[active_source_set].yaw; } +// get pos Z source +AP_NavEKF_Source::SourceZ AP_NavEKF_Source::getPosZSource() const +{ +#ifdef HAL_BARO_ALLOW_INIT_NO_BARO + // check for special case of missing baro + if ((_source_set[active_source_set].posz == SourceZ::BARO) && (AP::dal().baro().num_instances() == 0)) { + return SourceZ::NONE; + } +#endif + return _source_set[active_source_set].posz; +} + // align position of inactive sources to ahrs void AP_NavEKF_Source::align_inactive_sources() { @@ -385,6 +398,7 @@ bool AP_NavEKF_Source::pre_arm_check(bool requires_position, char *failure_msg, visualodom_required = true; break; case SourceZ::NONE: + break; default: // invalid posz value hal.util->snprintf(failure_msg, failure_msg_len, "Check EK3_SRC%d_POSZ", (int)i+1); diff --git a/libraries/AP_NavEKF/AP_NavEKF_Source.h b/libraries/AP_NavEKF/AP_NavEKF_Source.h index d07fb986fe16d3..b8bfa67d18a8d5 100644 --- a/libraries/AP_NavEKF/AP_NavEKF_Source.h +++ b/libraries/AP_NavEKF/AP_NavEKF_Source.h @@ -55,7 +55,7 @@ class AP_NavEKF_Source // get current position source SourceXY getPosXYSource() const { return _source_set[active_source_set].posxy; } - SourceZ getPosZSource() const { return _source_set[active_source_set].posz; } + SourceZ getPosZSource() const; // set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary void setPosVelYawSourceSet(uint8_t source_set_idx); diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index b63a8a2b433c9e..d7d4d3c61a8e58 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -165,7 +165,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = { // @Param: VEL_I_GATE // @DisplayName: GPS velocity innovation gate size - // @Description: This sets the percentage number of standard deviations applied to the GPS velocity measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted. + // @Description: This sets the percentage number of standard deviations applied to the GPS velocity measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted. If EK3_GLITCH_RAD set to 0 the velocity innovations will be clipped instead of rejected if they exceed the gate size and a smaller value of EK3_VEL_I_GATE not exceeding 300 is recommended to limit the effect of GPS transient errors. // @Range: 100 1000 // @Increment: 25 // @User: Advanced @@ -182,7 +182,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = { // @Param: POS_I_GATE // @DisplayName: GPS position measurement gate size - // @Description: This sets the percentage number of standard deviations applied to the GPS position measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted. + // @Description: This sets the percentage number of standard deviations applied to the GPS position measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted. If EK3_GLITCH_RAD has been set to 0 the horizontal position innovations will be clipped instead of rejected if they exceed the gate size so a smaller value of EK3_POS_I_GATE not exceeding 300 is recommended to limit the effect of GPS transient errors. // @Range: 100 1000 // @Increment: 25 // @User: Advanced @@ -190,7 +190,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = { // @Param: GLITCH_RAD // @DisplayName: GPS glitch radius gate size (m) - // @Description: This controls the maximum radial uncertainty in position between the value predicted by the filter and the value measured by the GPS before the filter position and velocity states are reset to the GPS. Making this value larger allows the filter to ignore larger GPS glitches but also means that non-GPS errors such as IMU and compass can create a larger error in position before the filter is forced back to the GPS position. + // @Description: This controls the maximum radial uncertainty in position between the value predicted by the filter and the value measured by the GPS before the filter position and velocity states are reset to the GPS. Making this value larger allows the filter to ignore larger GPS glitches but also means that non-GPS errors such as IMU and compass can create a larger error in position before the filter is forced back to the GPS position. If EK3_GLITCH_RAD set to 0 the GPS innovations will be clipped instead of rejected if they exceed the gate size set by EK3_VEL_I_GATE and EK3_POS_I_GATE which can be useful if poor quality sensor data is causing GPS rejection and loss of navigation but does make the EKF more susceptible to GPS glitches. If setting EK3_GLITCH_RAD to 0 it is recommended to reduce EK3_VEL_I_GATE and EK3_POS_I_GATE to 300. // @Range: 10 100 // @Increment: 5 // @User: Advanced @@ -207,8 +207,8 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = { // @Param: ALT_M_NSE // @DisplayName: Altitude measurement noise (m) - // @Description: This is the RMS value of noise in the altitude measurement. Increasing it reduces the weighting of the baro measurement and will make the filter respond more slowly to baro measurement errors, but will make it more sensitive to GPS and accelerometer errors. - // @Range: 0.1 10.0 + // @Description: This is the RMS value of noise in the altitude measurement. Increasing it reduces the weighting of the baro measurement and will make the filter respond more slowly to baro measurement errors, but will make it more sensitive to GPS and accelerometer errors. A larger value for EK3_ALT_M_NSE may be required when operating with EK3_SRCx_POSZ = 0. This parameter also sets the noise for the 'synthetic' zero height measurement that is used when EK3_SRCx_POSZ = 0. + // @Range: 0.1 100.0 // @Increment: 0.1 // @User: Advanced // @Units: m @@ -216,7 +216,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = { // @Param: HGT_I_GATE // @DisplayName: Height measurement gate size - // @Description: This sets the percentage number of standard deviations applied to the height measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted. + // @Description: This sets the percentage number of standard deviations applied to the height measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted. If EK3_GLITCH_RAD set to 0 the vertical position innovations will be clipped instead of rejected if they exceed the gate size and a smaller value of EK3_HGT_I_GATE not exceeding 300 is recommended to limit the effect of height sensor transient errors. // @Range: 100 1000 // @Increment: 25 // @User: Advanced diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp index c78bc763cbfe69..d2179f348cbeda 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp @@ -705,7 +705,8 @@ void NavEKF3_core::checkGyroCalStatus(void) void NavEKF3_core::updateFilterStatus(void) { // init return value - filterStatus.value = 0; + nav_filter_status status; + status.value = 0; bool doingBodyVelNav = (PV_AidingMode != AID_NONE) && (imuSampleTime_ms - prevBodyVelFuseTime_ms < 5000); bool doingFlowNav = (PV_AidingMode != AID_NONE) && flowDataValid; bool doingWindRelNav = (!tasTimeout && assume_zero_sideslip()) || !dragTimeout; @@ -718,28 +719,30 @@ void NavEKF3_core::updateFilterStatus(void) bool hgtNotAccurate = (frontend->sources.getPosZSource() == AP_NavEKF_Source::SourceZ::GPS) && !validOrigin; // set individual flags - filterStatus.flags.attitude = !stateStruct.quat.is_nan() && filterHealthy; // attitude valid (we need a better check) - filterStatus.flags.horiz_vel = someHorizRefData && filterHealthy; // horizontal velocity estimate valid - filterStatus.flags.vert_vel = someVertRefData && filterHealthy; // vertical velocity estimate valid - filterStatus.flags.horiz_pos_rel = ((doingFlowNav && gndOffsetValid) || doingWindRelNav || doingNormalGpsNav || doingBodyVelNav) && filterHealthy; // relative horizontal position estimate valid - filterStatus.flags.horiz_pos_abs = doingNormalGpsNav && filterHealthy; // absolute horizontal position estimate valid - filterStatus.flags.vert_pos = !hgtTimeout && filterHealthy && !hgtNotAccurate; // vertical position estimate valid - filterStatus.flags.terrain_alt = gndOffsetValid && filterHealthy; // terrain height estimate valid - filterStatus.flags.const_pos_mode = (PV_AidingMode == AID_NONE) && filterHealthy; // constant position mode - filterStatus.flags.pred_horiz_pos_rel = filterStatus.flags.horiz_pos_rel; // EKF3 enters the required mode before flight - filterStatus.flags.pred_horiz_pos_abs = filterStatus.flags.horiz_pos_abs; // EKF3 enters the required mode before flight - filterStatus.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected - filterStatus.flags.takeoff = dal.get_takeoff_expected(); // The EKF has been told to expect takeoff is in a ground effect mitigation mode and has started the EKF-GSF yaw estimator - filterStatus.flags.touchdown = dal.get_touchdown_expected(); // The EKF has been told to detect touchdown and is in a ground effect mitigation mode - filterStatus.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE); - filterStatus.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE) && (frontend->sources.getPosXYSource() == AP_NavEKF_Source::SourceXY::GPS); // GPS glitching is affecting navigation accuracy - filterStatus.flags.gps_quality_good = gpsGoodToAlign; + status.flags.attitude = !stateStruct.quat.is_nan() && filterHealthy; // attitude valid (we need a better check) + status.flags.horiz_vel = someHorizRefData && filterHealthy; // horizontal velocity estimate valid + status.flags.vert_vel = someVertRefData && filterHealthy; // vertical velocity estimate valid + status.flags.horiz_pos_rel = ((doingFlowNav && gndOffsetValid) || doingWindRelNav || doingNormalGpsNav || doingBodyVelNav) && filterHealthy; // relative horizontal position estimate valid + status.flags.horiz_pos_abs = doingNormalGpsNav && filterHealthy; // absolute horizontal position estimate valid + status.flags.vert_pos = !hgtTimeout && filterHealthy && !hgtNotAccurate; // vertical position estimate valid + status.flags.terrain_alt = gndOffsetValid && filterHealthy; // terrain height estimate valid + status.flags.const_pos_mode = (PV_AidingMode == AID_NONE) && filterHealthy; // constant position mode + status.flags.pred_horiz_pos_rel = status.flags.horiz_pos_rel; // EKF3 enters the required mode before flight + status.flags.pred_horiz_pos_abs = status.flags.horiz_pos_abs; // EKF3 enters the required mode before flight + status.flags.takeoff_detected = takeOffDetected; // takeoff for optical flow navigation has been detected + status.flags.takeoff = dal.get_takeoff_expected(); // The EKF has been told to expect takeoff is in a ground effect mitigation mode and has started the EKF-GSF yaw estimator + status.flags.touchdown = dal.get_touchdown_expected(); // The EKF has been told to detect touchdown and is in a ground effect mitigation mode + status.flags.using_gps = ((imuSampleTime_ms - lastPosPassTime_ms) < 4000) && (PV_AidingMode == AID_ABSOLUTE); + status.flags.gps_glitching = !gpsAccuracyGood && (PV_AidingMode == AID_ABSOLUTE) && (frontend->sources.getPosXYSource() == AP_NavEKF_Source::SourceXY::GPS); // GPS glitching is affecting navigation accuracy + status.flags.gps_quality_good = gpsGoodToAlign; // for reporting purposes we report rejecting airspeed after 3s of not fusing when we want to fuse the data - filterStatus.flags.rejecting_airspeed = lastTasFailTime_ms != 0 && + status.flags.rejecting_airspeed = lastTasFailTime_ms != 0 && (imuSampleTime_ms - lastTasFailTime_ms) < 1000 && (imuSampleTime_ms - lastTasPassTime_ms) > 3000; - filterStatus.flags.initalized = filterStatus.flags.initalized || healthy(); - filterStatus.flags.dead_reckoning = (PV_AidingMode != AID_NONE) && doingWindRelNav && !((doingFlowNav && gndOffsetValid) || doingNormalGpsNav || doingBodyVelNav); + status.flags.initalized = status.flags.initalized || healthy(); + status.flags.dead_reckoning = (PV_AidingMode != AID_NONE) && doingWindRelNav && !((doingFlowNav && gndOffsetValid) || doingNormalGpsNav || doingBodyVelNav); + + filterStatus.value = status.value; } void NavEKF3_core::runYawEstimatorPrediction() diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp index 2a9eeefdf47e3c..04bf81ec208299 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp @@ -621,7 +621,7 @@ void NavEKF3_core::send_status_report(GCS_MAVLINK &link) const velVar, posVar, hgtVar, - fmaxF(fmaxF(magVar.x,magVar.y),magVar.z), + fmaxf(fmaxf(magVar.x,magVar.y),magVar.z), temp, flags, tasVar diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp index a2ccb4744272f9..ee735a27d4a00a 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp @@ -770,6 +770,16 @@ void NavEKF3_core::FuseVelPosNED() if (posTestRatio < 1.0f || (PV_AidingMode == AID_NONE)) { posCheckPassed = true; lastPosPassTime_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; + varInnovVelPos[3] *= posTestRatio; + varInnovVelPos[4] *= posTestRatio; + posCheckPassed = true; + lastPosPassTime_ms = imuSampleTime_ms; } // Use position data if healthy or timed out or bad IMU data @@ -777,7 +787,9 @@ void NavEKF3_core::FuseVelPosNED() // from the measurement un-opposed if test threshold is exceeded. if (posCheckPassed || posTimeout || badIMUdata) { // if timed out or outside the specified uncertainty radius, reset to the external sensor - if (posTimeout || ((P[8][8] + P[7][7]) > sq(ftype(frontend->_gpsGlitchRadiusMax)))) { + // 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) { // reset the position to the current external sensor position ResetPosition(resetDataSource::DEFAULT); @@ -833,6 +845,17 @@ void NavEKF3_core::FuseVelPosNED() if (velTestRatio < 1.0) { velCheckPassed = true; lastVelPassTime_ms = imuSampleTime_ms; + } else if (frontend->_gpsGlitchRadiusMax <= 0) { + // 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; + for (uint8_t i = 0; i<=imax; i++) { + varInnovVelPos[i] *= velTestRatio; + } + velCheckPassed = true; + lastVelPassTime_ms = imuSampleTime_ms; } // Use velocity data if healthy, timed out or when IMU fault has been detected @@ -865,10 +888,20 @@ void NavEKF3_core::FuseVelPosNED() // When on ground we accept a larger test ratio to allow the filter to handle large switch on IMU // bias errors without rejecting the height sensor. - const float maxTestRatio = (PV_AidingMode == AID_NONE && onGround)? 3.0f : 1.0f; + const bool onGroundNotNavigating = (PV_AidingMode == AID_NONE) && onGround; + const float maxTestRatio = onGroundNotNavigating ? 3.0f : 1.0f; if (hgtTestRatio < maxTestRatio) { hgtCheckPassed = true; lastHgtPassTime_ms = imuSampleTime_ms; + } else if ((frontend->_gpsGlitchRadiusMax <= 0) && !onGroundNotNavigating && (activeHgtSource == AP_NavEKF_Source::SourceZ::GPS)) { + // 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; + varInnovVelPos[5] *= hgtTestRatio; + hgtCheckPassed = true; + lastHgtPassTime_ms = imuSampleTime_ms; } // Use height data if innovation check passed or timed out or if bad IMU data @@ -1118,7 +1151,10 @@ void NavEKF3_core::selectHeightForFusion() const bool extNavDataIsFresh = (imuSampleTime_ms - extNavMeasTime_ms < 500); #endif // select height source - if ((frontend->sources.getPosZSource() == AP_NavEKF_Source::SourceZ::RANGEFINDER) && _rng && rangeFinderDataIsFresh) { + if ((frontend->sources.getPosZSource() == AP_NavEKF_Source::SourceZ::NONE)) { + // user has specified no height sensor + activeHgtSource = AP_NavEKF_Source::SourceZ::NONE; + } 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; } else if ((frontend->_useRngSwHgt > 0) && ((frontend->sources.getPosZSource() == AP_NavEKF_Source::SourceZ::BARO) || (frontend->sources.getPosZSource() == AP_NavEKF_Source::SourceZ::GPS)) && _rng && rangeFinderDataIsFresh) { @@ -1266,12 +1302,24 @@ void NavEKF3_core::selectHeightForFusion() // enable fusion fuseHgtData = true; // set the observation noise - posDownObsNoise = sq(constrain_ftype(frontend->_baroAltNoise, 0.1f, 10.0f)); + posDownObsNoise = sq(constrain_ftype(frontend->_baroAltNoise, 0.1f, 100.0f)); // reduce weighting (increase observation noise) on baro if we are likely to be experiencing rotor wash ground interaction if (dal.get_takeoff_expected() || dal.get_touchdown_expected()) { posDownObsNoise *= frontend->gndEffectBaroScaler; } velPosObs[5] = -hgtMea; + } else if ((activeHgtSource == AP_NavEKF_Source::SourceZ::NONE && imuSampleTime_ms - lastHgtPassTime_ms > 70)) { + // fuse a constant height of 0 at 14 Hz + hgtMea = 0.0f; + fuseHgtData = true; + velPosObs[5] = -hgtMea; + if (onGround) { + // use a typical vertical positoin observation noise when not flying for faster IMU delta velocity bias estimation + posDownObsNoise = sq(2.0f); + } else { + // alow a larger value when flying to accomodate vertical maneouvres + posDownObsNoise = sq(constrain_ftype(frontend->_baroAltNoise, 2.0f, 100.0f)); + } } else { fuseHgtData = false; } diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp new file mode 100644 index 00000000000000..fa1b422008f5c7 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -0,0 +1,224 @@ + +#include "AP_Networking_Config.h" + +#if AP_NETWORKING_ENABLED + +#include "AP_Networking.h" +#include "AP_Networking_ChibiOS.h" +#include +#include + +extern const AP_HAL::HAL& hal; + +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#include +#include +#else +#include +#endif + + +const AP_Param::GroupInfo AP_Networking::var_info[] = { + // @Param: ENABLED + // @DisplayName: Networking Enable + // @Description: Networking Enable + // @Values: 0:Disable,1:Enable + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO_FLAGS("ENABLED", 1, AP_Networking, param.enabled, 0, AP_PARAM_FLAG_ENABLE), + + // @Group: IPADDR + // @Path: AP_Networking_address.cpp + AP_SUBGROUPINFO(param.ipaddr, "IPADDR", 2, AP_Networking, AP_Networking_IPV4), + + // @Param: NETMASK + // @DisplayName: IP Subnet mask + // @Description: Allows setting static subnet mask. The value is a count of consecutive bits. Examples: 24 = 255.255.255.0, 16 = 255.255.0.0 + // @Range: 0 32 + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("NETMASK", 3, AP_Networking, param.netmask, AP_NETWORKING_DEFAULT_NETMASK), + + // @Param: DHCP + // @DisplayName: DHCP client + // @Description: Enable/Disable DHCP client + // @Values: 0:Disable, 1:Enable + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("DHCP", 4, AP_Networking, param.dhcp, AP_NETWORKING_DEFAULT_DHCP_ENABLE), + + // @Group: GWADDR + // @Path: AP_Networking_address.cpp + AP_SUBGROUPINFO(param.gwaddr, "GWADDR", 5, AP_Networking, AP_Networking_IPV4), + + // @Group: MACADDR + // @Path: AP_Networking_macaddr.cpp + AP_SUBGROUPINFO(param.macaddr, "MACADDR", 6, AP_Networking, AP_Networking_MAC), + + AP_GROUPEND +}; + +/* + constructor + */ +AP_Networking::AP_Networking(void) +{ +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + if (singleton != nullptr) { + AP_HAL::panic("AP_Networking must be singleton"); + } +#endif + singleton = this; + AP_Param::setup_object_defaults(this, var_info); +} + +/* + initialise networking subsystem + */ +void AP_Networking::init() +{ + if (!param.enabled || backend != nullptr) { + return; + } + + // set default MAC Address as lower 3 bytes of the CRC of the UID + uint8_t uid[50]; + uint8_t uid_len = sizeof(uid); + if (hal.util->get_system_id_unformatted(uid, uid_len)) { + union { + uint8_t bytes[4]; + uint32_t value32; + } crc; + crc.value32 = crc_crc32(0, uid, uid_len); + + param.macaddr.set_default_address_byte(3, crc.bytes[0]); + param.macaddr.set_default_address_byte(4, crc.bytes[1]); + param.macaddr.set_default_address_byte(5, crc.bytes[2]); + } + +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + backend = new AP_Networking_ChibiOS(*this); +#endif + + if (backend == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: backend failed"); + return; + } + + if (!backend->init()) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: backend init failed"); + // the backend init function creates a thread which references the backend pointer; that thread may be running so don't remove the backend allocation. + backend = nullptr; + return; + } + + announce_address_changes(); + + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"NET: Initialized"); +} + +/* + check if we should announce changes to IP addresses + */ +void AP_Networking::announce_address_changes() +{ + auto &as = backend->activeSettings; + + if (as.last_change_ms == 0 || as.last_change_ms == announce_ms) { + // nothing changed and we've already printed it at least once. Nothing to do. + return; + } + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: IP %s", get_ip_active_str()); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Mask %s", get_netmask_active_str()); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Gateway %s", get_gateway_active_str()); + + announce_ms = as.last_change_ms; +} + +/* + update called at 10Hz + */ +void AP_Networking::update() +{ + if (!is_healthy()) { + return; + } + backend->update(); + announce_address_changes(); +} + +uint32_t AP_Networking::convert_netmask_bitcount_to_ip(const uint32_t netmask_bitcount) +{ + if (netmask_bitcount >= 32) { + return 0xFFFFFFFFU; + } + return ~((1U<<(32U-netmask_bitcount))-1U); +} + +uint8_t AP_Networking::convert_netmask_ip_to_bitcount(const uint32_t netmask_ip) +{ + uint32_t netmask_bitcount = 0; + for (uint32_t i=0; i<32; i++) { + // note, netmask LSB is IP MSB + if ((netmask_ip & (1UL< 255) { + return false; + } + addr[i] = v; + s = strtok_r(nullptr, ":", &ptr); + } + return true; +} + +AP_Networking *AP_Networking::singleton; + +namespace AP +{ +AP_Networking &network() +{ + return *AP_Networking::get_singleton(); +} +} + +#endif // AP_NETWORKING_ENABLED diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h new file mode 100644 index 00000000000000..0a5628c97eac79 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking.h @@ -0,0 +1,188 @@ + +#pragma once + +#include "AP_Networking_Config.h" + +#if AP_NETWORKING_ENABLED +#include +#include + +#include "AP_Networking_address.h" +#include "AP_Networking_backend.h" + +/* + Note! all uint32_t IPv4 addresses are in host byte order +*/ + +class AP_Networking +{ +public: + friend class AP_Networking_ChibiOS; + + AP_Networking(); + + /* Do not allow copies */ + CLASS_NO_COPY(AP_Networking); + + // initialize the library. This should only be run once + void init(); + + // update task, called at 10Hz + void update(); + + static AP_Networking *get_singleton(void) + { + return singleton; + } + + // Networking interface is enabled and initialized + bool is_healthy() const + { + return param.enabled && backend != nullptr; + } + + // returns true if DHCP is enabled + bool get_dhcp_enabled() const + { + return param.dhcp; + } + + // Sets DHCP to be enabled or disabled + void set_dhcp_enable(const bool enable) + { + param.dhcp.set(enable); + } + + // returns the 32bit value of the active IP address that is currently in use + uint32_t get_ip_active() const + { + return backend?backend->activeSettings.ip:0; + } + + // returns the 32bit value of the user-parameter static IP address + uint32_t get_ip_param() const + { + return param.ipaddr.get_uint32(); + } + + /* + returns a null terminated string of the active IP address. Example: "192.168.12.13" + Note that the returned + */ + const char *get_ip_active_str() const + { + return convert_ip_to_str(get_ip_active()); + } + + // sets the user-parameter static IP address from a 32bit value + void set_ip_param(const uint32_t ip) + { + param.ipaddr.set_uint32(ip); + } + + // returns the 32bit value of the active Netmask that is currently in use + uint32_t get_netmask_active() const + { + return backend?backend->activeSettings.nm:0; + } + + // returns the 32bit value of the of the user-parameter static Netmask + uint32_t get_netmask_param() const + { + return convert_netmask_bitcount_to_ip(param.netmask.get()); + } + + // returns a null terminated string of the active Netmask address. Example: "192.168.12.13" + const char *get_netmask_active_str() + { + return convert_ip_to_str(get_netmask_active()); + } + + const char *get_netmask_param_str() + { + return convert_ip_to_str(get_netmask_param()); + } + + void set_netmask_param_str(const char* nm_str) + { + set_netmask_param(convert_str_to_ip((char*)nm_str)); + } + + void set_netmask_param(const uint32_t nm) + { + param.netmask.set(convert_netmask_ip_to_bitcount(nm)); + } + + uint32_t get_gateway_active() const + { + return backend?backend->activeSettings.gw:0; + } + + uint32_t get_gateway_param() const + { + return param.gwaddr.get_uint32(); + } + + const char *get_gateway_active_str() + { + return convert_ip_to_str(get_gateway_active()); + } + + const char *get_gateway_param_str() + { + return convert_ip_to_str(get_gateway_param()); + } + + void set_gateway_param_str(const char* gw_str) + { + set_gateway_param(convert_str_to_ip((char*)gw_str)); + } + + void set_gateway_param(const uint32_t gw) + { + param.gwaddr.set_uint32(gw); + } + + // helper functions to convert between 32bit IP addresses and null terminated strings and back + static uint32_t convert_str_to_ip(const char* ip_str); + static const char* convert_ip_to_str(uint32_t ip); + + // convert string to ethernet mac address + static bool convert_str_to_macaddr(const char *mac_str, uint8_t addr[6]); + + // helper functions to convert between 32bit Netmask and counting consecutive bits and back + static uint32_t convert_netmask_bitcount_to_ip(const uint32_t netmask_bitcount); + static uint8_t convert_netmask_ip_to_bitcount(const uint32_t netmask_ip); + + static const struct AP_Param::GroupInfo var_info[]; + +private: + static AP_Networking *singleton; + + void announce_address_changes(); + + struct { + AP_Networking_IPV4 ipaddr{AP_NETWORKING_DEFAULT_STATIC_IP_ADDR}; + AP_Int8 netmask; // bits to mask. example: (16 == 255.255.0.0) and (24 == 255.255.255.0) + AP_Networking_IPV4 gwaddr{AP_NETWORKING_DEFAULT_STATIC_GW_ADDR}; + + AP_Int8 dhcp; + AP_Networking_MAC macaddr{AP_NETWORKING_DEFAULT_MAC_ADDR}; + AP_Int8 enabled; + AP_Int32 options; + } param; + + AP_Networking_backend *backend; + + HAL_Semaphore sem; + +private: + uint32_t announce_ms; +}; + +namespace AP +{ + AP_Networking &network(); +}; + +#endif // AP_NETWORKING_ENABLED diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp new file mode 100644 index 00000000000000..511408084d1e78 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp @@ -0,0 +1,178 @@ + +#include "AP_Networking_Config.h" + +#if AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + +#include "AP_Networking.h" +#include "AP_Networking_ChibiOS.h" +#include +#include + +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +#ifndef STM32_ETH_BUFFERS_EXTERN +#error "Must use external ethernet buffers" +#endif + +/* + these are referenced as globals inside lwip + */ +stm32_eth_rx_descriptor_t *__eth_rd; +stm32_eth_tx_descriptor_t *__eth_td; +uint32_t *__eth_rb[STM32_MAC_RECEIVE_BUFFERS]; +uint32_t *__eth_tb[STM32_MAC_TRANSMIT_BUFFERS]; + +/* + allocate buffers for LWIP + */ +bool AP_Networking_ChibiOS::allocate_buffers() +{ + #define AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE ((((STM32_MAC_BUFFERS_SIZE - 1) | 3) + 1) / 4) // typically == 381 + // check total size of buffers + const uint32_t total_size = sizeof(stm32_eth_rx_descriptor_t)*STM32_MAC_RECEIVE_BUFFERS + + sizeof(stm32_eth_tx_descriptor_t)*STM32_MAC_TRANSMIT_BUFFERS + + sizeof(uint32_t)*STM32_MAC_RECEIVE_BUFFERS*AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE + + sizeof(uint32_t)*STM32_MAC_TRANSMIT_BUFFERS*AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE; // typically == 9240 + + // ensure that we allocate 32-bit aligned memory, and mark it non-cacheable + uint32_t size = 2; + uint8_t rasr = 0; + // find size closest to power of 2 + while (size < total_size) { + size = size << 1; + rasr++; + } + void *mem = malloc_eth_safe(size); + if (mem == nullptr) { + return false; + } + // ensure our memory is aligned + // ref. Cortex-M7 peripherals PM0253, section 4.6.4 MPU region base address register + if (((uint32_t)mem) % size) { + AP_HAL::panic("Bad alignment of ETH memory"); + } + + // for total_size == 9240, size should be 16384 and (rasr-1) should be 13 (MPU_RASR_SIZE_16K) + const uint32_t rasr_size = MPU_RASR_SIZE(rasr-1); + + // set up MPU region for buffers + mpuConfigureRegion(STM32_NOCACHE_MPU_REGION_ETH, + (uint32_t)mem, + MPU_RASR_ATTR_AP_RW_RW | + MPU_RASR_ATTR_NON_CACHEABLE | + MPU_RASR_ATTR_S | + rasr_size | + MPU_RASR_ENABLE); + mpuEnable(MPU_CTRL_PRIVDEFENA); + SCB_CleanInvalidateDCache(); + + // assign buffers + __eth_rd = (stm32_eth_rx_descriptor_t *)mem; + __eth_td = (stm32_eth_tx_descriptor_t *)&__eth_rd[STM32_MAC_RECEIVE_BUFFERS]; + __eth_rb[0] = (uint32_t*)&__eth_td[STM32_MAC_TRANSMIT_BUFFERS]; + for (uint16_t i = 1; i < STM32_MAC_RECEIVE_BUFFERS; i++) { + __eth_rb[i] = &(__eth_rb[i-1][AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE]); + } + __eth_tb[0] = &(__eth_rb[STM32_MAC_RECEIVE_BUFFERS-1][AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE]); + for (uint16_t i = 1; i < STM32_MAC_TRANSMIT_BUFFERS; i++) { + __eth_tb[i] = &(__eth_tb[i-1][AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE]); + } + return true; +} + +/* + initialise ChibiOS network backend using LWIP + */ +bool AP_Networking_ChibiOS::init() +{ +#ifdef HAL_GPIO_ETH_ENABLE + hal.gpio->pinMode(HAL_GPIO_ETH_ENABLE, HAL_GPIO_OUTPUT); + hal.gpio->write(HAL_GPIO_ETH_ENABLE, frontend.param.enabled ? 1 : 0); +#endif + + if (!allocate_buffers()) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "NET: Failed to allocate buffers"); + return false; + } + + if (!macInit()) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "NET: macInit failed"); + return false; + } + +#if !AP_NETWORKING_DHCP_AVAILABLE + frontend.set_dhcp_enable(false); +#endif + + lwip_options = new lwipthread_opts; + + if (frontend.get_dhcp_enabled()) { + lwip_options->addrMode = NET_ADDRESS_DHCP; + } else { + lwip_options->addrMode = NET_ADDRESS_STATIC; + lwip_options->address = htonl(frontend.get_ip_param()); + lwip_options->netmask = htonl(frontend.get_netmask_param()); + lwip_options->gateway = htonl(frontend.get_gateway_param()); + } + frontend.param.macaddr.get_address(macaddr); + lwip_options->macaddress = macaddr; + + lwipInit(lwip_options); + + return true; +} + +/* + update called at 10Hz + */ +void AP_Networking_ChibiOS::update() +{ + const uint32_t ip = ntohl(lwipGetIp()); + const uint32_t nm = ntohl(lwipGetNetmask()); + const uint32_t gw = ntohl(lwipGetGateway()); + + if (ip != activeSettings.ip || + nm != activeSettings.nm || + gw != activeSettings.gw) { + activeSettings.ip = ip; + activeSettings.gw = gw; + activeSettings.nm = nm; + activeSettings.last_change_ms = AP_HAL::millis(); + } +} + +/* + send a UDP packet + */ +int32_t AP_Networking_ChibiOS::send_udp(struct udp_pcb *pcb, const ip4_addr_t &ip4_addr, const uint16_t port, const uint8_t* data, uint16_t data_len) +{ + if (pcb == nullptr) { + return ERR_ARG; + } + + data_len = (data == nullptr) ? 0 : data_len; + + struct pbuf *p = pbuf_alloc(PBUF_TRANSPORT, data_len, PBUF_RAM); + if (p == nullptr) { + return ERR_MEM; + } + + ip_addr_t dst; + ip_addr_copy_from_ip4(dst, ip4_addr); + + if (data_len > 0) { + memcpy(p->payload, data, data_len); + } + + const err_t err = udp_sendto(pcb, p, &dst, port); + pbuf_free(p); + + return err == ERR_OK ? data_len : err; +} + +#endif // AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.h b/libraries/AP_Networking/AP_Networking_ChibiOS.h new file mode 100644 index 00000000000000..196f621a0780c0 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.h @@ -0,0 +1,29 @@ +#pragma once + +#include "AP_Networking_Config.h" + +#if AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#include "AP_Networking_backend.h" + +class AP_Networking_ChibiOS : public AP_Networking_backend +{ +public: + using AP_Networking_backend::AP_Networking_backend; + + /* Do not allow copies */ + CLASS_NO_COPY(AP_Networking_ChibiOS); + + bool init() override; + void update() override; + +private: + bool allocate_buffers(void); + int32_t send_udp(struct udp_pcb *pcb, const struct ip4_addr &ip4_addr, const uint16_t port, const uint8_t* data, uint16_t data_len); + +private: + struct lwipthread_opts *lwip_options; + uint8_t macaddr[6]; +}; + +#endif // AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h new file mode 100644 index 00000000000000..54926c6d22942b --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -0,0 +1,45 @@ +#include + +#ifndef AP_NETWORKING_ENABLED +#define AP_NETWORKING_ENABLED 0 +#endif + +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#define AP_NETWORKING_DHCP_AVAILABLE LWIP_DHCP +#else +#define AP_NETWORKING_DHCP_AVAILABLE 1 // for non-ChibiOS, assume it's available +#endif + + +// --------------------------- +// Below are default params +// --------------------------- + +// Default DHCP +#ifndef AP_NETWORKING_DEFAULT_DHCP_ENABLE +#define AP_NETWORKING_DEFAULT_DHCP_ENABLE 1 +#endif + +// Default Static IP Address: 192.168.13.14 +#ifndef AP_NETWORKING_DEFAULT_STATIC_IP_ADDR +#define AP_NETWORKING_DEFAULT_STATIC_IP_ADDR "192.168.13.14" +#endif + +// Default Netmask: 24 +// Note, the netmask is the number of consecutive bits +#ifndef AP_NETWORKING_DEFAULT_NETMASK +#define AP_NETWORKING_DEFAULT_NETMASK 24 // 255.255.255.0 (for 10.0.xxx.xxx or 172.xxx.xxx.xxx type networks) +// #define AP_NETWORKING_DEFAULT_NETMASK 16 // 255.255.0.0 (for 192.168.xxx.xxxx type networks) +#endif + + +// Default Static IP Address: 192.168.13.1 +#ifndef AP_NETWORKING_DEFAULT_STATIC_GW_ADDR +#define AP_NETWORKING_DEFAULT_STATIC_GW_ADDR "192.168.13.1" +#endif + +// Default MAC Address: C2:AF:51:03:CF:46 +// Note, lower 3 bytes (ADDR3,4,5) will be replaced with the platform UUID +#ifndef AP_NETWORKING_DEFAULT_MAC_ADDR +#define AP_NETWORKING_DEFAULT_MAC_ADDR "C2:AF:51:03:CF:46" +#endif diff --git a/libraries/AP_Networking/AP_Networking_address.cpp b/libraries/AP_Networking/AP_Networking_address.cpp new file mode 100644 index 00000000000000..622e6f919a6679 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_address.cpp @@ -0,0 +1,71 @@ +/* + class for holding IPv4 address parameters + */ + +#include "AP_Networking_Config.h" + +#if AP_NETWORKING_ENABLED + +#include "AP_Networking.h" + +const AP_Param::GroupInfo AP_Networking_IPV4::var_info[] = { + // @Param: 0 + // @DisplayName: IPv4 Address 1st byte + // @Description: IPv4 address. Example: 192.xxx.xxx.xxx + // @Range: 0 255 + // @RebootRequired: True + AP_GROUPINFO("0", 1, AP_Networking_IPV4, addr[0], 0), + + // @Param: 1 + // @DisplayName: IPv4 Address 2nd byte + // @Description: IPv4 address. Example: xxx.168.xxx.xxx + // @Range: 0 255 + // @RebootRequired: True + AP_GROUPINFO("1", 2, AP_Networking_IPV4, addr[1], 0), + + // @Param: 2 + // @DisplayName: IPv4 Address 3rd byte + // @Description: IPv4 address. Example: xxx.xxx.13.xxx + // @Range: 0 255 + // @RebootRequired: True + AP_GROUPINFO("2", 3, AP_Networking_IPV4, addr[2], 0), + + // @Param: 3 + // @DisplayName: IPv4 Address 4th byte + // @Description: IPv4 address. Example: xxx.xxx.xxx.14 + // @Range: 0 255 + // @RebootRequired: True + AP_GROUPINFO("3", 4, AP_Networking_IPV4, addr[3], 0), + + AP_GROUPEND +}; + + +/* + IPV4 address parameter class + */ +AP_Networking_IPV4::AP_Networking_IPV4(const char *default_addr) +{ + AP_Param::setup_object_defaults(this, var_info); + set_default_uint32(AP_Networking::convert_str_to_ip(default_addr)); +} + +uint32_t AP_Networking_IPV4::get_uint32(void) const +{ + uint32_t v = 0; + uint8_t *b = (uint8_t*)&v; + for (uint8_t i=0; i<4; i++) { + b[3-i] = uint8_t(addr[i].get()); + } + return v; +} + +void AP_Networking_IPV4::set_default_uint32(uint32_t v) +{ + uint8_t *b = (uint8_t*)&v; + for (uint8_t i=0; i #include +#ifndef AP_NOTIFY_DISCRETE_RGB_ENABLED +#define AP_NOTIFY_DISCRETE_RGB_ENABLED 0 +#endif + #ifndef HAL_DISPLAY_ENABLED #define HAL_DISPLAY_ENABLED 1 #endif diff --git a/libraries/AP_Notify/DiscreteRGBLed.cpp b/libraries/AP_Notify/DiscreteRGBLed.cpp index d47773e01ea7c4..dbe0948b10b154 100644 --- a/libraries/AP_Notify/DiscreteRGBLed.cpp +++ b/libraries/AP_Notify/DiscreteRGBLed.cpp @@ -11,6 +11,10 @@ along with this program. If not, see . */ +#include "AP_Notify_config.h" + +#if AP_NOTIFY_DISCRETE_RGB_ENABLED + #include "DiscreteRGBLed.h" #include @@ -55,3 +59,5 @@ bool DiscreteRGBLed::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) return true; } + +#endif // AP_NOTIFY_DISCRETE_RGB_ENABLED diff --git a/libraries/AP_Notify/DiscreteRGBLed.h b/libraries/AP_Notify/DiscreteRGBLed.h index b0169a5a9e7805..ba1a2183a43310 100644 --- a/libraries/AP_Notify/DiscreteRGBLed.h +++ b/libraries/AP_Notify/DiscreteRGBLed.h @@ -18,6 +18,10 @@ #pragma once +#include "AP_Notify_config.h" + +#if AP_NOTIFY_DISCRETE_RGB_ENABLED + #include "RGBLed.h" class DiscreteRGBLed: public RGBLed { @@ -35,3 +39,5 @@ class DiscreteRGBLed: public RGBLed { uint16_t red_pin_number, green_pin_number, blue_pin_number; }; + +#endif // AP_NOTIFY_DISCRETE_RGB_ENABLED diff --git a/libraries/AP_Notify/Display.cpp b/libraries/AP_Notify/Display.cpp index 42814e1ca578fe..301cc862f3cc63 100644 --- a/libraries/AP_Notify/Display.cpp +++ b/libraries/AP_Notify/Display.cpp @@ -407,7 +407,9 @@ void Display::update_all() update_text(0); update_mode(1); update_battery(2); +#if AP_GPS_ENABLED update_gps(3); +#endif //update_gps_sats(4); update_prearm(4); update_ekf(5); @@ -475,6 +477,7 @@ void Display::update_prearm(uint8_t r) } } +#if AP_GPS_ENABLED void Display::update_gps(uint8_t r) { static const char * gpsfixname[] = {"Other", "NoGPS","NoFix","2D","3D","DGPS", "RTK f", "RTK F"}; @@ -516,6 +519,7 @@ void Display::update_gps_sats(uint8_t r) draw_char(COLUMN(8), ROW(r), (AP_Notify::flags.gps_num_sats / 10) + '0'); draw_char(COLUMN(9), ROW(r), (AP_Notify::flags.gps_num_sats % 10) + '0'); } +#endif void Display::update_ekf(uint8_t r) { diff --git a/libraries/AP_Notify/NeoPixel.cpp b/libraries/AP_Notify/NeoPixel.cpp index 08a3fd16a5862f..3e5b4952156414 100644 --- a/libraries/AP_Notify/NeoPixel.cpp +++ b/libraries/AP_Notify/NeoPixel.cpp @@ -61,7 +61,11 @@ uint16_t NeoPixel::init_ports() for (uint16_t chan=0; chan<16; chan++) { if ((1U<set_num_neopixel(chan+1, (pNotify->get_led_len())); + if (pNotify->get_led_type() & AP_Notify::Notify_LED_NeoPixel) { + led->set_num_neopixel(chan+1, pNotify->get_led_len()); + } else if (pNotify->get_led_type() & AP_Notify::Notify_LED_NeoPixelRGB) { + led->set_num_neopixel_rgb(chan+1, pNotify->get_led_len()); + } } } diff --git a/libraries/AP_Notify/OreoLED_I2C.h b/libraries/AP_Notify/OreoLED_I2C.h index a30e5322a2eedb..977fe53c58df7d 100644 --- a/libraries/AP_Notify/OreoLED_I2C.h +++ b/libraries/AP_Notify/OreoLED_I2C.h @@ -136,7 +136,7 @@ class OreoLED_I2C : public NotifyDevice { OREOLED_MODE_RGB_EXTENDED, }; - // Oreo LED modes + // Oreo LED Themes enum Oreo_LED_Theme { OreoLED_Disabled = 0, OreoLED_Aircraft = 1, diff --git a/libraries/AP_Notify/RGBLed.cpp b/libraries/AP_Notify/RGBLed.cpp index a0fe9af19fb298..b00ebdff0fa001 100644 --- a/libraries/AP_Notify/RGBLed.cpp +++ b/libraries/AP_Notify/RGBLed.cpp @@ -138,10 +138,12 @@ uint32_t RGBLed::get_colour_sequence(void) const // 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) { return sequence_armed; } +#endif // solid blue if armed with no GPS lock return sequence_armed_nogps; } @@ -150,6 +152,7 @@ uint32_t RGBLed::get_colour_sequence(void) const 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; } @@ -157,6 +160,7 @@ uint32_t RGBLed::get_colour_sequence(void) const if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D && AP_Notify::flags.pre_arm_gps_check) { return sequence_disarmed_good_gps; } +#endif return sequence_disarmed_bad_gps; } diff --git a/libraries/AP_OLC/AP_OLC.cpp b/libraries/AP_OLC/AP_OLC.cpp index 25b4a0228e2ce9..8faa5db431412e 100644 --- a/libraries/AP_OLC/AP_OLC.cpp +++ b/libraries/AP_OLC/AP_OLC.cpp @@ -16,50 +16,51 @@ */ #include "AP_OLC.h" - -#include +#include #include #if HAL_PLUSCODE_ENABLE // This is a port of https://github.com/google/open-location-code/blob/master/c/olc.c // to avoid double floating point math and use integer math as much as possible. -#define SEPARATOR_CHAR '+' -#define SEPARATOR_POS 8U -#define PADDING_CHAR '0' +static constexpr char SEPARATOR_CHAR = '+'; +static constexpr uint8_t SEPARATOR_POS = 8U; +static constexpr char PADDING_CHAR = '0'; -#define ENCODING_BASE 20U -#define PAIR_CODE_LEN 10U -#define CODE_LEN_MAX 15U +static constexpr uint8_t ENCODING_BASE = 20U; +static constexpr uint8_t PAIR_CODE_LEN = 10U; +static constexpr uint8_t CODE_LEN_MAX = 15U; -#define GRID_COLS 4U -#define GRID_ROWS (ENCODING_BASE / GRID_COLS) +static constexpr uint8_t GRID_COLS = 4U; +static constexpr uint8_t GRID_ROWS = (ENCODING_BASE / GRID_COLS); -#define OLC_DEG_MULTIPLIER 10000000U // 1e7 +static constexpr uint32_t OLC_DEG_MULTIPLIER = 10000000U; // 1e7 -#define LAT_MAX int32_t(90 * OLC_DEG_MULTIPLIER) -#define LON_MAX int32_t(180 * OLC_DEG_MULTIPLIER) +static constexpr int32_t LAT_MAX = static_cast(90 * OLC_DEG_MULTIPLIER); +static constexpr int32_t LON_MAX = static_cast(180 * OLC_DEG_MULTIPLIER); -const int32_t AP_OLC::initial_exponent = floorf(logf(2 * (LON_MAX / OLC_DEG_MULTIPLIER)) / logf(ENCODING_BASE)); -const int32_t AP_OLC::grid_size = (1 / powf(ENCODING_BASE, PAIR_CODE_LEN / 2 - (initial_exponent + 1))) * OLC_DEG_MULTIPLIER; -const int32_t AP_OLC::initial_resolution = powf(ENCODING_BASE, initial_exponent) * OLC_DEG_MULTIPLIER; +const int32_t AP_OLC::INITIAL_EXPONENT = floorf(logf(2 * (LON_MAX / OLC_DEG_MULTIPLIER)) / logf(ENCODING_BASE)); +// Work out the enclosing resolution (in degrees) for the grid algorithm. +const int32_t AP_OLC::GRID_SIZE = (1 / powf(ENCODING_BASE, PAIR_CODE_LEN / 2 - (INITIAL_EXPONENT + 1))) * OLC_DEG_MULTIPLIER; +// Work out the initial resolution +const int32_t AP_OLC::INITIAL_RESOLUTION = powf(ENCODING_BASE, INITIAL_EXPONENT) * OLC_DEG_MULTIPLIER; constexpr char AP_OLC::olc_alphabet[]; // Compute the latitude precision value for a given code length. Lengths <= 10 // have the same precision for latitude and longitude, but lengths > 10 have // different precisions due to the grid method having fewer columns than rows. -float AP_OLC::compute_precision_for_length(int length) +float AP_OLC::compute_precision_for_length(uint8_t length) { // Magic numbers! - if (length <= (int)PAIR_CODE_LEN) { + if (length <= PAIR_CODE_LEN) { return powf(ENCODING_BASE, floorf((length / -2) + 2)); } - return powf(ENCODING_BASE, -3) / powf(5, length - (int)PAIR_CODE_LEN); + return powf(ENCODING_BASE, -3) / powf(5, length - PAIR_CODE_LEN); } -int32_t AP_OLC::adjust_latitude(int32_t lat, size_t code_len) +int32_t AP_OLC::adjust_latitude(int32_t lat, uint8_t code_len) { lat = constrain_int32(lat, -LAT_MAX, LAT_MAX); @@ -89,24 +90,23 @@ int32_t AP_OLC::normalize_longitude(int32_t lon) // uses pairs of characters (latitude and longitude in that order) to represent // each step in a 20x20 grid. Each code, therefore, has 1/400th the area of // the previous code. -unsigned AP_OLC::encode_pairs(uint32_t lat, uint32_t lon, size_t length, char *buf, size_t bufsize) +uint32_t AP_OLC::encode_pairs(uint32_t lat, uint32_t lon, uint8_t length, char *buf, uint8_t bufsize) { if ((length + 1) >= bufsize) { buf[0] = '\0'; return 0; } - unsigned pos = 0; - int32_t resolution = initial_resolution; + uint32_t pos = 0; + int32_t resolution = INITIAL_RESOLUTION; // Add two digits on each pass. - for (size_t digit_count = 0; + for (uint8_t digit_count = 0; digit_count < length; digit_count += 2, resolution /= ENCODING_BASE) { - size_t digit_value; // Do the latitude - gets the digit for this place and subtracts that // for the next digit. - digit_value = lat / resolution; + auto digit_value = lat / resolution; lat -= digit_value * resolution; buf[pos++] = olc_alphabet[digit_value]; @@ -144,8 +144,8 @@ unsigned AP_OLC::encode_pairs(uint32_t lat, uint32_t lon, size_t length, char *b // // This allows default accuracy OLC codes to be refined with just a single // character. -int AP_OLC::encode_grid(uint32_t lat, uint32_t lon, size_t length, - char *buf, size_t bufsize) +int32_t AP_OLC::encode_grid(uint32_t lat, uint32_t lon, uint8_t length, + char *buf, uint8_t bufsize) { if ((length + 1) >= bufsize) { buf[0] = '\0'; @@ -154,13 +154,13 @@ int AP_OLC::encode_grid(uint32_t lat, uint32_t lon, size_t length, int pos = 0; - int32_t lat_grid_size = grid_size; - int32_t lon_grid_size = grid_size; + int32_t lat_grid_size = GRID_SIZE; + int32_t lon_grid_size = GRID_SIZE; lat %= lat_grid_size; lon %= lon_grid_size; - for (size_t i = 0; i < length; i++) { + for (uint8_t i = 0; i < length; i++) { int32_t lat_div = lat_grid_size / GRID_ROWS; int32_t lon_div = lon_grid_size / GRID_COLS; @@ -171,8 +171,8 @@ int AP_OLC::encode_grid(uint32_t lat, uint32_t lon, size_t length, } // Work out the row and column. - size_t row = lat / lat_div; - size_t col = lon / lon_div; + auto row = lat / lat_div; + auto col = lon / lon_div; lat_grid_size /= GRID_ROWS; lon_grid_size /= GRID_COLS; lat -= row * lat_grid_size; @@ -183,9 +183,9 @@ int AP_OLC::encode_grid(uint32_t lat, uint32_t lon, size_t length, return pos; } -int AP_OLC::olc_encode(int32_t lat, int32_t lon, size_t length, char *buf, size_t bufsize) +uint32_t AP_OLC::olc_encode(int32_t lat, int32_t lon, uint8_t length, char *buf, uint8_t bufsize) { - int pos = 0; + uint32_t pos = 0; length = MIN(length, CODE_LEN_MAX); diff --git a/libraries/AP_OLC/AP_OLC.h b/libraries/AP_OLC/AP_OLC.h index 061e3918f25273..2c34ed7ad7d5a5 100644 --- a/libraries/AP_OLC/AP_OLC.h +++ b/libraries/AP_OLC/AP_OLC.h @@ -32,22 +32,22 @@ class AP_OLC // olc_encodes the given coordinates in lat and lon (deg * OLC_DEG_MULTIPLIER) // as an OLC code of the given length. It returns the number of characters // written to buf. - static int olc_encode(int32_t lat, int32_t lon, size_t length, char *buf, size_t bufsize); + static uint32_t olc_encode(int32_t lat, int32_t lon, uint8_t length, char *buf, uint8_t bufsize); private: - static const int32_t initial_exponent; + static const int32_t INITIAL_EXPONENT; // Work out the enclosing resolution (in degrees) for the grid algorithm. - static const int32_t grid_size; + static const int32_t GRID_SIZE; // Work out the initial resolution - static const int32_t initial_resolution; + static const int32_t INITIAL_RESOLUTION; static constexpr char olc_alphabet[] = "23456789CFGHJMPQRVWX"; - static float compute_precision_for_length(int length); - static int32_t adjust_latitude(int32_t lat, size_t code_len); + static float compute_precision_for_length(uint8_t length); + static int32_t adjust_latitude(int32_t lat, uint8_t code_len); static int32_t normalize_longitude(int32_t lon); - static unsigned encode_pairs(uint32_t lat, uint32_t lon, size_t length, char *buf, size_t bufsize); - static int encode_grid(uint32_t lat, uint32_t lon, size_t length, char *buf, size_t bufsize); + static uint32_t encode_pairs(uint32_t lat, uint32_t lon, uint8_t length, char *buf, uint8_t bufsize); + static int32_t encode_grid(uint32_t lat, uint32_t lon, uint8_t length, char *buf, uint8_t bufsize); }; diff --git a/libraries/AP_OLC/tests/test_olc.cpp b/libraries/AP_OLC/tests/test_olc.cpp new file mode 100644 index 00000000000000..75405309ac5fa1 --- /dev/null +++ b/libraries/AP_OLC/tests/test_olc.cpp @@ -0,0 +1,52 @@ +#include +#include "AP_Math/AP_Math.h" +#include "AP_OLC/AP_OLC.h" + +AP_OLC olc; +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + +// Test the olc_encode function of AP_OLC +TEST(AP_OLCTest, OLC_EncodeTest) { + // Test cases + struct TestCase { + int32_t lat; + int32_t lon; + size_t length; + std::string expectedCode; + }; + + // Define the test cases + std::vector testCases = { + {500000000, 1000000000, 6, "9P2222"}, + {900000000, 2000000000, 8, "C3X2X2X2"}, + {000000000, 500000000, 9, "6HGG2222+"}, + {300000000, 500000000, 10, "8H2G2222+2"}, + {300000000, 500000000, 11, "8H2G2222+22"}, + {300000000, 500000000, 12, "8H2G2222+22"}, + {300000000, -1000000000, 10, "86222222+2"}, + {950000000, -1900000000, 12, "CVXGX2X2+X2"}, + // Add more test cases as needed + }; + // Run the test cases + for (const auto& testCase : testCases) { + std::string buf(testCase.length + 2, '\0'); // buf should be > length +1 as the coding add \0 + uint32_t result = olc.olc_encode(testCase.lat, testCase.lon, testCase.length, &buf[0], buf.size()); + if (testCase.length < 9) { + EXPECT_EQ(result, 9u); // 9 is separator min position + } else { + EXPECT_EQ(result, 11u); // length max is 11 + } + EXPECT_EQ(buf.substr(0, MIN(testCase.length, 11u)), testCase.expectedCode); + } + std::string buf(2, '\0'); + uint32_t result = olc.olc_encode(testCases[0].lat, testCases[0].lon, testCases[0].length, &buf[0], buf.size()); + EXPECT_EQ(result, 0u); + std::string empty_code(2, '\0'); + EXPECT_EQ(buf, empty_code); + std::string buf2(16, '\0'); // buf should be > length +1 as the coding add \0 + result = olc.olc_encode(testCases[0].lat, testCases[0].lon, 11, &buf2[0], buf2.size()); + EXPECT_EQ(result, 12u); + EXPECT_EQ(buf2.substr(0, 12), "9P222222+222"); +} + +AP_GTEST_MAIN() diff --git a/libraries/AP_OLC/tests/wscript b/libraries/AP_OLC/tests/wscript new file mode 100644 index 00000000000000..cd3e5e3ce7c9d9 --- /dev/null +++ b/libraries/AP_OLC/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_OSD/AP_OSD.cpp b/libraries/AP_OSD/AP_OSD.cpp index 6223e5d9f6171a..d4284cc7208981 100644 --- a/libraries/AP_OSD/AP_OSD.cpp +++ b/libraries/AP_OSD/AP_OSD.cpp @@ -85,7 +85,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = { // @Param: _OPTIONS // @DisplayName: OSD Options // @Description: This sets options that change the display - // @Bitmask: 0:UseDecimalPack, 1:InvertedWindArrow, 2:InvertedAHRoll, 3:Convert feet to miles at 5280ft instead of 10000ft, 4:DisableCrosshair, 5:TranslateArrows + // @Bitmask: 0:UseDecimalPack, 1:InvertedWindArrow, 2:InvertedAHRoll, 3:Convert feet to miles at 5280ft instead of 10000ft, 4:DisableCrosshair, 5:TranslateArrows, 6:AviationStyleAH // @User: Standard AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, OPTION_DECIMAL_PACK), @@ -352,8 +352,8 @@ bool AP_OSD::init_backend(const AP_OSD::osd_types type, const uint8_t instance) _backends[instance]->init_symbol_set(AP_OSD_AbstractScreen::symbols_lookup_table, AP_OSD_NUM_SYMBOLS); return true; } - return false; #endif + return false; } #if OSD_ENABLED diff --git a/libraries/AP_OSD/AP_OSD.h b/libraries/AP_OSD/AP_OSD.h index 1dd423c48305e1..8594e5d2d4aaa3 100644 --- a/libraries/AP_OSD/AP_OSD.h +++ b/libraries/AP_OSD/AP_OSD.h @@ -551,6 +551,7 @@ class AP_OSD OPTION_IMPERIAL_MILES = 1U<<3, OPTION_DISABLE_CROSSHAIR = 1U<<4, OPTION_BF_ARROWS = 1U<<5, + OPTION_AVIATION_AH = 1U<<6, }; enum { diff --git a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h index fa02451d4d6cd2..7e4919fda4c310 100644 --- a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h +++ b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.h @@ -73,13 +73,13 @@ class AP_OSD_MSP_DisplayPort : public AP_OSD_Backend static const uint8_t SYM_FS = 0x99; static const uint8_t SYM_KMH = 0x9E; static const uint8_t SYM_MPH = 0x9D; - static const uint8_t SYM_DEGR = 0x1D; + static const uint8_t SYM_DEGR = 0x08; static const uint8_t SYM_PCNT = 0x25; static const uint8_t SYM_RPM = 0x12; static const uint8_t SYM_ASPD = 0x41; - static const uint8_t SYM_GSPD = 0x70; - static const uint8_t SYM_WSPD = 0x1B; - static const uint8_t SYM_VSPD = 0x7F; + static const uint8_t SYM_GSPD = 0x47; + static const uint8_t SYM_WSPD = 0x57; + static const uint8_t SYM_VSPD = 0x5E; static const uint8_t SYM_WPNO = 0x23; static const uint8_t SYM_WPDIR = 0xE6; static const uint8_t SYM_WPDST = 0xE7; @@ -88,10 +88,10 @@ class AP_OSD_MSP_DisplayPort : public AP_OSD_Backend static const uint8_t SYM_SAT_L = 0x1E; static const uint8_t SYM_SAT_R = 0x1F; - static const uint8_t SYM_HDOP_L = 0x11; - static const uint8_t SYM_HDOP_R = 0x08; + static const uint8_t SYM_HDOP_L = 0x48; + static const uint8_t SYM_HDOP_R = 0x44; - static const uint8_t SYM_HOME = 0x05; + static const uint8_t SYM_HOME = 0x11; static const uint8_t SYM_WIND = 0x57; static const uint8_t SYM_ARROW_START = 0x60; @@ -120,30 +120,30 @@ class AP_OSD_MSP_DisplayPort : public AP_OSD_Backend static const uint8_t SYM_DEGREES_C = 0x0E; static const uint8_t SYM_DEGREES_F = 0x0D; - static const uint8_t SYM_GPS_LAT = 0x68; - static const uint8_t SYM_GPS_LONG = 0x6C; - static const uint8_t SYM_ARMED = 0x08; - static const uint8_t SYM_DISARMED = 0x08; + static const uint8_t SYM_GPS_LAT = 0x89; + static const uint8_t SYM_GPS_LONG = 0x98; + static const uint8_t SYM_ARMED = 0x00; + static const uint8_t SYM_DISARMED = 0x2A; static const uint8_t SYM_ROLL0 = 0x2D; static const uint8_t SYM_ROLLR = 0x64; static const uint8_t SYM_ROLLL = 0x6C; static const uint8_t SYM_PTCH0 = 0x7C; static const uint8_t SYM_PTCHUP = 0x68; static const uint8_t SYM_PTCHDWN = 0x60; - static const uint8_t SYM_XERR = 0xEE; + static const uint8_t SYM_XERR = 0x21; static const uint8_t SYM_KN = 0xF0; static const uint8_t SYM_NM = 0xF1; - static const uint8_t SYM_DIST = 0x22; + static const uint8_t SYM_DIST = 0x04; static const uint8_t SYM_FLY = 0x9C; static const uint8_t SYM_EFF = 0xF2; static const uint8_t SYM_AH = 0xF3; static const uint8_t SYM_MW = 0xF4; static const uint8_t SYM_CLK = 0x08; static const uint8_t SYM_KILO = 0x4B; - static const uint8_t SYM_TERALT = 0xEF; + static const uint8_t SYM_TERALT = 0x7F; static const uint8_t SYM_FENCE_ENABLED = 0xF5; static const uint8_t SYM_FENCE_DISABLED = 0xF6; - static const uint8_t SYM_RNGFD = 0x72; + static const uint8_t SYM_RNGFD = 0x7F; static const uint8_t SYM_LQ = 0xF8; static constexpr uint8_t symbols[AP_OSD_NUM_SYMBOLS] { diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index dea1ac0540ac6c..3a76f5b577d11d 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -1354,7 +1354,7 @@ void AP_OSD_Screen::draw_bat_volt(uint8_t instance, VoltageType type, uint8_t x, case VoltageType::RESTING_CELL: { blinkvolt = osd->warn_avgcellrestvolt; v = battery.voltage_resting_estimate(instance); - FALLTHROUGH; + FALLTHROUGH; } case VoltageType::AVG_CELL: { if (type == VoltageType::AVG_CELL) { //for fallthrough of RESTING_CELL @@ -1376,10 +1376,18 @@ void AP_OSD_Screen::draw_bat_volt(uint8_t instance, VoltageType type, uint8_t x, } if (!show_remaining_pct) { // Do not show battery percentage - backend->write(x,y, v < blinkvolt, "%2.1f%c", (double)v, SYMBOL(SYM_VOLT)); + if (type == VoltageType::RESTING_CELL || type == VoltageType::AVG_CELL) { + backend->write(x,y, v < blinkvolt, "%1.2f%c", (double)v, SYMBOL(SYM_VOLT)); + } else { + backend->write(x,y, v < blinkvolt, "%2.1f%c", (double)v, SYMBOL(SYM_VOLT)); + } return; } - backend->write(x,y, v < blinkvolt, "%c%2.1f%c", SYMBOL(SYM_BATT_FULL) + p, (double)v, SYMBOL(SYM_VOLT)); + if (type == VoltageType::RESTING_CELL || type == VoltageType::AVG_CELL) { + backend->write(x,y, v < blinkvolt, "%c%1.2f%c", SYMBOL(SYM_BATT_FULL) + p, (double)v, SYMBOL(SYM_VOLT)); + } else { + backend->write(x,y, v < blinkvolt, "%c%2.1f%c", SYMBOL(SYM_BATT_FULL) + p, (double)v, SYMBOL(SYM_VOLT)); + } } void AP_OSD_Screen::draw_bat_volt(uint8_t x, uint8_t y) @@ -1573,10 +1581,18 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y) WITH_SEMAPHORE(ahrs.get_semaphore()); float roll; float pitch; + bool inverted = false; AP::vehicle()->get_osd_roll_pitch_rad(roll,pitch); pitch *= -1; - - //inverted roll AH + // Are we inverted? then flash horizon line + if (abs(roll) >= radians(90)) { + inverted = true; + } + // Aviation style AH instead of Betaflight FPV style + if (inverted && check_option(AP_OSD::OPTION_AVIATION_AH)) { + pitch = -pitch; + } + //inverted roll AH (Russian HUD emulation) if (check_option(AP_OSD::OPTION_INVERTED_AH_ROLL)) { roll = -roll; } @@ -1595,7 +1611,7 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y) //chars in font in reversed order c = SYMBOL(SYM_AH_H_START) + ((SYMBOL(SYM_AH_H_COUNT) - 1) - c); if (dy >= -4 && dy <= 4) { - backend->write(x + dx, y - dy, false, "%c", c); + backend->write(x + dx, y - dy, inverted, "%c", c); } } } else { @@ -1605,7 +1621,7 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y) char c = (fx - dx) * SYMBOL(SYM_AH_V_COUNT); c = SYMBOL(SYM_AH_V_START) + c; if (dx >= -4 && dx <=4) { - backend->write(x + dx, y - dy, false, "%c", c); + backend->write(x + dx, y - dy, inverted, "%c", c); } } } @@ -2133,6 +2149,7 @@ void AP_OSD_Screen::draw_aspd2(uint8_t x, uint8_t y) #endif } +#if AP_RTC_ENABLED void AP_OSD_Screen::draw_clk(uint8_t x, uint8_t y) { AP_RTC &rtc = AP::rtc(); @@ -2144,6 +2161,7 @@ void AP_OSD_Screen::draw_clk(uint8_t x, uint8_t y) backend->write(x, y, false, "%c%02u:%02u", SYMBOL(SYM_CLK), hour, min); } } +#endif #if HAL_PLUSCODE_ENABLE void AP_OSD_Screen::draw_pluscode(uint8_t x, uint8_t y) @@ -2313,7 +2331,9 @@ void AP_OSD_Screen::draw(void) DRAW_SETTING(atemp); DRAW_SETTING(hdop); DRAW_SETTING(flightime); +#if AP_RTC_ENABLED DRAW_SETTING(clk); +#endif #if AP_VIDEOTX_ENABLED DRAW_SETTING(vtx_power); #endif diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp b/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp index f43289d248380c..a3cc3ed372503e 100644 --- a/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp @@ -132,9 +132,6 @@ void AP_OpenDroneID::set_basic_id() { if (pkt_basic_id.id_type != MAV_ODID_ID_TYPE_NONE) { return; } - if (id_len == 0) { - load_UAS_ID_from_persistent_memory(); - } if (id_len > 0) { // prepare basic id pkt uint8_t val = gcs().sysid_this_mav(); @@ -209,10 +206,12 @@ void AP_OpenDroneID::update() if ((pkt_basic_id.id_type == MAV_ODID_ID_TYPE_SERIAL_NUMBER) && (_options & LockUASIDOnFirstBasicIDRx) - && id_len == 0) { + && id_len == 0 + && !bootloader_flashed) { hal.util->flash_bootloader(); // reset the basic id on next set_basic_id call pkt_basic_id.id_type = MAV_ODID_ID_TYPE_NONE; + bootloader_flashed = true; } set_basic_id(); diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID.h b/libraries/AP_OpenDroneID/AP_OpenDroneID.h index 735bf358c76885..a4bb5f9856526c 100644 --- a/libraries/AP_OpenDroneID/AP_OpenDroneID.h +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID.h @@ -117,7 +117,7 @@ class AP_OpenDroneID char id_type[3]; size_t id_len; char id_str[21]; - + bool bootloader_flashed; enum Options : int16_t { EnforceArming = (1U << 0U), AllowNonGPSPosition = (1U << 1U), diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp index ff4cba123f1b9e..a23397881e3aaa 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp @@ -18,6 +18,7 @@ #if AP_OPTICALFLOW_CALIBRATOR_ENABLED #include "AP_OpticalFlow_Calibrator.h" +#include #include #include @@ -68,6 +69,7 @@ bool AP_OpticalFlow_Calibrator::update() { // prefix for reporting const char* prefix_str = "FlowCal:"; + (void)prefix_str; // in case !HAL_GCS_ENABLED // while running add samples if (_cal_state == CalState::RUNNING) { @@ -189,7 +191,9 @@ bool AP_OpticalFlow_Calibrator::calc_scalars(uint8_t axis, float& scalar, float& { // prefix for reporting const char* prefix_str = "FlowCal:"; + (void)prefix_str; // in case !HAL_GCS_ENABLED const char* axis_str = axis == 0 ? "x" : "y"; + (void)axis_str; // in case !HAL_GCS_ENABLED // check we have samples // this should never fail because this method should only be called once the sample buffer is full diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index cb5f6f0ef39aee..213c804f939669 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -103,7 +103,7 @@ void AP_Parachute::release() return; } - gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Released"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Parachute: Released"); AP::logger().Write_Event(LogEvent::PARACHUTE_RELEASED); // set release time to current system time diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index f9fc06454625a8..9e0ad48b854a40 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -94,9 +94,10 @@ HAL_Semaphore AP_Param::_count_sem; // storage and naming information about all types that can be saved const AP_Param::Info *AP_Param::_var_info; -struct AP_Param::param_override *AP_Param::param_overrides = nullptr; -uint16_t AP_Param::num_param_overrides = 0; -uint16_t AP_Param::num_read_only = 0; +struct AP_Param::param_override *AP_Param::param_overrides; +uint16_t AP_Param::param_overrides_len; +uint16_t AP_Param::num_param_overrides; +uint16_t AP_Param::num_read_only; ObjectBuffer_TS AP_Param::save_queue{30}; bool AP_Param::registered_save_handler; @@ -2169,7 +2170,7 @@ bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaul return true; } -bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass) +bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass, uint16_t &idx) { // try opening the file both in the posix filesystem and using AP::FS int file_apfs = AP::FS().open(filename, O_RDONLY, true); @@ -2178,7 +2179,6 @@ bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass) return false; } - uint16_t idx = 0; char line[100]; while (AP::FS().fgets(line, sizeof(line)-1, file_apfs)) { char *pname; @@ -2201,6 +2201,10 @@ bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass) } continue; } + if (idx >= param_overrides_len) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + break; + } param_overrides[idx].object_ptr = vp; param_overrides[idx].value = value; param_overrides[idx].read_only = read_only; @@ -2244,6 +2248,7 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass) free(mutable_filename); delete[] param_overrides; + param_overrides_len = 0; num_param_overrides = 0; num_read_only = 0; @@ -2252,6 +2257,7 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass) AP_HAL::panic("AP_Param: Failed to allocate overrides"); return false; } + param_overrides_len = num_defaults; if (num_defaults == 0) { return true; @@ -2262,10 +2268,11 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass) if (mutable_filename == nullptr) { AP_HAL::panic("AP_Param: Failed to allocate mutable string"); } + uint16_t idx = 0; for (char *pname = strtok_r(mutable_filename, ",", &saveptr); pname != nullptr; pname = strtok_r(nullptr, ",", &saveptr)) { - if (!read_param_defaults_file(pname, last_pass)) { + if (!read_param_defaults_file(pname, last_pass, idx)) { free(mutable_filename); return false; } @@ -2336,6 +2343,7 @@ void AP_Param::load_embedded_param_defaults(bool last_pass) { delete[] param_overrides; param_overrides = nullptr; + param_overrides_len = 0; num_param_overrides = 0; num_read_only = 0; @@ -2350,6 +2358,8 @@ void AP_Param::load_embedded_param_defaults(bool last_pass) return; } + param_overrides_len = num_defaults; + const volatile char *ptr = param_defaults_data.data; int32_t length = param_defaults_data.length; uint16_t idx = 0; diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index d3a95294b2305e..d40a7a30f86e54 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -724,7 +724,7 @@ class AP_Param load a parameter defaults file. This happens as part of load_all() */ static bool count_defaults_in_file(const char *filename, uint16_t &num_defaults); - static bool read_param_defaults_file(const char *filename, bool last_pass); + static bool read_param_defaults_file(const char *filename, bool last_pass, uint16_t &idx); /* load defaults from embedded parameters @@ -775,6 +775,7 @@ class AP_Param }; static struct param_override *param_overrides; static uint16_t num_param_overrides; + static uint16_t param_overrides_len; static uint16_t num_read_only; // values filled into the EEPROM header diff --git a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp index 8c19d322ef2ad1..1cd68ac08aa0a2 100644 --- a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp +++ b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp @@ -399,6 +399,7 @@ void AP_PiccoloCAN::update() } } +#if HAL_GCS_ENABLED // send ESC telemetry messages over MAVLink void AP_PiccoloCAN::send_esc_telemetry_mavlink(uint8_t mav_chan) { @@ -473,7 +474,7 @@ void AP_PiccoloCAN::send_esc_telemetry_mavlink(uint8_t mav_chan) } } } - +#endif // send servo messages over CAN void AP_PiccoloCAN::send_servo_messages(void) diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index 7587835e594088..ac1d6786e6c6ba 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -28,6 +28,8 @@ #include "AP_Proximity_AirSimSITL.h" #include "AP_Proximity_Cygbot_D1.h" #include "AP_Proximity_DroneCAN.h" +#include "AP_Proximity_Scripting.h" +#include "AP_Proximity_LD06.h" #include @@ -198,6 +200,12 @@ void AP_Proximity::init() num_instances = instance+1; break; #endif +#if AP_PROXIMITY_SCRIPTING_ENABLED + case Type::Scripting: + state[instance].instance = instance; + drivers[instance] = new AP_Proximity_Scripting(*this, state[instance], params[instance]); + break; +#endif #if AP_PROXIMITY_SITL_ENABLED case Type::SITL: state[instance].instance = instance; @@ -209,6 +217,15 @@ void AP_Proximity::init() state[instance].instance = instance; drivers[instance] = new 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); + serial_instance++; + } + break; #endif } @@ -272,6 +289,15 @@ AP_Proximity::Status AP_Proximity::get_status() const return Status::Good; } +// return proximity backend for Lua scripting +AP_Proximity_Backend *AP_Proximity::get_backend(uint8_t id) const +{ + if (!valid_instance(id)) { + return nullptr; + } + return drivers[id]; +} + // prearm checks bool AP_Proximity::prearm_healthy(char *failure_msg, const uint8_t failure_msg_len) const { diff --git a/libraries/AP_Proximity/AP_Proximity.h b/libraries/AP_Proximity/AP_Proximity.h index f65536a84f7544..0363fea8f4da97 100644 --- a/libraries/AP_Proximity/AP_Proximity.h +++ b/libraries/AP_Proximity/AP_Proximity.h @@ -80,6 +80,12 @@ class AP_Proximity #endif #if AP_PROXIMITY_DRONECAN_ENABLED DroneCAN = 14, +#endif +#if AP_PROXIMITY_SCRIPTING_ENABLED + Scripting = 15, +#endif +#if AP_PROXIMITY_LD06_ENABLED + LD06 = 16, #endif }; @@ -180,6 +186,9 @@ class AP_Proximity static AP_Proximity *get_singleton(void) { return _singleton; }; + // return backend object for Lua scripting + AP_Proximity_Backend *get_backend(uint8_t id) const; + // 3D boundary AP_Proximity_Boundary_3D boundary; diff --git a/libraries/AP_Proximity/AP_Proximity_Backend.h b/libraries/AP_Proximity/AP_Proximity_Backend.h index 6ed390d26b09b3..7f97e061d0d8ed 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend.h +++ b/libraries/AP_Proximity/AP_Proximity_Backend.h @@ -43,6 +43,18 @@ class AP_Proximity_Backend // handle mavlink messages virtual void handle_msg(const mavlink_message_t &msg) {} +#if AP_SCRIPTING_ENABLED + // handle scripting obstacle messages + virtual bool set_distance_min_max(float min, float max) { return false; } + // this is in body frame + virtual bool handle_script_distance_msg(float dist_m, float yaw_deg, float pitch_deg, bool push_to_boundary) { return false; } + virtual bool handle_script_3d_msg(const Vector3f &vec_to_obstacle, bool push_to_boundary) { return false; } + virtual bool update_virtual_boundary() { return false; } +#endif + + // return the type of sensor + AP_Proximity::Type type() const { return (AP_Proximity::Type)params.type.get(); } + protected: // set status and update valid_count diff --git a/libraries/AP_Proximity/AP_Proximity_LD06.cpp b/libraries/AP_Proximity/AP_Proximity_LD06.cpp new file mode 100644 index 00000000000000..409a3352e3a2c2 --- /dev/null +++ b/libraries/AP_Proximity/AP_Proximity_LD06.cpp @@ -0,0 +1,198 @@ +/* + 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 . + */ + +/* + * ArduPilot device driver for Inno-Maker LD06 LiDAR + * + * ALL INFORMATION REGARDING PROTOCOL WAS DERIVED FROM InnoMaker DATASHEET: + * + * http://wiki.inno-maker.com/display/HOMEPAGE/LD06?preview=/6949506/6949511/LDROBOT_LD06_Development%20manual_v1.0_en.pdf + * + * Author: Adithya Patil, Georgia Institute of Technology + * Based on the SLAMTEC RPLiDAR code written by Steven Josefs, IAV GmbH and CYGBOT D1 LiDAR code + * + */ + +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_LD06_ENABLED +#include "AP_Proximity_LD06.h" + +#define LD_START_CHAR 0x54 +#define PROXIMITY_LD06_TIMEOUT_MS 50 + +// Indices in data array where each value starts being recorded +// See comment below about data payload for more info about formatting +#define START_BEGIN_CHARACTER 0 +#define START_DATA_LENGTH 1 +#define START_RADAR_SPEED 2 +#define START_BEGIN_ANGLE 4 +#define START_PAYLOAD 6 +#define START_END_ANGLE 42 +#define START_CHECK_SUM 46 +#define MEASUREMENT_PAYLOAD_LENGTH 3 +#define PAYLOAD_COUNT 12 + + /* ------------------------------------------ + Data Packet Structure: + Start Character : 1 Byte + Data Length : 1 Byte + Radar Speed : 2 Bytes + Start Angle : 2 Bytes + Data Measurements : 36 Bytes + Contains 12 measurements of 3 Bytes each + Each measurement has 2 Bytes for distance to closest object + Each measurement has the 3rd Byte as measurement Confidence + End Angle : 2 Bytes + Timestamp : 2 Bytes + Checksum : 1 Byte + ------------------------------------------ */ +// ----> 47 data bytes in total for one packet + +// Update the sensor readings +void AP_Proximity_LD06::update(void) +{ + // Escape if no connection detected/supported while running + if (_uart == nullptr) { + return; + } + + // Begin getting sensor readings + // Calls method that repeatedly reads through UART channel + get_readings(); + + // Check if the data is being received correctly and sets Proximity Status + if (_last_distance_received_ms == 0 || (AP_HAL::millis() - _last_distance_received_ms > PROXIMITY_LD06_TIMEOUT_MS)) { + set_status(AP_Proximity::Status::NoData); + } else { + set_status(AP_Proximity::Status::Good); + } +} + +// Called repeatedly to get the readings at the current instant +void AP_Proximity_LD06::get_readings() +{ + if (_uart == nullptr) { + return; + } + + // Store the number of bytes available on the UART input + uint32_t nbytes = MIN((uint16_t) 4000, _uart->available()); + + // Loops through all bytes that were received + while (nbytes-- > 0) { + + // Gets and logs the current byte being read + const uint8_t c = _uart->read(); + + // Stores the byte in an array if the byte is a start byte or we have already read a start byte + if (c == LD_START_CHAR || _response_data) { + + // Sets to true if a start byte has been read, default false otherwise + _response_data = true; + + // Stores the next byte in an array + _response[_byte_count] = c; + _byte_count++; + + if (_byte_count == _response[START_DATA_LENGTH] + 3) { + + const uint32_t current_ms = AP_HAL::millis(); + + // Stores the last distance taken, used to reduce number of readings taken + if (_last_distance_received_ms != current_ms) { + _last_distance_received_ms = current_ms; + } + + // Updates the temporary boundary and passes off the completed data + parse_response_data(); + _temp_boundary.update_3D_boundary(state.instance, frontend.boundary); + _temp_boundary.reset(); + + // Resets the bytes read and whether or not we are reading data to accept a new payload + _byte_count = 0; + _response_data = false; + } + } + } +} + +// Parses the data packet received from the LiDAR +void AP_Proximity_LD06::parse_response_data() +{ + + // Data interpretation based on: + // http://wiki.inno-maker.com/display/HOMEPAGE/LD06?preview=/6949506/6949511/LDROBOT_LD06_Development%20manual_v1.0_en.pdf + + // Second byte in array stores length of data - not used but stored for debugging + // const uint8_t data_length = _response[START_DATA_LENGTH]; + + // Respective bits store the radar speed, start/end angles + // Use bitwise operations to correctly obtain correct angles + // Divide angles by 100 as per manual + const float start_angle = float(UINT16_VALUE(_response[START_BEGIN_ANGLE + 1], _response[START_BEGIN_ANGLE])) * 0.01; + const float end_angle = float(UINT16_VALUE(_response[START_END_ANGLE + 1], _response[START_END_ANGLE])) * 0.01; + + // Verify the checksum that is stored in the last element of the response array + // Return if checksum is incorrect - i.e. bad data, bad readings, etc. + const uint8_t check_sum = _response[START_CHECK_SUM]; + if (check_sum != crc8_generic(&_response[0], sizeof(_response) / sizeof(_response[0]) - 1, 0x4D)) { + return; + } + + // Calculates the angle that this point was sampled at + float sampled_counts = 0; + const float angle_step = (end_angle - start_angle) / (PAYLOAD_COUNT - 1); + float uncorrected_angle = start_angle + (end_angle - start_angle) * 0.5; + + // Handles the case that the angles read went from 360 to 0 (jumped) + if (angle_step < 0) { + uncorrected_angle = wrap_360(start_angle + (end_angle + 360 - start_angle) * 0.5); + } + + // Takes the angle in the middle of the readings to be pushed to the database + const float push_angle = correct_angle_for_orientation(uncorrected_angle); + + float distance_avg = 0.0; + + // Each recording point is three bytes long, goes through all of that and updates database + for (uint16_t i = START_PAYLOAD; i < START_PAYLOAD + MEASUREMENT_PAYLOAD_LENGTH * PAYLOAD_COUNT; i += MEASUREMENT_PAYLOAD_LENGTH) { + + // Gets the distance recorded and converts to meters + const float distance_meas = UINT16_VALUE(_response[i + 1], _response[i]) * 0.001; + + // Validates data and checks if it should be included + if (distance_meas > distance_min() && distance_meas < distance_max()) { + if (ignore_reading(push_angle, distance_meas)) { + continue; + } + + sampled_counts ++; + distance_avg += distance_meas; + } + } + + // Convert angle to appropriate face and adds to database + // Since angle increments are only about 3 degrees, ignore readings if there were only 1 or 2 measurements + // (likely outliers) recorded in the range + if (sampled_counts > 2) { + // Gets the average distance read + distance_avg /= sampled_counts; + + // Pushes the average distance and angle to the obstacle avoidance database + const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(push_angle); + _temp_boundary.add_distance(face, push_angle, distance_avg); + database_push(push_angle, distance_avg); + } +} +#endif // AP_PROXIMITY_LD06_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_LD06.h b/libraries/AP_Proximity/AP_Proximity_LD06.h new file mode 100644 index 00000000000000..c51adbb102e821 --- /dev/null +++ b/libraries/AP_Proximity/AP_Proximity_LD06.h @@ -0,0 +1,69 @@ +/* + 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 . + */ + +/* + * ArduPilot device driver for Inno-Maker LD06 LiDAR + * + * ALL INFORMATION REGARDING PROTOCOL WAS DERIVED FROM LD06 DATASHEET: + * + * http://wiki.inno-maker.com/display/HOMEPAGE/LD06?preview=/6949506/6949511/LDROBOT_LD06_Development%20manual_v1.0_en.pdf + * + * Author: Adithya Patil, Georgia Institute of Technology + * Based on the SLAMTEC RPLiDAR code written by Steven Josefs, IAV GmbH + * + */ + +#pragma once +#include "AP_Proximity_config.h" + +#if AP_PROXIMITY_LD06_ENABLED + +#include "AP_Proximity_Backend_Serial.h" + +#define MESSAGE_LENGTH_LD06 47 + +// Minimum and maximum distance that the sensor can read in meters +#define MAX_READ_DISTANCE_LD06 12.0f +#define MIN_READ_DISTANCE_LD06 0.02f + +class AP_Proximity_LD06 : public AP_Proximity_Backend_Serial +{ +public: + + using AP_Proximity_Backend_Serial::AP_Proximity_Backend_Serial; + + // Update the state of the sensor + void update(void) override; + + // Get the max and min distances for the sensor being used + float distance_max() const override { return MAX_READ_DISTANCE_LD06; } + float distance_min() const override { return MIN_READ_DISTANCE_LD06; } + +private: + + // Get and parse the sensor data + void parse_response_data(); + void get_readings(); + + // Store and keep track of the bytes being read from the sensor + uint8_t _response[MESSAGE_LENGTH_LD06]; + bool _response_data; + uint16_t _byte_count; + + // Store for error-tracking purposes + uint32_t _last_distance_received_ms; + + // Boundary to store the measurements + AP_Proximity_Temp_Boundary _temp_boundary; +}; +#endif // AP_PROXIMITY_LD06_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_Params.cpp b/libraries/AP_Proximity/AP_Proximity_Params.cpp index 1baf22d567452b..046a29c3b71810 100644 --- a/libraries/AP_Proximity/AP_Proximity_Params.cpp +++ b/libraries/AP_Proximity/AP_Proximity_Params.cpp @@ -8,7 +8,7 @@ const AP_Param::GroupInfo AP_Proximity_Params::var_info[] = { // @Param: _TYPE // @DisplayName: Proximity type // @Description: What type of proximity sensor is connected - // @Values: 0:None,7:LightwareSF40c,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2,6:TeraRangerTowerEvo,8:LightwareSF45B,10:SITL,12:AirSimSITL,13:CygbotD1, 14:DroneCAN + // @Values: 0:None,7:LightwareSF40c,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2,6:TeraRangerTowerEvo,8:LightwareSF45B,10:SITL,12:AirSimSITL,13:CygbotD1, 14:DroneCAN, 15:Scripting, 16:LD06 // @RebootRequired: True // @User: Standard AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Proximity_Params, type, 0, AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_Proximity/AP_Proximity_Scripting.cpp b/libraries/AP_Proximity/AP_Proximity_Scripting.cpp new file mode 100644 index 00000000000000..d6e931852de314 --- /dev/null +++ b/libraries/AP_Proximity/AP_Proximity_Scripting.cpp @@ -0,0 +1,127 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_Proximity_Scripting.h" + +#if HAL_PROXIMITY_ENABLED && AP_SCRIPTING_ENABLED + +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +#define PROXIMITY_SCRIPTING_TIMEOUT_MS 1500 // distance messages must arrive within this many milliseconds + +// update the state of the sensor +void AP_Proximity_Scripting::update(void) +{ + // check for timeout and set health status + if ((_last_update_ms == 0 || (AP_HAL::millis() - _last_update_ms > PROXIMITY_SCRIPTING_TIMEOUT_MS)) && + (_last_upward_update_ms == 0 || (AP_HAL::millis() - _last_upward_update_ms > PROXIMITY_SCRIPTING_TIMEOUT_MS))) { + set_status(AP_Proximity::Status::NoData); + } else { + set_status(AP_Proximity::Status::Good); + } +} + +// Set max and min range of the sensor. Only needs to be set once +bool AP_Proximity_Scripting::set_distance_min_max(float min, float max) +{ + if (min >= max) { + return false; + } + _distance_min = min; + _distance_max = max; + return true; +} + +// get distance upwards in meters. returns true on success +bool AP_Proximity_Scripting::get_upward_distance(float &distance) const +{ + if ((_last_upward_update_ms != 0) && (AP_HAL::millis() - _last_upward_update_ms <= PROXIMITY_SCRIPTING_TIMEOUT_MS)) { + distance = _distance_upward; + return true; + } + return false; +} + +// handle script distance messages +bool AP_Proximity_Scripting::handle_script_distance_msg(float dist_m, float yaw_deg, float pitch_deg, bool push_to_boundary) +{ + _last_update_ms = AP_HAL::millis(); + + Vector3f current_pos; + Matrix3f body_to_ned; + const bool database_ready = database_prepare_for_push(current_pos, body_to_ned); + + if (dist_m < distance_min() || dist_m > distance_max() || is_zero(dist_m)) { + // message isn't healthy + return false; + } + + // store upward distance + if (is_equal(pitch_deg, 90.f)) { + _distance_upward = dist_m; + _last_upward_update_ms = _last_update_ms; + return true; + } + + yaw_deg = correct_angle_for_orientation(yaw_deg); + + if (ignore_reading(pitch_deg, yaw_deg, dist_m, false)) { + // obstacle is probably near ground or out of range + return false; + } + + // allot to correct layer and sector based on calculated pitch and yaw + const AP_Proximity_Boundary_3D::Face face = frontend.boundary.get_face(pitch_deg, yaw_deg); + + // add to temp boundary + temp_boundary.add_distance(face, pitch_deg, yaw_deg, dist_m); + + if (push_to_boundary) { + temp_boundary.update_3D_boundary(state.instance, frontend.boundary); + temp_boundary.reset(); + } + + if (database_ready) { + database_push(yaw_deg, pitch_deg, dist_m, _last_update_ms, current_pos, body_to_ned); + } + + return true; +} + +// handle script vector messages +bool AP_Proximity_Scripting::handle_script_3d_msg(const Vector3f &vec_to_obstacle, bool push_to_boundary) +{ + // convert to FRU + const Vector3f obstacle(vec_to_obstacle.x, vec_to_obstacle.y, vec_to_obstacle.z * -1.0f); + + // extract yaw and pitch from Obstacle Vector + const float yaw = wrap_360(degrees(atan2f(obstacle.y, obstacle.x))); + const float pitch = wrap_180(degrees(M_PI_2 - atan2f(obstacle.xy().length(), obstacle.z))); + + // now simply handle as a distance msg + return handle_script_distance_msg(obstacle.length(), yaw, pitch, push_to_boundary); +} + +// update the temporary (buffer) boundary +bool AP_Proximity_Scripting::update_virtual_boundary() +{ + temp_boundary.update_3D_boundary(state.instance, frontend.boundary); + temp_boundary.reset(); + return true; +} + +#endif // HAL_PROXIMITY_ENABLED && AP_SCRIPTING_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_Scripting.h b/libraries/AP_Proximity/AP_Proximity_Scripting.h new file mode 100644 index 00000000000000..2aa13efeac05cf --- /dev/null +++ b/libraries/AP_Proximity/AP_Proximity_Scripting.h @@ -0,0 +1,51 @@ +#pragma once + +#include "AP_Proximity_Backend.h" + +#if HAL_PROXIMITY_ENABLED && AP_SCRIPTING_ENABLED + +class AP_Proximity_Scripting : public AP_Proximity_Backend +{ + +public: + // constructor + using AP_Proximity_Backend::AP_Proximity_Backend; + + // update state + void update(void) override; + + // get maximum and minimum distances (in meters) of sensor + float distance_max() const override { return _distance_max; } + float distance_min() const override { return _distance_min; } + + // Set max and min range of the sensor. only needs to be set once + bool set_distance_min_max(float min, float max) override; + + // get distance upwards in meters. returns true on success + bool get_upward_distance(float &distance) const override; + + // handle script messages + bool handle_script_distance_msg(float dist_m, float yaw_deg, float pitch_deg, bool push_to_boundary) override; + bool handle_script_3d_msg(const Vector3f &vec_to_obstacle, bool push_to_boundary) override; + + // update the temporary (buffer) boundary + bool update_virtual_boundary() override; + +private: + + // temp boundary to store and sort distances + AP_Proximity_Temp_Boundary temp_boundary; + + // horizontal distance support + uint32_t _last_update_ms; // system time of last script message received + + // upward distance support + uint32_t _last_upward_update_ms; // system time of last update of upward distance + float _distance_upward; // upward distance in meters + + // min and max distance of sensor + float _distance_min; + float _distance_max; +}; + +#endif // HAL_PROXIMITY_ENABLED && AP_SCRIPTING_ENABLED diff --git a/libraries/AP_Proximity/AP_Proximity_config.h b/libraries/AP_Proximity/AP_Proximity_config.h index cf9923b36f8d16..a2130b0b5c4f25 100644 --- a/libraries/AP_Proximity/AP_Proximity_config.h +++ b/libraries/AP_Proximity/AP_Proximity_config.h @@ -24,6 +24,11 @@ #define AP_PROXIMITY_DRONECAN_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS #endif + +#ifndef AP_PROXIMITY_LD06_ENABLED +#define AP_PROXIMITY_LD06_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED +#endif + #ifndef AP_PROXIMITY_LIGHTWARE_SF40C_ENABLED #define AP_PROXIMITY_LIGHTWARE_SF40C_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED #endif @@ -32,6 +37,10 @@ #define AP_PROXIMITY_LIGHTWARE_SF45B_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED #endif +#ifndef AP_PROXIMITY_SCRIPTING_ENABLED +#define AP_PROXIMITY_SCRIPTING_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED && AP_SCRIPTING_ENABLED +#endif + #ifndef AP_PROXIMITY_MAV_ENABLED #define AP_PROXIMITY_MAV_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED #endif @@ -55,3 +64,7 @@ #ifndef AP_PROXIMITY_TERARANGERTOWEREVO_ENABLED #define AP_PROXIMITY_TERARANGERTOWEREVO_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED #endif + +#ifndef AP_PROXIMITY_LD06_ENABLED +#define AP_PROXIMITY_LD06_ENABLED AP_PROXIMITY_BACKEND_DEFAULT_ENABLED +#endif diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.cpp b/libraries/AP_RCProtocol/AP_RCProtocol.cpp index 4b02171695b583..9c8ef679a1643b 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol.cpp @@ -32,6 +32,7 @@ #include "AP_RCProtocol_ST24.h" #include "AP_RCProtocol_FPort.h" #include "AP_RCProtocol_FPort2.h" +#include "AP_RCProtocol_DroneCAN.h" #include #include @@ -78,6 +79,9 @@ void AP_RCProtocol::init() #if AP_RCPROTOCOL_FPORT_ENABLED backend[AP_RCProtocol::FPORT] = new AP_RCProtocol_FPort(*this, true); #endif +#if AP_RCPROTOCOL_DRONECAN_ENABLED + backend[AP_RCProtocol::DRONECAN] = new AP_RCProtocol_DroneCAN(*this); +#endif } AP_RCProtocol::~AP_RCProtocol() @@ -359,9 +363,6 @@ void AP_RCProtocol::update() bool AP_RCProtocol::new_input() { - bool ret = _new_input; - _new_input = false; - // if we have an extra UART from a SERIALn_PROTOCOL then check it for data check_added_uart(); @@ -371,6 +372,25 @@ bool AP_RCProtocol::new_input() backend[i]->update(); } } + +#if AP_RCPROTOCOL_DRONECAN_ENABLED + uint32_t now = AP_HAL::millis(); + if (should_search(now)) { + if (backend[AP_RCProtocol::DRONECAN] != nullptr && + backend[AP_RCProtocol::DRONECAN]->new_input()) { + _detected_protocol = AP_RCProtocol::DRONECAN; + _last_input_ms = now; + } + } else if (_detected_protocol == AP_RCProtocol::DRONECAN) { + _new_input = backend[AP_RCProtocol::DRONECAN]->new_input(); + if (_new_input) { + _last_input_ms = now; + } + } +#endif + + bool ret = _new_input; + _new_input = false; return ret; } @@ -480,6 +500,10 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol) #if AP_RCPROTOCOL_FPORT2_ENABLED case FPORT2: return "FPORT2"; +#endif +#if AP_RCPROTOCOL_DRONECAN_ENABLED + case DRONECAN: + return "DroneCAN"; #endif case NONE: break; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.h b/libraries/AP_RCProtocol/AP_RCProtocol.h index ca219f5d8580de..eeacb6fa0a0b62 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol.h @@ -66,6 +66,9 @@ class AP_RCProtocol { #endif #if AP_RCPROTOCOL_FASTSBUS_ENABLED FASTSBUS = 12, +#endif +#if AP_RCPROTOCOL_DRONECAN_ENABLED + DRONECAN = 13, #endif NONE //last enum always is None }; @@ -142,6 +145,9 @@ class AP_RCProtocol { #endif #if AP_RCPROTOCOL_ST24_ENABLED case ST24: +#endif +#if AP_RCPROTOCOL_DRONECAN_ENABLED + case DRONECAN: #endif case NONE: return false; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp index 9575ab22f74757..7c61f5355d3735 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp @@ -178,7 +178,8 @@ void AP_RCProtocol_Backend::configure_vtx(uint8_t band, uint8_t channel, uint8_t */ void AP_RCProtocol_Backend::log_data(AP_RCProtocol::rcprotocol_t prot, uint32_t timestamp, const uint8_t *data, uint8_t len) const { -#if HAL_LOGGING_ENABLED +#if HAL_LOGGING_ENABLED && AP_RC_CHANNEL_ENABLED + #if (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX) if (&rc() == nullptr) { // allow running without RC_Channels if we are doing the examples return; @@ -214,7 +215,7 @@ void AP_RCProtocol_Backend::log_data(AP_RCProtocol::rcprotocol_t prot, uint32_t u32[0], u32[1], u32[2], u32[3], u32[4], u32[5], u32[6], u32[7], u32[8], u32[9]); } -#endif // HAL_LOGGING_ENABLED +#endif // HAL_LOGGING_ENABLED && AP_RC_CHANNEL_ENABLED } #endif // AP_RCPROTOCOL_ENABLED diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h index 474a3ab20c580a..cbb0b1135be712 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h @@ -122,7 +122,7 @@ class AP_RCProtocol_Backend { void log_data(AP_RCProtocol::rcprotocol_t prot, uint32_t timestamp, const uint8_t *data, uint8_t len) const; // decode channels from the standard 11bit format (used by CRSF and SBUS) - void decode_11bit_channels(const uint8_t* data, uint8_t nchannels, uint16_t *values, uint16_t mult, uint16_t div, uint16_t offset); + static void decode_11bit_channels(const uint8_t* data, uint8_t nchannels, uint16_t *values, uint16_t mult, uint16_t div, uint16_t offset); private: uint32_t rc_input_count; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.cpp new file mode 100644 index 00000000000000..879344e3236cee --- /dev/null +++ b/libraries/AP_RCProtocol/AP_RCProtocol_DroneCAN.cpp @@ -0,0 +1,103 @@ +#include "AP_RCProtocol_config.h" + +#if AP_RCPROTOCOL_DRONECAN_ENABLED + +#include +#include +#include +#include "AP_RCProtocol_DroneCAN.h" + +extern const AP_HAL::HAL& hal; + +#define LOG_TAG "RCInput" + +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) +{ + if (ap_dronecan == nullptr) { + return; + } + + if (Canard::allocate_sub_arg_callback(ap_dronecan, &handle_rcinput, ap_dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("rc_sub"); + } +} + +AP_RCProtocol_DroneCAN* AP_RCProtocol_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id) +{ + if (_singleton == nullptr) { + return nullptr; + } + + if (ap_dronecan == nullptr) { + return nullptr; + } + + for (auto &device : registry.detected_devices) { + if (device.driver == nullptr) { + continue; + } + if (device.ap_dronecan != ap_dronecan) { + continue; + } + if (device.node_id != node_id ) { + continue; + } + return device.driver; + } + + // not found in registry; add it if possible. + for (auto &device : registry.detected_devices) { + if (device.ap_dronecan == nullptr) { + device.ap_dronecan = ap_dronecan; + device.node_id = node_id; + device.driver = _singleton; + return device.driver; + } + } + + return nullptr; +} + +void AP_RCProtocol_DroneCAN::handle_rcinput(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_rc_RCInput &msg) +{ + AP_RCProtocol_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id); + if (driver == nullptr) { + return; + } + + auto &rcin = driver->rcin; + WITH_SEMAPHORE(rcin.sem); + rcin.quality = msg.quality; + rcin.status = msg.status; + rcin.num_channels = MIN(msg.rcin.len, ARRAY_SIZE(rcin.channels)); + for (auto i=0; i + +#include + +class AP_RCProtocol_DroneCAN : public AP_RCProtocol_Backend { +public: + + AP_RCProtocol_DroneCAN(AP_RCProtocol &_frontend) : + AP_RCProtocol_Backend(_frontend) { + _singleton = this; + } + + static void subscribe_msgs(AP_DroneCAN* ap_dronecan); + + void update() override; + +private: + + static class AP_RCProtocol_DroneCAN *_singleton; + + static void handle_rcinput(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const dronecan_sensors_rc_RCInput &msg); + + static AP_RCProtocol_DroneCAN* get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id); + + struct { + uint8_t quality; + union { + uint16_t status; + struct { + uint8_t QUALITY_VALID : 1; + uint8_t FAILSAFE : 1; + } bits; + }; + uint8_t num_channels; + uint16_t channels[MAX_RCIN_CHANNELS]; + + uint32_t last_sample_time_ms; + HAL_Semaphore sem; + } rcin; + + // Module Detection Registry + static struct Registry { + struct DetectedDevice { + AP_DroneCAN* ap_dronecan; + uint8_t node_id; + AP_RCProtocol_DroneCAN *driver; + } detected_devices[1]; + HAL_Semaphore sem; + } registry; + + uint32_t last_receive_ms; +}; + + +#endif // AP_RCPROTOCOL_DRONECAN_ENABLED diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp index a9037ad8f84189..08bc5a06fa7912 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp @@ -103,7 +103,7 @@ void AP_RCProtocol_FPort::decode_control(const FPort_Frame &frame) */ void AP_RCProtocol_FPort::decode_downlink(const FPort_Frame &frame) { -#if !APM_BUILD_TYPE(APM_BUILD_iofirmware) +#if !APM_BUILD_TYPE(APM_BUILD_iofirmware) && AP_FRSKY_SPORT_TELEM_ENABLED switch (frame.downlink.prim) { case FPORT_PRIM_DATA: // we've seen at least one 0x10 frame diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.h b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.h index e1287a212ae6e6..a060c3b6a6a076 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.h @@ -53,10 +53,12 @@ class AP_RCProtocol_FPort : public AP_RCProtocol_Backend { const bool inverted; +#if AP_FRSKY_SPORT_TELEM_ENABLED struct { bool available = false; AP_Frsky_SPort::sport_packet_t packet; } telem_data; +#endif // AP_FRSKY_SPORT_TELEM_ENABLED // receiver sends 0x10 when ready to receive telemetry frames (R-XSR) bool rx_driven_frame_rate = false; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp index 7b860f66810ebf..b3d30b27bfe005 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp @@ -88,7 +88,7 @@ AP_RCProtocol_SBUS::AP_RCProtocol_SBUS(AP_RCProtocol &_frontend, bool _inverted, // decode a full SBUS frame bool AP_RCProtocol_SBUS::sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values, - bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values) + bool &sbus_failsafe, uint16_t max_values) { /* check frame boundary markers to avoid out-of-sync cases */ if ((frame[0] != 0x0f)) { @@ -97,7 +97,7 @@ bool AP_RCProtocol_SBUS::sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t chancount = SBUS_INPUT_CHANNELS; - decode_11bit_channels((const uint8_t*)(&frame[1]), SBUS_INPUT_CHANNELS, values, + decode_11bit_channels((const uint8_t*)(&frame[1]), max_values, values, SBUS_TARGET_RANGE, SBUS_RANGE_RANGE, SBUS_SCALE_OFFSET); /* decode switch channels if data fields are wide enough */ @@ -113,11 +113,25 @@ bool AP_RCProtocol_SBUS::sbus_decode(const uint8_t frame[25], uint16_t *values, /* note the number of channels decoded */ *num_values = chancount; + /* + as SBUS is such a weak protocol we additionally check if any of + the first 4 channels are at or below the minimum value of + 875. We consider the frame as a failsafe in that case, which + means we log the data but won't use it + */ + bool invalid_data = false; + for (uint8_t i=0; i<4; i++) { + if (values[i] <= SBUS_SCALE_OFFSET) { + invalid_data = true; + } + } + /* decode and handle failsafe and frame-lost flags */ if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */ /* report that we failed to read anything valid off the receiver */ - *sbus_failsafe = true; - *sbus_frame_drop = true; + sbus_failsafe = true; + } else if (invalid_data) { + sbus_failsafe = true; } else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */ /* set a special warning flag * @@ -125,11 +139,9 @@ bool AP_RCProtocol_SBUS::sbus_decode(const uint8_t frame[25], uint16_t *values, * condition as fail-safe greatly reduces the reliability and range of the radio link, * e.g. by prematurely issuing return-to-launch!!! */ - *sbus_failsafe = false; - *sbus_frame_drop = true; + sbus_failsafe = false; } else { - *sbus_failsafe = false; - *sbus_frame_drop = false; + sbus_failsafe = false; } return true; @@ -181,9 +193,8 @@ void AP_RCProtocol_SBUS::_process_byte(uint32_t timestamp_us, uint8_t b) uint16_t values[SBUS_INPUT_CHANNELS]; uint16_t num_values=0; bool sbus_failsafe = false; - bool sbus_frame_drop = false; if (sbus_decode(byte_input.buf, values, &num_values, - &sbus_failsafe, &sbus_frame_drop, SBUS_INPUT_CHANNELS) && + sbus_failsafe, SBUS_INPUT_CHANNELS) && num_values >= MIN_RCIN_CHANNELS) { add_input(num_values, values, sbus_failsafe); } diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.h b/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.h index c9c43a052b38e7..c830372e21a604 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_SBUS.h @@ -30,10 +30,11 @@ class AP_RCProtocol_SBUS : public AP_RCProtocol_Backend { void process_pulse(uint32_t width_s0, uint32_t width_s1) override; void process_byte(uint8_t byte, uint32_t baudrate) override; + static bool sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values, + bool &sbus_failsafe, uint16_t max_values); + private: void _process_byte(uint32_t timestamp_us, uint8_t byte); - bool sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values, - bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values); bool inverted; SoftSerial ss; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_config.h b/libraries/AP_RCProtocol/AP_RCProtocol_config.h index 959dae61d5d227..5619c5373c0819 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_config.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_config.h @@ -15,8 +15,12 @@ #define AP_RCPROTOCOL_CRSF_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED #endif +#ifndef AP_RCPROTOCOL_DRONECAN_ENABLED +#define AP_RCPROTOCOL_DRONECAN_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS +#endif + #ifndef AP_RCPROTOCOL_FPORT_ENABLED -#define AP_RCPROTOCOL_FPORT_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED +#define AP_RCPROTOCOL_FPORT_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED #endif #ifndef AP_RCPROTOCOL_FPORT2_ENABLED #define AP_RCPROTOCOL_FPORT2_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_FRSKY_SPORT_TELEM_ENABLED diff --git a/libraries/AP_RCProtocol/tests/test_sbus.cpp b/libraries/AP_RCProtocol/tests/test_sbus.cpp new file mode 100644 index 00000000000000..9908d1b18e6ecd --- /dev/null +++ b/libraries/AP_RCProtocol/tests/test_sbus.cpp @@ -0,0 +1,46 @@ +/* + test that SBUS decoding matches SBUS encoding + */ +#include +#include +#include +#include + +#define SBUS_RANGE_MIN 200 +#define SBUS_RANGE_MAX 1800 +#define SBUS_RANGE_RANGE (SBUS_RANGE_MAX - SBUS_RANGE_MIN) + +#define SBUS_TARGET_MIN 1000 +#define SBUS_TARGET_MAX 2000 +#define SBUS_TARGET_RANGE (SBUS_TARGET_MAX - SBUS_TARGET_MIN) + +// this is 875 +#define SBUS_SCALE_OFFSET (SBUS_TARGET_MIN - ((SBUS_TARGET_RANGE * SBUS_RANGE_MIN / SBUS_RANGE_RANGE))) + +TEST(SBUSEncodeDecode, test_sbus_encode_decode) +{ + const uint8_t num_channels = 8; + uint16_t values_in[num_channels]; + uint16_t values_out[num_channels]; + uint8_t frame[25]; + + for (uint16_t v=875;v<2155; v++) { + for (uint8_t i=0; iis_initialized()) { return false; } - - // warn the user if their setup is sub-optimal +#if !defined (STM32H7) + // warn the user if their setup is sub-optimal, H7 does not need DMA on serial port if (_telem_bootstrap_msg_pending && !uart->is_dma_enabled()) { - gcs().send_text(MAV_SEVERITY_WARNING, "%s: running on non-DMA serial port", get_protocol_string()); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s: running on non-DMA serial port", get_protocol_string()); } +#endif // note if option was set to show LQ in place of RSSI bool current_lq_as_rssi_active = rc().option_is_enabled(RC_Channels::Option::USE_CRSF_LQ_AS_RSSI); if(_telem_bootstrap_msg_pending || _noted_lq_as_rssi_active != current_lq_as_rssi_active){ _noted_lq_as_rssi_active = current_lq_as_rssi_active; - gcs().send_text(MAV_SEVERITY_INFO, "%s: RSSI now displays %s", get_protocol_string(), current_lq_as_rssi_active ? " as LQ" : "normally"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s: RSSI now displays %s", get_protocol_string(), current_lq_as_rssi_active ? " as LQ" : "normally"); } _telem_bootstrap_msg_pending = false; @@ -209,7 +210,7 @@ bool AP_CRSF_Telem::process_rf_mode_changes() if ((now - _telem_last_report_ms > 5000)) { // report an RF mode change or a change in telemetry rate if we haven't done so in the last 5s if (!rc().option_is_enabled(RC_Channels::Option::SUPPRESS_CRSF_MESSAGE) && (_telem_rf_mode != current_rf_mode || abs(int16_t(_telem_last_avg_rate) - int16_t(_scheduler.avg_packet_rate)) > 25)) { - gcs().send_text(MAV_SEVERITY_INFO, "%s: Link rate %dHz, Telemetry rate %dHz", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s: Link rate %dHz, Telemetry rate %dHz", get_protocol_string(), crsf->get_link_rate(_crsf_version.protocol), get_telemetry_rate()); } // tune the scheduler based on telemetry speed high/low transitions @@ -464,10 +465,10 @@ void AP_CRSF_Telem::process_packet(uint8_t idx) _crsf_version.minor = 0; _crsf_version.major = 0; disable_scheduler_entry(VERSION_PING); - gcs().send_text(MAV_SEVERITY_DEBUG,"%s: RX device ping failed", get_protocol_string()); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG,"%s: RX device ping failed", get_protocol_string()); } else { calc_device_ping(AP_RCProtocol_CRSF::CRSF_ADDRESS_CRSF_RECEIVER); - gcs().send_text(MAV_SEVERITY_DEBUG,"%s: requesting RX device info", get_protocol_string()); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG,"%s: requesting RX device info", get_protocol_string()); } break; case DEVICE_PING: diff --git a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp index efc5b26e3254f2..c57c3d35cefe17 100644 --- a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp +++ b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp @@ -39,7 +39,7 @@ extern const AP_HAL::HAL& hal; */ bool AP_RCTelemetry::init(void) { -#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) +#if HAL_GCS_ENABLED && !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) // make telemetry available to GCS_MAVLINK (used to queue statustext messages from GCS_MAVLINK) // add firmware and frame info to message queue const char* _frame_string = gcs().frame_string(); @@ -283,7 +283,13 @@ uint32_t AP_RCTelemetry::sensor_status_flags() const uint32_t present; uint32_t enabled; uint32_t health; +#if HAL_GCS_ENABLED gcs().get_sensor_status_flags(present, enabled, health); +#else + present = 0; + enabled = 0; + health = 0; +#endif return ~health & enabled & present; } diff --git a/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp b/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp index c1d81848a94e50..3e669206ec847f 100644 --- a/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_Spektrum_Telem.cpp @@ -544,7 +544,15 @@ void AP_Spektrum_Telem::calc_gps_status() _telem.gpsstat.speed = ((knots % 10000 / 1000) << 12) | ((knots % 1000 / 100) << 8) | ((knots % 100 / 10) << 4) | (knots % 10); // BCD, knots, format 3.1 uint16_t ms; uint8_t h, m, s; +#if AP_RTC_ENABLED AP::rtc().get_system_clock_utc(h, m, s, ms); // BCD, format HH:MM:SS.S, format 6.1 + // FIXME: the above call can fail! +#else + h = 0; + m = 0; + s = 0; + ms = 0; +#endif _telem.gpsstat.UTC = ((((h / 10) << 4) | (h % 10)) << 20) | ((((m / 10) << 4) | (m % 10)) << 12) | ((((s / 10) << 4) | (s % 10)) << 4) | (ms / 100) ; uint8_t nsats = AP::gps().num_sats(); _telem.gpsstat.numSats = ((nsats / 10) << 4) | (nsats % 10); // BCD, 0-99 diff --git a/libraries/AP_RPM/AP_RPM.cpp b/libraries/AP_RPM/AP_RPM.cpp index 11c1bd89e8b3e1..ef0061553eaa7f 100644 --- a/libraries/AP_RPM/AP_RPM.cpp +++ b/libraries/AP_RPM/AP_RPM.cpp @@ -17,6 +17,7 @@ #if AP_RPM_ENABLED +#include "RPM_Backend.h" #include "RPM_Pin.h" #include "RPM_SITL.h" #include "RPM_EFI.h" @@ -199,6 +200,10 @@ void AP_RPM::update(void) } drivers[i]->update(); + +#if AP_RPM_ESC_TELEM_OUTBOUND_ENABLED + drivers[i]->update_esc_telem_outbound(); +#endif } } diff --git a/libraries/AP_RPM/AP_RPM.h b/libraries/AP_RPM/AP_RPM.h index 82df5e21eb0dc2..6a6b0e48175705 100644 --- a/libraries/AP_RPM/AP_RPM.h +++ b/libraries/AP_RPM/AP_RPM.h @@ -24,9 +24,6 @@ #include #include "AP_RPM_Params.h" -// Maximum number of RPM measurement instances available on this platform -#define RPM_MAX_INSTANCES 2 - class AP_RPM_Backend; class AP_RPM diff --git a/libraries/AP_RPM/AP_RPM_Params.cpp b/libraries/AP_RPM/AP_RPM_Params.cpp index 8a3419594e3d1f..1d58d41eb693b2 100644 --- a/libraries/AP_RPM/AP_RPM_Params.cpp +++ b/libraries/AP_RPM/AP_RPM_Params.cpp @@ -68,6 +68,16 @@ const AP_Param::GroupInfo AP_RPM_Params::var_info[] = { // @User: Advanced AP_GROUPINFO("ESC_MASK", 7, AP_RPM_Params, esc_mask, 0), +#if AP_RPM_ESC_TELEM_OUTBOUND_ENABLED + // @Param: ESC_INDEX + // @DisplayName: ESC Telemetry Index to write RPM to + // @Description: ESC Telemetry Index to write RPM to. Use 0 to disable. + // @Range: 0 10 + // @Increment: 1 + // @User: Advanced + AP_GROUPINFO("ESC_INDEX", 8, AP_RPM_Params, esc_telem_outbound_index, 0), +#endif + AP_GROUPEND }; diff --git a/libraries/AP_RPM/AP_RPM_Params.h b/libraries/AP_RPM/AP_RPM_Params.h index c6f5d77adb3637..591bd76e7fdaad 100644 --- a/libraries/AP_RPM/AP_RPM_Params.h +++ b/libraries/AP_RPM/AP_RPM_Params.h @@ -14,6 +14,7 @@ */ #pragma once #include +#include "AP_RPM_config.h" class AP_RPM_Params { @@ -29,6 +30,9 @@ class AP_RPM_Params { AP_Float minimum; AP_Float quality_min; AP_Int32 esc_mask; +#if AP_RPM_ESC_TELEM_OUTBOUND_ENABLED + AP_Int8 esc_telem_outbound_index; +#endif static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AP_RPM/AP_RPM_config.h b/libraries/AP_RPM/AP_RPM_config.h index 2e58881677b378..bda4d1c8e36444 100644 --- a/libraries/AP_RPM/AP_RPM_config.h +++ b/libraries/AP_RPM/AP_RPM_config.h @@ -4,11 +4,17 @@ #include #include +#include +#include #ifndef AP_RPM_ENABLED #define AP_RPM_ENABLED 1 #endif +#ifndef RPM_MAX_INSTANCES +#define RPM_MAX_INSTANCES 2 +#endif + #ifndef AP_RPM_BACKEND_DEFAULT_ENABLED #define AP_RPM_BACKEND_DEFAULT_ENABLED AP_RPM_ENABLED #endif @@ -18,11 +24,11 @@ #endif #ifndef AP_RPM_ESC_TELEM_ENABLED -#define AP_RPM_ESC_TELEM_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED +#define AP_RPM_ESC_TELEM_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && HAL_WITH_ESC_TELEM #endif #ifndef AP_RPM_HARMONICNOTCH_ENABLED -#define AP_RPM_HARMONICNOTCH_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED +#define AP_RPM_HARMONICNOTCH_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && AP_INERTIALSENSOR_ENABLED #endif #ifndef AP_RPM_PIN_ENABLED @@ -36,3 +42,7 @@ #ifndef AP_RPM_GENERATOR_ENABLED #define AP_RPM_GENERATOR_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && HAL_GENERATOR_ENABLED #endif + +#ifndef AP_RPM_ESC_TELEM_OUTBOUND_ENABLED +#define AP_RPM_ESC_TELEM_OUTBOUND_ENABLED AP_RPM_BACKEND_DEFAULT_ENABLED && HAL_WITH_ESC_TELEM +#endif diff --git a/libraries/AP_RPM/RPM_Backend.cpp b/libraries/AP_RPM/RPM_Backend.cpp index 9c90fb56a54e59..a04778fd37f13c 100644 --- a/libraries/AP_RPM/RPM_Backend.cpp +++ b/libraries/AP_RPM/RPM_Backend.cpp @@ -19,6 +19,10 @@ #include "AP_RPM.h" +#if HAL_WITH_ESC_TELEM +#include "AP_ESC_Telem/AP_ESC_Telem.h" +#endif + /* base class constructor. */ @@ -29,4 +33,22 @@ AP_RPM_Backend::AP_RPM_Backend(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_St state.instance = instance; } +#if AP_RPM_ESC_TELEM_OUTBOUND_ENABLED +void AP_RPM_Backend::update_esc_telem_outbound() +{ + const uint8_t esc_index = ap_rpm._params[state.instance].esc_telem_outbound_index; + if (esc_index == 0) { + // Disabled if there's no ESC identified to route the data to + return; + } + if (!ap_rpm.healthy(state.instance)) { + // If we're unhealthy don't update the telemetry. Let it + // timeout on it's own instead of showing potentially wrong data + return; + } + + AP::esc_telem().update_rpm(esc_index-1, state.rate_rpm, 0); +} +#endif + #endif // AP_RPM_ENABLED diff --git a/libraries/AP_RPM/RPM_Backend.h b/libraries/AP_RPM/RPM_Backend.h index 7c2726c7edbe24..1ba4625da537d5 100644 --- a/libraries/AP_RPM/RPM_Backend.h +++ b/libraries/AP_RPM/RPM_Backend.h @@ -38,6 +38,8 @@ class AP_RPM_Backend return ap_rpm._params[state.instance].pin.get(); } + void update_esc_telem_outbound(); + protected: AP_RPM &ap_rpm; diff --git a/libraries/AP_RPM/RPM_EFI.cpp b/libraries/AP_RPM/RPM_EFI.cpp index 1cfa0ad0118381..82e126bf3cea45 100644 --- a/libraries/AP_RPM/RPM_EFI.cpp +++ b/libraries/AP_RPM/RPM_EFI.cpp @@ -13,19 +13,14 @@ along with this program. If not, see . */ -#include - -#include "RPM_EFI.h" +#include "AP_RPM_config.h" #if AP_RPM_EFI_ENABLED +#include "RPM_EFI.h" +#include #include -AP_RPM_EFI::AP_RPM_EFI(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) : - AP_RPM_Backend(_ap_rpm, _instance, _state) -{ -} - void AP_RPM_EFI::update(void) { AP_EFI *efi = AP::EFI(); diff --git a/libraries/AP_RPM/RPM_EFI.h b/libraries/AP_RPM/RPM_EFI.h index 76710a300932c6..9d5ef49d25ec30 100644 --- a/libraries/AP_RPM/RPM_EFI.h +++ b/libraries/AP_RPM/RPM_EFI.h @@ -14,7 +14,7 @@ */ #pragma once -#include "AP_RPM.h" +#include "AP_RPM_config.h" #if AP_RPM_EFI_ENABLED @@ -23,13 +23,13 @@ class AP_RPM_EFI : public AP_RPM_Backend { public: + // constructor - AP_RPM_EFI(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state); + using AP_RPM_Backend::AP_RPM_Backend; // update state void update(void) override; -private: }; #endif diff --git a/libraries/AP_RPM/RPM_ESC_Telem.cpp b/libraries/AP_RPM/RPM_ESC_Telem.cpp index 97a12770e93138..ea44ea29e9a98b 100644 --- a/libraries/AP_RPM/RPM_ESC_Telem.cpp +++ b/libraries/AP_RPM/RPM_ESC_Telem.cpp @@ -13,33 +13,21 @@ along with this program. If not, see . */ -#include -#include - -#include "RPM_ESC_Telem.h" +#include "AP_RPM_config.h" #if AP_RPM_ESC_TELEM_ENABLED -extern const AP_HAL::HAL& hal; - -/* - open the sensor in constructor -*/ -AP_RPM_ESC_Telem::AP_RPM_ESC_Telem(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) : - AP_RPM_Backend(_ap_rpm, _instance, _state) -{ -} - +#include +#include "RPM_ESC_Telem.h" +#include void AP_RPM_ESC_Telem::update(void) { -#if HAL_WITH_ESC_TELEM AP_ESC_Telem &esc_telem = AP::esc_telem(); float esc_rpm = esc_telem.get_average_motor_rpm(ap_rpm._params[state.instance].esc_mask); state.rate_rpm = esc_rpm * ap_rpm._params[state.instance].scaling; state.signal_quality = 0.5f; state.last_reading_ms = AP_HAL::millis(); -#endif } #endif // AP_RPM_ESC_TELEM_ENABLED diff --git a/libraries/AP_RPM/RPM_ESC_Telem.h b/libraries/AP_RPM/RPM_ESC_Telem.h index e8ef243871a360..f9ebb632db874c 100644 --- a/libraries/AP_RPM/RPM_ESC_Telem.h +++ b/libraries/AP_RPM/RPM_ESC_Telem.h @@ -14,16 +14,17 @@ */ #pragma once -#include "AP_RPM.h" -#include "RPM_Backend.h" +#include "AP_RPM_config.h" #if AP_RPM_ESC_TELEM_ENABLED +#include "RPM_Backend.h" + class AP_RPM_ESC_Telem : public AP_RPM_Backend { public: // constructor - AP_RPM_ESC_Telem(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state); + using AP_RPM_Backend::AP_RPM_Backend; // update state void update(void) override; diff --git a/libraries/AP_RPM/RPM_Generator.cpp b/libraries/AP_RPM/RPM_Generator.cpp index 81b087f20f5a8e..0ed375d0cbb405 100644 --- a/libraries/AP_RPM/RPM_Generator.cpp +++ b/libraries/AP_RPM/RPM_Generator.cpp @@ -13,12 +13,12 @@ along with this program. If not, see . */ -#include - -#include "RPM_Generator.h" +#include "AP_RPM_config.h" #if AP_RPM_GENERATOR_ENABLED -extern const AP_HAL::HAL& hal; + +#include "RPM_Generator.h" +#include void AP_RPM_Generator::update(void) { diff --git a/libraries/AP_RPM/RPM_Generator.h b/libraries/AP_RPM/RPM_Generator.h index 627fc8ae9c0884..a9da14a121509b 100644 --- a/libraries/AP_RPM/RPM_Generator.h +++ b/libraries/AP_RPM/RPM_Generator.h @@ -14,12 +14,12 @@ */ #pragma once -#include "AP_RPM.h" -#include "RPM_Backend.h" -#include +#include "AP_RPM_config.h" #if AP_RPM_GENERATOR_ENABLED +#include "RPM_Backend.h" + class AP_RPM_Generator : public AP_RPM_Backend { public: diff --git a/libraries/AP_RPM/RPM_HarmonicNotch.cpp b/libraries/AP_RPM/RPM_HarmonicNotch.cpp index e5dbbe766cfed8..8fba5499178d31 100644 --- a/libraries/AP_RPM/RPM_HarmonicNotch.cpp +++ b/libraries/AP_RPM/RPM_HarmonicNotch.cpp @@ -13,18 +13,15 @@ along with this program. If not, see . */ -#include "RPM_HarmonicNotch.h" +#include "AP_RPM_config.h" #if AP_RPM_HARMONICNOTCH_ENABLED +#include "RPM_HarmonicNotch.h" + #include #include -AP_RPM_HarmonicNotch::AP_RPM_HarmonicNotch(AP_RPM &_ap_rpm, uint8_t _instance, AP_RPM::RPM_State &_state) : - AP_RPM_Backend(_ap_rpm, _instance, _state) -{ -} - void AP_RPM_HarmonicNotch::update(void) { const AP_InertialSensor& ins = AP::ins(); diff --git a/libraries/AP_RPM/RPM_HarmonicNotch.h b/libraries/AP_RPM/RPM_HarmonicNotch.h index 81d13a4cfa879f..5ea617f30d93a2 100644 --- a/libraries/AP_RPM/RPM_HarmonicNotch.h +++ b/libraries/AP_RPM/RPM_HarmonicNotch.h @@ -14,16 +14,17 @@ */ #pragma once -#include "AP_RPM.h" -#include "RPM_Backend.h" +#include "AP_RPM_config.h" #if AP_RPM_HARMONICNOTCH_ENABLED +#include "RPM_Backend.h" + class AP_RPM_HarmonicNotch : public AP_RPM_Backend { public: // constructor - AP_RPM_HarmonicNotch(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state); + using AP_RPM_Backend::AP_RPM_Backend; // update state void update(void) override; diff --git a/libraries/AP_RPM/RPM_Pin.cpp b/libraries/AP_RPM/RPM_Pin.cpp index 91cea52ccbb538..43d9443eb54090 100644 --- a/libraries/AP_RPM/RPM_Pin.cpp +++ b/libraries/AP_RPM/RPM_Pin.cpp @@ -13,26 +13,20 @@ along with this program. If not, see . */ -#include "RPM_Pin.h" +#include "AP_RPM_config.h" #if AP_RPM_PIN_ENABLED -#include +#include "RPM_Pin.h" +#include #include #include +#include extern const AP_HAL::HAL& hal; AP_RPM_Pin::IrqState AP_RPM_Pin::irq_state[RPM_MAX_INSTANCES]; -/* - open the sensor in constructor -*/ -AP_RPM_Pin::AP_RPM_Pin(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state) : - AP_RPM_Backend(_ap_rpm, instance, _state) -{ -} - /* handle interrupt on an instance */ @@ -70,7 +64,7 @@ void AP_RPM_Pin::update(void) AP_HAL::GPIO::INTERRUPT_RISING)) { interrupt_attached = true; } else { - gcs().send_text(MAV_SEVERITY_WARNING, "RPM: Failed to attach to pin %d", last_pin); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "RPM: Failed to attach to pin %d", last_pin); } } } diff --git a/libraries/AP_RPM/RPM_Pin.h b/libraries/AP_RPM/RPM_Pin.h index e196eddc21ca3f..95c957f1f5d2bc 100644 --- a/libraries/AP_RPM/RPM_Pin.h +++ b/libraries/AP_RPM/RPM_Pin.h @@ -14,20 +14,19 @@ */ #pragma once -#include "AP_RPM.h" - -#include "RPM_Backend.h" +#include "AP_RPM_config.h" #if AP_RPM_PIN_ENABLED +#include "RPM_Backend.h" + #include -#include class AP_RPM_Pin : public AP_RPM_Backend { public: - // constructor - AP_RPM_Pin(AP_RPM &ranger, uint8_t instance, AP_RPM::RPM_State &_state); + + using AP_RPM_Backend::AP_RPM_Backend; // update state void update(void) override; diff --git a/libraries/AP_RSSI/AP_RSSI.cpp b/libraries/AP_RSSI/AP_RSSI.cpp index 594317fe8b2125..883ae2662e0682 100644 --- a/libraries/AP_RSSI/AP_RSSI.cpp +++ b/libraries/AP_RSSI/AP_RSSI.cpp @@ -225,7 +225,11 @@ float AP_RSSI::read_pwm_pin_rssi() float AP_RSSI::read_telemetry_radio_rssi() { +#if HAL_GCS_ENABLED return GCS_MAVLINK::telemetry_radio_rssi(); +#else + return 0; +#endif } // Scale and constrain a float rssi value to 0.0 to 1.0 range diff --git a/libraries/AP_RTC/AP_RTC.cpp b/libraries/AP_RTC/AP_RTC.cpp index aa2c80be7754e9..d695e57420ad99 100644 --- a/libraries/AP_RTC/AP_RTC.cpp +++ b/libraries/AP_RTC/AP_RTC.cpp @@ -1,3 +1,7 @@ +#include "AP_RTC_config.h" + +#if AP_RTC_ENABLED + #include "AP_RTC.h" #include @@ -240,3 +244,5 @@ AP_RTC &rtc() } } + +#endif // AP_RTC_ENABLED diff --git a/libraries/AP_RTC/AP_RTC.h b/libraries/AP_RTC/AP_RTC.h index 77720113502563..d03846bf6f29b1 100644 --- a/libraries/AP_RTC/AP_RTC.h +++ b/libraries/AP_RTC/AP_RTC.h @@ -1,5 +1,9 @@ #pragma once +#include "AP_RTC_config.h" + +#if AP_RTC_ENABLED + #include #include @@ -71,3 +75,5 @@ class AP_RTC { namespace AP { AP_RTC &rtc(); }; + +#endif // AP_RTC_ENABLED diff --git a/libraries/AP_RTC/AP_RTC_config.h b/libraries/AP_RTC/AP_RTC_config.h new file mode 100644 index 00000000000000..caea31bcccbf3e --- /dev/null +++ b/libraries/AP_RTC/AP_RTC_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef AP_RTC_ENABLED +#define AP_RTC_ENABLED 1 +#endif diff --git a/libraries/AP_Rally/AP_Rally.cpp b/libraries/AP_Rally/AP_Rally.cpp index 93e2cc12b3d202..c8c586e5b01aa2 100644 --- a/libraries/AP_Rally/AP_Rally.cpp +++ b/libraries/AP_Rally/AP_Rally.cpp @@ -1,5 +1,7 @@ -/// @file AP_Rally.h -/// @brief Handles rally point storage and retrieval. +#include "AP_Rally_config.h" + +#if HAL_RALLY_ENABLED + #include "AP_Rally.h" #include @@ -7,7 +9,6 @@ #include #include -#if HAL_RALLY_ENABLED // storage object StorageAccess AP_Rally::_storage(StorageManager::StorageRally); diff --git a/libraries/AP_Rally/AP_Rally.h b/libraries/AP_Rally/AP_Rally.h index aa4d49baefa68c..0eda3e2fd826a1 100644 --- a/libraries/AP_Rally/AP_Rally.h +++ b/libraries/AP_Rally/AP_Rally.h @@ -14,11 +14,11 @@ */ #pragma once -#include +#include "AP_Rally_config.h" + +#if HAL_RALLY_ENABLED -#ifndef HAL_RALLY_ENABLED -#define HAL_RALLY_ENABLED 1 -#endif +#include #include #include @@ -98,3 +98,5 @@ class AP_Rally { namespace AP { AP_Rally *rally(); }; + +#endif // HAL_RALLY_ENABLED diff --git a/libraries/AP_Rally/AP_Rally_config.h b/libraries/AP_Rally/AP_Rally_config.h new file mode 100644 index 00000000000000..01b08a1bf20f9c --- /dev/null +++ b/libraries/AP_Rally/AP_Rally_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef HAL_RALLY_ENABLED +#define HAL_RALLY_ENABLED 1 +#endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index 5aa620e6217d2d..154c432c74a62e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -61,6 +61,7 @@ #include #include #include +#include extern const AP_HAL::HAL &hal; @@ -72,7 +73,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { AP_SUBGROUPINFO(params[0], "1_", 25, RangeFinder, AP_RangeFinder_Params), // @Group: 1_ - // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp + // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp AP_SUBGROUPVARPTR(drivers[0], "1_", 57, RangeFinder, backend_var_info[0]), #if RANGEFINDER_MAX_INSTANCES > 1 @@ -81,7 +82,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { AP_SUBGROUPINFO(params[1], "2_", 27, RangeFinder, AP_RangeFinder_Params), // @Group: 2_ - // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp + // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp AP_SUBGROUPVARPTR(drivers[1], "2_", 58, RangeFinder, backend_var_info[1]), #endif @@ -91,7 +92,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { AP_SUBGROUPINFO(params[2], "3_", 29, RangeFinder, AP_RangeFinder_Params), // @Group: 3_ - // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp + // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp AP_SUBGROUPVARPTR(drivers[2], "3_", 59, RangeFinder, backend_var_info[2]), #endif @@ -101,7 +102,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { AP_SUBGROUPINFO(params[3], "4_", 31, RangeFinder, AP_RangeFinder_Params), // @Group: 4_ - // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp + // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp AP_SUBGROUPVARPTR(drivers[3], "4_", 60, RangeFinder, backend_var_info[3]), #endif @@ -111,7 +112,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { AP_SUBGROUPINFO(params[4], "5_", 33, RangeFinder, AP_RangeFinder_Params), // @Group: 5_ - // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp + // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp AP_SUBGROUPVARPTR(drivers[4], "5_", 34, RangeFinder, backend_var_info[4]), #endif @@ -121,7 +122,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { AP_SUBGROUPINFO(params[5], "6_", 35, RangeFinder, AP_RangeFinder_Params), // @Group: 6_ - // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp + // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp AP_SUBGROUPVARPTR(drivers[5], "6_", 36, RangeFinder, backend_var_info[5]), #endif @@ -131,7 +132,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { AP_SUBGROUPINFO(params[6], "7_", 37, RangeFinder, AP_RangeFinder_Params), // @Group: 7_ - // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp + // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp AP_SUBGROUPVARPTR(drivers[6], "7_", 38, RangeFinder, backend_var_info[6]), #endif @@ -141,7 +142,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { AP_SUBGROUPINFO(params[7], "8_", 39, RangeFinder, AP_RangeFinder_Params), // @Group: 8_ - // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp + // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp AP_SUBGROUPVARPTR(drivers[7], "8_", 40, RangeFinder, backend_var_info[7]), #endif @@ -151,7 +152,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { AP_SUBGROUPINFO(params[8], "9_", 41, RangeFinder, AP_RangeFinder_Params), // @Group: 9_ - // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp + // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp AP_SUBGROUPVARPTR(drivers[8], "9_", 42, RangeFinder, backend_var_info[8]), #endif @@ -161,7 +162,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { AP_SUBGROUPINFO(params[9], "A_", 43, RangeFinder, AP_RangeFinder_Params), // @Group: A_ - // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Benewake_CAN.cpp,AP_RangeFinder_USD1_CAN.cpp + // @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp AP_SUBGROUPVARPTR(drivers[9], "A_", 44, RangeFinder, backend_var_info[9]), #endif @@ -538,6 +539,7 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) _add_backend(new AP_RangeFinder_Lua(state[instance], params[instance]), instance); #endif break; + case Type::NoopLoop_P: #if AP_RANGEFINDER_NOOPLOOP_ENABLED serial_create_fn = AP_RangeFinder_NoopLoop::create; @@ -549,6 +551,17 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) break; #endif + case Type::TOFSenseP_CAN: +#if AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED + _add_backend(new AP_RangeFinder_TOFSenseP_CAN(state[instance], params[instance]), instance); +#endif + break; + case Type::NRA24_CAN: +#if AP_RANGEFINDER_NRA24_CAN_ENABLED + _add_backend(new AP_RangeFinder_NRA24_CAN(state[instance], params[instance]), instance); +#endif + break; + case Type::NONE: break; } @@ -760,6 +773,10 @@ void RangeFinder::Log_RFND() const continue; } + int8_t signal_quality; + if (!s->get_signal_quality_pct(signal_quality)) { + signal_quality = -1; + } const struct log_RFND pkt = { LOG_PACKET_HEADER_INIT(LOG_RFND_MSG), time_us : AP_HAL::micros64(), @@ -767,6 +784,7 @@ void RangeFinder::Log_RFND() const dist : s->distance_cm(), status : (uint8_t)s->status(), orient : s->orientation(), + quality : signal_quality, }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } @@ -786,6 +804,7 @@ bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_le // backend-specific checks. This might end up drivers[i]->arming_checks(...). switch (drivers[i]->allocated_type()) { +#if AP_RANGEFINDER_PWM_ENABLED || AP_RANGEFINDER_ANALOG_ENABLED case Type::ANALOG: case Type::PX4_PWM: case Type::PWM: { @@ -811,6 +830,20 @@ bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_le } break; } +#endif + +#if AP_RANGEFINDER_NRA24_CAN_ENABLED + case Type::NRA24_CAN: { + if (drivers[i]->status() == Status::NoData) { + // This sensor stops sending data if there is no relative motion. This will mostly happen during takeoff, before arming + // To avoid pre-arm failure, return true even though there is no data. + // This sensor also sends a "heartbeat" so we can differentiate between "NoData" and "NotConnected" + return true; + } + break; + } +#endif + default: break; } @@ -824,7 +857,7 @@ bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_le return false; case Status::OutOfRangeLow: case Status::OutOfRangeHigh: - case Status::Good: + case Status::Good: break; } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp index 54036e2bba05c2..42e64add72e823 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp @@ -83,6 +83,15 @@ bool AP_RangeFinder_BLPing::get_reading(float &reading_m) return false; } +bool AP_RangeFinder_BLPing::get_signal_quality_pct(int8_t &quality_pct) const +{ + if (status() != RangeFinder::Status::Good) { + return false; + } + quality_pct = protocol.get_confidence(); + return true; +} + uint8_t PingProtocol::get_confidence() const { return msg.payload[4]; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h index 3a64e8f0b1f1d6..e61386bf4249e5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h @@ -133,6 +133,13 @@ class AP_RangeFinder_BLPing : public AP_RangeFinder_Backend_Serial */ void update(void) override; + /** + * @brief Get the reading confidence + * 100 is best quality, 0 is worst + * + */ + bool get_signal_quality_pct(int8_t &quality_pct) const override WARN_IF_UNUSED; + protected: /** * @brief Return the sensor type diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h index 27694752e9eac4..5ae14f0d5b96d6 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h @@ -74,7 +74,7 @@ class AP_RangeFinder_Backend // 0 is no return value, 100 is perfect. false means signal // quality is not available - virtual bool get_signal_quality_pct(uint8_t &quality_pct) const { return false; } + virtual bool get_signal_quality_pct(int8_t &quality_pct) const { return false; } // return the actual type of the rangefinder, as opposed to the // parameter value which may be changed at runtime. diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp new file mode 100644 index 00000000000000..96c45d523870af --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp @@ -0,0 +1,96 @@ +/* + 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 "AP_RangeFinder_Backend_CAN.h" + +#if HAL_MAX_CAN_PROTOCOL_DRIVERS + +const AP_Param::GroupInfo AP_RangeFinder_Backend_CAN::var_info[] = { + + // @Param: RECV_ID + // @DisplayName: RangeFinder CAN receive ID + // @Description: The receive ID of the CAN frames. A value of zero means all IDs are accepted. + // @Range: 0 65535 + // @User: Advanced + AP_GROUPINFO("RECV_ID", 10, AP_RangeFinder_Backend_CAN, receive_id, 0), + + // @Param: SNR_MIN + // @DisplayName: RangeFinder Minimum signal strength + // @Description: RangeFinder Minimum signal strength (SNR) to accept distance + // @Range: 0 65535 + // @User: Advanced + AP_GROUPINFO("SNR_MIN", 11, AP_RangeFinder_Backend_CAN, snr_min, 0), + + AP_GROUPEND +}; + +// constructor +AP_RangeFinder_Backend_CAN::AP_RangeFinder_Backend_CAN( + RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) : + AP_RangeFinder_Backend(_state, _params) +{ + AP_Param::setup_object_defaults(this, var_info); + state.var_info = var_info; +} + +// update the state of the sensor +void AP_RangeFinder_Backend_CAN::update(void) +{ + if (get_reading(state.distance_m)) { + // update range_valid state based on distance measured + state.last_reading_ms = AP_HAL::millis(); + update_status(); + } else if (AP_HAL::millis() - state.last_reading_ms >= read_timeout_ms()) { + set_status(RangeFinder::Status::NoData); + } +} + +// get distance measurement +bool AP_RangeFinder_Backend_CAN::get_reading(float &reading_m) +{ + WITH_SEMAPHORE(_sem); + if (_distance_count != 0) { + reading_m = _distance_sum / _distance_count; + _distance_sum = 0; + _distance_count = 0; + return true; + } + + return false; +} + +// return true if the CAN ID is correct +bool AP_RangeFinder_Backend_CAN::is_correct_id(uint32_t id) const +{ + if (receive_id != 0 && id != uint32_t(receive_id.get())) { + // incorrect receive ID + return false; + } + return true; +} + +// handle frames from CANSensor, passing to the drivers +void RangeFinder_MultiCAN::handle_frame(AP_HAL::CANFrame &frame) +{ + WITH_SEMAPHORE(sem); + for (auto *d = drivers; d != nullptr; d=d->next) { + if (d->handle_frame(frame)) { + break; + } + } +} + +#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h new file mode 100644 index 00000000000000..cc936130352916 --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h @@ -0,0 +1,78 @@ +#pragma once + +#include "AP_RangeFinder_Backend.h" + +#if HAL_MAX_CAN_PROTOCOL_DRIVERS + +#include +#include + +class RangeFinder_MultiCAN; + +class AP_RangeFinder_Backend_CAN : public AP_RangeFinder_Backend +{ +public: + // constructor + AP_RangeFinder_Backend_CAN(RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params); + + friend class RangeFinder_MultiCAN; + + static const struct AP_Param::GroupInfo var_info[]; + +protected: + + // update state + virtual void update(void) override; + + // get distance measurement + bool get_reading(float &reading_m); + + // it is essential that anyone relying on the base-class update to implement this + virtual bool handle_frame(AP_HAL::CANFrame &frame) = 0; + + // maximum time between readings before we change state to NoData: + virtual uint32_t read_timeout_ms() const { return 200; } + + virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { + return MAV_DISTANCE_SENSOR_RADAR; + } + + // return true if the CAN ID is correct + bool is_correct_id(uint32_t can_id) const; + + // set distance and count + void accumulate_distance_m(float distance_m) { + _distance_sum += distance_m; + _distance_count++; + }; + + // linked list + AP_RangeFinder_Backend_CAN *next; + + AP_Int32 receive_id; // CAN ID to receive for this backend + AP_Int32 snr_min; // minimum signal strength to accept packet + +private: + + float _distance_sum; // meters + uint32_t _distance_count; +}; + +// a class to allow for multiple CAN backends with one +// CANSensor driver +class RangeFinder_MultiCAN : public CANSensor { +public: + RangeFinder_MultiCAN(AP_CAN::Protocol can_type, const char *driver_name) : CANSensor(driver_name) { + register_driver(can_type); + } + + // handler for incoming frames + void handle_frame(AP_HAL::CANFrame &frame) override; + + // Semaphore for access to shared backend data + HAL_Semaphore sem; + AP_RangeFinder_Backend_CAN *drivers; +}; + +#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.cpp index 40c8118ec6f06f..180c114f2a14a8 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.cpp @@ -5,35 +5,16 @@ #if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED -const AP_Param::GroupInfo AP_RangeFinder_Benewake_CAN::var_info[] = { - - // @Param: RECV_ID - // @DisplayName: CAN receive ID - // @Description: The receive ID of the CAN frames. A value of zero means all IDs are accepted. - // @Range: 0 65535 - // @User: Advanced - AP_GROUPINFO("RECV_ID", 10, AP_RangeFinder_Benewake_CAN, receive_id, 0), - - // @Param: SNR_MIN - // @DisplayName: Minimum signal strength - // @Description: Minimum signal strength (SNR) to accept distance - // @Range: 0 65535 - // @User: Advanced - AP_GROUPINFO("SNR_MIN", 11, AP_RangeFinder_Benewake_CAN, snr_min, 0), - - AP_GROUPEND -}; - -Benewake_MultiCAN *AP_RangeFinder_Benewake_CAN::multican; +RangeFinder_MultiCAN *AP_RangeFinder_Benewake_CAN::multican; /* constructor */ AP_RangeFinder_Benewake_CAN::AP_RangeFinder_Benewake_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) : - AP_RangeFinder_Backend(_state, _params) + AP_RangeFinder_Backend_CAN(_state, _params) { if (multican == nullptr) { - multican = new Benewake_MultiCAN(); + multican = new RangeFinder_MultiCAN(AP_CAN::Protocol::Benewake, "Benewake MultiCAN"); if (multican == nullptr) { AP_BoardConfig::allocation_error("Benewake_CAN"); } @@ -46,26 +27,6 @@ AP_RangeFinder_Benewake_CAN::AP_RangeFinder_Benewake_CAN(RangeFinder::RangeFinde next = prev; multican->drivers = this; } - - AP_Param::setup_object_defaults(this, var_info); - state.var_info = var_info; -} - -// update state -void AP_RangeFinder_Benewake_CAN::update(void) -{ - WITH_SEMAPHORE(_sem); - const uint32_t now = AP_HAL::millis(); - if (_distance_count == 0 && now - state.last_reading_ms > 500) { - // no new data. - set_status(RangeFinder::Status::NoData); - } else if (_distance_count != 0) { - state.distance_m = 0.01 * (_distance_sum_cm / _distance_count); - state.last_reading_ms = AP_HAL::millis(); - _distance_sum_cm = 0; - _distance_count = 0; - update_status(); - } } // handler for incoming frames for H30 radar @@ -83,8 +44,7 @@ bool AP_RangeFinder_Benewake_CAN::handle_frame_H30(AP_HAL::CANFrame &frame) //uint16_t target2 = be16toh_ptr(&frame.data[2]); //uint16_t target3 = be16toh_ptr(&frame.data[4]); - _distance_sum_cm += target1_cm; - _distance_count++; + accumulate_distance_m(target1_cm * 0.01); return true; } @@ -96,28 +56,16 @@ bool AP_RangeFinder_Benewake_CAN::handle_frame(AP_HAL::CANFrame &frame) if (frame.isExtended()) { // H30 radar uses extended frames const int32_t id = int32_t(frame.id & AP_HAL::CANFrame::MaskExtID); - if (receive_id != 0 && id != receive_id.get()) { - // incorrect receive ID + if (!is_correct_id(id)) { return false; } - if (last_recv_id != -1 && id != last_recv_id) { - // changing ID - return false; - } - last_recv_id = id; return handle_frame_H30(frame); } const uint16_t id = frame.id & AP_HAL::CANFrame::MaskStdID; - if (receive_id != 0 && id != uint16_t(receive_id.get())) { - // incorrect receive ID + if (!is_correct_id(id)) { return false; } - if (last_recv_id != -1 && id != last_recv_id) { - // changing ID - return false; - } - last_recv_id = id; const uint16_t dist_cm = le16toh_ptr(&frame.data[0]); const uint16_t snr = le16toh_ptr(&frame.data[2]); @@ -125,20 +73,9 @@ bool AP_RangeFinder_Benewake_CAN::handle_frame(AP_HAL::CANFrame &frame) // too low signal strength return true; } - _distance_sum_cm += dist_cm; - _distance_count++; - return true; -} -// handle frames from CANSensor, passing to the drivers -void Benewake_MultiCAN::handle_frame(AP_HAL::CANFrame &frame) -{ - WITH_SEMAPHORE(sem); - for (auto *d = drivers; d; d=d->next) { - if (d->handle_frame(frame)) { - break; - } - } + accumulate_distance_m(dist_cm * 0.01); + return true; } #endif // AP_RANGEFINDER_BENEWAKE_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h index 7830ab99b042f6..6bc7057bedcd2b 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_CAN.h @@ -3,58 +3,18 @@ #include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED +#include "AP_RangeFinder_Backend_CAN.h" -#include "AP_RangeFinder_Backend.h" -#include - -class Benewake_MultiCAN; - -class AP_RangeFinder_Benewake_CAN : public AP_RangeFinder_Backend { +class AP_RangeFinder_Benewake_CAN : public AP_RangeFinder_Backend_CAN { public: - friend class Benewake_MultiCAN; - AP_RangeFinder_Benewake_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); - void update() override; - // handler for incoming frames. Return true if consumed - bool handle_frame(AP_HAL::CANFrame &frame); + bool handle_frame(AP_HAL::CANFrame &frame) override; bool handle_frame_H30(AP_HAL::CANFrame &frame); - static const struct AP_Param::GroupInfo var_info[]; - -protected: - virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { - return MAV_DISTANCE_SENSOR_RADAR; - } - private: - float _distance_sum_cm; - uint32_t _distance_count; - int32_t last_recv_id = -1; - - AP_Int32 snr_min; - AP_Int32 receive_id; - - static Benewake_MultiCAN *multican; - AP_RangeFinder_Benewake_CAN *next; -}; - -// a class to allow for multiple Benewake_CAN backends with one -// CANSensor driver -class Benewake_MultiCAN : public CANSensor { -public: - Benewake_MultiCAN() : CANSensor("Benewake") { - register_driver(AP_CAN::Protocol::Benewake); - } - - // handler for incoming frames - void handle_frame(AP_HAL::CANFrame &frame) override; - - HAL_Semaphore sem; - AP_RangeFinder_Benewake_CAN *drivers; + static RangeFinder_MultiCAN *multican; }; #endif // AP_RANGEFINDER_BENEWAKE_CAN_ENABLED - - diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp index 19cc404e48083e..4db29571beda1b 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp @@ -65,7 +65,7 @@ AP_RangeFinder_DroneCAN* AP_RangeFinder_DroneCAN::get_dronecan_backend(AP_DroneC if (driver == nullptr) { break; } - gcs().send_text(MAV_SEVERITY_INFO, "RangeFinder[%u]: added DroneCAN node %u addr %u", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "RangeFinder[%u]: added DroneCAN node %u addr %u", unsigned(i), unsigned(node_id), unsigned(address)); //Assign node id and respective uavcan driver, for identification if (driver->_ap_dronecan == nullptr) { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h index 17b5ef46eaede0..cbdfe5d6a52f2f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h @@ -26,7 +26,7 @@ class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend_Serial return MAV_DISTANCE_SENSOR_LASER; } - bool get_signal_quality_pct(uint8_t &quality_pct) const override { + bool get_signal_quality_pct(int8_t &quality_pct) const override { quality_pct = no_signal ? 0 : 100; return true; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp index 5e52a9a2223bc8..66ad7aebada8f7 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp @@ -27,13 +27,21 @@ void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg) mavlink_distance_sensor_t packet; mavlink_msg_distance_sensor_decode(&msg, &packet); - // only accept distances for the configured orentation + // only accept distances for the configured orientation if (packet.orientation == orientation()) { state.last_reading_ms = AP_HAL::millis(); distance_cm = packet.current_distance; _max_distance_cm = packet.max_distance; _min_distance_cm = packet.min_distance; sensor_type = (MAV_DISTANCE_SENSOR)packet.type; + signal_quality = packet.signal_quality; + if (signal_quality == 0) { + // MAVLink's 0 means invalid/unset, so we map it to -1 + signal_quality = -1; + } else if (signal_quality == 1) { + // Map 1 to 0 as that is what ardupilot uses as the worst signal quality + signal_quality = 0; + } } } @@ -77,4 +85,13 @@ void AP_RangeFinder_MAVLink::update(void) } } +bool AP_RangeFinder_MAVLink::get_signal_quality_pct(int8_t &quality_pct) const +{ + if (status() != RangeFinder::Status::Good) { + return false; + } + quality_pct = signal_quality; + return true; +} + #endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h index b38c6fcc494750..e2140260d19071 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h @@ -31,6 +31,10 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend int16_t max_distance_cm() const override; int16_t min_distance_cm() const override; + // Get the reading confidence + // 100 is best quality, 0 is worst + WARN_IF_UNUSED bool get_signal_quality_pct(int8_t &quality_pct) const override; + protected: MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { @@ -43,6 +47,7 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend uint16_t distance_cm; uint16_t _max_distance_cm; uint16_t _min_distance_cm; + int8_t signal_quality; // start a reading static bool start_reading(void); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NRA24_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_NRA24_CAN.cpp new file mode 100644 index 00000000000000..1c922e121bbfc4 --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NRA24_CAN.cpp @@ -0,0 +1,89 @@ +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_NRA24_CAN_ENABLED + +#include "AP_RangeFinder_NRA24_CAN.h" +#include +#include + +RangeFinder_MultiCAN *AP_RangeFinder_NRA24_CAN::multican_NRA24; + +// constructor +AP_RangeFinder_NRA24_CAN::AP_RangeFinder_NRA24_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) : + AP_RangeFinder_Backend_CAN(_state, _params) +{ + if (multican_NRA24 == nullptr) { + multican_NRA24 = new RangeFinder_MultiCAN(AP_CAN::Protocol::NanoRadar_NRA24, "NRA24 MultiCAN"); + if (multican_NRA24 == nullptr) { + AP_BoardConfig::allocation_error("Rangefinder_MultiCAN"); + } + } + + { + // add to linked list of drivers + WITH_SEMAPHORE(multican_NRA24->sem); + auto *prev = multican_NRA24->drivers; + next = prev; + multican_NRA24->drivers = this; + } +} + +// update the state of the sensor +void AP_RangeFinder_NRA24_CAN::update(void) +{ + WITH_SEMAPHORE(_sem); + if (get_reading(state.distance_m)) { + // update range_valid state based on distance measured + state.last_reading_ms = AP_HAL::millis(); + update_status(); + } else if (AP_HAL::millis() - state.last_reading_ms > read_timeout_ms()) { + if (AP_HAL::millis() - last_heartbeat_ms > read_timeout_ms()) { + // no heartbeat, must be disconnected + set_status(RangeFinder::Status::NotConnected); + } else { + // Have heartbeat, just no data. Probably because this sensor doesn't output data when there is no relative motion infront of the radar. + // This case has special pre-arm check handling + set_status(RangeFinder::Status::NoData); + } + } +} + +// handler for incoming frames +bool AP_RangeFinder_NRA24_CAN::handle_frame(AP_HAL::CANFrame &frame) +{ + WITH_SEMAPHORE(_sem); + const uint32_t id = frame.id; + + if (!is_correct_id(get_radar_id(id))) { + return false; + } + + switch (id & 0xFU) { + case 0xAU: + // heart beat in the form of Radar Status. The contents of this message aren't really useful so we won't parse them for now + last_heartbeat_ms = AP_HAL::millis(); + break; + + case 0xCU: + { + // Target Information + const float dist_m = (frame.data[2] * 0x100U + frame.data[3]) * 0.01; + const uint8_t snr = frame.data[7] - 128; + + if ((snr_min != 0 && snr < uint16_t(snr_min.get()))) { + // too low signal strength + return false; + } + accumulate_distance_m(dist_m); + } + break; + + default: + // not parsing these messages + break; + } + + return true; +} + +#endif // AP_RANGEFINDER_NRA24_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NRA24_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_NRA24_CAN.h new file mode 100644 index 00000000000000..4a114be187d9ab --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NRA24_CAN.h @@ -0,0 +1,27 @@ +#pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_NRA24_CAN_ENABLED +#include "AP_RangeFinder_Backend_CAN.h" + +class AP_RangeFinder_NRA24_CAN : public AP_RangeFinder_Backend_CAN { +public: + AP_RangeFinder_NRA24_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); + + void update(void) override; + + // handler for incoming frames + bool handle_frame(AP_HAL::CANFrame &frame) override; + + static const struct AP_Param::GroupInfo var_info[]; + +private: + + uint32_t get_radar_id(uint32_t id) const { return ((id & 0xF0U) >> 4U); } + + static RangeFinder_MultiCAN *multican_NRA24; + + uint32_t last_heartbeat_ms; // last status message received from the sensor +}; + +#endif // AP_RANGEFINDER_USD1_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.cpp index 15166dad5dd453..dcb409377d4ed5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NoopLoop.cpp @@ -27,7 +27,7 @@ extern const AP_HAL::HAL& hal; #define NOOPLOOP_FRAME_HEADER 0x57 #define NOOPLOOP_FRAME_HEADER_1 0x00 #define NOOPLOOP_FRAME_LENGTH 16 -#define NOOPLOOP_DIST_MAX_MM 8000000 +#define NOOPLOOP_DIST_MAX_MM 8000 // format of serial packets received from NoopLoop TOF Sense P and F lidar // diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp index 63d44c0f5f7150..3f3cd9511d5c73 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp @@ -2,12 +2,7 @@ #include "AP_RangeFinder.h" #ifndef AP_RANGEFINDER_DEFAULT_ORIENTATION -#ifndef HAL_BUILD_AP_PERIPH #define AP_RANGEFINDER_DEFAULT_ORIENTATION ROTATION_PITCH_270 -#else -// AP_Periph expects ROTATION_NONE -#define AP_RANGEFINDER_DEFAULT_ORIENTATION ROTATION_NONE -#endif #endif // table of user settable parameters diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp index ed7a02cfce35b2..2feac018be6361 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp @@ -34,13 +34,13 @@ void AP_RangeFinder_SITL::update(void) { const float dist = AP::sitl()->get_rangefinder(_instance); - // negative distance means nothing is connected - if (is_negative(dist)) { + // nan distance means nothing is connected + if (isnan(dist)) { state.status = RangeFinder::Status::NoData; return; } - state.distance_m = dist; + state.distance_m = MAX(0, dist); state.last_reading_ms = AP_HAL::millis(); // update range_valid state based on distance measured diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseP_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseP_CAN.cpp new file mode 100644 index 00000000000000..5b9465a1dde7d9 --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseP_CAN.cpp @@ -0,0 +1,58 @@ +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED + +#include "AP_RangeFinder_TOFSenseP_CAN.h" +#include +#include +#include + +RangeFinder_MultiCAN *AP_RangeFinder_TOFSenseP_CAN::multican_TOFSenseP; + +/* + constructor + */ +AP_RangeFinder_TOFSenseP_CAN::AP_RangeFinder_TOFSenseP_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) : + AP_RangeFinder_Backend_CAN(_state, _params) +{ + if (multican_TOFSenseP == nullptr) { + multican_TOFSenseP = new RangeFinder_MultiCAN(AP_CAN::Protocol::TOFSenseP, "TOFSenseP MultiCAN"); + if (multican_TOFSenseP == nullptr) { + AP_BoardConfig::allocation_error("Rangefinder_MultiCAN"); + } + } + + { + // add to linked list of drivers + WITH_SEMAPHORE(multican_TOFSenseP->sem); + auto *prev = multican_TOFSenseP->drivers; + next = prev; + multican_TOFSenseP->drivers = this; + } +} + + +// handler for incoming frames. These come in at 10-30Hz +bool AP_RangeFinder_TOFSenseP_CAN::handle_frame(AP_HAL::CANFrame &frame) +{ + WITH_SEMAPHORE(_sem); + const uint32_t id = frame.id - 0x200U; + + if (!is_correct_id(id)) { + return false; + } + + const int32_t dist_mm = (int32_t)(frame.data[0] << 8U | frame.data[1] << 16U | frame.data[2] << 24U) >> 8; + const uint8_t status = frame.data[3]; + const uint16_t snr = le16toh_ptr(&frame.data[4]); + + if ((snr_min != 0 && snr < uint16_t(snr_min.get())) || status > 0) { + // too low signal strength or bad status + return false; + } + + accumulate_distance_m(dist_mm * 0.001); + return true; +} + +#endif // AP_RANGEFINDER_TOFSenseP_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseP_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseP_CAN.h new file mode 100644 index 00000000000000..a3100eef09dbe0 --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseP_CAN.h @@ -0,0 +1,22 @@ +#pragma once +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED + +#include "AP_RangeFinder_Backend_CAN.h" + +class AP_RangeFinder_TOFSenseP_CAN : public AP_RangeFinder_Backend_CAN { +public: + AP_RangeFinder_TOFSenseP_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); + + // handler for incoming frames + bool handle_frame(AP_HAL::CANFrame &frame) override; + + static const struct AP_Param::GroupInfo var_info[]; + +private: + static RangeFinder_MultiCAN *multican_TOFSenseP; + +}; + +#endif // AP_RANGEFINDER_USD1_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.cpp index ac7dcda430f987..780308aabde6ca 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.cpp @@ -1,32 +1,19 @@ #include "AP_RangeFinder_USD1_CAN.h" -#include #if AP_RANGEFINDER_USD1_CAN_ENABLED #include -const AP_Param::GroupInfo AP_RangeFinder_USD1_CAN::var_info[] = { - - // @Param: RECV_ID - // @DisplayName: CAN receive ID - // @Description: The receive ID of the CAN frames. A value of zero means all IDs are accepted. - // @Range: 0 65535 - // @User: Advanced - AP_GROUPINFO("RECV_ID", 12, AP_RangeFinder_USD1_CAN, receive_id, 0), - - AP_GROUPEND -}; - -USD1_MultiCAN *AP_RangeFinder_USD1_CAN::multican; +RangeFinder_MultiCAN *AP_RangeFinder_USD1_CAN::multican; /* constructor */ AP_RangeFinder_USD1_CAN::AP_RangeFinder_USD1_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) : - AP_RangeFinder_Backend(_state, _params) + AP_RangeFinder_Backend_CAN(_state, _params) { if (multican == nullptr) { - multican = new USD1_MultiCAN(); + multican = new RangeFinder_MultiCAN(AP_CAN::Protocol::USD1, "USD1 MultiCAN"); if (multican == nullptr) { AP_BoardConfig::allocation_error("USD1_CAN"); } @@ -39,26 +26,6 @@ AP_RangeFinder_USD1_CAN::AP_RangeFinder_USD1_CAN(RangeFinder::RangeFinder_State next = prev; multican->drivers = this; } - - AP_Param::setup_object_defaults(this, var_info); - state.var_info = var_info; -} - -// update state -void AP_RangeFinder_USD1_CAN::update(void) -{ - WITH_SEMAPHORE(_sem); - const uint32_t now = AP_HAL::millis(); - if (_distance_count == 0 && now - state.last_reading_ms > 500) { - // no new data. - set_status(RangeFinder::Status::NoData); - } else if (_distance_count != 0) { - state.distance_m = _distance_sum / _distance_count; - state.last_reading_ms = AP_HAL::millis(); - _distance_sum = 0; - _distance_count = 0; - update_status(); - } } // handler for incoming frames. These come in at 100Hz @@ -66,31 +33,14 @@ bool AP_RangeFinder_USD1_CAN::handle_frame(AP_HAL::CANFrame &frame) { WITH_SEMAPHORE(_sem); const uint16_t id = frame.id & AP_HAL::CANFrame::MaskStdID; - if (receive_id != 0 && id != uint16_t(receive_id.get())) { - // incorrect receive ID - return false; - } - if (last_recv_id != -1 && id != last_recv_id) { - // changing ID + + if (!is_correct_id(id)) { return false; } - last_recv_id = id; const uint16_t dist_cm = (frame.data[0]<<8) | frame.data[1]; - _distance_sum += dist_cm * 0.01; - _distance_count++; + accumulate_distance_m(dist_cm * 0.01); return true; } -// handle frames from CANSensor, passing to the drivers -void USD1_MultiCAN::handle_frame(AP_HAL::CANFrame &frame) -{ - WITH_SEMAPHORE(sem); - for (auto *d = drivers; d; d=d->next) { - if (d->handle_frame(frame)) { - break; - } - } -} - #endif // AP_RANGEFINDER_USD1_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h index 4ca6890fbeed55..5a3827585ac305 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_CAN.h @@ -3,54 +3,22 @@ #include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_USD1_CAN_ENABLED +#include "AP_RangeFinder_Backend_CAN.h" -#include "AP_RangeFinder_Backend.h" -#include - -class USD1_MultiCAN; - -class AP_RangeFinder_USD1_CAN : public AP_RangeFinder_Backend { +class AP_RangeFinder_USD1_CAN : public AP_RangeFinder_Backend_CAN { public: - friend class USD1_MultiCAN; AP_RangeFinder_USD1_CAN(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params); - void update() override; - // handler for incoming frames - bool handle_frame(AP_HAL::CANFrame &frame); + bool handle_frame(AP_HAL::CANFrame &frame) override; static const struct AP_Param::GroupInfo var_info[]; - -protected: - virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { - return MAV_DISTANCE_SENSOR_RADAR; - } private: - float _distance_sum; - uint32_t _distance_count; - int32_t last_recv_id = -1; - - AP_Int32 receive_id; - static USD1_MultiCAN *multican; - AP_RangeFinder_USD1_CAN *next; -}; - -// a class to allow for multiple USD1_CAN backends with one -// CANSensor driver -class USD1_MultiCAN : public CANSensor { -public: - USD1_MultiCAN() : CANSensor("USD1") { - register_driver(AP_CAN::Protocol::USD1); - } - - // handler for incoming frames - void handle_frame(AP_HAL::CANFrame &frame) override; + static RangeFinder_MultiCAN *multican; - HAL_Semaphore sem; - AP_RangeFinder_USD1_CAN *drivers; }; #endif // AP_RANGEFINDER_USD1_CAN_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_config.h b/libraries/AP_RangeFinder/AP_RangeFinder_config.h index ed10e44160ea68..36c5dcf89c98ec 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_config.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_config.h @@ -4,6 +4,7 @@ #include #include #include +#include #ifndef AP_RANGEFINDER_ENABLED #define AP_RANGEFINDER_ENABLED 1 @@ -97,7 +98,7 @@ #endif #ifndef AP_RANGEFINDER_MAVLINK_ENABLED -#define AP_RANGEFINDER_MAVLINK_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#define AP_RANGEFINDER_MAVLINK_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && HAL_GCS_ENABLED #endif #ifndef AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED @@ -120,6 +121,11 @@ #define AP_RANGEFINDER_NOOPLOOP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024 #endif + +#ifndef AP_RANGEFINDER_NRA24_CAN_ENABLED +#define AP_RANGEFINDER_NRA24_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) +#endif + #ifndef AP_RANGEFINDER_PWM_ENABLED #define AP_RANGEFINDER_PWM_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) #endif @@ -136,6 +142,10 @@ #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) +#endif + #ifndef AP_RANGEFINDER_TRI2C_ENABLED #define AP_RANGEFINDER_TRI2C_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED #endif @@ -155,3 +165,4 @@ #ifndef AP_RANGEFINDER_WASP_ENABLED #define AP_RANGEFINDER_WASP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED #endif + diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index cb74a230403043..1c4cb143f7b0fc 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -5,11 +5,14 @@ * Author: Amilcar Lucas */ -#include -#include "AP_Relay.h" +#include "AP_Relay_config.h" #if AP_RELAY_ENABLED +#include "AP_Relay.h" + +#include +#include #include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -153,8 +156,10 @@ void AP_Relay::set(const uint8_t instance, const bool value) _last_log_ms = now; _last_logged_pin_states = _pin_states; } -#if AP_SIM_ENABLED && (CONFIG_HAL_BOARD != HAL_BOARD_SITL) - return; +#if AP_SIM_ENABLED + if (!(AP::sitl()->on_hardware_relay_enable_mask & (1U << instance))) { + return; + } #endif hal.gpio->pinMode(_pin[instance], HAL_GPIO_OUTPUT); hal.gpio->write(_pin[instance], value); @@ -190,6 +195,40 @@ bool AP_Relay::arming_checks(size_t buflen, char *buffer) const return true; } + +#if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED +// this method may only return false if there is no space in the +// supplied link for the message. +bool AP_Relay::send_relay_status(const GCS_MAVLINK &link) const +{ + if (!HAVE_PAYLOAD_SPACE(link.get_chan(), RELAY_STATUS)) { + return false; + } + + uint16_t present_mask = 0; + uint16_t on_mask = 0; + for (auto i=0; i 0x07ff) { value = 0x07ff; } diff --git a/libraries/AP_Scheduler/PerfInfo.cpp b/libraries/AP_Scheduler/PerfInfo.cpp index beb8f075fda95c..1a9db4a96ecd1e 100644 --- a/libraries/AP_Scheduler/PerfInfo.cpp +++ b/libraries/AP_Scheduler/PerfInfo.cpp @@ -196,7 +196,7 @@ float AP::PerfInfo::get_filtered_loop_rate_hz() const void AP::PerfInfo::update_logging() const { - gcs().send_text(MAV_SEVERITY_INFO, + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PERF: %u/%u [%lu:%lu] F=%uHz sd=%lu Ex=%lu", (unsigned)get_num_long_running(), (unsigned)get_num_loops(), diff --git a/libraries/AP_Scripting/AP_Scripting.cpp b/libraries/AP_Scripting/AP_Scripting.cpp index d8771a0f46f808..1e1bfc96f9f1b9 100644 --- a/libraries/AP_Scripting/AP_Scripting.cpp +++ b/libraries/AP_Scripting/AP_Scripting.cpp @@ -154,17 +154,18 @@ void AP_Scripting::init(void) { const char *dir_name = SCRIPTING_DIRECTORY; if (AP::FS().mkdir(dir_name)) { if (errno != EEXIST) { - gcs().send_text(MAV_SEVERITY_INFO, "Scripting: failed to create (%s)", dir_name); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scripting: failed to create (%s)", dir_name); } } if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Scripting::thread, void), "Scripting", SCRIPTING_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_SCRIPTING, 0)) { - gcs().send_text(MAV_SEVERITY_ERROR, "Scripting: %s", "failed to start"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Scripting: %s", "failed to start"); _thread_failed = true; } } +#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: @@ -186,6 +187,7 @@ MAV_RESULT AP_Scripting::handle_command_int_packet(const mavlink_command_int_t & return MAV_RESULT_UNSUPPORTED; } +#endif bool AP_Scripting::repl_start(void) { if (terminal.session) { // it's already running, this is fine @@ -197,7 +199,7 @@ bool AP_Scripting::repl_start(void) { if ((AP::FS().stat(REPL_DIRECTORY, &st) == -1) && (AP::FS().unlink(REPL_DIRECTORY) == -1) && (errno != EEXIST)) { - gcs().send_text(MAV_SEVERITY_INFO, "Scripting: Unable to delete old REPL %s", strerror(errno)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scripting: Unable to delete old REPL %s", strerror(errno)); } // create a new folder @@ -209,7 +211,7 @@ bool AP_Scripting::repl_start(void) { // make the output pointer terminal.output_fd = AP::FS().open(REPL_OUT, O_WRONLY|O_CREAT|O_TRUNC); if (terminal.output_fd == -1) { - gcs().send_text(MAV_SEVERITY_INFO, "Scripting: %s", "Unable to make new REPL"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scripting: %s", "Unable to make new REPL"); return false; } @@ -240,14 +242,14 @@ void AP_Scripting::thread(void) { lua_scripts *lua = new lua_scripts(_script_vm_exec_count, _script_heap_size, _debug_options, terminal); if (lua == nullptr || !lua->heap_allocated()) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Scripting: %s", "Unable to allocate memory"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Scripting: %s", "Unable to allocate memory"); _init_failed = true; } else { // run won't return while scripting is still active lua->run(); // only reachable if the lua backend has died for any reason - gcs().send_text(MAV_SEVERITY_CRITICAL, "Scripting: %s", "stopped"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Scripting: %s", "stopped"); } delete lua; lua = nullptr; @@ -289,11 +291,11 @@ void AP_Scripting::thread(void) { } // must be enabled to get this far if (cleared || _restart) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Scripting: %s", "restarted"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Scripting: %s", "restarted"); break; } if ((_debug_options.get() & uint8_t(lua_scripts::DebugLevel::NO_SCRIPTS_TO_RUN)) != 0) { - gcs().send_text(MAV_SEVERITY_DEBUG, "Scripting: %s", "stopped"); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Scripting: %s", "stopped"); } } } @@ -314,7 +316,7 @@ void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd mission_data = nullptr; } if (mission_data == nullptr) { - gcs().send_text(MAV_SEVERITY_INFO, "Scripting: %s", "unable to receive mission command"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scripting: %s", "unable to receive mission command"); return; } } @@ -362,6 +364,7 @@ void AP_Scripting::restart_all() _stop = true; } +#if HAL_GCS_ENABLED void AP_Scripting::handle_message(const mavlink_message_t &msg, const mavlink_channel_t chan) { if (mavlink_data.rx_buffer == nullptr) { return; @@ -396,6 +399,7 @@ bool AP_Scripting::is_handling_command(uint16_t cmd_id) return false; } +#endif // HAL_GCS_ENABLED AP_Scripting *AP_Scripting::_singleton = nullptr; diff --git a/libraries/AP_Scripting/AP_Scripting.h b/libraries/AP_Scripting/AP_Scripting.h index df37eb7bbc83a7..2895aafe64b971 100644 --- a/libraries/AP_Scripting/AP_Scripting.h +++ b/libraries/AP_Scripting/AP_Scripting.h @@ -16,6 +16,7 @@ #if AP_SCRIPTING_ENABLED +#include #include #include #include @@ -43,16 +44,20 @@ class AP_Scripting bool enabled(void) const { return _enable != 0; }; bool should_run(void) const { return enabled() && !_stop; } +#if HAL_GCS_ENABLED void handle_message(const mavlink_message_t &msg, const mavlink_channel_t chan); // Check if command ID is blocked bool is_handling_command(uint16_t cmd_id); +#endif static AP_Scripting * get_singleton(void) { return _singleton; } static const struct AP_Param::GroupInfo var_info[]; +#if HAL_GCS_ENABLED MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet); +#endif void handle_mission_command(const class AP_Mission::Mission_Command& cmd); diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/README.md b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/README.md index b016c978c12a65..49c1f46aa57919 100644 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/README.md +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/README.md @@ -1,5 +1,7 @@ # Scripted Aerobatics +NOTE: this script requires an ArduPilot version of 4.4.1 or greater to execute + The lua script "plane_aerobatics.lua" implements scripted aerobatics, allowing fixed wing aircraft to execute a number of aerobatic manoeuvres either in AUTO mission or by triggering using pilot commands 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 2cf05e2154da26..f72a5fb43d6068 100644 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/RateBased/sport_aerobatics.lua +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/RateBased/sport_aerobatics.lua @@ -84,6 +84,7 @@ TRIK_SEL_FN = bind_add_param2("_SEL_FN", 2, 301) TRIK_ACT_FN = bind_add_param2("_ACT_FN", 3, 300) TRIK_COUNT = bind_add_param2("_COUNT", 4, 3) TRICKS = {} +local last_trick_action_state = rc:get_aux_cached(TRIK_ACT_FN:get()) function tricks_exist() @@ -764,7 +765,6 @@ function check_auto_mission() end end -local last_trick_action_state = rc:get_aux_cached(TRIK_ACT_FN:get()) local trick_sel_chan = nil local last_trick_selection = 0 diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua index eec4b767ceb715..184ee3768d05fb 100644 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/plane_aerobatics.lua @@ -334,6 +334,7 @@ local function sq(x) return x*x end +local last_trick_action_state = nil if TRIK_ENABLE:get() > 0 then --[[ // @Param: TRIK_SEL_FN @@ -358,6 +359,8 @@ if TRIK_ENABLE:get() > 0 then TRIK_COUNT = bind_add_param2("_COUNT", 4, 3) TRICKS = {} + last_trick_action_state = rc:get_aux_cached(TRIK_ACT_FN:get()) + -- setup parameters for tricks local count = math.floor(constrain(TRIK_COUNT:get(),1,11)) for i = 1, count do @@ -3110,7 +3113,6 @@ function check_auto_mission() end end -local last_trick_action_state = rc:get_aux_cached(TRIK_ACT_FN:get()) local trick_sel_chan = nil local last_trick_selection = nil diff --git a/libraries/AP_Scripting/applets/BattEstimate.lua b/libraries/AP_Scripting/applets/BattEstimate.lua new file mode 100644 index 00000000000000..1221a4b74dbb94 --- /dev/null +++ b/libraries/AP_Scripting/applets/BattEstimate.lua @@ -0,0 +1,282 @@ +--[[ + battery state of charge (SOC) estimator based on resting voltage + + See Tools/scripts/battery_fit.py for a tool to calculate the coefficients from a log +--]] + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +local PARAM_TABLE_KEY = 14 +local PARAM_TABLE_PREFIX = "BATT_SOC" + +-- bind a parameter to a variable +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +-- setup quicktune specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 32), 'could not add param table') + +--[[ + // @Param: BATT_SOC_COUNT + // @DisplayName: Count of SOC estimators + // @Description: Number of battery SOC estimators + // @Range: 0 4 + // @User: Standard +--]] +local BATT_SOC_COUNT = bind_add_param('_COUNT', 1, 0) + +if BATT_SOC_COUNT:get() <= 0 then + return +end + +--[[ + // @Param: BATT_SOC1_IDX + // @DisplayName: Battery estimator index + // @Description: Battery estimator index + // @Range: 0 4 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC1_NCELL + // @DisplayName: Battery estimator cell count + // @Description: Battery estimator cell count + // @Range: 0 48 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC1_C1 + // @DisplayName: Battery estimator coefficient1 + // @Description: Battery estimator coefficient1 + // @Range: 100 200 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC1_C2 + // @DisplayName: Battery estimator coefficient2 + // @Description: Battery estimator coefficient2 + // @Range: 2 5 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC1_C3 + // @DisplayName: Battery estimator coefficient3 + // @Description: Battery estimator coefficient3 + // @Range: 0.01 0.5 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC2_IDX + // @DisplayName: Battery estimator index + // @Description: Battery estimator index + // @Range: 0 4 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC2_NCELL + // @DisplayName: Battery estimator cell count + // @Description: Battery estimator cell count + // @Range: 0 48 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC2_C1 + // @DisplayName: Battery estimator coefficient1 + // @Description: Battery estimator coefficient1 + // @Range: 100 200 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC2_C2 + // @DisplayName: Battery estimator coefficient2 + // @Description: Battery estimator coefficient2 + // @Range: 2 5 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC2_C3 + // @DisplayName: Battery estimator coefficient3 + // @Description: Battery estimator coefficient3 + // @Range: 0.01 0.5 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC3_IDX + // @DisplayName: Battery estimator index + // @Description: Battery estimator index + // @Range: 0 4 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC3_NCELL + // @DisplayName: Battery estimator cell count + // @Description: Battery estimator cell count + // @Range: 0 48 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC3_C1 + // @DisplayName: Battery estimator coefficient1 + // @Description: Battery estimator coefficient1 + // @Range: 100 200 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC3_C2 + // @DisplayName: Battery estimator coefficient2 + // @Description: Battery estimator coefficient2 + // @Range: 2 5 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC3_C3 + // @DisplayName: Battery estimator coefficient3 + // @Description: Battery estimator coefficient3 + // @Range: 0.01 0.5 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC4_IDX + // @DisplayName: Battery estimator index + // @Description: Battery estimator index + // @Range: 0 4 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC4_NCELL + // @DisplayName: Battery estimator cell count + // @Description: Battery estimator cell count + // @Range: 0 48 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC4_C1 + // @DisplayName: Battery estimator coefficient1 + // @Description: Battery estimator coefficient1 + // @Range: 100 200 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC4_C2 + // @DisplayName: Battery estimator coefficient2 + // @Description: Battery estimator coefficient2 + // @Range: 2 5 + // @User: Standard +--]] + +--[[ + // @Param: BATT_SOC4_C3 + // @DisplayName: Battery estimator coefficient3 + // @Description: Battery estimator coefficient3 + // @Range: 0.01 0.5 + // @User: Standard +--]] + +local params = {} +local last_armed_ms = 0 + +--[[ + add parameters for an estimator +--]] +function add_estimator(i) + id = string.format("%u_", i) + pidx = 2+(i-1)*5 + params[i] = {} + params[i]['IDX'] = bind_add_param(id .. "IDX", pidx+0, 0) + params[i]['NCELL'] = bind_add_param(id .. "NCELL", pidx+1, 0) + params[i]['C1'] = bind_add_param(id .. "C1", pidx+2, 111.56) + params[i]['C2'] = bind_add_param(id .. "C2", pidx+3, 3.65) + params[i]['C3'] = bind_add_param(id .. "C3", pidx+4, 0.205) +end + +local count = math.floor(BATT_SOC_COUNT:get()) +for i = 1, count do + add_estimator(i) +end + +local function constrain(v, vmin, vmax) + return math.max(math.min(v, vmax), vmin) +end + +--[[ + simple model of state of charge versus resting voltage. + With thanks to Roho for the form of the equation + https://electronics.stackexchange.com/questions/435837/calculate-battery-percentage-on-lipo-battery +--]] +local function SOC_model(cell_volt, c1, c2, c3) + local p0 = 80.0 + local soc = c1*(1.0-1.0/(1+(cell_volt/c2)^p0)^c3) + return constrain(soc, 0, 100) +end + +--[[ + update one estimator +--]] +local function update_estimator(i) + local idx = math.floor(params[i]['IDX']:get()) + local ncell = math.floor(params[i]['NCELL']:get()) + if idx <= 0 or ncell <= 0 then + return + end + local C1 = params[i]['C1']:get() + local C2 = params[i]['C2']:get() + local C3 = params[i]['C3']:get() + local num_batts = battery:num_instances() + if idx > num_batts then + return + end + local voltR = battery:voltage_resting_estimate(idx-1) + local soc = SOC_model(voltR/ncell, C1, C2, C3) + battery:reset_remaining(idx-1, soc) +end + +--[[ + main update function, called at 1Hz +--]] +function update() + local now_ms = millis() + if arming:is_armed() then + last_armed_ms = now_ms + return update, 1000 + end + -- don't update for 10s after disarm, to get logging of charge recovery + if now_ms - last_armed_ms < 10000 then + return update, 1000 + end + for i = 1, #params do + update_estimator(i) + end + return update, 1000 +end + +gcs:send_text(MAV_SEVERITY.INFO, string.format("Loaded BattEstimate for %u batteries", #params)) + +-- start running update loop +return update, 1000 + diff --git a/libraries/AP_Scripting/applets/BattEstimate.md b/libraries/AP_Scripting/applets/BattEstimate.md new file mode 100644 index 00000000000000..252a4f838e646a --- /dev/null +++ b/libraries/AP_Scripting/applets/BattEstimate.md @@ -0,0 +1,62 @@ +# Battery State of Charge Estimator + +This script implements a battery state of charge estimator based on +resting voltage and a simple LiPo cell model. + +This allows the remaining battery percentage to be automatically set +based on the resting voltage when disarmed. + +# Parameters + +You will need to start by setting BATT_SOC_COUNT to the number of +estimators you want (how many batteries you want to do SoC estimation +for). + +Then you should restart scripting or reboot and set the following +parameters per SoC estimator. + +## BATT_SOCn_IDX + +The IDX is the battery index, starting at 1. + +## BATT_SOCn_NCELL + +Set the number of cells in your battery in the NCELL parameter + +## BATT_SOCn_C1 + +C1 is the first coefficient from your fit of your battery + +## BATT_SOCn_C2 + +C2 is the second coefficient from your fit of your battery + +## BATT_SOCn_C3 + +C3 is the second coefficient from your fit of your battery + +# Usage + +You need to start by working out the coefficients C1, C2 and C3 for your +battery. You can do this by starting with a fully charged battery and +slowly discharging it with LOG_DISARMED set to 1. Alternatively you +can provide a CSV file with battery percentage in the first column and +voltage in the 2nd column. + +Then run the resulting log or csv file through the script at +Tools/scripts/battery_fit.py. You will need to tell the script the +following: + + - the number of cells + - the final percentage charge your log stops at + - the battery index you want to fit to (1 is the first battery) + +That will produce a graph and a set of coefficients like this: + - Coefficients C1=111.5629 C2=3.6577 C3=0.2048 + +Use the C1, C2 and C3 parameters in the parameters for this script. + +The remaining battery percentage is only set when disarmed, and won't +be set till 10 seconds after you disarm from a flight. + + diff --git a/libraries/AP_Scripting/applets/RockBlock.lua b/libraries/AP_Scripting/applets/RockBlock.lua index 1d105ecb8677ed..f8e675cbb0484a 100644 --- a/libraries/AP_Scripting/applets/RockBlock.lua +++ b/libraries/AP_Scripting/applets/RockBlock.lua @@ -784,7 +784,7 @@ function HLSatcom() hl2.temperature_air = math.floor(baro:get_external_temperature()) - if battery:num_instances() > 0 then + if battery:num_instances() > 0 and battery:capacity_remaining_pct(0) ~= nil then hl2.battery = battery:capacity_remaining_pct(0) else hl2.battery = 0 diff --git a/libraries/AP_Scripting/applets/revert_param.lua b/libraries/AP_Scripting/applets/revert_param.lua index 6124d8353b413e..b6cedcd227feb6 100644 --- a/libraries/AP_Scripting/applets/revert_param.lua +++ b/libraries/AP_Scripting/applets/revert_param.lua @@ -57,6 +57,8 @@ local PID_prefixes = { "_RAT_RLL_", "_RAT_PIT_", "_RAT_YAW_" } local PID_suffixes = { "FF", "P", "I", "D", "IMAX", "FLTD", "FLTE", "FLTT", "SMAX" } local angle_axes = { "RLL", "PIT", "YAW" } local PSC_types = { "ACCZ", "VELZ", "POSZ", "VELXY", "POSXY" } +local OTHER_PARAMS = { "INS_GYRO_FILTER", "INS_ACCEL_FILTER" } + if PREV_ENABLE:get() == 0 then return end @@ -103,6 +105,11 @@ for _, psc in ipairs(PSC_prefixes) do end end +-- add in other parameters +for _, p in ipairs(OTHER_PARAMS) do + add_param(p) +end + local function revert_parameters() local count = 0 diff --git a/libraries/AP_Scripting/applets/rover-quicktune.lua b/libraries/AP_Scripting/applets/rover-quicktune.lua new file mode 100644 index 00000000000000..15e3410a56bcc9 --- /dev/null +++ b/libraries/AP_Scripting/applets/rover-quicktune.lua @@ -0,0 +1,796 @@ +--[[ + +Rover QuickTune tunes the steering (aka turn rate), speed and position controller velocity gains for rovers and boats + +The script is designed to be used in Circle mode and updates the following parameters + +ATC_STR_RAT_P +ATC_STR_RAT_I +ATC_STR_RAT_D +ATC_STR_RAT_FF +ATC_SPEED_P +ATC_SPEED_I +ATC_SPEED_D +CRUISE_SPEED +CRUISE_THROTTLE +PSC_VEL_P +PSC_VEL_I +PSC_VEL_D + +See the accompanying rover-quiktune.md file for instructions on how to use + +--]] + +-- 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 = 12 +local PARAM_TABLE_PREFIX = "RTUN_" + +-- bind a parameter to a variable +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format("RTun: 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("RTun: could not add param %s", name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +-- setup quicktune specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 12), "RTun: could not add param table") + +--[[ + // @Param: RTUN_ENABLE + // @DisplayName: Rover Quicktune enable + // @Description: Enable quicktune system + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +local RTUN_ENABLE = bind_add_param('ENABLE', 1, 1) + +--[[ + // @Param: RTUN_AXES + // @DisplayName: Rover Quicktune axes + // @Description: axes to tune + // @Bitmask: 0:Steering,1:Speed,2:Velocity + // @User: Standard +--]] +local RTUN_AXES = bind_add_param('AXES', 2, 7) + +--[[ + // @Param: RTUN_DOUBLE_TIME + // @DisplayName: Rover Quicktune doubling time + // @Description: Time to double a tuning parameter. Raise this for a slower tune. + // @Range: 5 20 + // @Units: s + // @User: Standard +--]] +local RTUN_DOUBLE_TIME = bind_add_param('DOUBLE_TIME', 3, 10) + +--[[ + // @Param: RTUN_PD_GAINMARG + // @DisplayName: Rover Quicktune P and D gain margin + // @Description: Reduction in P and D gain after oscillation detected. Raise this number to get a more conservative tune + // @Range: 20 90 + // @Units: % + // @User: Standard +--]] +local RTUN_PD_GAINMARG = bind_add_param('PD_GAINMARG', 4, 80) + +--[[ + // @Param: RTUN_OSC_SMAX + // @DisplayName: Rover Quicktune oscillation rate threshold + // @Description: Threshold for oscillation detection. A lower value will lead to a more conservative tune. + // @Range: 1 10 + // @User: Standard +--]] +local RTUN_OSC_SMAX = bind_add_param('OSC_SMAX', 5, 1) + +--[[ + // @Param: RTUN_SPD_P_MAX + // @DisplayName: Rover Quicktune Speed P max + // @Description: Maximum value for speed P gain + // @Range: 0.1 10 + // @User: Standard +--]] +local RTUN_SPD_P_MAX = bind_add_param('SPD_P_MAX', 6, 5.0) + +--[[ + // @Param: RTUN_SPD_D_MAX + // @DisplayName: Rover Quicktune Speed D max + // @Description: Maximum value for speed D gain + // @Range: 0.001 1 + // @User: Standard +--]] +local RTUN_SPD_D_MAX = bind_add_param('SPD_D_MAX', 7, 0.5) + +--[[ + // @Param: RTUN_PI_RATIO + // @DisplayName: Rover Quicktune PI ratio + // @Description: Ratio between P and I gains. Raise this to get a lower I gain, 0 to disable + // @Range: 0.5 1.0 + // @User: Standard +--]] +local RTUN_PI_RATIO = bind_add_param('PI_RATIO', 8, 1.0) + +--[[ + // @Param: RTUN_AUTO_FILTER + // @DisplayName: Rover 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 +--]] +local RTUN_AUTO_FILTER = bind_add_param('AUTO_FILTER', 9, 1) + +--[[ + // @Param: RTUN_AUTO_SAVE + // @DisplayName: Rover 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 + // @Units: s + // @User: Standard +--]] +local RTUN_AUTO_SAVE = bind_add_param('AUTO_SAVE', 10, 0) + +--[[ + // @Param: RTUN_RC_FUNC + // @DisplayName: Rover Quicktune RC function + // @Description: RCn_OPTION number to use to control tuning stop/start/save + // @Values: 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 + // @User: Standard +--]] +local RTUN_RC_FUNC = bind_add_param('RC_FUNC', 11, 300) + +--[[ + // @Param: RTUN_FF_GAINMARG + // @DisplayName: Rover Quicktune Steering Rate FeedForward gain margin + // @Description: Reduction in Steering Turn Rate FF gain from measured outputs and response. Raise this number to get a more conservative tune + // @Range: 0 80 + // @Units: % + // @User: Standard +--]] +local RTUN_FF_GAINMARG = bind_add_param('FF_GAINMARG', 12, 10) + +-- other vehicle parameters used by this script +local INS_GYRO_FILTER = bind_param("INS_GYRO_FILTER") +local GCS_PID_MASK = bind_param("GCS_PID_MASK") +local RCMAP_ROLL = bind_param("RCMAP_ROLL") +local RCMAP_THROTTLE = bind_param("RCMAP_THROTTLE") +local RCIN_ROLL = rc:get_channel(RCMAP_ROLL:get()) +local RCIN_THROTTLE = rc:get_channel(RCMAP_THROTTLE:get()) + +-- definitions +local UPDATE_RATE_HZ = 40 -- this script updates at 40hz +local STAGE_DELAY = 4.0 -- gains increased every 4 seconds +local PILOT_INPUT_DELAY = 4.0 -- gains are not updated for 4 seconds after pilot releases sticks +local FLTD_MUL = 0.5 -- ATC_STR_RAT_FLTD set to 0.5 * INS_GYRO_FILTER +local FLTT_MUL = 0.5 -- ATC_STR_RAT_FLTT set to 0.5 * INS_GYRO_FILTER +local STR_RAT_FF_TURNRATE_MIN = math.rad(10) -- steering rate feedforward min vehicle turn rate (in radians/sec) +local STR_RAT_FF_STEERING_MIN = 0.10 -- steering rate feedforward min steering output (in the range 0 to 1) +local SPEED_FF_SPEED_MIN = 0.5 -- speed feedforward minimum vehicle speed (in m/s) +local SPEED_FF_THROTTLE_MIN = 0.20 -- speed feedforward requires throttle output (in the range 0 to 1) + +-- get time in seconds since boot +function get_time() + return millis():tofloat() * 0.001 +end + +-- local variables +local axis_names = { "ATC_STR_RAT", "ATC_SPEED", "PSC_VEL" } -- table of axis that may be tuned +local param_suffixes = { "FF", "P", "I", "D", "FLTT", "FLTD", "FLTE" } -- table of parameters that may be tuned +local params_extra = {"CRUISE_SPEED", "CRUISE_THROTTLE"} -- table of extra parameters that may be changed +local params_skip = {"PSC_VEL_FLTT"} -- parameters that should be skipped from saving/restoring (because they do not exist) +local stages = { "D", "P", "FF" } -- table of tuning stages +local stage = stages[1] -- current tuning stage +local last_stage_change = get_time() -- time (in seconds) that stage last changed +local last_gain_report = get_time() -- time of last update to user on parameter gain actively being tuned +local last_pilot_input = get_time() -- time pilot last provided RC input +local tune_done_time = nil -- time that tuning completed (used for auto save feature) +local slew_parm = nil -- parameter name being slewed towards a target. params are sometimes slewed to reduce impact on controllers +local slew_delta = 0 -- gain change increment to be applied to parameter being actively tuned +local slew_steps = 0 -- max number of times to increment parameter being actively tuned +local axes_done = {} -- list of axes that have been tuned +local filters_done = {} -- table recording if filters have been set for each axis +local gcs_pid_mask_done = {} -- table recording if GCS_PID_MASK has been set for each axis +local gcs_pid_mask_orig -- GCS_PID_MASK value before tuning started + +-- feed forward tuning related local variables +local ff_throttle_sum = 0 -- total throttle recorded during speed FF tuning (divided by count to calc average) +local ff_speed_sum = 0 -- total speed recorded during speed FF tuning (divided by count to calc average) +local ff_speed_count = 0 -- number of speed and throttle samples taken during FF tuning +local ff_steering_sum = 0 -- total steering input recorded during steering rate FF tuning (divided by count to calc average) +local ff_turn_rate_sum = 0 -- total turn rate recorded during steering rate FF tuning (divided by count to calc average) +local ff_turn_rate_count = 0 -- number of steering and turn rate samples taken during FF tuning +local ff_last_warning = 0 -- time of last warning to user + +-- params dictionary indexed by name, such as "ATC_STR_RAT_P" +local params = {} -- table of all parameters that may be tuned +local params_axis = {} -- table of each parameter's axis (used for logging of the appropriate srate) +local param_saved = {} -- table holding backup of each parameter's value from before tuning +local param_changed = {} -- table holding whether each param's gain has been saved +local need_restore = false -- true if any param's gain has been changed + +-- check for an item within a table +-- returns true if found, false if not found +function in_skip_table(pname) + for _, skip_item in ipairs(params_skip) do + if pname == skip_item then + return true + end + end + return false +end + +-- initialise params, params_axis and param_changed tables +function init_params_tables() + -- add parameters to params dictionary + for _, axis in ipairs(axis_names) do + for _, suffix in ipairs(param_suffixes) do + local pname = axis .. "_" .. suffix + if not in_skip_table(pname) then + params[pname] = bind_param(pname) + params_axis[pname] = axis + param_changed[pname] = false + end + end + end + + -- add extra parameters to param dictionary + for _, extra_param_name in ipairs(params_extra) do + params[extra_param_name] = bind_param(extra_param_name) + params_axis[extra_param_name] = "ATC_SPEED" -- axis hard-coded to always be ATC_SPEED + param_changed[extra_param_name] = false + end +end + +-- initialise all state variables so we are ready to start another tune +function reset_axes_done() + for _, axis in ipairs(axis_names) do + axes_done[axis] = false + filters_done[axis] = false + gcs_pid_mask_done[axis] = false + end + tune_done_time = nil + stage = stages[1] +end + +-- get all current param values into param_saved dictionary +function get_all_params() + for pname in pairs(params) do + param_saved[pname] = params[pname]:get() + end +end + +-- restore all param values from param_saved dictionary +function restore_all_params() + for pname in pairs(params) do + if param_changed[pname] then + params[pname]:set(param_saved[pname]) + param_changed[pname] = false + end + end +end + +-- save all param values to storage +function save_all_params() + for pname in pairs(params) do + if param_changed[pname] then + params[pname]:set_and_save(params[pname]:get()) + param_saved[pname] = params[pname]:get() + param_changed[pname] = false + end + end + gcs:send_text(MAV_SEVERITY.NOTICE, "RTun: tuning gains saved") +end + +-- setup filter frequencies +function setup_filters(axis) + if RTUN_AUTO_FILTER:get() > 0 then + if axis == "ATC_STR_RAT" then + adjust_gain(axis .. "_FLTT", INS_GYRO_FILTER:get() * FLTT_MUL) + adjust_gain(axis .. "_FLTD", INS_GYRO_FILTER:get() * FLTD_MUL) + end + end + filters_done[axis] = true +end + +-- backup GCS_PID_MASK to value before tuning +function save_gcs_pid_mask() + gcs_pid_mask_orig = GCS_PID_MASK:get() +end + +-- restore GCS_PID_MASK to value before tuning started +function restore_gcs_pid_mask() + GCS_PID_MASK:set(gcs_pid_mask_orig) +end + +-- setup GCS_PID_MASK to provide real-time PID info to GCS during tuning +function setup_gcs_pid_mask(axis) + if axis == "ATC_STR_RAT" then + GCS_PID_MASK:set(1) + elseif axis == "ATC_SPEED" then + GCS_PID_MASK:set(2) + elseif axis == "PSC_VEL" then + GCS_PID_MASK:set(64) + else + gcs:send_text(MAV_SEVERITY.CRITICAL, string.format("RTun: setup_gcs_pid_mask received unhandled aixs %s", axis)) + end + gcs_pid_mask_done[axis] = true +end + +-- check for pilot input to pause tune +function have_pilot_input() + if (math.abs(RCIN_ROLL:norm_input_dz()) > 0 or + math.abs(RCIN_THROTTLE:norm_input_dz()) > 0) then + return true + end + return false +end + +-- get the axis name we are working on, or nil for all done +function get_current_axis() + local axes = RTUN_AXES:get() + for i = 1, #axis_names do + local mask = (1 << (i-1)) + local axis_name = axis_names[i] + if (mask & axes) ~= 0 and axes_done[axis_name] == false then + return axis_names[i] + end + end + return nil +end + +-- get slew rate for an axis +function get_slew_rate(axis) + local steering_srate, speed_srate = AR_AttitudeControl:get_srate() + if axis == "ATC_STR_RAT" then + return steering_srate + end + if axis == "ATC_SPEED" then + return speed_srate + end + if axis == "PSC_VEL" then + local velocity_srate = AR_PosControl:get_srate() + return velocity_srate + end + gcs:send_text(MAV_SEVERITY.CRITICAL, string.format("RTUN: get_slew_rate unsupported axis:%s", axis)) + return 0.0 +end + +-- move to next stage of tune +function advance_stage(axis) + local now_sec = get_time() + if stage == "D" then + stage = "P" + elseif stage == "P" then + stage = "FF" + else + local prev_axis = get_current_axis() + axes_done[axis] = true + gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: %s tuning done", axis)) + stage = "D" + -- check for tune completion + if prev_axis ~= nil and get_current_axis() == nil then + gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: Tuning DONE")) + tune_done_time = now_sec + end + end + last_stage_change = now_sec +end + +-- change a gain +function adjust_gain(pname, value) + -- sanity check parameter shouldn't be skipped + if in_skip_table(pname) then + gcs:send_text(MAV_SEVERITY.CRITICAL, string.format("RTun: attempted to update skipped param %s", pname)) + return + end + local P = params[pname] + need_restore = true + param_changed[pname] = true + P:set(value) + if string.sub(pname, -2) == "_P" then + -- if we are updating a P value we may also update I + local ffname = string.gsub(pname, "_P", "_FF") + local FF = params[ffname] + if FF:get() > 0 then + -- if we have any FF on an axis then we don't couple I to P, + -- usually we want I = FF for a one sectond time constant for trim + return + end + -- if PI_RATIO is non-zero then update I + local PI_ratio = RTUN_PI_RATIO:get() + if PI_ratio > 0 then + local iname = string.gsub(pname, "_P", "_I") + local I = params[iname] + new_I_gain = value/PI_ratio + I:set(new_I_gain) + param_changed[iname] = true + write_log(iname) + end + end +end + +-- return gain multipler for one loop +function get_gain_mul() + return math.exp(math.log(2.0)/(UPDATE_RATE_HZ*RTUN_DOUBLE_TIME:get())) +end + +-- setup parameter slewing. slewing some changes over 2 seconds reduces shock to controllers +function setup_slew_gain(pname, gain) + slew_parm = pname + slew_steps = UPDATE_RATE_HZ / 2 + slew_delta = (gain - params[pname]:get()) / slew_steps +end + +-- update parameter slewing. slewing some changes over 2 seconds reduces shock to controllers +function update_slew_gain() + if slew_parm ~= nil then + local P = params[slew_parm] + adjust_gain(slew_parm, P:get()+slew_delta) + write_log(slew_parm) + slew_steps = slew_steps - 1 + -- check if slewing is complete + if slew_steps == 0 then + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: %s %.3f", slew_parm, P:get())) + slew_parm = nil + end + end +end + +-- log parameter, current gain and current slew rate +function write_log(pname) + local param_gain = params[pname]:get() + local pname_axis = params_axis[pname] + local slew_rate = get_slew_rate(pname_axis) + logger:write("RTUN","SRate,Gain,Param", "ffN", slew_rate, param_gain, pname) +end + +-- return gain limits on a parameter, or 0 for no limit +function gain_limit(pname) + if pname == "ATC_SPEED_P" then + return RTUN_SPD_P_MAX:get() + elseif pname == "ATC_SPEED_D" then + return RTUN_SPD_D_MAX:get() + end + return 0.0 +end + +-- check if parameter's gain has reached its limit +function reached_limit(pname, gain) + local limit = gain_limit(pname) + if limit > 0.0 and gain >= limit then + return true + end + return false +end + +-- initialise steering ff tuning +function init_steering_ff() + ff_steering_sum = 0 + ff_turn_rate_sum = 0 + ff_turn_rate_count = 0 +end + +-- run steering turn rate controller feedforward calibration +function update_steering_ff(pname) + -- get steering, turn rate, throttle and speed + local steering_out, _ = vehicle:get_steering_and_throttle() + local turn_rate_rads = ahrs:get_gyro():z() + + -- update user every 5 sec + local now_sec = get_time() + local update_user = false + if (now_sec > ff_last_warning + 5) then + update_user = true + ff_last_warning = now_sec + end + + -- calculate percentage complete + local turn_rate_complete_pct = (ff_turn_rate_sum / math.pi * 2.0) * 100 + local time_complete_pct = (ff_turn_rate_count / (10 * UPDATE_RATE_HZ)) * 100 + local complete_pct = math.min(turn_rate_complete_pct, time_complete_pct) + + -- check steering and turn rate and accumulate output and response + local steering_ok = steering_out >= STR_RAT_FF_STEERING_MIN + local turnrate_ok = math.abs(turn_rate_rads) > STR_RAT_FF_TURNRATE_MIN + if (steering_ok and turnrate_ok) then + ff_steering_sum = ff_steering_sum + steering_out + ff_turn_rate_sum = ff_turn_rate_sum + math.abs(turn_rate_rads) + ff_turn_rate_count = ff_turn_rate_count + 1 + if (update_user) then + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: %s %.0f%% complete", pname, complete_pct)) + end + else + if update_user then + if not steering_ok then + gcs:send_text(MAV_SEVERITY.WARNING, string.format("RTun: increase steering (%d%% < %d%%)", math.floor(steering_out * 100), math.floor(STR_RAT_FF_STEERING_MIN * 100))) + elseif not turnrate_ok then + gcs:send_text(MAV_SEVERITY.WARNING, string.format("RTun: increase turn rate (%d deg/s < %d)", math.floor(math.deg(math.abs(turn_rate_rads))), math.floor(math.deg(STR_RAT_FF_TURNRATE_MIN)))) + end + end + end + + -- check for completion of two rotations of turns data and 10 seconds + if complete_pct >= 100 then + local old_gain = params[pname]:get() + local new_gain = (ff_steering_sum / ff_turn_rate_sum) * (1.0-(RTUN_FF_GAINMARG:get()*0.01)) + adjust_gain(pname, new_gain) + write_log(pname) + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusted %s %.3f -> %.3f", pname, old_gain, new_gain)) + + -- set I gain equal to FF + local iname = string.gsub(pname, "_FF", "_I") + local I = params[iname] + local I_old_gain = I:get() + I:set(new_gain) + param_changed[iname] = true + write_log(iname) + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusted %s %.3f -> %.3f", iname, I_old_gain, new_gain)) + return true + end + + return false +end + +-- run speed controller feedforward calibration +function update_speed_ff(pname) + -- get steering, turn rate, throttle and speed + local _, throttle_out = vehicle:get_steering_and_throttle() + local velocity_ned = ahrs:get_velocity_NED() + if velocity_ned then + speed = ahrs:earth_to_body(velocity_ned):x() + end + + -- update user every 5 sec + local now_sec = get_time() + local update_user = false + if (now_sec > ff_last_warning + 5) then + update_user = true + ff_last_warning = now_sec + end + + -- calculate percentage complete + local complete_pct = (ff_speed_count / (10 * UPDATE_RATE_HZ)) * 100 + + -- check throttle and speed + local throttle_ok = throttle_out >= SPEED_FF_THROTTLE_MIN + local speed_ok = speed > SPEED_FF_SPEED_MIN + if (throttle_ok and speed_ok) then + ff_throttle_sum = ff_throttle_sum + throttle_out + ff_speed_sum = ff_speed_sum + speed + ff_speed_count = ff_speed_count + 1 + if (update_user) then + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: %s %.0f%% complete", pname, complete_pct)) + end + else + if update_user then + if not throttle_ok then + gcs:send_text(MAV_SEVERITY.WARNING, string.format("RTun: increase throttle (%d < %d)", math.floor(throttle_out * 100), math.floor(SPEED_FF_THROTTLE_MIN * 100))) + elseif not turnrate_ok then + gcs:send_text(MAV_SEVERITY.WARNING, string.format("RTun: increase speed (%3.1f < %3.1f)", speed, SPEED_FF_SPEED_MIN)) + end + end + end + + -- check for 10 seconds of data + if complete_pct >= 100 then + local cruise_speed_old = params["CRUISE_SPEED"]:get() + local cruise_speed_new = ff_speed_sum / ff_speed_count + local cruise_throttle_old = params["CRUISE_THROTTLE"]:get() + local cruise_throttle_new = (ff_throttle_sum / ff_speed_count) * 100 + adjust_gain("CRUISE_SPEED", cruise_speed_new) + adjust_gain("CRUISE_THROTTLE", cruise_throttle_new) + write_log("CRUISE_SPEED") + write_log("CRUISE_THROTTLE") + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusted %s %.2f -> %.2f", "CRUISE_SPEED", cruise_speed_old, cruise_speed_new)) + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusted %s %.1f -> %.1f", "CRUISE_THROTTLE", cruise_throttle_old, cruise_throttle_new)) + + -- set I gain equal to FF + local iname = string.gsub(pname, "_FF", "_I") + local I = params[iname] + local I_old_gain = I:get() + local I_new_gain = ff_throttle_sum / ff_speed_sum + I:set(I_new_gain) + param_changed[iname] = true + write_log(iname) + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusted %s %.3f -> %.3f", iname, I_old_gain, I_new_gain)) + return true + end + + return false +end + +-- initialisation +init_params_tables() +reset_axes_done() +get_all_params() +save_gcs_pid_mask() +gcs:send_text(MAV_SEVERITY.INFO, "Rover quiktune loaded") + +-- main update function +local last_warning = get_time() +function update() + + -- exit immediately if not enabled + if RTUN_ENABLE:get() <= 0 then + return + end + + if have_pilot_input() then + last_pilot_input = get_time() + end + + local sw_pos = rc:get_aux_cached(RTUN_RC_FUNC:get()) + if not sw_pos then + return + end + + -- get output throttle + local _, throttle_out = vehicle:get_steering_and_throttle() + + -- check switch position (0:low is stop, 1:middle is tune, 2:high is save gains + if sw_pos == 1 and (not arming:is_armed() or (throttle_out <= 0)) and get_time() > last_warning + 5 then + gcs:send_text(MAV_SEVERITY.CRITICAL, "RTun: must be armed and moving to tune") + last_warning = get_time() + return + end + if sw_pos == 0 or not arming:is_armed() then + -- abort, revert parameters + if need_restore then + need_restore = false + restore_all_params() + restore_gcs_pid_mask() + gcs:send_text(MAV_SEVERITY.CRITICAL, "RTun: gains reverted") + end + reset_axes_done() + return + end + if sw_pos == 2 then + -- save all params + if need_restore then + need_restore = false + save_all_params() + restore_gcs_pid_mask() + end + end + + -- if we reach here we must be tuning + if sw_pos ~= 1 then + return + end + + -- update param gains for params being slewed towards a target + update_slew_gain() + + -- return if we have just changed stages to give time for oscillations to subside + if get_time() - last_stage_change < STAGE_DELAY then + return + end + + -- get axis currently being tuned + axis = get_current_axis() + + -- if no axis is being tuned we must be done + if axis == nil then + -- check if params should be auto saved + if tune_done_time ~= nil and RTUN_AUTO_SAVE:get() > 0 then + if get_time() - tune_done_time > RTUN_AUTO_SAVE:get() then + need_restore = false + save_all_params() + restore_gcs_pid_mask() + tune_done_time = nil + end + end + return + end + + if not need_restore then + -- we are just starting tuning, get current values + get_all_params() + end + + -- return immediately if pilot has provided input recently + if get_time() - last_pilot_input < PILOT_INPUT_DELAY then + return + end + + -- check filters have been set for this axis + if not filters_done[axis] then + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: starting %s tune", axis)) + setup_filters(axis) + end + + -- check GCS_PID_MASK has been set for this axis + if not gcs_pid_mask_done[axis] then + setup_gcs_pid_mask(axis) + end + + -- get parameter currently being tuned + local srate = get_slew_rate(axis) + local pname = axis .. "_" .. stage + local param = params[pname] + + if stage == "FF" then + -- feedforward tuning + local ff_done + if axis == "ATC_STR_RAT" then + ff_done = update_steering_ff(pname) + elseif axis == "ATC_SPEED" then + ff_done = update_speed_ff(pname) + elseif axis == "PSC_VEL" then + -- position controller feed-forward is not tuned + ff_done = true + else + gcs:send_text(MAV_SEVERITY.CRITICAL, string.format("RTun: unsupported FF tuning %s", pname)) + ff_done = true + end + if ff_done then + gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: %s tuning done", pname)) + advance_stage(axis) + end + else + local oscillating = srate > RTUN_OSC_SMAX:get() + local limited = reached_limit(pname, param:get()) + if limited or oscillating then + local reduction = (100.0-RTUN_PD_GAINMARG:get())*0.01 + if not oscillating then + reduction = 1.0 + end + local new_gain = param:get() * reduction + local limit = gain_limit(pname) + if limit > 0.0 and new_gain > limit then + gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: %s passed limit (>%.3f)", pname, limit)) + new_gain = limit + end + local old_gain = param_saved[pname] + if new_gain < old_gain and string.sub(pname,-2) == '_D' then + -- we are lowering a D gain from the original gain. Also lower the P gain by the same amount + -- so that we don't trigger P oscillation. We don't drop P by more than a factor of 2 + local ratio = math.max(new_gain / old_gain, 0.5) + local P_name = string.gsub(pname, "_D", "_P") + local old_P = params[P_name]:get() + local new_P = old_P * ratio + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusting %s %.3f -> %.3f", P_name, old_P, new_P)) + adjust_gain(P_name, new_P) + write_log(P_name) + end + -- slew gain change over 2 seconds to ease impact on controller + setup_slew_gain(pname, new_gain) + gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: %s tuning done %.3f", pname, new_gain)) + advance_stage(axis) + else + local new_gain = param:get()*get_gain_mul() + if new_gain <= 0.0001 then + new_gain = 0.001 + end + adjust_gain(pname, new_gain) + write_log(pname) + if get_time() - last_gain_report > 3 then + last_gain_report = get_time() + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: %s %.3f sr:%.2f", pname, new_gain, srate)) + end + end + end +end + +-- wrapper around update(). This calls update() at 10Hz, +-- and if update faults then an error is displayed, but the script is not +-- stopped +function protected_wrapper() + local success, err = pcall(update) + if not success then + gcs:send_text(MAV_SEVERITY.CRITICAL, "RTun: Internal Error: " .. err) + -- when we fault we run the update function again after 1s, slowing it + -- down a bit so we don't flood the console with errors + --return protected_wrapper, 1000 + return + end + return protected_wrapper, 1000/UPDATE_RATE_HZ +end + +-- start running update loop +return protected_wrapper() diff --git a/libraries/AP_Scripting/applets/rover-quicktune.md b/libraries/AP_Scripting/applets/rover-quicktune.md new file mode 100644 index 00000000000000..21dc1f647e01da --- /dev/null +++ b/libraries/AP_Scripting/applets/rover-quicktune.md @@ -0,0 +1,145 @@ +# Rover QuickTune + +Rover QuickTune tunes the steering (aka turn rate), speed and position controller velocity gains for rovers and boats + +The script is designed to be used in Circle mode and updates the following parameters + +ATC_STR_RAT_P +ATC_STR_RAT_I +ATC_STR_RAT_D +ATC_STR_RAT_FF +ATC_STR_RAT_FLTD +ATC_STR_RAT_FLTT +ATC_SPEED_P +ATC_SPEED_I +ATC_SPEED_D +CRUISE_SPEED +CRUISE_THROTTLE +PSC_VEL_P +PSC_VEL_I +PSC_VEL_D + +# How To Use +Install this script in the autopilot's SD card's APM/scripts directory +Set SCR_ENABLE to 1 and reboot the autopilot +Set RTUN_ENABLE to 1. + +Set RCx_OPTION = 300 where "x" refers to the transmitter's 2 or 3 position switch +use to start/stop/save tuning. E.g. if channel 6 is used set RC6_OPTION = 300 + +If necessary, the RTUN_RC_FUNC parameter can be set to another number (e.g. 302 for scripting3) +to avoid RCx_OPTION conflicts with other scripts. + +If only a 2-position switch is available set RTUN_AUTO_SAVE to 1 + +Arm the vehicle and switch to Circle mode +Optionally set CIRC_SPEED (or WP_SPEED) to about half the vehicle's max speed +Optionally set CIRC_RADIUS to a value at least twice the vehicle's turning radius +Note the above parmaters only take effect when the vehicle is switched into Circle mode + +Move the RC switch to the middle position to begin the tuning process. +Text messages should appear on the ground station's messages area showing progress + +For P and D gain tuning, the relevant gain is slowly raised until the vehicle begins to oscillate after which the gain is reduced and the script moves onto the next gain. + +For FF tuning, the steering or throttle output are compared to the response for at least 10 seconds. +A message may appear stating the steering, turn rate, throttle or speed are too low in which case +the vehicle speed should be increased (Mission Planner's Action tab "Change Speed" button may be used) +or the radius should be reduced. The velocity FF is not tuned (nor does it need to be). + +By default the gains will be tuned in this order: + + - ATC_STR_RAT_D + - ATC_STR_RAT_P and I + - ATC_STR_RAT_FF + - ATC_SPEED_D + - ATC_SPEED_P + - CRUISE_SPEED and CRUISE_THROTTLE + - PSC_VEL_D + - PSC_VEL_P and I + +The script will also adjust filter settings: + + - ATC_STR_RAT_FLTD and FLTT will be set to half of the INS_GYRO_FILTER value + +Once tuning is complete "RTUN: tuning done" will be displayed +Save the tune by raising the RC switch to the high position + +If the RC switch is moved high (ie. Save Tune) before the tune is completed the tune will pause, and any parameters completed will be saved and the current value of the one being actively tuned will remain active. You can resume tuning by returning the switch again to the middle position. If the RC switch is moved to the low position, the parameter currently being tuned will be reverted but any previously saved parameters will remain. + +If you move the switch to the low position at any time in the tune before using the Tune Save switch position, then all parameters will be reverted to their original values. Parameters will also be reverted if you disarm before saving. + +If the pilot gives steering or throttle input during tuning then tuning is paused for 4 seconds. Tuning restarts once the pilot returns to the input to the neutral position. + +# Parameters + +The script has the following parameters to configure its behaviour + +## RTUN_ENABLE + +Set to 1 to enable the script + +## RTUN_RC_FUNC + +The RCx_OPTIONS function number to be used to start/stop tuning +By default RCx_OPTIONS of 300 (scripting1) is used + +## RTUN_AXES + +The axes that will be tuned. The default is 7 meaning steering, speed and velocity +This parameter is a bitmask, so set 1 to tune just steering. 2 for speed. 4 for velocity + +## RTUN_DOUBLE_TIME + +How quickly a gain is raised while tuning. This is the number of seconds +for the gain to double. Most users will want to leave this at the default of 10 seconds. + +## RTUN_PD_GAINMARG + +The percentage P and D gain margin to use. Once the oscillation point is found +the gain is reduced by this percentage. The default of 80% is good for most users. + +## RTUN_FF_GAINMARG + +The percentage FF gain margin to use. Once the output and response are used to calculate +the ideal feed-forward, the value is reduced by this percentage. The default of 20% is good for most users. + +## RTUN_OSC_SMAX + +The Oscillation threshold in Hertz for detecting oscillation +The default of 5Hz is good for most vehicles but on very large vehicles +you may wish to lower this. For a vehicle of 50kg a value of 3 is likely to be good. +For a vehicle of 100kg a value of 1.5 is likely to be good. + +You can tell you have this set too high if you still have visible +oscillations after a parameter has completed tuning. In that case +halve this parameter and try again. + +## RTUN_SPD_P_MAX + +The speed controller P gain max (aka ATC_SPEED_P) + +## RTUN_SPD_D_MAX + +The speed controller D gain max (aka ATC_SPEED_D) + +## RTUN_PI_RATIO + +The ratio for P to I. This should normally be 1, but on some large vehicles a value of up to 3 can be +used if the I term in the PID is causing too much phase lag. + +If RTUN_RP_PI_RATIO is less than 1 then the I value will not be +changed at all when P is changed. + +## RTUN_AUTO_FILTER + +This enables automatic setting of the PID filters based on the +INS_GYRO_FILTER value. Set to zero to disable this feature. + +## RTUN_AUTO_SAVE + +Enables automatic saving of the gains this many seconds after the tuning +completes unless the pilot move the RC switch low to revert the tune. +Setting this to a non-zero value allows you to use quicktune with a 2-position +switch, with the switch settings as low and mid positions. A zero +value disables auto-save and you need to have a 3 position switch. diff --git a/libraries/AP_Scripting/applets/winch-control.lua b/libraries/AP_Scripting/applets/winch-control.lua new file mode 100644 index 00000000000000..12496f8891f5dc --- /dev/null +++ b/libraries/AP_Scripting/applets/winch-control.lua @@ -0,0 +1,108 @@ +-- winch-control.lua: allows the winch to be deployed or retracted at a fixed speed using an auxiliary switch +-- +-- How To Use +-- 1. set RCx_OPTION to 300 to enable controlling the winch rate from an auxiliary switch +-- 2. set WINCH_RATE_UP to the fixed retract speed (in m/s) +-- 3. set WINCH_RATE_DN to the fixed deploy speed (in m/s) +-- 4. raise the RC auxiliary switch to retract the winch's line +-- 5. lower the RC auxiliary switch to deploy the winch's line +-- 6. center the RC auxiliary switch to stop the winch +-- Alternatively Mission Planner's Aux Function screen can be used in place of an actual RC switch +-- + +-- 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 +local PARAM_TABLE_PREFIX = "WINCH_" + +-- bind a parameter to a variable +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format("WinchControl: 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("WinchControl: could not add param %s", name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +-- setup quicktune specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 3), "WinchControl: could not add param table") + +--[[ + // @Param: WINCH_RATE_UP + // @DisplayName: WinchControl Rate Up + // @Description: Maximum rate when retracting line + // @Range: 0.1 5.0 + // @User: Standard +--]] +local WINCH_RATE_UP = bind_add_param('RATE_UP', 1, 0.5) + +--[[ + // @Param: WINCH_RATE_DN + // @DisplayName: WinchControl Rate Down + // @Description: Maximum rate when releasing line + // @Range: 0.1 5.0 + // @User: Standard +--]] +local WINCH_RATE_DN = bind_add_param('RATE_DN', 2, 2.0) + +--[[ + // @Param: WINCH_RC_FUNC + // @DisplayName: Winch Rate Control RC function + // @Description: RCn_OPTION number to use to control winch rate + // @Values: 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 + // @User: Standard +--]] +local WINCH_RC_FUNC = bind_add_param('RC_FUNC', 3, 300) + +-- local variables and definitions +local UPDATE_INTERVAL_MS = 100 +local last_rc_switch_pos = -1 -- last known rc switch position. Used to detect change in RC switch position + +-- initialisation +gcs:send_text(MAV_SEVERITY.INFO, "WinchControl: started") + +-- the main update function +function update() + + -- get RC switch position + local rc_switch_pos = rc:get_aux_cached(WINCH_RC_FUNC:get()) + if not rc_switch_pos then + -- if rc switch has never been set the return immediately + return update, UPDATE_INTERVAL_MS + end + + -- initialise RC switch at startup + if last_rc_switch_pos == -1 then + last_rc_switch_pos = rc_switch_pos + end + + -- check if user has moved RC switch + if rc_switch_pos == last_rc_switch_pos then + return update, UPDATE_INTERVAL_MS + end + last_rc_switch_pos = rc_switch_pos + + -- set winch rate based on switch position + if rc_switch_pos == 0 then -- LOW, deploy winch line + local rate_dn = math.abs(WINCH_RATE_DN:get()) + winch:set_desired_rate(rate_dn) + gcs:send_text(6, string.format("Winch: lowering at %.1f m/s", rate_dn)) + end + if rc_switch_pos == 1 then -- MIDDLE, stop winch + winch:set_desired_rate(0) + gcs:send_text(6, "Winch: stopped") + end + if rc_switch_pos == 2 then -- HIGH, retract winch line + local rate_up = math.abs(WINCH_RATE_UP:get()) + winch:set_desired_rate(-rate_up) + gcs:send_text(6, string.format("Winch: raising at %.1f m/s", rate_up)) + end + + return update, UPDATE_INTERVAL_MS +end + +return update() diff --git a/libraries/AP_Scripting/applets/winch-control.md b/libraries/AP_Scripting/applets/winch-control.md new file mode 100644 index 00000000000000..9238faf7f3e6d5 --- /dev/null +++ b/libraries/AP_Scripting/applets/winch-control.md @@ -0,0 +1,20 @@ +# Winch Control + +Allows the winch to be deployed or retracted at a fixed speed using an auxiliary switch + +# Parameters + +WINCH_RATE_UP : rate (in m/s) when retracting line +WINCH_RATE_DN : rate (in m/s) when deploying line +WINCH_RC_FUNC : RCn_OPTION number to use to control winch rate. Default is 300 (Scripting1) + +# How To Use + +1. set RCx_OPTION to 300 to enable controlling the winch rate from an auxiliary switch +2. set WINCH_RATE_UP to the fixed retract speed (in m/s) +3. set WINCH_RATE_DN to the fixed release speed (in m/s) +4. raise the RC auxiliary switch to retract the winch's line +5. lower the RC auxiliary switch to deploy the winch's line +6. center the RC auxiliary switch to stop the winch + +Alternatively Mission Planner's Aux Function screen can be used in place of an actual RC switch diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 6b95120dd92559..67e9812074b2f5 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -45,6 +45,11 @@ function micros() end ---@return number|nil -- command param 4 function mission_receive() end +-- Print text, if MAVLink is available the value will be sent with debug severity +-- If no MAVLink the value will be sent over can +-- equivalent to gcs:send_text(7, text) or periph:can_printf(text) +---@param text string|number|integer +function print(text) end -- data flash logging to SD card ---@class logger @@ -1536,6 +1541,22 @@ function MotorsMatrix:get_lost_motor() end ---@return boolean function MotorsMatrix:get_thrust_boost() end + +-- Sub singleton +---@class sub +sub = {} + +-- Return true if joystick button is currently pressed +---@param index integer +---@return boolean +function sub:is_button_pressed(index) end + +-- Get count of joystick button presses, then clear count +---@param index integer +---@return integer +function sub:get_and_clear_button_count(index) end + + -- desc ---@class quadplane quadplane = {} @@ -1952,6 +1973,11 @@ function serialLED:set_num_profiled(chan, num_leds) end ---@return boolean function serialLED:set_num_neopixel(chan, num_leds) end +-- desc +---@param chan integer +---@param num_leds integer +---@return boolean +function serialLED:set_num_neopixel_rgb(chan, num_leds) end -- desc ---@class vehicle @@ -1994,6 +2020,11 @@ function vehicle:get_wp_distance_m() end ---@return boolean function vehicle:set_steering_and_throttle(steering, throttle) end +-- desc +---@return number|nil +---@return number|nil +function vehicle:get_steering_and_throttle() end + -- desc ---@param rate_dps number ---@return boolean @@ -2417,11 +2448,47 @@ function rangefinder:has_orientation(orientation) end ---@return integer function rangefinder:num_sensors() end +-- Proximity backend methods +---@class AP_Proximity_Backend_ud +local AP_Proximity_Backend_ud = {} + +-- Push virtual proximity boundary into actual boundary +---@return boolean +function AP_Proximity_Backend_ud:update_virtual_boundary() end + +-- Set sensor min and max. Only need to do it once +---@param min number +---@param max number +---@return boolean +function AP_Proximity_Backend_ud:set_distance_min_max(min, max) end + +-- type of backend +---@return integer +function AP_Proximity_Backend_ud:type() end + +-- send 3d object as 3d vector +---@param vector_3d Vector3f_ud +---@param update_boundary boolean +---@return boolean +function AP_Proximity_Backend_ud:handle_script_3d_msg(vector_3d, update_boundary) end + +-- send 3d object as angles +---@param dist_m number +---@param yaw_deg number +---@param pitch_deg number +---@param update_boundary boolean +---@return boolean +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 +function proximity:get_backend(instance) end + -- desc ---@param object_number integer ---@return number|nil @@ -2834,6 +2901,23 @@ AC_AttitudeControl = {} ---@return number -- yaw slew rate function AC_AttitudeControl:get_rpy_srate() end +-- desc +---@class AR_AttitudeControl +AR_AttitudeControl = {} + +-- return attitude controller slew rates for rovers +---@return number -- steering slew rate +---@return number -- spees slew rate +function AR_AttitudeControl:get_srate() end + +-- desc +---@class AR_PosControl +AR_PosControl = {} + +-- return position controller slew rates for rovers +---@return number -- velocity slew rate +function AR_PosControl:get_srate() end + -- desc ---@class follow follow = {} diff --git a/libraries/AP_Scripting/drivers/EFI_DLA.lua b/libraries/AP_Scripting/drivers/EFI_DLA.lua new file mode 100644 index 00000000000000..9c764ac4a38b2f --- /dev/null +++ b/libraries/AP_Scripting/drivers/EFI_DLA.lua @@ -0,0 +1,188 @@ +--[[ + DLA serial EFI protocol + + Note that this protocol is gap framed, no CRC + + https://www.austars-model.com/dla-232cc-uavuas-engine-optional-one-key-startauto-startergenerator_g17937.html +--]] + +local PARAM_TABLE_KEY = 41 +local PARAM_TABLE_PREFIX = "EFI_DLA_" + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +-- bind a parameter to a variable given +local 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 +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 + +-- setup script specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 8), 'could not add param table') + +--[[ + // @Param: EFI_DLA_ENABLE + // @DisplayName: EFI DLA enable + // @Description: Enable EFI DLA driver + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +EFI_DLA_ENABLE = bind_add_param("ENABLE", 1, 0) + +--[[ + // @Param: EFI_DLA_LPS + // @DisplayName: EFI DLA fuel scale + // @Description: EFI DLA litres of fuel per second of injection time + // @Range: 0.00001 1 + // @Units: litres + // @User: Standard +--]] +EFI_DLA_LPS = bind_add_param("LPS", 2, 0.001) + +if EFI_DLA_ENABLE:get() ~= 1 then + return +end + +local uart = serial:find_serial(0) -- first scripting serial +if not uart then + gcs:send_text(MAV_SEVERITY.ERROR, "EFI_DLA: unable to find scripting serial") + return +end +uart:begin(115200) + +local efi_backend = efi:get_backend(0) +if not efi_backend then + gcs:send_text(MAV_SEVERITY.ERROR, "EFI_DLA: unable to find EFI backend") + return +end + +--[[ + discard n bytes +--]] +local function discard_bytes(n) + for _ = 1, n do + uart:read() + end +end + +local function read_bytes(n) + local ret = "" + for _ = 1, n do + ret = ret .. string.char(uart:read()) + end + return ret +end + +local state = {} +state.last_read_us = uint32_t(0) +state.total_fuel_cm3 = 0.0 + +--[[ + check for input and parse data +--]] +local function check_input() + local n_bytes = uart:available():toint() + --gcs:send_text(MAV_SEVERITY.INFO, string.format("n_bytes=%u %.2f", n_bytes, millis():tofloat()*0.001)) + if n_bytes < 82 then + return + end + if n_bytes > 82 then + discard_bytes(n_bytes) + return + end + + state.seconds, state.pw1, state.pw2 = string.unpack(" 83 then + discard_pending() + return + end + + local tus = micros() + state.chk0 = 0 + state.chk1 = 0 + + -- look for basic data table 2 + header0, header1, source, target, dtype, num, id, ack = string.unpack(" 3 then + error("TOFSENSE: Only 3 devices supported") + end + + for i = 1, MAX_SENSORS:get() do + local backends_found = 0 + local sensor_driver_found = false + local lua_driver_backend + for j = 0, sensor_count -1 do + local device = sensor:get_backend(j) + if ((not sensor_driver_found) and device and (device:type() == param_num)) then + -- this is a lua driver + backends_found = backends_found + 1 + if backends_found == backend_driver[i].INSTANCE:get() then + -- get the correct instance as we may have multile scripting backends doing different things + sensor_driver_found = true + lua_driver_backend = device + end + end + end + if not sensor_driver_found then + -- We can't use this script if user hasn't setup a lua backend + error(string.format("TOFSENSE: Could not find SCR Backend ".. tostring(i))) + return + end + backend_driver[i].sensor_driver_found = true + backend_driver[i].lua_driver_backend = lua_driver_backend + end + +end + +-- get yaw and pitch of the pixel based message index. +function convert_to_angle(index) + -- The distances are sent in either a 4x4 or 8x8 grid. The horizontal and vertical FOV are 45 degrees so we can work out the angles + local index_row_max = 8 + if (MODE:get() ~= 0) then + index_row_max = 4 + end + local angle_division = 45/index_row_max + local horizontal_index = (index) % index_row_max + local vertical_index = math.floor(index / index_row_max) + local yaw = -22.5 + (horizontal_index*angle_division) + local pitch = -22.5 + (vertical_index*angle_division) + return yaw, pitch +end + +-- send the message down to proximity library. This needs to be a 3D vector +function sent_prx_message(prx_backend, dist, yaw_deg, pitch_deg, push_to_boundary) + if (dist > 0) then + prx_backend:set_distance_min_max(0,4) + prx_backend:handle_script_distance_msg(dist, yaw_deg, pitch_deg, push_to_boundary) + end +end + +-- send the message down to proximity library. This needs to be a single distance +function send_rfnd_message(rfnd_backend, dist) + if dist > 0 and (SET_PRX:get() == 0) then + local sent_successfully = rfnd_backend:handle_script_msg(dist) + if not sent_successfully then + -- This should never happen as we already checked for a valid configured lua backend above + gcs:send_text(0, string.format("RFND Lua Script Error")) + end + end +end + +-- get the correct instance from parameters according to the CAN ID received +function get_instance_from_CAN_ID(frame) + for i = 1, MAX_SENSORS:get() do + if ((uint32_t(frame:id() - 0x200)) == uint32_t(backend_driver[i].CAN_ID:get())) then + return i + end + end + return 0 +end + +-- this is the loop which periodically runs +function update() + + -- setup the sensor according to user preference of using proximity library or rangefinder + if not sensor_setup_done then + if SET_PRX:get() == 0 then + setup_sensor(rangefinder, param_num_lua_driver_backend) + else + setup_sensor(proximity, param_num_lua_prx_backend) + end + sensor_setup_done = true + end + + -- read frame if available + local frame = driver:read_frame() + if not frame then + return + end + + local instance + if ((backend_driver[1].CAN_ID:get() ~= 0)) then + instance = get_instance_from_CAN_ID(frame) + if (instance == 0) then + -- wrong ID + return + end + else + -- Simply accept any ID + instance = 1 + end + + -- Correct ID, so parse the data + local distance = ((frame:data(0)<<8 | frame:data(1)<<16 | frame:data(2)<<24)/256) / 1000 + local status = frame:data(3) + local index = frame:data(6) + local update_rfnd = false + if (index < backend_driver[instance].last_index) then + -- One cycle of data has come. Lets update all backends involved + if SET_PRX:get() == 1 then + backend_driver[instance].lua_driver_backend:update_virtual_boundary() + else + update_rfnd = true + end + end + backend_driver[instance].last_index = index + + if status < 255 then + -- Status is healthy + if (SET_PRX:get() == 1) then + -- Send 3D data to Proximity Library + local yaw, pitch = convert_to_angle(index) + sent_prx_message(backend_driver[instance].lua_driver_backend, distance, yaw, pitch, false) + end + if (backend_driver[instance].min_distance == 0 or distance < backend_driver[instance].min_distance) then + -- store min data incase user wants to use it as a 1-D RangeFinder + backend_driver[instance].min_distance = distance + end + end + + if (update_rfnd) then + send_rfnd_message(backend_driver[instance].lua_driver_backend, backend_driver[instance].min_distance) + -- reset + backend_driver[instance].min_distance = 0 + end +end + +-- wrapper around update(). This calls update() and if update faults +-- then an error is displayed, but the script is not stopped +function protected_wrapper() + local success, err = pcall(update) + if not success then + gcs:send_text(MAV_SEVERITY_ERROR, "Internal Error: " .. err) + -- when we fault we run the update function again after 1s, slowing it + -- down a bit so we don't flood the console with errors + return protected_wrapper, 1000 + end + return protected_wrapper, update_rate_ms +end + +-- start running update loop +return protected_wrapper() diff --git a/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_CAN.md b/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_CAN.md new file mode 100644 index 00000000000000..a6a494f299fc4c --- /dev/null +++ b/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_CAN.md @@ -0,0 +1,50 @@ +# TOFSense-M CAN Driver + +TOFSense-M CAN Driver lua script. Only Copter/Rover/Plane 4.5 and above + +## How to use - Pre-Configuration + +- Connect sensors to autopilot's CAN1 port or CAN2 port +- If connected to CAN1, set CAN_D1_PROTOCOL = 10 (Scripting), CAN_P1_DRIVER = 1 (First driver) +- If connected to CAN2, set CAN_D2_PROTOCOL = 10 (Scripting), CAN_P2_DRIVER = 2 (Second driver) +- Set SCR_ENABLE = 1 to enable scripting +- Set SCR_HEAP_SIZE = 150000 (or higher) +- If using the sensor as a 1-D Rangefinder (typically for terrain following); set RNGFND1_TYPE = 36 (Scripting) to enable the rangefinder scripting driver +- If using the sensor as a 3-D Proximity sensor (typically for obstacle); set PRX1_TYPE = 15 (Scripting) to enable the proximity scripting driver +- Reboot the autopilot +- Copy the TOFSense-M_CAN.lua script to the autopilot's SD card in the APM/scripts directory and reboot the autopilot + + +## How to use - Script Parameter Configuration + +If everything above is done correctly, new "TOFSENSE_" parameters should be visible (only after script loads. Please refresh parameters if not visible). Script parameters to adjust are listed below + +### TOFSENSE_PRX +If you have set RNGFND1_TYPE = 36, then set this as 0 +If you have set PRX1_TYPE = 15, then set this as 1 +Any change in this parameter will require a reboot (or scripting restart), ignore any errors on change before reboot. Make sure RNGFND/PRX is configured before setting this. + + +### TOFSENSE_NO +Total number of TOFSense-M CAN sensors connected on the bus. Change will require a reboot + + +### TOFSENSE_MODE +TOFSENSE-M mode to be used. +- 0 for 8x8 mode. +- 1 for 4x4 mode. +All sensors must be in same mode. You can change the mode of sensor from NAssistant Software + +### TOFSENSE_ID1 +First TOFSENSE-M sensor ID. Leave this at 0 to accept all IDs and if only one sensor is present. You can change ID of sensor from NAssistant Software. + + +### TOFSENSE_INST1 +First TOFSENSE-M sensors RNGFND_/PRX_ Instance +Setting this to 1 will pick the first backend from PRX_ or RNG_ Parameters. +So for example if RNGFND1_TYPE = 36, RNGFND2_TYPE = 36, then you can set this parameter to 2, to pick RNGFND2_ parameters to configure this sensor + + +### Configuring more than one sensor on same CAN bus + +As described above, TOFSENSE_INST2, TOFSENSE_ID2 and TOFSENSE_INST3, TOFSENSE_ID3 can be adjusted so to support multiple sensors \ No newline at end of file diff --git a/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_Serial.lua b/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_Serial.lua new file mode 100644 index 00000000000000..d6c495422cc23c --- /dev/null +++ b/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_Serial.lua @@ -0,0 +1,252 @@ +--[[ + Upto 3 CAN devices supported in this script although its easy to extend. +--]] + +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 +local debug_enable = false -- helpgul debug GCS prints + +-- Global variables (DO NOT CHANGE) +local NOOPLOOP_FRAME_HEADER = 0x57 +local NOOPLOOP_FRAME_HEADER_1 = 0x01 +local param_num_lua_driver_backend = 36 -- parameter number for lua rangefinder +local param_num_lua_prx_backend = 15 -- parameter number for lua proximity +local lua_driver_backend -- store lua backend here +local sensor_driver_found = false -- true if user has configured lua backend +local num_pixels = 16 -- automatically updated if 64. User can select between 16/64 from NAssistant software +local total_bytes_to_expect = 112 -- total bytes in one complete packet +local linebuf = {} -- serial buffer +local linebuf_len = 0 +local index_row_max = 8 + +local PARAM_TABLE_KEY = 109 + sensor_no +local PARAM_TABLE_PREFIX = string.format("TOFSENSE_S" .. sensor_no.. "_") + +-- bind a parameter to a variable +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +-- setup parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 3), 'could not add param table') + +--[[ + // @Param: TOFSENSE_S1_PRX + // @DisplayName: TOFSENSE-M to be used as Proximity sensor + // @Description: Set 0 if sensor is to be used as a 1-D rangefinder (minimum of all distances will be sent, typically used for height detection). Set 1 if it should be used as a 3-D proximity device (Eg. Obstacle Avoidance) + // @Values: 0:Set as Rangefinder, 1:Set as Proximity sensor + // @User: Standard +--]] +SET_PRX = bind_add_param('PRX', 1, 0) + +--[[ + // @Param: TOFSENSE_S1_SP + // @DisplayName: TOFSENSE-M serial port config + // @Description: UART instance sensor is connected to. Set 1 if sensor is connected to the port with fist SERIALx_PROTOCOL = 28. + // @Range: 1 4 + // @User: Standard +--]] +SERIAL_PORT = bind_add_param('SP', 2, 1) + +--[[ + // @Param: TOFSENSE_S1_BR + // @DisplayName: TOFSENSE-M serial port baudrate + // @Description: Serial Port baud rate. Sensor baud rate can be changed from Nassistant software + // @User: Standard +--]] +SERIAL_BAUD = bind_add_param('BR', 3, 230400) + +-- find the serial scripting serial port instance. 0 indexed. +-- SERIALx_PROTOCOL 28 +local port = assert(serial:find_serial(SERIAL_PORT:get() - 1),"Could not find Scripting Serial Port") + +-- begin the serial port +port:begin(SERIAL_BAUD:get()) +-- port:set_flow_control(0) + +function setup_sensor(sensor, param_num) + local sensor_count = sensor:num_sensors() -- number of sensors connected + for j = 0, sensor_count -1 do + local device = sensor:get_backend(j) + if ((not sensor_driver_found) and device and (device:type() == param_num)) then + -- this is a lua driver + sensor_driver_found = true + lua_driver_backend = device + end + end + if not sensor_driver_found then + -- We can't use this script if user hasn't setup a lua backend + gcs:send_text(0, string.format("Configure Lua Sensor")) + return + end +end + +-- get yaw and pitch of the pixel based message index. +function convert_to_angle(index) + -- The distances are sent in either a 4x4 or 8x8 grid. The horizontal and vertical FOV are 45 degrees so we can work out the angles + local angle_division = 45/index_row_max + local horizontal_index = (index) % index_row_max + local vertical_index = math.floor(index / index_row_max) + local yaw = -22.5 + (horizontal_index*angle_division) + local pitch = -22.5 + (vertical_index*angle_division) + return yaw, pitch +end + +-- send the message down to proximity library. This needs to be a 3D vector. User of this function needs to ensure prx backend exists +function sent_prx_message(dist, yaw_deg, pitch_deg, push_to_boundary) + if dist > 0 then + lua_driver_backend:set_distance_min_max(0,4) + lua_driver_backend:handle_script_distance_msg(dist, yaw_deg, pitch_deg, push_to_boundary) + end +end + +-- send the message down to proximity library. This needs to be a single distance. User of this function needs to ensure rngfnd backend exists +function send_rfnd_message(dist) + if dist > 0 then + local sent_successfully = lua_driver_backend:handle_script_msg(dist) + if not sent_successfully then + -- This should never happen as we already checked for a valid configured lua backend above + gcs:send_text(0, string.format("RFND Lua Script Error")) + end +end +end + +function update() -- this is the loop which periodically runs + + if not sensor_driver_found then + if SET_PRX:get() == 0 then + setup_sensor(rangefinder, param_num_lua_driver_backend) + else + setup_sensor(proximity, param_num_lua_prx_backend) + end + end + + if (not sensor_driver_found) then + -- We can't use this script if user hasn't setup a lua backend + return + end + + local nbytes = port:available() + nbytes = math.min(nbytes, bytes_to_parse) + while nbytes > 0 do + nbytes = nbytes - 1 + local r = port:read() + if r < 0 then + break + end + local c = r + + -- if buffer is empty and this byte is 0x57, add to buffer + if linebuf_len == 0 then + if c == NOOPLOOP_FRAME_HEADER then + -- lua table indexing starts from 1 + linebuf[linebuf_len + 1] = c + linebuf_len = linebuf_len + 1 + else + linebuf_len = 0 + end + elseif linebuf_len == 1 then + -- if buffer has 1 element and this byte is 0x00, add it to buffer + -- if not clear the buffer + if c == NOOPLOOP_FRAME_HEADER_1 then + linebuf[linebuf_len + 1] = c + linebuf_len = linebuf_len + 1 + else + linebuf_len = 0 + end + + elseif linebuf_len == 8 then + -- store the next character as "number of pixels" + num_pixels = tonumber(c) + linebuf[linebuf_len + 1] = c + linebuf_len = linebuf_len + 1 + -- Check if num_pixels is either 64 or 16 + if num_pixels ~= 64 and num_pixels ~= 16 then + linebuf_len = 0 + end + --update total bytes to expect + total_bytes_to_expect = 16 + (num_pixels * 6) + if num_pixels == 16 then + index_row_max = 4 + end + else + -- add character to buffer + linebuf[linebuf_len + 1] = c + linebuf_len = linebuf_len + 1 + if linebuf_len == total_bytes_to_expect then + -- calculate checksum + local checksum = 0 + for i = 1, total_bytes_to_expect - 1 do + checksum = (checksum + linebuf[i]) % 256 + end + -- if checksum matches extract contents + if checksum ~= linebuf[total_bytes_to_expect] then + if debug_enable then + gcs:send_text(0, "Checksum does not matches") + end + else + local min_distance = 0 + local min_index = 0 + local index = -1 + for i = 10, total_bytes_to_expect - 7, 6 do + local distance = ((linebuf[i]<<8 | linebuf[i+1]<<16 | linebuf[i+2]<<24)/256) / 1000000 + local status = linebuf[i+3] + index = index + 1 + if status < 255 then + if (SET_PRX:get() == 1) then + local yaw, pitch = convert_to_angle(index) + if debug_enable then + gcs:send_text(0, "Distance debug: " .. distance .. " mm, status: " .. status .. "Yaw " .. yaw .. "pitch " .. pitch) + end + sent_prx_message(distance, yaw, pitch, false) + end + if status == 0 and (min_distance == 0 or distance < min_distance) then + min_distance = distance + min_index = index + end + end + end + + if (SET_PRX:get() == 1) then + -- update prx boundary now that we have parsed all data + lua_driver_backend:update_virtual_boundary() + else if min_distance > 0 then + if debug_enable then + local yaw,pitch = convert_to_angle(min_index) + gcs:send_text(0, "Distance: " .. min_distance .. " m. Yaw " .. yaw .. "pitch " .. pitch) + end + send_rfnd_message(min_distance) + end + end + end + -- clear buffer + linebuf_len = 0 + end + end + end +end + +-- wrapper around update(). This calls update() and if update faults +-- then an error is displayed, but the script is not stopped +function protected_wrapper() + local success, err = pcall(update) + if not success then + gcs:send_text(MAV_SEVERITY_ERROR, "Internal Error: " .. err) + -- when we fault we run the update function again after 1s, slowing it + -- down a bit so we don't flood the console with errors + return protected_wrapper, 1000 + end + return protected_wrapper, update_rate_ms +end + +-- start running update loop +return protected_wrapper() diff --git a/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_Serial.md b/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_Serial.md new file mode 100644 index 00000000000000..40d8951fcf12b2 --- /dev/null +++ b/libraries/AP_Scripting/drivers/TOFSense-M/TOFSense-M_Serial.md @@ -0,0 +1,37 @@ +# TOFSense-M Serial Driver + +TOFSense-M Serial Driver lua script. Only Copter/Rover/Plane 4.5 and above + +## How to use - Pre-Configuration + +- Connect sensors to one of autopilot's Serial port +- Set SERIALx_PROTOCOL 28 +- Set SCR_ENABLE = 1 to enable scripting +- Set SCR_HEAP_SIZE = 150000 (or higher) +- If using the sensor as a 1-D Rangefinder (typically for terrain following); set RNGFND1_TYPE = 36 (Scripting) to enable the rangefinder scripting driver +- If using the sensor as a 3-D Proximity sensor (typically for obstacle); set PRX1_TYPE = 15 (Scripting) to enable the proximity scripting driver +- Reboot the autopilot +- Copy the TOFSense-M_Serial.lua script to the autopilot's SD card in the APM/scripts directory and reboot the autopilot + +## How to use - Script Parameter Configuration + +If everything above is done correctly, new "TOFSENSE_S_" parameters should be visible (only after script loads. Please refresh parameters if not visible). Script parameters to adjust are listed below. Any changes would require reboot + +### TOFSENSE_S1_PRX +If you have set RNGFND1_TYPE = 36, then set this as 0 +If you have set PRX1_TYPE = 15, then set this as 1 +Any change in this parameter will require a reboot (or scripting restart), ignore any errors on change before reboot. Make sure RNGFND/PRX is configured before setting this. + +### TOFSENSE_S1_SP +UART instance sensor is connected to. Set 1 if sensor is connected to the port with fist SERIALx_PROTOCOL = 28. For example, if SERIAL1_PROTOCOL = 28, and SERIAL2_PROTOCOL = 28, then setting this parameter 2 would assume the SERIAL2 port is attached to the sensor + +### TOFSENSE_S1_BR +Serial Port baud rate. Sensor baud rate of the sensor can be changed from Nassistant software + + +## Advanced: Configuring more than one sensor on different Serial ports + +It is not recommended to use this driver for more than one sensor. However, it is possible if you wish to do it. +Simply make a copy of the lua script, open it and change the first line "local sensor_no = 1" to "local sensor_no = 2" and upload that script along side the first script. +Once a reboot is done, new TOFSENSE_S2_ parameters should be visible which can be configured as described above. + diff --git a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua index 7f94df7b4e5817..ac050cabc66339 100644 --- a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua @@ -462,7 +462,7 @@ function send_target_angles(roll_angle_deg, pitch_angle_deg, yaw_angle_deg, time end -- ensure angles are integers - roll_angle_deg = -math.floor(roll_angle_deg + 0.5) + roll_angle_deg = math.floor(roll_angle_deg + 0.5) pitch_angle_deg = math.floor(pitch_angle_deg + 0.5) yaw_angle_deg = math.floor(yaw_angle_deg + 0.5) time_sec = math.floor(time_sec + 0.5) @@ -657,8 +657,8 @@ function parse_byte(b) local ret_code = parse_buff[13] if ret_code == RETURN_CODE.SUCCESS then local yaw_deg = int16_value(parse_buff[16],parse_buff[15]) * 0.1 - local roll_deg = -int16_value(parse_buff[18],parse_buff[17]) * 0.1 - local pitch_deg = int16_value(parse_buff[20],parse_buff[19]) * 0.1 + local pitch_deg = int16_value(parse_buff[18],parse_buff[17]) * 0.1 + local roll_deg = int16_value(parse_buff[20],parse_buff[19]) * 0.1 mount:set_attitude_euler(MOUNT_INSTANCE, roll_deg, pitch_deg, yaw_deg) if DJIR_DEBUG:get() > 1 then gcs:send_text(MAV_SEVERITY.INFO, string.format("DJIR: roll:%4.1f pitch:%4.1f yaw:%4.1f", roll_deg, pitch_deg, yaw_deg)) diff --git a/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua b/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua index dcbf158561fbc3..9786e6327bba34 100644 --- a/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua @@ -379,7 +379,7 @@ function parse_byte(b) local servo_status = (parse_data_buff[24] & 0xF0 >> 4) local roll_deg = int16_value(parse_data_buff[24] & 0x0F, parse_data_buff[25]) * (180.0/4095.0) - 90.0 local yaw_deg = int16_value(parse_data_buff[26], parse_data_buff[27]) * (360.0 / 65536.0) - local pitch_deg = int16_value(parse_data_buff[28], parse_data_buff[29]) * (360.0 / 65536.0) + local pitch_deg = -int16_value(parse_data_buff[28], parse_data_buff[29]) * (360.0 / 65536.0) mount:set_attitude_euler(MOUNT_INSTANCE, roll_deg, pitch_deg, yaw_deg) if VIEP_DEBUG:get() > 0 then diff --git a/libraries/AP_Scripting/examples/MAVLinkHL.lua b/libraries/AP_Scripting/examples/MAVLinkHL.lua index 6067f81316529d..3ee4f4f5e0f789 100644 --- a/libraries/AP_Scripting/examples/MAVLinkHL.lua +++ b/libraries/AP_Scripting/examples/MAVLinkHL.lua @@ -440,7 +440,7 @@ function HLSatcom() hl2.temperature_air = math.floor(baro:get_external_temperature()) - if battery:num_instances() > 0 then + if battery:num_instances() > 0 and battery:capacity_remaining_pct(0) ~= nil then hl2.battery = battery:capacity_remaining_pct(0) else hl2.battery = 0 diff --git a/libraries/AP_Scripting/examples/UART_log.lua b/libraries/AP_Scripting/examples/UART_log.lua index 28b91b0ee2c82e..927b6054c6ae1c 100644 --- a/libraries/AP_Scripting/examples/UART_log.lua +++ b/libraries/AP_Scripting/examples/UART_log.lua @@ -100,7 +100,7 @@ function update() -- format characters specify the type of variable to be logged, see AP_Logger/README.md -- not all format types are supported by scripting only: i, L, e, f, n, M, B, I, E, N, and Z -- Note that Lua automatically adds a timestamp in micro seconds - logger:write('SCR','Sensor1, Sensor2, Sensor3','fff',table.unpack(log_data)) + logger:write('SCR','Sensor1,Sensor2,Sensor3','fff',table.unpack(log_data)) -- reset for the next message log_data = {} diff --git a/libraries/AP_Scripting/examples/copter_pingpong.lua b/libraries/AP_Scripting/examples/copter_pingpong.lua new file mode 100644 index 00000000000000..2544883db8296c --- /dev/null +++ b/libraries/AP_Scripting/examples/copter_pingpong.lua @@ -0,0 +1,108 @@ +-- This script makes the drone go forward and backward at a defined distance and number of times. +-- The stages are: +-- 0) Change to Guided mode +-- 1) Takeoff to the height defined by takeoff_alt +-- 2) Wait until reaching the takeoff altitude +-- 3) Go forward to the defined distance +-- 4) Go back to the initial position +-- 5) Change to Land mode + +local takeoff_alt = 3 -- Takeoff height +local copter_guided_mode_num = 4 +local copter_land_mode_num = 9 +local stage = 0 +local count = 0 -- Number of times the drone has gone forward +local max_count = 2 -- Maximum number of times the drone should go forward +local ping_pong_distance = 10 -- Distance up to which the drone should go forward (m) +local vel = 1 -- Drone velocity (m/s) + +function update() + -- Checking if the drone is armed + if not arming:is_armed() then + -- Reset state when disarmed + stage = 0 + gcs:send_text(6, "Arming") + else + if stage == 0 then -- Stage0: Change to guided mode + if vehicle:set_mode(copter_guided_mode_num) then -- Change to Guided mode + stage = stage + 1 + end + + elseif stage == 1 then -- Stage1: Takeoff + gcs:send_text(6, "Taking off") + if vehicle:start_takeoff(takeoff_alt) then + stage = stage + 1 + end + + elseif stage == 2 then -- Stage2: Check if the vehicle has reached the target altitude + local home = ahrs:get_home() + local curr_loc = ahrs:get_position() + if home and curr_loc then + local vec_from_home = home:get_distance_NED(curr_loc) + gcs:send_text(6, "Altitude above home: " .. tostring(math.floor(-vec_from_home:z()))) + if math.abs(takeoff_alt + vec_from_home:z()) < 1 then + stage = stage + 1 + end + end + elseif stage == 3 then -- Stage3: Moving Forward + -- If the number of times is exceeded, switch to stage5 + if count >= max_count then + stage = stage + 2 + end + + -- Calculate velocity vector + local target_vel = Vector3f() + target_vel:x(vel) + target_vel:y(0) + target_vel:z(0) + + -- Send velocity request + if not vehicle:set_target_velocity_NED(target_vel) then + gcs:send_text(6, "Failed to execute velocity command") + end + + -- Checking if the stop point is reached + local home = ahrs:get_home() + local curr_loc = ahrs:get_position() + if home and curr_loc then + local vec_from_home = home:get_distance_NED(curr_loc) + gcs:send_text(6, "Distance from home: " .. tostring(math.floor(vec_from_home:x()))) + if math.abs(ping_pong_distance - vec_from_home:x()) < 1 then + count = count + 1 + stage = stage + 1 + end + end + + elseif stage == 4 then -- Stage4: Moving Back + -- Calculate velocity vector + local target_vel = Vector3f() + target_vel:x(-vel) + target_vel:y(0) + target_vel:z(0) + + -- Send velocity request + if not vehicle:set_target_velocity_NED(target_vel) then + gcs:send_text(6, "Failed to execute velocity command") + end + + -- Checking if the stop point is reached + local home = ahrs:get_home() + local curr_loc = ahrs:get_position() + if home and curr_loc then + local vec_from_home = home:get_distance_NED(curr_loc) + gcs:send_text(6, "Distance from home: " .. tostring(math.floor(vec_from_home:x()))) + if math.abs(vec_from_home:x()) < 1 then + stage = stage - 1 + end + end + + elseif stage == 5 then -- Stage5: Change to land mode + vehicle:set_mode(copter_land_mode_num) + stage = stage + 1 + gcs:send_text(6, "Finished pingpong, switching to land") + end + end + return update, 100 +end + +return update() \ No newline at end of file diff --git a/libraries/AP_Scripting/examples/copter_pingpong.md b/libraries/AP_Scripting/examples/copter_pingpong.md new file mode 100644 index 00000000000000..612054b8b3b9bb --- /dev/null +++ b/libraries/AP_Scripting/examples/copter_pingpong.md @@ -0,0 +1,188 @@ +# Drone Ping-Pong Code + +This script makes the drone go forward and backward a defined distance and number of times. + + +## Stages +- 0: Change to Guided mode +- 1: Takeoff to the height defined by `takeoff_alt` +- 2: Wait until reaching the takeoff altitude +- 3: Go forward to the defined distance +- 4: Go back to the initial position +- 5: Change to Land mode + +## Variables: +- `takeoff_alt`: Takeoff height (m) +- `copter_guided_mode_num`: Guided mode number +- `copter_land_mode_num`: Land mode number +- `stage`: current stage +- `count`: Number of times the drone has gone forward +- `max_count`: Maximum number of times the drone should go forward +- `ping_pong_distance`: Distance up to which the drone should go forward (m) +- `vel`: Drone velocity (m/s) + +## Understand the code: +First, there is a comment explaining what the code is about and how it works. Then, the local variables that will be used are declared. + The `copter_guided_mode_num` and `copter_land_mode_num `are standard numbers, defined by ArduPilot, for the Guided and Land flight modes, respectively. The other variables are user-defined settings according to the desired behavior, as indicated in the comments in front of each one. + +```lua +-- This script makes the drone go forward and backward at a defined distance and number of times. +-- The stages are: +-- 0) Change to Guided mode +-- 1) Takeoff to the height defined by takeoff_alt +-- 2) Wait until reaching the takeoff altitude +-- 3) Go forward to the defined distance +-- 4) Go back to the initial position +-- 5) Change to Land mode + + +local takeoff_alt = 3 -- Takeoff height +local copter_guided_mode_num = 4 +local copter_land_mode_num = 9 +local stage = 0 +local count = 0 -- Number of times the drone has gone forward +local max_count = 2 -- Maximum number of times the drone should go forward +local ping_pong_distance = 10 -- Distance up to which the drone should go forward (m) +local vel = 1 + +``` +Next, there's the main function of the code, the `update()` function, which will be called once the code is started (since it wasn't indicated a waiting time at the last line of the code) and its `return` indicates that this same fucntion will be called again 100ms after finishing its executuion. + + + +```lua +function update() + -- [Code] + return update(), 100 +end + +return update() +``` + +In the presented if, the code is waiting for the drone to be armed to change to the next stage. The is_armed() function from the arming library is used to check if the drone is armed or not. The send_text() function from the gcs library is used to send a message ("Arming") with severity 6 (information) to the GCS (Ground Control Station). Thus, while the drone is not armed, it remains in stage 0 of the code. + +``` lua +if not arming:is_armed() then + stage = 0 + gcs:send_text(6, "Arming") +``` +If the drone is armed, it moves to the else section, which presents a behavior for each stage. +In `stage 0`, the drone flight mode is changed to GUIDED MODE. To do this, it's used the function `set_mode()` of `vehicle` library, which receives the desired flight mode number(copter_guided_mode_num, defined in the local variables). When it verifies the drone has switched to the desired flight mode, it moves to the next stage. + + +``` lua +else + if stage == 0 then + if vehicle:set_mode(copter_guided_mode_num) then + stage = stage + 1 + end +``` +in stage 1, it's used the `start_takeoff()` function from the `vehicle` library for the drone to take off to a height defined by the variable `takeoff_alt`. + +``` lua +elseif stage == 1 then + gcs:send_text(6, "Taking off") + if vehicle:start_takeoff(takeoff_alt) then + stage = stage + 1 + end +``` + +In stage 2, it's used the `ahrs:get_home()` function to get the drone's takeoff location, and the `ahrs:get_position()` function to get the drone's current position. In line 4, it checks that the obtained values are not null. Then, the `home:get_distance_NED()` function stores in `vec_from_home` a 3D vector, starting from `curr_loc` and ending at `home`. In line 7, the code sends to the GCS the value contained in the z-coordinate of `vec_from_home`, i.e., the current altitude of the drone (multiplied by -1 since the vector points towards home, which is at a lower altitude than the current position). + +When the difference between `takeoff_alt` and `vec_from_home:z()` is less than 1, indicating that the drone has reached the takeoff altitude, it moves to the next stage (`math.abs()` is used to get the absolute value, and we performed an addition instead of subtraction because the z component is negative). + +``` lua +elseif stage == 2 then + local home = ahrs:get_home() + local curr_loc = ahrs:get_position() + if home and curr_loc then + local vec_from_home = home:get_distance_NED(curr_loc) + gcs:send_text(6, "Altitude above home: " .. tostring(math.floor(-vec_from_home:z()))) + if math.abs(takeoff_alt + vec_from_home:z()) < 1 then + stage = stage + 1 + end + end +``` + +In `stage3`, first, the drone checks if it has already performed all the requested loops specified in `max_count`. If so, it switches to `stage5`. If not, it executes the commands of `stage3`. + +First, it creates a 3D vector `target_vel` to store the desired velocity. Then, it sets the value of each of the components of this created vector (0 for y and z, and `vel` for x). + +Then, it uses the `vehicle:set_target_velocity_NED(target_vel)` function to set the drone's velocity as that of `target_vel`. If it encounters any issues, it sends a warning message. + + +``` lua +elseif (stage == 3) then -- Stage 3: Moving Forward + -- If the maximum number of times is exceeded, move to stage 5 + if (count >= max_count) then + stage = stage + 2 + end + + -- Calculate velocity vector + local target_vel = Vector3f() + target_vel:x(vel) + target_vel:y(0) + target_vel:z(0) + + -- Send velocity request + if not (vehicle:set_target_velocity_NED(target_vel)) then + gcs:send_text(6, "Failed to execute velocity command") + end + +``` + +After that, it uses the same strategy as shown before to calculate the distance vector from the takeoff location to verify the distance `x` traveled. When the difference between the distance `x` that the drone traveled and the `ping_pong_distance` is less than 1, it increments the `count` and moves to the next stage. +``` lua + + -- checking if reached stop point + local home = ahrs:get_home() + local curr_loc = ahrs:get_position() + if home and curr_loc then + local vec_from_home = home:get_distance_NED(curr_loc) + gcs:send_text(6, "Distance from home: " .. tostring(math.floor(vec_from_home:x()))) + if(math.abs(ping_pong_distance - vec_from_home:x()) < 1) then + count = count + 1 + stage = stage + 1 + end + end +end + +``` +In `Stage4`, the velocity in `x` is multiplied by -1 for the drone to fly in the opposite direction, returning to the takeoff position. When the difference between the drone's position `x` and the takeoff position's `x` is less than 1, it goes back to `Stage3` to start the forward movement again (or not, if the `count` has reached `max_count`). + +``` lua +elseif (stage == 4) then -- Stage 4: Moving Back + -- calculate velocity vector + local target_vel = Vector3f() + target_vel:x(-vel) + target_vel:y(0) + target_vel:z(0) + + -- send velocity request + if not (vehicle:set_target_velocity_NED(target_vel)) then + gcs:send_text(6, "Failed to execute velocity command") + end + + -- checking if reached stop point + local home = ahrs:get_home() + local curr_loc = ahrs:get_position() + if home and curr_loc then + local vec_from_home = home:get_distance_NED(curr_loc) + gcs:send_text(6, "Distance from home: " .. tostring(math.floor(vec_from_home:x()))) + if(math.abs(vec_from_home:x()) < 1) then + stage = stage - 1 + end + end +end + +``` +In `stage5`, the drone simply changes to the Land flight mode and lands, indicating the completion of the code through a message. +``` lua +elseif (stage == 5) then -- Stage 5: Change to LAND mode + vehicle:set_mode(copter_rtl_mode_num) + stage = stage + 1 + gcs:send_text(6, "Finished pingpong, switching to LAND") +end + +``` + diff --git a/libraries/AP_Scripting/examples/rover-MinFixType.lua b/libraries/AP_Scripting/examples/rover-MinFixType.lua old mode 100755 new mode 100644 diff --git a/libraries/AP_Scripting/examples/rover-SaveTurns.lua b/libraries/AP_Scripting/examples/rover-SaveTurns.lua old mode 100755 new mode 100644 diff --git a/libraries/AP_Scripting/examples/test_script_button.lua b/libraries/AP_Scripting/examples/test_script_button.lua new file mode 100644 index 00000000000000..c5b0c6f5eab799 --- /dev/null +++ b/libraries/AP_Scripting/examples/test_script_button.lua @@ -0,0 +1,33 @@ +-- Test ArduSub script buttons + +-- This will map the script buttons to the _shifted_ XBox controller buttons A, B, Z, Y: +-- param set BTN0_SFUNCTION 108 +-- param set BTN1_SFUNCTION 109 +-- param set BTN2_SFUNCTION 110 +-- param set BTN3_SFUNCTION 111 + +function update() + -- called every 5s + + -- show current status of the buttons + local is_pressed = {} + for i = 1, 4 do + is_pressed[i] = sub:is_button_pressed(i) + end + + gcs:send_text(6, string.format("is script button pressed? %s, %s, %s, %s", + tostring(is_pressed[1]), tostring(is_pressed[2]), tostring(is_pressed[3]), tostring(is_pressed[4]))) + + -- count how many times the buttons were pressed in the last five seconds + local count = {} + for i = 1, 4 do + count[i] = sub:get_and_clear_button_count(i) + end + + gcs:send_text(6, string.format("script button counts: %d, %d, %d, %d", + count[1], count[2], count[3], count[4])) + + return update, 5000 +end + +return update(), 5000 diff --git a/libraries/AP_Scripting/examples/winch-test.lua b/libraries/AP_Scripting/examples/winch-test.lua deleted file mode 100644 index 857e62c48be6f5..00000000000000 --- a/libraries/AP_Scripting/examples/winch-test.lua +++ /dev/null @@ -1,97 +0,0 @@ --- mount-test.lua: allows the winch to be deployed or retracted at a fixed speed using an auxiliary switch --- --- How To Use --- 1. set RCx_OPTION to 300 to enable controlling the winch rate from an auxiliary switch --- 2. optionally set WINCH_RATE_UP to the fixed retract speed (in m/s) --- 3. optionally set WINCH_RATE_DN to the fixed deploy speed (in m/s) --- 4. raise the RC auxiliary switch to retract the winch's line --- 5. lower the RC auxiliary switch to deploy the winch's line --- 6. center the RC auxiliary switch to stop the winch --- Alternatively a servo *output* can be used in place of the auxiliary switch input by setting WINCH_SRV_SRC_FN to match a servo channel's function. For example --- a. set SERVO10_FUNCTION = 28 (Gripper) --- b. set WINCH_SRV_SRC_FN to 28 --- c. use Mission Planner's Data screen's Servo/Relay tab to set the SERVO10 output to Low, Mid or High values --- Note: the full list of SERVOx_FUNCTION values that will work are 0:None, 1:Manual, 22:SprayerPump, 23:SprayerSpinner, 28/Gripper, 51:RCIN1 to 66:RCIN16 --- - --- global definitions -local UPDATE_INTERVAL_MS = 100 - --- add new parameters -local PARAM_TABLE_KEY = 80 -assert(param:add_table(PARAM_TABLE_KEY, "WINCH_", 3), "could not add param table") -assert(param:add_param(PARAM_TABLE_KEY, 1, "RATE_UP", 0.5), "could not add WINCH_RATE_UP param") -assert(param:add_param(PARAM_TABLE_KEY, 2, "RATE_DN", 2), "could not add WINCH_RATE_DN param") -assert(param:add_param(PARAM_TABLE_KEY, 3, "SRV_SRC_FN", -1), "could not add WINCH_SRV_SRC_FN param") - -local winch_rate_up = Parameter("WINCH_RATE_UP") -local winch_rate_dn = Parameter("WINCH_RATE_DN") -local winch_srv_src_fn = Parameter("WINCH_SRV_SRC_FN") - --- local variables and definitions -local last_rc_switch_pos = -1 -- last known rc switch position. Used to detect change in RC switch position - --- the main update function -function update() - - local rc_switch_pos = 1 -- default to middle position - - -- check if servo output is used (as an input) - if winch_srv_src_fn:get() > 0 then - if not SRV_Channels:find_channel(winch_srv_src_fn:get()) then - gcs:send_text(3, string.format("Winch: SERVOx_FUNCTION = %d not found", winch_srv_src_fn:get())) -- MAV_SEVERITY_ERROR - return update, 10000 -- check again in 10 seconds - end - local output_pwm = SRV_Channels:get_output_pwm(winch_srv_src_fn:get()) - if output_pwm <= 0 then - -- servo output all zero so ignore - return update, UPDATE_INTERVAL_MS - end - if output_pwm <= 1300 then - rc_switch_pos = 0 -- LOW - elseif output_pwm >= 1700 then - rc_switch_pos = 2 -- HIGH - end - else - -- find RC channel used to control winch - local rc_switch_ch = rc:find_channel_for_option(300) --scripting ch 1 - if (rc_switch_ch == nil) then - gcs:send_text(3, "Winch: RCx_OPTION = 300 not set") -- MAV_SEVERITY_ERROR - return update, 10000 -- check again in 10 seconds - end - - -- get RC switch position - rc_switch_pos = rc_switch_ch:get_aux_switch_pos() - end - - -- initialise RC switch at startup - if last_rc_switch_pos == -1 then - last_rc_switch_pos = rc_switch_pos - end - - -- check if user has moved RC switch - if rc_switch_pos == last_rc_switch_pos then - return update, UPDATE_INTERVAL_MS - end - last_rc_switch_pos = rc_switch_pos - - -- set winch rate based on switch position - if rc_switch_pos == 0 then -- LOW, deploy winch line - local rate_dn = math.abs(winch_rate_dn:get()) - winch:set_desired_rate(rate_dn) - gcs:send_text(6, string.format("Winch: lowering at %.1f m/s", rate_dn)) - end - if rc_switch_pos == 1 then -- MIDDLE, stop winch - winch:set_desired_rate(0) - gcs:send_text(6, "Winch: stopped") - end - if rc_switch_pos == 2 then -- HIGH, retract winch line - local rate_up = math.abs(winch_rate_up:get()) - winch:set_desired_rate(-rate_up) - gcs:send_text(6, string.format("Winch: raising at %.1f m/s", rate_up)) - end - - return update, UPDATE_INTERVAL_MS -end - -return update() diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index bf0a2c26828247..b47e877241c86c 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -169,14 +169,23 @@ singleton AP_Notify method handle_rgb void uint8_t'skip_check uint8_t'skip_check singleton AP_Notify method handle_rgb_id void uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check include AP_Proximity/AP_Proximity.h +include AP_Proximity/AP_Proximity_Backend.h singleton AP_Proximity depends HAL_PROXIMITY_ENABLED == 1 +ap_object AP_Proximity_Backend depends HAL_PROXIMITY_ENABLED == 1 +ap_object AP_Proximity_Backend method handle_script_distance_msg boolean float'skip_check float'skip_check float'skip_check boolean +ap_object AP_Proximity_Backend method handle_script_3d_msg boolean Vector3f boolean +ap_object AP_Proximity_Backend method type uint8_t +ap_object AP_Proximity_Backend method set_distance_min_max boolean float'skip_check float'skip_check +ap_object AP_Proximity_Backend method update_virtual_boundary boolean + singleton AP_Proximity rename proximity singleton AP_Proximity method get_status uint8_t singleton AP_Proximity method num_sensors uint8_t singleton AP_Proximity method get_object_count uint8_t singleton AP_Proximity method get_closest_object boolean float'Null float'Null singleton AP_Proximity method get_object_angle_and_distance boolean uint8_t'skip_check float'Null float'Null +singleton AP_Proximity method get_backend AP_Proximity_Backend uint8_t'skip_check include AP_RangeFinder/AP_RangeFinder.h include AP_RangeFinder/AP_RangeFinder_Backend.h @@ -222,6 +231,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 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 @@ -229,9 +239,11 @@ singleton GCS method send_named_float void string float'skip_check singleton GCS method frame_type MAV_TYPE'enum singleton GCS method get_hud_throttle int16_t -singleton GCS depends HAL_HIGH_LATENCY2_ENABLED == 1 singleton GCS method get_high_latency_status boolean +singleton GCS method get_high_latency_status depends HAL_HIGH_LATENCY2_ENABLED == 1 + singleton GCS method enable_high_latency_connections void boolean +singleton GCS method enable_high_latency_connections depends HAL_HIGH_LATENCY2_ENABLED == 1 include AP_ONVIF/AP_ONVIF.h depends ENABLE_ONVIF == 1 singleton AP_ONVIF depends ENABLE_ONVIF == 1 @@ -263,6 +275,7 @@ singleton AP_Vehicle method set_target_angle_and_climbrate boolean float -180 18 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 +singleton AP_Vehicle method get_steering_and_throttle boolean float'Null float'Null singleton AP_Vehicle method get_wp_distance_m boolean float'Null singleton AP_Vehicle method get_wp_bearing_deg boolean float'Null singleton AP_Vehicle method get_wp_crosstrack_error_m boolean float'Null @@ -285,6 +298,7 @@ include AP_SerialLED/AP_SerialLED.h singleton AP_SerialLED rename serialLED singleton AP_SerialLED depends AP_SERIALLED_ENABLED singleton AP_SerialLED method set_num_neopixel boolean uint8_t 1 16 uint8_t 0 AP_SERIALLED_MAX_LEDS +singleton AP_SerialLED method set_num_neopixel_rgb boolean uint8_t 1 16 uint8_t 0 AP_SERIALLED_MAX_LEDS singleton AP_SerialLED method set_num_profiled boolean uint8_t 1 16 uint8_t 0 AP_SERIALLED_MAX_LEDS singleton AP_SerialLED method set_RGB void uint8_t 1 16 int8_t -1 INT8_MAX uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check singleton AP_SerialLED method send void uint8_t 1 16 @@ -304,6 +318,7 @@ singleton SRV_Channels method set_range void SRV_Channel::Aux_servo_function_t'e singleton SRV_Channels method get_emergency_stop boolean singleton SRV_Channels manual get_safety_state SRV_Channels_get_safety_state 0 +ap_object RC_Channel depends AP_RC_CHANNEL_ENABLED ap_object RC_Channel method norm_input float ap_object RC_Channel method norm_input_dz float ap_object RC_Channel method get_aux_switch_pos uint8_t @@ -311,6 +326,7 @@ ap_object RC_Channel method norm_input_ignore_trim float ap_object RC_Channel method set_override void uint16_t 0 2200 0'literal include RC_Channel/RC_Channel.h +singleton RC_Channels depends AP_RC_CHANNEL_ENABLED singleton RC_Channels rename rc singleton RC_Channels scheduler-semaphore singleton RC_Channels method get_pwm boolean uint8_t 1 NUM_RC_CHANNELS uint16_t'Null @@ -432,7 +448,9 @@ singleton AP_Button depends HAL_BUTTON_ENABLED == 1 singleton AP_Button rename button singleton AP_Button method get_button_state boolean uint8_t 1 AP_BUTTON_NUM_PINS -include AP_Notify/ScriptingLED.h +include AP_Notify/ScriptingLED.h depends AP_NOTIFY_SCRIPTING_LED_ENABLED +include AP_Notify/AP_Notify_config.h +singleton ScriptingLED depends AP_NOTIFY_SCRIPTING_LED_ENABLED singleton ScriptingLED rename LED singleton ScriptingLED method get_rgb void uint8_t'Ref uint8_t'Ref uint8_t'Ref @@ -444,6 +462,12 @@ singleton QuadPlane method in_assisted_flight boolean singleton QuadPlane method abort_landing boolean singleton QuadPlane method in_vtol_land_descent boolean +include ../ArduSub/Sub.h depends APM_BUILD_TYPE(APM_BUILD_ArduSub) +singleton Sub rename sub +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 + include AP_Motors/AP_MotorsMatrix.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI singleton AP_MotorsMatrix depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI singleton AP_MotorsMatrix rename MotorsMatrix @@ -585,8 +609,8 @@ singleton AP::fwversion() field patch uint8_t read singleton AP::fwversion() field fw_hash_str string read singleton AP::fwversion() field fw_hash_str rename hash -include AP_Follow/AP_Follow.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI -singleton AP_Follow depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI +include AP_Follow/AP_Follow.h +singleton AP_Follow depends AP_FOLLOW_ENABLED && (APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI) singleton AP_Follow rename follow singleton AP_Follow method have_target boolean singleton AP_Follow method get_last_update_ms uint32_t @@ -598,6 +622,14 @@ 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 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 + +include APM_Control/AR_PosControl.h depends APM_BUILD_TYPE(APM_BUILD_Rover) +singleton AR_PosControl depends APM_BUILD_TYPE(APM_BUILD_Rover) +singleton AR_PosControl method get_srate void float'Ref + include AP_Mount/AP_Mount.h singleton AP_Mount depends HAL_MOUNT_ENABLED == 1 singleton AP_Mount rename mount @@ -695,6 +727,7 @@ singleton AP_EFI method get_state void EFI_State'Ref -- ----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 method log_file_content void string @@ -727,7 +760,9 @@ 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 diff --git a/libraries/AP_Scripting/generator/src/main.c b/libraries/AP_Scripting/generator/src/main.c index 368330ebb454b1..9959af32398bd9 100644 --- a/libraries/AP_Scripting/generator/src/main.c +++ b/libraries/AP_Scripting/generator/src/main.c @@ -352,6 +352,7 @@ struct method { struct type return_type; struct argument * arguments; uint32_t flags; // filled out with TYPE_FLAGS + char *dependency; }; enum alias_type { @@ -796,6 +797,15 @@ void handle_method(struct userdata *node) { } string_copy(&(method->deprecate), deprecate); return; + + } else if (strcmp(token, keyword_depends) == 0) { + char *dependency = strtok(NULL, ""); + if (dependency == NULL) { + error(ERROR_USERDATA, "Expected dependency string for %s %s on line", parent_name, name, state.line_num); + } + string_copy(&(method->dependency), dependency); + return; + } error(ERROR_USERDATA, "Method %s already exists for %s (declared on %d)", name, parent_name, method->line); } @@ -1227,6 +1237,7 @@ void emit_userdata_allocators(void) { struct userdata * node = parsed_userdata; 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, " void *ud = lua_newuserdata(L, sizeof(%s));\n", node->name); @@ -1235,6 +1246,22 @@ void emit_userdata_allocators(void) { fprintf(source, " lua_setmetatable(L, -2);\n"); fprintf(source, " return 1;\n"); fprintf(source, "}\n"); + + // New method used externally, includes argcheck, overridden by custom creation function if provided + if (node->creation == NULL) { + fprintf(source, "\n"); + fprintf(source, "int lua_new_%s(lua_State *L) {\n", node->sanatized_name); + + // emit one time warning if augments are parsed + fprintf(source, " static bool warned = false;\n"); + fprintf(source, " if (!warned && userdata_zero_arg_check(L)) {\n"); + fprintf(source, " warned = true;\n"); + fprintf(source, " }\n"); + + fprintf(source, " return new_%s(L);\n", node->sanatized_name); + fprintf(source, "}\n"); + } + end_dependency(source, node->dependency); fprintf(source, "\n"); node = node->next; @@ -1312,6 +1339,9 @@ void emit_userdata_declarations(void) { while (node) { start_dependency(header, node->dependency); fprintf(header, "int new_%s(lua_State *L);\n", node->sanatized_name); + if (node->creation == NULL) { + fprintf(header, "int lua_new_%s(lua_State *L);\n", 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; @@ -1709,8 +1739,8 @@ void emit_userdata_fields() { emit_userdata_field(node, field); field = field->next; } + end_dependency(source, node->dependency); } - end_dependency(source, node->dependency); node = node->next; } } @@ -1801,6 +1831,7 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth int arg_count = 1; start_dependency(source, data->dependency); + start_dependency(source, method->dependency); // bind ud early if it's a singleton, so that we can use it in the range checks fprintf(source, "static int %s_%s(lua_State *L) {\n", data->sanatized_name, method->sanatized_name); @@ -2071,6 +2102,7 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth } fprintf(source, "}\n"); + end_dependency(source, method->dependency); end_dependency(source, data->dependency); fprintf(source, "\n"); @@ -2178,7 +2210,9 @@ void emit_index(struct userdata *head) { struct method *method = node->methods; while (method) { + start_dependency(source, method->dependency); fprintf(source, " {\"%s\", %s_%s},\n", method->rename ? method->rename : method->name, node->sanatized_name, method->name); + end_dependency(source, method->dependency); method = method->next; } @@ -2364,7 +2398,7 @@ void emit_sandbox(void) { // expose custom creation function to user (not used internally) fprintf(source, " {\"%s\", %s},\n", data->rename ? data->rename : data->name, data->creation); } else { - fprintf(source, " {\"%s\", new_%s},\n", data->rename ? data->rename : data->name, data->sanatized_name); + fprintf(source, " {\"%s\", lua_new_%s},\n", data->rename ? data->rename : data->name, data->sanatized_name); } end_dependency(source, data->dependency); } @@ -2414,6 +2448,40 @@ void emit_argcheck_helper(void) { fprintf(source, " return 0;\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"); + fprintf(source, " return false;\n"); + fprintf(source, " }\n"); + + // Try and get debug info + fprintf(source, " lua_Debug ar;\n"); + + // Line number and file name + fprintf(source, " if (lua_getstack(L, 1, &ar)) {\n"); + fprintf(source, " lua_getinfo(L, \"Sl\", &ar);\n"); + fprintf(source, " if (ar.currentline != 0) {\n"); + + // Function name + fprintf(source, " if (lua_getstack(L, 0, &ar)) {\n"); + fprintf(source, " lua_getinfo(L, \"n\", &ar);\n"); + fprintf(source, " if (ar.name != NULL) {\n"); + + // Print warning with debug info + fprintf(source, " lua_scripts::set_and_print_new_error_message(MAV_SEVERITY_WARNING, \"%%s:%%d Warning: %%s does not take arguments, will be fatal in future\", ar.short_src, ar.currentline, ar.name);\n"); + fprintf(source, " return true;\n"); + + fprintf(source, " }\n"); + fprintf(source, " }\n"); + fprintf(source, " }\n"); + fprintf(source, " }\n"); + + // Print generic warning + fprintf(source, " lua_scripts::set_and_print_new_error_message(MAV_SEVERITY_WARNING, \"Warning: userdate creation does not take arguments, will be fatal in future\");\n"); + + fprintf(source, " return true;\n"); + fprintf(source, "}\n\n"); + fprintf(source, "lua_Integer get_integer(lua_State *L, int arg_num, lua_Integer min_val, lua_Integer max_val) {\n"); fprintf(source, " const lua_Integer lua_int = luaL_checkinteger(L, arg_num);\n"); fprintf(source, " luaL_argcheck(L, (lua_int >= min_val) && (lua_int <= max_val), arg_num, \"out of range\");\n"); @@ -2894,6 +2962,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, "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"); fprintf(header, "int16_t get_int16_t(lua_State *L, int arg_num);\n"); diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index c73b0cba3ebab9..51d6e519c8eb3b 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -43,6 +43,7 @@ int lua_micros(lua_State *L) { return 1; } +#if HAL_GCS_ENABLED int lua_mavlink_init(lua_State *L) { // Allow : and . access @@ -212,6 +213,7 @@ int lua_mavlink_block_command(lua_State *L) { lua_pushboolean(L, true); return 1; } +#endif // HAL_GCS_ENABLED int lua_mission_receive(lua_State *L) { binding_argcheck(L, 0); @@ -241,6 +243,7 @@ int lua_mission_receive(lua_State *L) { return 5; } +#if HAL_LOGGING_ENABLED int AP_Logger_Write(lua_State *L) { AP_Logger * AP_logger = AP_Logger::get_singleton(); if (AP_logger == nullptr) { @@ -526,6 +529,7 @@ int AP_Logger_Write(lua_State *L) { return 0; } +#endif // HAL_LOGGING_ENABLED int lua_get_i2c_device(lua_State *L) { @@ -755,4 +759,14 @@ int lua_get_current_ref() return scripting->get_current_ref(); } +// Simple print to GCS or over CAN +int lua_print(lua_State *L) { + // Only support a single argument + binding_argcheck(L, 1); + + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "%s", luaL_checkstring(L, 1)); + + return 0; +} + #endif // AP_SCRIPTING_ENABLED diff --git a/libraries/AP_Scripting/lua_bindings.h b/libraries/AP_Scripting/lua_bindings.h index 07b5403ec32d5c..8eef08bca35ac9 100644 --- a/libraries/AP_Scripting/lua_bindings.h +++ b/libraries/AP_Scripting/lua_bindings.h @@ -19,3 +19,4 @@ int lua_mavlink_receive_chan(lua_State *L); int lua_mavlink_register_rx_msgid(lua_State *L); int lua_mavlink_send_chan(lua_State *L); int lua_mavlink_block_command(lua_State *L); +int lua_print(lua_State *L); diff --git a/libraries/AP_Scripting/lua_scripts.cpp b/libraries/AP_Scripting/lua_scripts.cpp index 8b56b19600d622..02ab51d2c2c5e5 100644 --- a/libraries/AP_Scripting/lua_scripts.cpp +++ b/libraries/AP_Scripting/lua_scripts.cpp @@ -127,7 +127,7 @@ int lua_scripts::atpanic(lua_State *L) { 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) { - gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: Time: %u Mem: %d + %d", + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: Time: %u Mem: %d + %d", (unsigned int)run_time, (int)total_mem, (int)run_mem); @@ -238,7 +238,7 @@ void lua_scripts::load_all_scripts_in_dir(lua_State *L, const char *dirname) { auto *d = AP::FS().opendir(dirname); if (d == nullptr) { - gcs().send_text(MAV_SEVERITY_INFO, "Lua: open directory (%s) failed", dirname); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Lua: open directory (%s) failed", dirname); return; } @@ -450,7 +450,7 @@ void lua_scripts::run(void) { bool succeeded_initial_load = false; if (!_heap.available()) { - gcs().send_text(MAV_SEVERITY_INFO, "Lua: Unable to allocate a heap"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Lua: Unable to allocate a heap"); return; } @@ -475,7 +475,7 @@ void lua_scripts::run(void) { lua_state = lua_newstate(alloc, NULL); lua_State *L = lua_state; if (L == nullptr) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: Couldn't allocate a lua state"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Lua: Couldn't allocate a lua state"); return; } @@ -504,7 +504,7 @@ void lua_scripts::run(void) { loaded = true; } if (!loaded) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Lua: All directory's disabled see SCR_DIR_DISABLE"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Lua: All directory's disabled see SCR_DIR_DISABLE"); } #ifndef __clang_analyzer__ @@ -543,7 +543,7 @@ void lua_scripts::run(void) { } if ((_debug_options.get() & uint8_t(DebugLevel::RUNTIME_MSG)) != 0) { - gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: Running %s", scripts->name); + 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; @@ -572,7 +572,7 @@ void lua_scripts::run(void) { } else { if ((_debug_options.get() & uint8_t(DebugLevel::NO_SCRIPTS_TO_RUN)) != 0) { - gcs().send_text(MAV_SEVERITY_DEBUG, "Lua: No scripts to run"); + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG, "Lua: No scripts to run"); } hal.scheduler->delay(1000); } diff --git a/libraries/AP_SerialLED/AP_SerialLED.cpp b/libraries/AP_SerialLED/AP_SerialLED.cpp index ca1d837796e128..fafccd2af2fbe9 100644 --- a/libraries/AP_SerialLED/AP_SerialLED.cpp +++ b/libraries/AP_SerialLED/AP_SerialLED.cpp @@ -36,6 +36,15 @@ bool AP_SerialLED::set_num_neopixel(uint8_t chan, uint8_t num_leds) return false; } +// set number of NeoPixels per pin in RGB mode +bool AP_SerialLED::set_num_neopixel_rgb(uint8_t chan, uint8_t num_leds) +{ + if (chan >= 1 && chan <= 16 && num_leds <= AP_SERIALLED_MAX_LEDS) { + return hal.rcout->set_serial_led_num_LEDs(chan-1, num_leds, AP_HAL::RCOutput::MODE_NEOPIXELRGB); + } + return false; +} + // set number of ProfiLEDs per pin bool AP_SerialLED::set_num_profiled(uint8_t chan, uint8_t num_leds) { diff --git a/libraries/AP_SerialLED/AP_SerialLED.h b/libraries/AP_SerialLED/AP_SerialLED.h index 8f83c887abf6a0..4ec45ab8d58091 100644 --- a/libraries/AP_SerialLED/AP_SerialLED.h +++ b/libraries/AP_SerialLED/AP_SerialLED.h @@ -18,6 +18,7 @@ #pragma once #include +#include #include "AP_SerialLED_config.h" @@ -34,13 +35,15 @@ class AP_SerialLED { // set number of LEDs per pin bool set_num_neopixel(uint8_t chan, uint8_t num_leds); bool set_num_profiled(uint8_t chan, uint8_t num_leds); + // set number of LEDs per pin in RGB mode + bool set_num_neopixel_rgb(uint8_t chan, uint8_t num_leds); // set RGB value on mask of LEDs. chan is PWM output, 1..16 void set_RGB_mask(uint8_t chan, uint32_t ledmask, uint8_t red, uint8_t green, uint8_t blue); // set RGB value on LED. LED -1 is all LEDs. LED 0 is first LED. chan is PWM output, 1..16 void set_RGB(uint8_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue); - + // trigger sending of LED changes to LEDs void send(uint8_t chan); diff --git a/libraries/AP_SerialLED/AP_SerialLED_config.h b/libraries/AP_SerialLED/AP_SerialLED_config.h index f7c3381c43352f..357dfea0f57aa9 100644 --- a/libraries/AP_SerialLED/AP_SerialLED_config.h +++ b/libraries/AP_SerialLED/AP_SerialLED_config.h @@ -3,5 +3,5 @@ #include #ifndef AP_SERIALLED_ENABLED -#define AP_SERIALLED_ENABLED 1 +#define AP_SERIALLED_ENABLED HAL_SERIALLED_ENABLED #endif diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index c760a7d04f0d4f..bc717a99fb3cda 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -157,7 +157,7 @@ extern const AP_HAL::HAL& hal; #endif const AP_Param::GroupInfo AP_SerialManager::var_info[] = { -#if SERIALMANAGER_NUM_PORTS > 0 +#if HAL_HAVE_SERIAL0 // @Param: 0_BAUD // @DisplayName: Serial0 baud rate // @Description: The baud rate used on the USB console. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults. @@ -174,7 +174,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { AP_GROUPINFO("0_PROTOCOL", 11, AP_SerialManager, state[0].protocol, SerialProtocol_MAVLink2), #endif -#if SERIALMANAGER_NUM_PORTS > 1 +#if HAL_HAVE_SERIAL1 // @Param: 1_PROTOCOL // @DisplayName: Telem1 protocol selection // @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details. @@ -191,7 +191,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { AP_GROUPINFO("1_BAUD", 2, AP_SerialManager, state[1].baud, DEFAULT_SERIAL1_BAUD), #endif -#if SERIALMANAGER_NUM_PORTS > 2 +#if HAL_HAVE_SERIAL2 // @Param: 2_PROTOCOL // @CopyFieldsFrom: SERIAL1_PROTOCOL // @DisplayName: Telemetry 2 protocol selection @@ -205,7 +205,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { AP_GROUPINFO("2_BAUD", 4, AP_SerialManager, state[2].baud, DEFAULT_SERIAL2_BAUD), #endif -#if SERIALMANAGER_NUM_PORTS > 3 +#if HAL_HAVE_SERIAL3 // @Param: 3_PROTOCOL // @CopyFieldsFrom: SERIAL1_PROTOCOL // @DisplayName: Serial 3 (GPS) protocol selection @@ -219,7 +219,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { AP_GROUPINFO("3_BAUD", 6, AP_SerialManager, state[3].baud, DEFAULT_SERIAL3_BAUD), #endif -#if SERIALMANAGER_NUM_PORTS > 4 +#if HAL_HAVE_SERIAL4 // @Param: 4_PROTOCOL // @CopyFieldsFrom: SERIAL1_PROTOCOL // @DisplayName: Serial4 protocol selection @@ -233,7 +233,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { AP_GROUPINFO("4_BAUD", 8, AP_SerialManager, state[4].baud, DEFAULT_SERIAL4_BAUD), #endif -#if SERIALMANAGER_NUM_PORTS > 5 +#if HAL_HAVE_SERIAL5 // @Param: 5_PROTOCOL // @CopyFieldsFrom: SERIAL1_PROTOCOL // @DisplayName: Serial5 protocol selection @@ -249,7 +249,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // index 11 used by 0_PROTOCOL -#if SERIALMANAGER_NUM_PORTS > 6 +#if HAL_HAVE_SERIAL6 // @Param: 6_PROTOCOL // @CopyFieldsFrom: SERIAL1_PROTOCOL // @DisplayName: Serial6 protocol selection @@ -263,7 +263,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { AP_GROUPINFO("6_BAUD", 13, AP_SerialManager, state[6].baud, DEFAULT_SERIAL6_BAUD), #endif -#if SERIALMANAGER_NUM_PORTS > 1 +#if HAL_HAVE_SERIAL1 // @Param: 1_OPTIONS // @DisplayName: Telem1 options // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards. @@ -273,35 +273,35 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { AP_GROUPINFO("1_OPTIONS", 14, AP_SerialManager, state[1].options, DEFAULT_SERIAL1_OPTIONS), #endif -#if SERIALMANAGER_NUM_PORTS > 2 +#if HAL_HAVE_SERIAL2 // @Param: 2_OPTIONS // @CopyFieldsFrom: SERIAL1_OPTIONS // @DisplayName: Telem2 options AP_GROUPINFO("2_OPTIONS", 15, AP_SerialManager, state[2].options, DEFAULT_SERIAL2_OPTIONS), #endif -#if SERIALMANAGER_NUM_PORTS > 3 +#if HAL_HAVE_SERIAL3 // @Param: 3_OPTIONS // @CopyFieldsFrom: SERIAL1_OPTIONS // @DisplayName: Serial3 options AP_GROUPINFO("3_OPTIONS", 16, AP_SerialManager, state[3].options, DEFAULT_SERIAL3_OPTIONS), #endif -#if SERIALMANAGER_NUM_PORTS > 4 +#if HAL_HAVE_SERIAL4 // @Param: 4_OPTIONS // @CopyFieldsFrom: SERIAL1_OPTIONS // @DisplayName: Serial4 options AP_GROUPINFO("4_OPTIONS", 17, AP_SerialManager, state[4].options, DEFAULT_SERIAL4_OPTIONS), #endif -#if SERIALMANAGER_NUM_PORTS > 5 +#if HAL_HAVE_SERIAL5 // @Param: 5_OPTIONS // @CopyFieldsFrom: SERIAL1_OPTIONS // @DisplayName: Serial5 options AP_GROUPINFO("5_OPTIONS", 18, AP_SerialManager, state[5].options, DEFAULT_SERIAL5_OPTIONS), #endif -#if SERIALMANAGER_NUM_PORTS > 6 +#if HAL_HAVE_SERIAL6 // @Param: 6_OPTIONS // @CopyFieldsFrom: SERIAL1_OPTIONS // @DisplayName: Serial6 options @@ -330,7 +330,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @User: Advanced AP_GROUPINFO("_PASSTIMO", 22, AP_SerialManager, passthru_timeout, 15), -#if SERIALMANAGER_NUM_PORTS > 7 +#if HAL_HAVE_SERIAL7 // @Param: 7_PROTOCOL // @CopyFieldsFrom: SERIAL1_PROTOCOL // @DisplayName: Serial7 protocol selection @@ -349,7 +349,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { AP_GROUPINFO("7_OPTIONS", 25, AP_SerialManager, state[7].options, 0), #endif -#if SERIALMANAGER_NUM_PORTS > 8 +#if HAL_HAVE_SERIAL8 // @Param: 8_PROTOCOL // @CopyFieldsFrom: SERIAL1_PROTOCOL // @DisplayName: Serial8 protocol selection @@ -368,7 +368,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { AP_GROUPINFO("8_OPTIONS", 28, AP_SerialManager, state[8].options, 0), #endif -#if SERIALMANAGER_NUM_PORTS > 9 +#if HAL_HAVE_SERIAL9 // @Param: 9_PROTOCOL // @CopyFieldsFrom: SERIAL1_PROTOCOL // @DisplayName: Serial9 protocol selection diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index d4f2f92b2ff895..e3673c6183937b 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -37,6 +37,41 @@ #define SERIALMANAGER_NUM_PORTS 8 #endif +#ifndef HAL_NUM_SERIAL_PORTS +#define HAL_NUM_SERIAL_PORTS SERIALMANAGER_NUM_PORTS +#endif + +#ifndef HAL_HAVE_SERIAL0 +#define HAL_HAVE_SERIAL0 HAL_NUM_SERIAL_PORTS > 0 +#endif +#ifndef HAL_HAVE_SERIAL1 +#define HAL_HAVE_SERIAL1 HAL_NUM_SERIAL_PORTS > 1 +#endif +#ifndef HAL_HAVE_SERIAL2 +#define HAL_HAVE_SERIAL2 HAL_NUM_SERIAL_PORTS > 2 +#endif +#ifndef HAL_HAVE_SERIAL3 +#define HAL_HAVE_SERIAL3 HAL_NUM_SERIAL_PORTS > 3 +#endif +#ifndef HAL_HAVE_SERIAL4 +#define HAL_HAVE_SERIAL4 HAL_NUM_SERIAL_PORTS > 4 +#endif +#ifndef HAL_HAVE_SERIAL5 +#define HAL_HAVE_SERIAL5 HAL_NUM_SERIAL_PORTS > 5 +#endif +#ifndef HAL_HAVE_SERIAL6 +#define HAL_HAVE_SERIAL6 HAL_NUM_SERIAL_PORTS > 6 +#endif +#ifndef HAL_HAVE_SERIAL7 +#define HAL_HAVE_SERIAL7 HAL_NUM_SERIAL_PORTS > 7 +#endif +#ifndef HAL_HAVE_SERIAL8 +#define HAL_HAVE_SERIAL8 HAL_NUM_SERIAL_PORTS > 8 +#endif +#ifndef HAL_HAVE_SERIAL9 +#define HAL_HAVE_SERIAL9 HAL_NUM_SERIAL_PORTS > 9 +#endif + /* array size for state[]. This needs to be at least SERIALMANAGER_NUM_PORTS, but we want it to be the same length on diff --git a/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp b/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp index 920ea205874b4a..849d7376bb8734 100644 --- a/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp +++ b/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp @@ -45,7 +45,7 @@ bool AP_ServoRelayEvents::do_set_servo(uint8_t _channel, uint16_t pwm) case SRV_Channel::k_rcin1 ... SRV_Channel::k_rcin16: // rc pass-thru break; default: - gcs().send_text(MAV_SEVERITY_INFO, "ServoRelayEvent: Channel %d is already in use", _channel); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ServoRelayEvent: Channel %d is already in use", _channel); return false; } if (type == EVENT_TYPE_SERVO && @@ -102,7 +102,7 @@ bool AP_ServoRelayEvents::do_repeat_servo(uint8_t _channel, uint16_t _servo_valu case SRV_Channel::k_rcin1 ... SRV_Channel::k_rcin16: // rc pass-thru break; default: - gcs().send_text(MAV_SEVERITY_INFO, "ServoRelayEvent: Channel %d is already in use", _channel); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ServoRelayEvent: Channel %d is already in use", _channel); return false; } channel = _channel; diff --git a/libraries/AP_SmartRTL/AP_SmartRTL.cpp b/libraries/AP_SmartRTL/AP_SmartRTL.cpp index f751dbd47668c8..049e7506b6aba0 100644 --- a/libraries/AP_SmartRTL/AP_SmartRTL.cpp +++ b/libraries/AP_SmartRTL/AP_SmartRTL.cpp @@ -230,7 +230,9 @@ void AP_SmartRTL::set_home(bool position_ok, const Vector3f& current_pos) } // successfully added point and reset path - _last_good_position_ms = AP_HAL::millis(); + const uint32_t now = AP_HAL::millis(); + _last_good_position_ms = now; + _last_position_save_ms = now; _active = true; _home_saved = true; } diff --git a/libraries/AP_Stats/AP_Stats.cpp b/libraries/AP_Stats/AP_Stats.cpp index 9c82a0e32e84e9..13992983a487da 100644 --- a/libraries/AP_Stats/AP_Stats.cpp +++ b/libraries/AP_Stats/AP_Stats.cpp @@ -108,6 +108,7 @@ void AP_Stats::update() params.flttime.set_and_save_ifchanged(0); params.runtime.set_and_save_ifchanged(0); uint32_t system_clock = 0; // in seconds +#if AP_RTC_ENABLED uint64_t rtc_clock_us; if (AP::rtc().get_utc_usec(rtc_clock_us)) { system_clock = rtc_clock_us / 1000000; @@ -115,6 +116,7 @@ void AP_Stats::update() // time base to Jan 1st 2016: system_clock -= 1451606400; } +#endif params.reset.set_and_save_ifchanged(system_clock); copy_variables_from_parameters(); } diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index c87bd020b0ecd8..5787c019063e6e 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -238,7 +238,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = { // @Param: SYNAIRSPEED // @DisplayName: Enable the use of synthetic airspeed - // @Description: This enable the use of synthetic airspeed for aircraft that don't have a real airspeed sensor. This is useful for development testing where the user is aware of the considerable limitations of the synthetic airspeed system, such as very poor estimates when a wind estimate is not accurate. Do not enable this option unless you fully understand the limitations of a synthetic airspeed estimate. + // @Description: This enables the use of synthetic airspeed in TECS for aircraft that don't have a real airspeed sensor. This is useful for development testing where the user is aware of the considerable limitations of the synthetic airspeed system, such as very poor estimates when a wind estimate is not accurate. Do not enable this option unless you fully understand the limitations of a synthetic airspeed estimate. This option has no effect if a healthy airspeed sensor is being used for airspeed measurements. // @Values: 0:Disable,1:Enable // @User: Advanced AP_GROUPINFO("SYNAIRSPEED", 27, AP_TECS, _use_synthetic_airspeed, 0), @@ -831,6 +831,9 @@ float AP_TECS::_get_i_gain(void) */ void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge) { + // reset clip status after possible use of synthetic airspeed + _thr_clip_status = clipStatus::NONE; + // Calculate throttle demand by interpolating between pitch and throttle limits float nomThr; //If landing and we don't have an airspeed sensor and we have a non-zero @@ -1088,6 +1091,7 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) _lag_comp_hgt_offset = 0.0f; _post_TO_hgt_offset = 0.0f; _takeoff_start_ms = 0; + _use_synthetic_airspeed_once = false; _flags.underspeed = false; _flags.badDescent = false; @@ -1155,8 +1159,18 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, float hgt_afe, float load_factor) { - // Calculate time in seconds since last update uint64_t now = AP_HAL::micros64(); + // check how long since we last did the 50Hz update; do nothing in + // this loop if that hasn't run for some signficant period of + // time. Notably, it may never have run, leaving _TAS_state as + // zero and subsequently division-by-zero errors. + const float _DT_for_update_50hz = (now - _update_50hz_last_usec) * 1.0e-6f; + if (_update_50hz_last_usec == 0 || _DT_for_update_50hz > 1.0) { + // more than 1 second since it was run, don't do anything yet: + return; + } + + // Calculate time in seconds since last update _DT = (now - _update_pitch_throttle_last_usec) * 1.0e-6f; _DT = MAX(_DT, 0.001f); _update_pitch_throttle_last_usec = now; diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp index fce79c1a3b1383..68ac7027abe3cb 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp @@ -25,8 +25,10 @@ #if !AP_TEMPERATURE_SENSOR_DUMMY_METHODS_ENABLED #include "AP_TemperatureSensor_TSYS01.h" +#include "AP_TemperatureSensor_TSYS03.h" #include "AP_TemperatureSensor_MCP9600.h" #include "AP_TemperatureSensor_MAX31865.h" +#include "AP_TemperatureSensor_Analog.h" #include #include @@ -50,53 +52,95 @@ const AP_Param::GroupInfo AP_TemperatureSensor::var_info[] = { // @Path: AP_TemperatureSensor_Params.cpp AP_SUBGROUPINFO(_params[0], "1_", 10, AP_TemperatureSensor, AP_TemperatureSensor_Params), + // @Group: 1_ + // @Path: AP_TemperatureSensor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[0], "1_", 19, AP_TemperatureSensor, backend_var_info[0]), + #if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 2 // @Group: 2_ // @Path: AP_TemperatureSensor_Params.cpp AP_SUBGROUPINFO(_params[1], "2_", 11, AP_TemperatureSensor, AP_TemperatureSensor_Params), + + // @Group: 2_ + // @Path: AP_TemperatureSensor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[1], "2_", 20, AP_TemperatureSensor, backend_var_info[1]), #endif #if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 3 // @Group: 3_ // @Path: AP_TemperatureSensor_Params.cpp AP_SUBGROUPINFO(_params[2], "3_", 12, AP_TemperatureSensor, AP_TemperatureSensor_Params), + + // @Group: 3_ + // @Path: AP_TemperatureSensor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[2], "3_", 21, AP_TemperatureSensor, backend_var_info[2]), #endif #if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 4 // @Group: 4_ // @Path: AP_TemperatureSensor_Params.cpp AP_SUBGROUPINFO(_params[3], "4_", 13, AP_TemperatureSensor, AP_TemperatureSensor_Params), + + // @Group: 4_ + // @Path: AP_TemperatureSensor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[3], "4_", 22, AP_TemperatureSensor, backend_var_info[3]), #endif #if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 5 // @Group: 5_ // @Path: AP_TemperatureSensor_Params.cpp AP_SUBGROUPINFO(_params[4], "5_", 14, AP_TemperatureSensor, AP_TemperatureSensor_Params), + + // @Group: 5_ + // @Path: AP_TemperatureSensor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[4], "5_", 23, AP_TemperatureSensor, backend_var_info[4]), #endif + #if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 6 // @Group: 6_ // @Path: AP_TemperatureSensor_Params.cpp AP_SUBGROUPINFO(_params[5], "6_", 15, AP_TemperatureSensor, AP_TemperatureSensor_Params), + + // @Group: 6_ + // @Path: AP_TemperatureSensor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[5], "6_", 24, AP_TemperatureSensor, backend_var_info[5]), #endif + #if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 7 // @Group: 7_ // @Path: AP_TemperatureSensor_Params.cpp AP_SUBGROUPINFO(_params[6], "7_", 16, AP_TemperatureSensor, AP_TemperatureSensor_Params), + + // @Group: 7_ + // @Path: AP_TemperatureSensor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[6], "7_", 25, AP_TemperatureSensor, backend_var_info[6]), #endif + #if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 8 // @Group: 8_ // @Path: AP_TemperatureSensor_Params.cpp AP_SUBGROUPINFO(_params[7], "8_", 17, AP_TemperatureSensor, AP_TemperatureSensor_Params), + + // @Group: 8_ + // @Path: AP_TemperatureSensor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[7], "8_", 26, AP_TemperatureSensor, backend_var_info[7]), #endif + #if AP_TEMPERATURE_SENSOR_MAX_INSTANCES >= 9 // @Group: 9_ // @Path: AP_TemperatureSensor_Params.cpp AP_SUBGROUPINFO(_params[8], "9_", 18, AP_TemperatureSensor, AP_TemperatureSensor_Params), + + // @Group: 9_ + // @Path: AP_TemperatureSensor_Analog.cpp + AP_SUBGROUPVARPTR(drivers[8], "9_", 26, AP_TemperatureSensor, backend_var_info[8]), #endif AP_GROUPEND }; +const AP_Param::GroupInfo *AP_TemperatureSensor::backend_var_info[AP_TEMPERATURE_SENSOR_MAX_INSTANCES]; + // Default Constructor AP_TemperatureSensor::AP_TemperatureSensor() { @@ -141,6 +185,16 @@ void AP_TemperatureSensor::init() case AP_TemperatureSensor_Params::Type::MAX31865: drivers[instance] = new 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]); + 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]); + break; #endif case AP_TemperatureSensor_Params::Type::NONE: default: @@ -149,6 +203,12 @@ void AP_TemperatureSensor::init() // call init function for each backend if (drivers[instance] != nullptr) { + if (_state[instance].var_info != nullptr) { + // Load backend specific params + backend_var_info[instance] = _state[instance].var_info; + AP_Param::load_object_from_eeprom(drivers[instance], backend_var_info[instance]); + } + drivers[instance]->init(); // _num_instances is actually the index for looping over instances // the user may have TEMP_TYPE=0 and TEMP2_TYPE=7, in which case diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor.h b/libraries/AP_TemperatureSensor/AP_TemperatureSensor.h index cf5cdc84c17a11..1a4bffa656ccbd 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor.h +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor.h @@ -25,6 +25,8 @@ class AP_TemperatureSensor_Backend; class AP_TemperatureSensor_TSYS01; class AP_TemperatureSensor_MCP9600; class AP_TemperatureSensor_MAX31865; +class AP_TemperatureSensor_TSYS03; +class AP_TemperatureSensor_Analog; class AP_TemperatureSensor { @@ -32,6 +34,8 @@ class AP_TemperatureSensor friend class AP_TemperatureSensor_TSYS01; friend class AP_TemperatureSensor_MCP9600; friend class AP_TemperatureSensor_MAX31865; + friend class AP_TemperatureSensor_TSYS03; + friend class AP_TemperatureSensor_Analog; public: @@ -61,6 +65,7 @@ class AP_TemperatureSensor int32_t get_source_id(const uint8_t instance = AP_TEMPERATURE_SENSOR_PRIMARY_INSTANCE) const; static const struct AP_Param::GroupInfo var_info[]; + static const struct AP_Param::GroupInfo *backend_var_info[AP_TEMPERATURE_SENSOR_MAX_INSTANCES]; protected: // parameters @@ -74,6 +79,7 @@ class AP_TemperatureSensor uint32_t last_time_ms; // time when the sensor was last read in milliseconds float temperature; // temperature (deg C) uint8_t instance; // instance number + const struct AP_Param::GroupInfo *var_info; }; TemperatureSensor_State _state[AP_TEMPERATURE_SENSOR_MAX_INSTANCES]; diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.cpp new file mode 100644 index 00000000000000..e2871ca14615ee --- /dev/null +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.cpp @@ -0,0 +1,97 @@ +/* + 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_TemperatureSensor_config.h" + +#if AP_TEMPERATURE_SENSOR_ANALOG_ENABLED + +#include "AP_TemperatureSensor_Analog.h" + + +extern const AP_HAL::HAL &hal; + +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. + // @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 + 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 + 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 + 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 + 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 + AP_GROUPINFO("A4", 6, AP_TemperatureSensor_Analog, _a[4], 0), + + AP_GROUPEND +}; + +AP_TemperatureSensor_Analog::AP_TemperatureSensor_Analog(AP_TemperatureSensor &front, + AP_TemperatureSensor::TemperatureSensor_State &state, + AP_TemperatureSensor_Params ¶ms) : + AP_TemperatureSensor_Backend(front, state, params) +{ + AP_Param::setup_object_defaults(this, var_info); + _state.var_info = var_info; + _analog_source = hal.analogin->channel(_pin); +} + +// Update function called at 5Hz +void AP_TemperatureSensor_Analog::update() +{ + if ((_analog_source == nullptr) || !_analog_source->set_pin(_pin)) { + // Invalid pln + return; + } + + // Use ratiometric voltage, measured voltage is relative to supply + const float voltage = _analog_source->voltage_average_ratiometric(); + + // Evaluate polynomial + // temperature (deg) = a0 + a1*voltage + a2*voltage^2 + a3*voltage^3 + a4*voltage^4 + float temp = 0.0; + float poly = 1.0; + for (uint8_t i = 0; i < ARRAY_SIZE(_a); i++) { + temp += _a[i] * poly; + poly *= voltage; + } + + // update state + set_temperature(temp); +} + +#endif // AP_TEMPERATURE_SENSOR_ANALOG_ENABLED + diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.h b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.h new file mode 100644 index 00000000000000..a342c165332e9b --- /dev/null +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Analog.h @@ -0,0 +1,45 @@ +/* + 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_TemperatureSensor_config.h" + +#if AP_TEMPERATURE_SENSOR_ANALOG_ENABLED + +#include "AP_TemperatureSensor_Backend.h" +#include + +class AP_TemperatureSensor_Analog : public AP_TemperatureSensor_Backend { +public: + AP_TemperatureSensor_Analog(AP_TemperatureSensor &front, AP_TemperatureSensor::TemperatureSensor_State &state, AP_TemperatureSensor_Params ¶ms); + + void update(void) override; + + static const struct AP_Param::GroupInfo var_info[]; + +private: + + AP_HAL::AnalogSource *_analog_source; + + // Pin used to measure voltage + AP_Int8 _pin; + + // Polynomial coefficients to calculate temperature from voltage + AP_Float _a[5]; + +}; + +#endif // AP_TEMPERATURE_SENSOR_ANALOG_ENABLED diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Backend.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Backend.cpp index 7d2d7d59371fcf..4aadb2cf49a03f 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Backend.cpp +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Backend.cpp @@ -90,6 +90,7 @@ void AP_TemperatureSensor_Backend::update_external_libraries(const float tempera #endif case AP_TemperatureSensor_Params::Source::None: + case AP_TemperatureSensor_Params::Source::Pitot_tube: default: break; } diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MCP9600.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MCP9600.cpp index a9e2d8eb3cfc86..c0c91382cee13d 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MCP9600.cpp +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MCP9600.cpp @@ -17,7 +17,7 @@ * Code by Tom Pittenger */ /* - Implements I2C driver for Microchip MCP9600 digital thermocouple EMF to Temperature converter + Implements I2C driver for Microchip MCP9600 and MCP9601 digital thermocouple EMF to Temperature converter */ #include "AP_TemperatureSensor_MCP9600.h" @@ -35,13 +35,15 @@ static const uint8_t MCP9600_CMD_HOT_JUNCT_TEMP = 0x00; // thermocoupler //static const uint8_t MCP9600_CMD_JUNCT_TEMP_DELTA = 0x01; //static const uint8_t MCP9600_CMD_COLD_JUNCT_TEMP = 0x02; // ambient temp //static const uint8_t MCP9600_CMD_RAW_DATA_ADC = 0x03; -//static const uint8_t MCP9600_CMD_STATUS = 0x04; +static const uint8_t MCP9600_CMD_STATUS = 0x04; static const uint8_t MCP9600_CMD_SENSOR_CFG = 0x05; //static const uint8_t MCP9600_CMD_DEVICE_CFG = 0x06; static const uint8_t MCP9600_CMD_DEVICE_ID_REV = 0x20; // to fetch WHOAMI +static const uint8_t MCP9600_CMD_STATUS_UPDATE_READY = 0x40; static const uint8_t MCP9600_WHOAMI = 0x40; +static const uint8_t MCP9601_WHOAMI = 0x41; #define MCP9600_ADDR_LOW 0x60 // ADDR pin pulled low @@ -69,14 +71,13 @@ void AP_TemperatureSensor_MCP9600::init() #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)) { - printf("%s wrong I2C addr of 0x%2X, setting to 0x%2X. Reboot needed.", name, (unsigned)_params.bus_address.get(), (unsigned)MCP9600_ADDR_LOW); _params.bus_address.set(MCP9600_ADDR_LOW); } #endif _dev = std::move(hal.i2c_mgr->get_device(_params.bus, _params.bus_address)); if (!_dev) { - printf("%s device is null!", name); + // device not found return; } @@ -84,13 +85,13 @@ void AP_TemperatureSensor_MCP9600::init() _dev->set_retries(10); - uint8_t buf[2]; - if (!_dev->read_registers(MCP9600_CMD_DEVICE_ID_REV, buf, 2)) { + uint8_t buf; + if (!_dev->read_registers(MCP9600_CMD_DEVICE_ID_REV, &buf, 1)) { printf("%s failed to get WHOAMI", name); return; } - if (buf[0] != MCP9600_WHOAMI) { - printf("%s Got wrong WHOAMI: detected 0x%2X but expected 0x%2X", name, (unsigned)buf[0], (unsigned)MCP9600_WHOAMI); + if (buf != MCP9600_WHOAMI && buf != MCP9601_WHOAMI) { + printf("%s Got wrong WHOAMI: detected 0x%2X", name, (unsigned)buf); return; } if (!set_config(ThermocoupleType::K, AP_TemperatureSensor_MCP9600_Filter)) { @@ -98,10 +99,6 @@ void AP_TemperatureSensor_MCP9600::init() return; } -#if 0 - printf("%s Detected! Rev %u.%u on bus: %u addr: 0x%2X", name, (unsigned)(buf[1] >> 4), (unsigned)(buf[1] & 0x0F), (unsigned)_params.bus, (unsigned)_params.bus_address); -#endif - // lower retries for run _dev->set_retries(3); @@ -129,12 +126,29 @@ bool AP_TemperatureSensor_MCP9600::set_config(const ThermocoupleType thermoType, bool AP_TemperatureSensor_MCP9600::read_temperature(float &temperature) { + // confirm new temperature is available and then read it + + // First, read STATUS register: uint8_t data[2]; + if (!_dev->read_registers(MCP9600_CMD_STATUS, data, 1)) { + return false; + } + // check UPDATE bit for new temperature data ready: + 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; } + // scale temperature: temperature = int16_t(UINT16_VALUE(data[0], data[1])) * AP_TemperatureSensor_MCP9600_SCALE_FACTOR; + return true; } #endif // AP_TEMPERATURE_SENSOR_MCP9600_ENABLED diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.cpp index 763e4564d76c4e..361eaf9c13f1ef 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 + // @Values: 0:Disabled, 1:TSYS01, 2:MCP9600, 3:MAX31865, 4:TSYS03, 5:Analog // @User: Standard // @RebootRequired: True AP_GROUPINFO_FLAGS("TYPE", 1, AP_TemperatureSensor_Params, type, (float)Type::NONE, AP_PARAM_FLAG_ENABLE), @@ -58,7 +58,7 @@ const AP_Param::GroupInfo AP_TemperatureSensor_Params::var_info[] = { // @Param: SRC // @DisplayName: Sensor Source // @Description: Sensor Source is used to designate which device's temperature report will be replaced by this temperature sensor's data. If 0 (None) then the data is only available via log. In the future a new Motor temperature report will be created for returning data directly. - // @Values: 0: None, 1:ESC, 2:Motor(not implemented yet), 3:Battery Index, 4:Battery ID/SerialNumber + // @Values: 0: None, 1:ESC, 2:Motor(not implemented yet), 3:Battery Index, 4:Battery ID/SerialNumber, 5: CAN based Pitot tube // @User: Standard AP_GROUPINFO("SRC", 4, AP_TemperatureSensor_Params, source, (float)Source::None), diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.h b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.h index 1e4bfbf22ee9e3..46d41e8c659ad7 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.h +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Params.h @@ -31,6 +31,8 @@ class AP_TemperatureSensor_Params { TSYS01 = 1, MCP9600 = 2, MAX31865 = 3, + TSYS03 = 4, + ANALOG = 5, }; // option to map to another system component @@ -40,6 +42,7 @@ class AP_TemperatureSensor_Params { Motor = 2, Battery_Index = 3, Battery_ID_SerialNumber = 4, + Pitot_tube = 5, }; AP_Enum type; // 0=disabled, others see frontend enum TYPE diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_TSYS03.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_TSYS03.cpp new file mode 100644 index 00000000000000..649a0063a31b06 --- /dev/null +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_TSYS03.cpp @@ -0,0 +1,120 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_TemperatureSensor_TSYS03.h" + +#if AP_TEMPERATURE_SENSOR_TSYS03_ENABLED +#include +#include +#include +#include + +#include + +#ifndef AP_TEMPERATURE_SENSOR_TSYS03_ENFORCE_KNOWN_VALID_I2C_ADDRESS +#define AP_TEMPERATURE_SENSOR_TSYS03_ENFORCE_KNOWN_VALID_I2C_ADDRESS 1 +#endif + +extern const AP_HAL::HAL &hal; + +static const uint8_t TSYS03_CMD_RESET = 0x1E; +static const uint8_t TSYS03_CMD_CONVERT = 0x46; +static const uint8_t TSYS03_CMD_READ_ADC = 0x00; + +void AP_TemperatureSensor_TSYS03::init() +{ + constexpr char name[] = "TSYS03"; + +#if AP_TEMPERATURE_SENSOR_TSYS03_ENFORCE_KNOWN_VALID_I2C_ADDRESS + // I2C Address: Default to using TSYS03_ADDR_CSB0 & Check I2C Address is Correct + if ((_params.bus_address != TSYS03_ADDR_CSB0) ) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s wrong I2C addr of 0x%2X, setting to 0x%2X", name, (unsigned)_params.bus_address.get(), (unsigned)TSYS03_ADDR_CSB0); + _params.bus_address.set(TSYS03_ADDR_CSB0); + } +#endif + + _dev = std::move(hal.i2c_mgr->get_device(_params.bus, _params.bus_address)); + if (!_dev) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s device is null!", name); + return; + } + + WITH_SEMAPHORE(_dev->get_semaphore()); + + _dev->set_retries(10); + + // reset + if (!_dev->transfer(&TSYS03_CMD_RESET, 1, nullptr, 0)) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s reset failed", name); + return; + } + + hal.scheduler->delay(4); + + start_next_sample(); + + // lower retries for run + _dev->set_retries(3); + + /* Request 20Hz update */ + // Max conversion time is 9.04 ms + _dev->register_periodic_callback(50 * AP_USEC_PER_MSEC, + FUNCTOR_BIND_MEMBER(&AP_TemperatureSensor_TSYS03::_timer, void)); +} + +uint16_t AP_TemperatureSensor_TSYS03::read_adc() const +{ + uint8_t val[3]; + if (!_dev->transfer(&TSYS03_CMD_READ_ADC, 1, val, 3)) { + return 0; + } + + // ensure crc is correct: + uint8_t expected_crc = 0; + for (uint8_t i=0; i<2; i++) { + expected_crc = crc8_dvb(expected_crc, val[i], 0x31); + } + if (expected_crc != val[2]) { + return 0; + } + + return UINT16_VALUE(val[0],val[1]); +} + +void AP_TemperatureSensor_TSYS03::_timer(void) +{ + const uint16_t adc = read_adc(); + + if (adc != 0) { + const float temp = calculate(adc); + set_temperature(temp); + } + + start_next_sample(); +} + +void AP_TemperatureSensor_TSYS03::start_next_sample() +{ + _dev->transfer(&TSYS03_CMD_CONVERT, 1, nullptr, 0); +} + +float AP_TemperatureSensor_TSYS03::calculate(const uint16_t adc) const +{ + const float temperature = -40.0 + adc * 165 / (powf(2, 16) - 1.0); + + return temperature; +} + +#endif // AP_TEMPERATURE_SENSOR_TSYS03_ENABLED diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_TSYS03.h b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_TSYS03.h new file mode 100644 index 00000000000000..609cf5a10a0e5d --- /dev/null +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_TSYS03.h @@ -0,0 +1,54 @@ +/* + 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 . + */ + +/* + * I2C driver for Measurement Specialties MEAS TSYS03 digital temperature sensor + */ + +#pragma once +#include "AP_TemperatureSensor_Backend.h" + +#ifndef AP_TEMPERATURE_SENSOR_TSYS03_ENABLED +#define AP_TEMPERATURE_SENSOR_TSYS03_ENABLED AP_TEMPERATURE_SENSOR_ENABLED +#endif + +#if AP_TEMPERATURE_SENSOR_TSYS03_ENABLED + +#define TSYS03_ADDR_CSB0 0x40 + +class AP_TemperatureSensor_TSYS03 : public AP_TemperatureSensor_Backend { + using AP_TemperatureSensor_Backend::AP_TemperatureSensor_Backend; + +public: + void init(void) override; + + void update() override {}; + + +private: + // reset device + bool reset(void) const; + + // begin an ADC conversion (min:7.40ms typ:8.22ms max:9.04ms) + void start_next_sample(); + uint16_t read_adc(void) const; + + // update the temperature, called at 20Hz + void _timer(void); + + // calculate temperature using adc reading and internal calibration + float calculate(const uint16_t adc) const; +}; +#endif // AP_TEMPERATURE_SENSOR_TSYS03_ENABLED diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_config.h b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_config.h index 8e5bd97b1776a4..b34ac029c38678 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_config.h +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_config.h @@ -20,6 +20,9 @@ #define AP_TEMPERATURE_SENSOR_MAX31865_ENABLED AP_TEMPERATURE_SENSOR_ENABLED #endif +#ifndef AP_TEMPERATURE_SENSOR_ANALOG_ENABLED + #define AP_TEMPERATURE_SENSOR_ANALOG_ENABLED AP_TEMPERATURE_SENSOR_ENABLED +#endif // maximum number of Temperature Sensors diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index 9cf721383f24ad..7e9e75403662ec 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -234,16 +234,30 @@ bool AP_Terrain::height_terrain_difference_home(float &terrain_difference, bool */ bool AP_Terrain::height_above_terrain(float &terrain_altitude, bool extrapolate) { - float terrain_difference; - if (!height_terrain_difference_home(terrain_difference, extrapolate)) { + const AP_AHRS &ahrs = AP::ahrs(); + + Location current_loc; + if (!ahrs.get_location(current_loc)) { + // we don't know where we are return false; } - float relative_home_altitude; - AP::ahrs().get_relative_position_D_home(relative_home_altitude); - relative_home_altitude = -relative_home_altitude; + float theight_loc; + if (!height_amsl(current_loc, theight_loc)) { + if (!extrapolate) { + return false; + } + // we don't have data at the current location, but the caller + // has asked for extrapolation, so use the last available + // terrain height. This can be used to fill in while new data + // is fetched. It should be very rarely used + theight_loc = last_current_loc_height; + } + + int32_t height_amsl_cm = 0; + UNUSED_RESULT(current_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, height_amsl_cm)); - terrain_altitude = relative_home_altitude - terrain_difference; + terrain_altitude = height_amsl_cm*0.01 - theight_loc; return true; } @@ -271,6 +285,22 @@ bool AP_Terrain::height_relative_home_equivalent(float terrain_altitude, return false; } relative_home_altitude = terrain_altitude + terrain_difference; + + /* + adjust for height of home above terrain height at home + */ + const AP_AHRS &ahrs = AP::ahrs(); + const auto &home = ahrs.get_home(); + int32_t home_height_amsl_cm = 0; + UNUSED_RESULT(home.get_alt_cm(Location::AltFrame::ABSOLUTE, home_height_amsl_cm)); + + float theight_home; + if (!height_amsl(home, theight_home)) { + return false; + } + + relative_home_altitude += theight_home - home_height_amsl_cm*0.01; + return true; } @@ -457,7 +487,7 @@ bool AP_Terrain::allocate(void) } cache = (struct grid_cache *)calloc(TERRAIN_GRID_BLOCK_CACHE_SIZE, sizeof(cache[0])); if (cache == nullptr) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed"); memory_alloc_failed = true; return false; } diff --git a/libraries/AP_Terrain/TerrainGCS.cpp b/libraries/AP_Terrain/TerrainGCS.cpp index 6316e28fdab169..8ad7ae352e2ce2 100644 --- a/libraries/AP_Terrain/TerrainGCS.cpp +++ b/libraries/AP_Terrain/TerrainGCS.cpp @@ -37,6 +37,9 @@ extern const AP_HAL::HAL& hal; */ 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)) { @@ -72,6 +75,7 @@ bool AP_Terrain::request_missing(mavlink_channel_t chan, struct grid_cache &gcac last_request_time_ms[chan] = AP_HAL::millis(); return true; +#endif } /* @@ -211,42 +215,29 @@ void AP_Terrain::handle_data(mavlink_channel_t chan, const mavlink_message_t &ms */ void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc, bool extrapolate) { +#if HAL_GCS_ENABLED float terrain_height = 0; - float home_terrain_height = 0; uint16_t spacing = 0; - Location current_loc; - const AP_AHRS &ahrs = AP::ahrs(); - if (ahrs.get_location(current_loc) && - height_amsl(ahrs.get_home(), home_terrain_height) && - height_amsl(loc, terrain_height)) { + if (height_amsl(loc, terrain_height)) { // non-zero spacing indicates we have data spacing = grid_spacing; } else if (extrapolate && have_current_loc_height) { // show the extrapolated height, so logs show what height is // being used for navigation terrain_height = last_current_loc_height; - } else { - // report terrain height if we can, but can't give current_height - height_amsl(loc, terrain_height); } uint16_t pending, loaded; get_statistics(pending, loaded); float current_height = 0.0f; - if (spacing == 0 && !(extrapolate && have_current_loc_height)) { - current_height = 0; - } else if (!current_loc.is_zero()) { - int32_t height_above_home_cm = 0; - UNUSED_RESULT(current_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, height_above_home_cm)); - current_height = height_above_home_cm * 0.01f; // cm -> m - } - current_height += home_terrain_height - terrain_height; + height_above_terrain(current_height, extrapolate); if (HAVE_PAYLOAD_SPACE(chan, TERRAIN_REPORT)) { mavlink_msg_terrain_report_send(chan, loc.lat, loc.lng, spacing, terrain_height, current_height, pending, loaded); } +#endif } /* diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.cpp b/libraries/AP_Torqeedo/AP_Torqeedo.cpp index 84b0856595e30e..1fd14eded794b3 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.cpp +++ b/libraries/AP_Torqeedo/AP_Torqeedo.cpp @@ -22,6 +22,7 @@ #include #include #include +#include #define TORQEEDO_SERIAL_BAUD 19200 // communication is always at 19200 #define TORQEEDO_PACKET_HEADER 0xAC // communication packet header @@ -345,24 +346,24 @@ void AP_Torqeedo::report_error_codes() // report display system errors const char* msg_prefix = "Torqeedo:"; if (_display_system_state.flags.set_throttle_stop) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "%s zero throttle required", msg_prefix); + 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); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s high temp", msg_prefix); } - if (_display_system_state.flags.temp_warning) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "%s batt nearly empty", 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) { const char *error_string = map_master_error_code_to_string(_display_system_state.master_error_code); if (error_string != nullptr) { - gcs().send_text( + GCS_SEND_TEXT( MAV_SEVERITY_CRITICAL, "%s err:%u %s", msg_prefix, _display_system_state.master_error_code, error_string); } else { - gcs().send_text( + GCS_SEND_TEXT( MAV_SEVERITY_CRITICAL, "%s err:%u", msg_prefix, _display_system_state.master_error_code); @@ -371,28 +372,28 @@ void AP_Torqeedo::report_error_codes() // report motor status errors if (_motor_status.error_flags.overcurrent) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "%s overcurrent", msg_prefix); + 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); + 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); + 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); + 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); + 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); + 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); + 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); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "%s tilted", msg_prefix); } // display OK if all errors cleared @@ -405,7 +406,7 @@ void AP_Torqeedo::report_error_codes() (_motor_status.error_flags_value != 0); if (!now_errored && prev_errored) { - gcs().send_text(MAV_SEVERITY_INFO, "%s OK", msg_prefix); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s OK", msg_prefix); } // record change in state and reporting time @@ -594,7 +595,7 @@ void AP_Torqeedo::parse_message() // 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", + 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, @@ -649,7 +650,7 @@ void AP_Torqeedo::parse_message() // 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%%", + 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, @@ -716,7 +717,7 @@ void AP_Torqeedo::parse_message() // 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", + 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, @@ -750,7 +751,7 @@ void AP_Torqeedo::parse_message() // send to GCS if ((_options & options::DEBUG_TO_GCS) != 0) { - gcs().send_text(MAV_SEVERITY_INFO,"TRMS S:%d Err:%d", + GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRMS S:%d Err:%d", _motor_status.status_flags_value, _motor_status.error_flags_value); } @@ -1102,7 +1103,7 @@ void AP_Torqeedo::log_TRQD(bool force_logging) } if ((_options & options::DEBUG_TO_GCS) != 0) { - gcs().send_text(MAV_SEVERITY_INFO,"TRQD h:%u dspd:%d spd:%d succ:%ld err:%ld", + 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, diff --git a/libraries/AP_Torqeedo/AP_Torqeedo_config.h b/libraries/AP_Torqeedo/AP_Torqeedo_config.h index a44e894e8d7ad4..be2392bf04e6bd 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo_config.h +++ b/libraries/AP_Torqeedo/AP_Torqeedo_config.h @@ -3,5 +3,5 @@ #include #ifndef HAL_TORQEEDO_ENABLED -#define HAL_TORQEEDO_ENABLED BOARD_FLASH_SIZE > 1024 && !defined(HAL_BUILD_AP_PERIPH) +#define HAL_TORQEEDO_ENABLED BOARD_FLASH_SIZE > 1024 #endif diff --git a/libraries/AP_Tuning/AP_Tuning.cpp b/libraries/AP_Tuning/AP_Tuning.cpp index 0fcc4e63f4e1cb..b07aec2d8e6510 100644 --- a/libraries/AP_Tuning/AP_Tuning.cpp +++ b/libraries/AP_Tuning/AP_Tuning.cpp @@ -1,3 +1,7 @@ +#include "AP_Tuning_config.h" + +#if AP_TUNING_ENABLED + #include "AP_Tuning.h" #include @@ -87,7 +91,7 @@ void AP_Tuning::check_selector_switch(void) // save tune save_parameters(); re_center(); - gcs().send_text(MAV_SEVERITY_INFO, "Tuning: Saved"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Tuning: Saved"); AP_Notify::events.tune_save = 1; changed = false; need_revert = 0; @@ -101,7 +105,7 @@ void AP_Tuning::check_selector_switch(void) } else if (hold_time < 2000) { // re-center the value re_center(); - gcs().send_text(MAV_SEVERITY_INFO, "Tuning: recentered %s", get_tuning_name(current_parm)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Tuning: recentered %s", get_tuning_name(current_parm)); } else if (hold_time < 5000) { // change parameter next_parameter(); @@ -136,7 +140,7 @@ void AP_Tuning::check_input(uint8_t flightmode) // check for revert on changed flightmode if (flightmode != last_flightmode) { if (need_revert != 0 && mode_revert != 0) { - gcs().send_text(MAV_SEVERITY_INFO, "Tuning: reverted"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Tuning: reverted"); revert_parameters(); re_center(); } @@ -209,7 +213,7 @@ void AP_Tuning::check_input(uint8_t flightmode) } // starting tuning mid_point_wait = false; - gcs().send_text(MAV_SEVERITY_INFO, "Tuning: mid-point %s", get_tuning_name(current_parm)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Tuning: mid-point %s", get_tuning_name(current_parm)); AP_Notify::events.tune_started = 1; } last_channel_value = chan_value; @@ -315,7 +319,7 @@ void AP_Tuning::next_parameter(void) } current_parm = tuning_sets[i].parms[current_parm_index]; re_center(); - gcs().send_text(MAV_SEVERITY_INFO, "Tuning: started %s", get_tuning_name(current_parm)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Tuning: started %s", get_tuning_name(current_parm)); AP_Notify::events.tune_next = current_parm_index+1; break; } @@ -334,3 +338,5 @@ const char *AP_Tuning::get_tuning_name(uint8_t parm) } return "UNKNOWN"; } + +#endif // AP_TUNING_ENABLED diff --git a/libraries/AP_Tuning/AP_Tuning.h b/libraries/AP_Tuning/AP_Tuning.h index 9be466391bd083..88ffda0c4b08ab 100644 --- a/libraries/AP_Tuning/AP_Tuning.h +++ b/libraries/AP_Tuning/AP_Tuning.h @@ -1,5 +1,9 @@ #pragma once +#include "AP_Tuning_config.h" + +#if AP_TUNING_ENABLED + #include #include "stdint.h" @@ -100,3 +104,5 @@ class AP_Tuning // parmset is in vehicle subclass var table AP_Int16 parmset; }; + +#endif // AP_TUNING_ENABLED diff --git a/libraries/AP_Tuning/AP_Tuning_config.h b/libraries/AP_Tuning/AP_Tuning_config.h new file mode 100644 index 00000000000000..69045eb0afda95 --- /dev/null +++ b/libraries/AP_Tuning/AP_Tuning_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef AP_TUNING_ENABLED +#define AP_TUNING_ENABLED 1 +#endif diff --git a/libraries/AP_Vehicle/AP_FixedWing.h b/libraries/AP_Vehicle/AP_FixedWing.h index 00eab8cfe4d890..df9bac196cab04 100644 --- a/libraries/AP_Vehicle/AP_FixedWing.h +++ b/libraries/AP_Vehicle/AP_FixedWing.h @@ -20,6 +20,7 @@ struct AP_FixedWing { AP_Int16 pitch_limit_max_cd; AP_Int16 pitch_limit_min_cd; AP_Int8 autotune_level; + AP_Int32 autotune_options; AP_Int8 stall_prevention; AP_Int16 loiter_radius; AP_Int16 pitch_trim_cd; diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index e098e7246ade56..ff333b0a424ba3 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -18,6 +18,10 @@ #include #endif #include +#if HAL_WITH_IO_MCU +#include +extern AP_IOMCU iomcu; +#endif #define SCHED_TASK(func, rate_hz, max_time_micros, prio) SCHED_TASK_CLASS(AP_Vehicle, &vehicle, func, rate_hz, max_time_micros, prio) @@ -202,6 +206,12 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = { #endif // APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_Rover) +#if AP_NETWORKING_ENABLED + // @Group: NET_ + // @Path: ../AP_Networking/AP_Networking.cpp + AP_SUBGROUPINFO(networking, "NET_", 21, AP_Vehicle, AP_Networking), +#endif + AP_GROUPEND }; @@ -261,15 +271,23 @@ void AP_Vehicle::setup() // survivability. set_control_channels(); +#if HAL_GCS_ENABLED // initialise serial manager as early as sensible to get // diagnostic output during boot process. We have to initialise // the GCS singleton first as it sets the global mavlink system ID // which may get used very early on. gcs().init(); +#endif + +#if AP_NETWORKING_ENABLED + networking.init(); +#endif // initialise serial ports serial_manager.init(); +#if HAL_GCS_ENABLED gcs().setup_console(); +#endif // Register scheduler_delay_cb, which will run anytime you have // more than 5ms remaining in your call to hal.scheduler->delay @@ -382,11 +400,11 @@ void AP_Vehicle::setup() // initialisation AP_Param::invalidate_count(); - gcs().send_text(MAV_SEVERITY_INFO, "ArduPilot Ready"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ArduPilot Ready"); #if AP_DDS_ENABLED if (!init_dds_client()) { - gcs().send_text(MAV_SEVERITY_ERROR, "DDS Client: Failed to Initialize"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DDS Client: Failed to Initialize"); } #endif } @@ -416,7 +434,7 @@ void AP_Vehicle::loop() const uint32_t new_internal_errors = AP::internalerror().errors(); if(_last_internal_errors != new_internal_errors) { AP::logger().Write_Error(LogErrorSubsystem::INTERNAL_ERROR, LogErrorCode::INTERNAL_ERRORS_DETECTED); - gcs().send_text(MAV_SEVERITY_CRITICAL, "Internal Errors 0x%x", (unsigned)new_internal_errors); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Internal Errors 0x%x", (unsigned)new_internal_errors); _last_internal_errors = new_internal_errors; } } @@ -485,6 +503,9 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = { #if AP_OPENDRONEID_ENABLED SCHED_TASK_CLASS(AP_OpenDroneID, &vehicle.opendroneid, update, 10, 50, 236), #endif +#if AP_NETWORKING_ENABLED + SCHED_TASK_CLASS(AP_Networking, &vehicle.networking, update, 10, 50, 238), +#endif #if OSD_ENABLED SCHED_TASK(publish_osd_info, 1, 10, 240), #endif @@ -541,21 +562,23 @@ void AP_Vehicle::scheduler_delay_callback() const uint32_t tnow = AP_HAL::millis(); if (tnow - last_1hz > 1000) { last_1hz = tnow; - gcs().send_message(MSG_HEARTBEAT); - gcs().send_message(MSG_SYS_STATUS); + GCS_SEND_MESSAGE(MSG_HEARTBEAT); + GCS_SEND_MESSAGE(MSG_SYS_STATUS); } if (tnow - last_50hz > 20) { last_50hz = tnow; +#if HAL_GCS_ENABLED gcs().update_receive(); gcs().update_send(); +#endif _singleton->notify.update(); } if (tnow - last_5s > 5000) { last_5s = tnow; if (AP_BoardConfig::in_config_error()) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Config Error: fix problem then reboot"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Config Error: fix problem then reboot"); } else { - gcs().send_text(MAV_SEVERITY_INFO, "Initialising ArduPilot"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Initialising ArduPilot"); } } @@ -569,7 +592,8 @@ void AP_Vehicle::send_watchdog_reset_statustext() return; } const AP_HAL::Util::PersistentData &pd = hal.util->last_persistent_data; - gcs().send_text(MAV_SEVERITY_CRITICAL, + (void)pd; // in case !HAL_GCS_ENABLED + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "WDG: T%d SL%u FL%u FT%u FA%x FTP%u FLR%x FICSR%u MM%u MC%u IE%u IEC%u TN:%.4s", pd.scheduler_task, pd.semaphore_line, @@ -772,6 +796,10 @@ void AP_Vehicle::reboot(bool hold_in_bootloader) // the IO board safety to be forced on, the parameters to flush, ... hal.scheduler->delay(200); +#if HAL_WITH_IO_MCU + iomcu.soft_reboot(); +#endif + hal.scheduler->reboot(hold_in_bootloader); } @@ -895,7 +923,7 @@ void AP_Vehicle::check_motor_noise() float energy = gyro_fft.has_noise_at_frequency_hz(esc_data[i]); energy = esc_noise[i].apply(energy, 0.2f); if (energy > 40.0f && AP_HAL::millis() - last_motor_noise_ms > 5000) { - gcs().send_text(MAV_SEVERITY_WARNING, "Noise %.fdB on motor %u at %.fHz", energy, i+1, esc_data[i]); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Noise %.fdB on motor %u at %.fHz", energy, i+1, esc_data[i]); output_error = true; } } diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 7d7e0835cc6d66..18b43fc0209ca8 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -22,6 +22,7 @@ #include "ModeReason.h" // reasons can't be defined in this header due to circular loops #include +#include #include #include #include // board configuration library @@ -44,6 +45,7 @@ #include #include #include +#include #include #include #include @@ -175,8 +177,9 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { virtual bool get_circle_radius(float &radius_m) { return false; } virtual bool set_circle_rate(float rate_dps) { return false; } - // set steering and throttle (-1 to +1) (for use by scripting with Rover) + // get or set steering and throttle (-1 to +1) (for use by scripting with Rover) virtual bool set_steering_and_throttle(float steering, float throttle) { return false; } + virtual bool get_steering_and_throttle(float& steering, float& throttle) { return false; } // set turn rate in deg/sec and speed in meters/sec (for use by scripting with Rover) virtual bool set_desired_turn_rate_and_speed(float turn_rate, float speed) { return false; } @@ -286,7 +289,9 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { float G_Dt; // sensor drivers +#if AP_GPS_ENABLED AP_GPS gps; +#endif AP_Baro barometer; Compass compass; AP_InertialSensor ins; @@ -358,6 +363,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { AP_Tramp tramp; #endif +#if AP_NETWORKING_ENABLED + AP_Networking networking; +#endif + #if HAL_EFI_ENABLED // EFI Engine Monitor AP_EFI efi; diff --git a/libraries/AP_Vehicle/ModeReason.h b/libraries/AP_Vehicle/ModeReason.h index 905b2697d70767..d1e124426f28e7 100644 --- a/libraries/AP_Vehicle/ModeReason.h +++ b/libraries/AP_Vehicle/ModeReason.h @@ -68,4 +68,6 @@ enum class ModeReason : uint8_t { RADIO_FAILSAFE_RECOVERY = 48, QLAND_INSTEAD_OF_RTL = 49, DEADRECKON_FAILSAFE = 50, + MODE_TAKEOFF_FAILSAFE = 51, + DDS_COMMAND = 52, }; diff --git a/libraries/AP_VideoTX/AP_Tramp.h b/libraries/AP_VideoTX/AP_Tramp.h index efad47fd80dd65..7d812cb3a5938f 100644 --- a/libraries/AP_VideoTX/AP_Tramp.h +++ b/libraries/AP_VideoTX/AP_Tramp.h @@ -29,7 +29,7 @@ #define VTX_TRAMP_POWER_COUNT 5 -#define VTX_TRAMP_MIN_FREQUENCY_MHZ 5000 //min freq in MHz +#define VTX_TRAMP_MIN_FREQUENCY_MHZ 1000 //min freq in MHz #define VTX_TRAMP_MAX_FREQUENCY_MHZ 5999 //max freq in MHz // Maximum number of requests sent to try a config change // Some VTX fail to respond to every request (like Matek FCHUB-VTX) so diff --git a/libraries/AP_VideoTX/AP_VideoTX.cpp b/libraries/AP_VideoTX/AP_VideoTX.cpp index 72fe6e4e54c89f..8bfa7c14ca6462 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 + // @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 AP_GROUPINFO("BAND", 4, AP_VideoTX, _band, 0), // @Param: FREQ @@ -59,7 +59,7 @@ const AP_Param::GroupInfo AP_VideoTX::var_info[] = { // @Description: Video Transmitter Frequency. The frequency is derived from the setting of BAND and CHANNEL // @User: Standard // @ReadOnly: True - // @Range: 5000 6000 + // @Range: 1000 6000 AP_GROUPINFO("FREQ", 5, AP_VideoTX, _frequency_mhz, 0), // @Param: OPTIONS @@ -96,7 +96,9 @@ const uint16_t AP_VideoTX::VIDEO_CHANNELS[AP_VideoTX::MAX_BANDS][VTX_MAX_CHANNEL { 5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945}, /* Band E */ { 5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880}, /* Airwave */ { 5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917}, /* Race */ - { 5621, 5584, 5547, 5510, 5473, 5436, 5399, 5362} /* LO Race */ + { 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 */ }; // mapping of power level to milliwatt to dbm diff --git a/libraries/AP_VideoTX/AP_VideoTX.h b/libraries/AP_VideoTX/AP_VideoTX.h index 4ffa6c21ab477e..55a9b503660fe3 100644 --- a/libraries/AP_VideoTX/AP_VideoTX.h +++ b/libraries/AP_VideoTX/AP_VideoTX.h @@ -62,6 +62,8 @@ class AP_VideoTX { FATSHARK, RACEBAND, LOW_RACEBAND, + BAND_1G3_A, + BAND_1G3_B, MAX_BANDS }; diff --git a/libraries/AP_VisualOdom/AP_VisualOdom.cpp b/libraries/AP_VisualOdom/AP_VisualOdom.cpp index 2bc4240ae4264d..d8cbcb05c48d78 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom.cpp @@ -179,7 +179,7 @@ void AP_VisualOdom::handle_vision_position_delta_msg(const mavlink_message_t &ms // general purpose method to consume position estimate data and send to EKF // distances in meters, roll, pitch and yaw are in radians -void AP_VisualOdom::handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float posErr, float angErr, uint8_t reset_counter) +void AP_VisualOdom::handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float posErr, float angErr, uint8_t reset_counter) { // exit immediately if not enabled if (!enabled()) { @@ -191,12 +191,12 @@ void AP_VisualOdom::handle_vision_position_estimate(uint64_t remote_time_us, uin // convert attitude to quaternion and call backend Quaternion attitude; attitude.from_euler(roll, pitch, yaw); - _driver->handle_vision_position_estimate(remote_time_us, time_ms, x, y, z, attitude, posErr, angErr, reset_counter); + _driver->handle_pose_estimate(remote_time_us, time_ms, x, y, z, attitude, posErr, angErr, reset_counter); } } // general purpose method to consume position estimate data and send to EKF -void AP_VisualOdom::handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) +void AP_VisualOdom::handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) { // exit immediately if not enabled if (!enabled()) { @@ -205,7 +205,7 @@ void AP_VisualOdom::handle_vision_position_estimate(uint64_t remote_time_us, uin // call backend if (_driver != nullptr) { - _driver->handle_vision_position_estimate(remote_time_us, time_ms, x, y, z, attitude, posErr, angErr, reset_counter); + _driver->handle_pose_estimate(remote_time_us, time_ms, x, y, z, attitude, posErr, angErr, reset_counter); } } diff --git a/libraries/AP_VisualOdom/AP_VisualOdom.h b/libraries/AP_VisualOdom/AP_VisualOdom.h index 5a11a6e9ac6ac6..47606abb97f815 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom.h @@ -90,8 +90,8 @@ class AP_VisualOdom // general purpose methods to consume position estimate data and send to EKF // distances in meters, roll, pitch and yaw are in radians - void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float posErr, float angErr, uint8_t reset_counter); - void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter); + void handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float posErr, float angErr, uint8_t reset_counter); + void handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter); // general purpose methods to consume velocity estimate data and send to EKF // velocity in NED meters per second diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h index 853698ce8bee21..b17eef76e73915 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h @@ -30,8 +30,8 @@ class AP_VisualOdom_Backend // consume vision_position_delta mavlink messages void handle_vision_position_delta_msg(const mavlink_message_t &msg); - // consume vision position estimate data and send to EKF. distances in meters - virtual void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) = 0; + // consume vision pose estimate data and send to EKF. distances in meters + virtual void handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) = 0; // consume vision velocity estimate data and send to EKF, velocity in NED meters per second virtual void handle_vision_speed_estimate(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, uint8_t reset_counter) = 0; diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp index 610f49af260a40..ebec6eebdd0e91 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp @@ -27,8 +27,8 @@ extern const AP_HAL::HAL& hal; -// consume vision position estimate data and send to EKF. distances in meters -void AP_VisualOdom_IntelT265::handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) +// consume vision pose estimate data and send to EKF. distances in meters +void AP_VisualOdom_IntelT265::handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) { const float scale_factor = _frontend.get_pos_scale(); Vector3f pos{x * scale_factor, y * scale_factor, z * scale_factor}; @@ -143,7 +143,11 @@ bool AP_VisualOdom_IntelT265::align_yaw_to_ahrs(const Vector3f &position, const } // do not align until ahrs yaw initialised - if (!AP::ahrs().initialised() || !AP::ahrs().dcm_yaw_initialised()) { + if (!AP::ahrs().initialised() +#if AP_AHRS_DCM_ENABLED + || !AP::ahrs().dcm_yaw_initialised() +#endif + ) { return false; } diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.h b/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.h index 7c5b74e8d0028f..8a78bd1b7ae37c 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.h @@ -13,8 +13,8 @@ class AP_VisualOdom_IntelT265 : public AP_VisualOdom_Backend using AP_VisualOdom_Backend::AP_VisualOdom_Backend; - // consume vision position estimate data and send to EKF. distances in meters - void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) override; + // consume vision pose estimate data and send to EKF. distances in meters + void handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) override; // consume vision velocity estimate data and send to EKF, velocity in NED meters per second void handle_vision_speed_estimate(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, uint8_t reset_counter) override; diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp index b8c6d0ba30d3b7..0117e56af84575 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp @@ -22,8 +22,8 @@ #include #include -// consume vision position estimate data and send to EKF. distances in meters -void AP_VisualOdom_MAV::handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) +// consume vision pose estimate data and send to EKF. distances in meters +void AP_VisualOdom_MAV::handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) { const float scale_factor = _frontend.get_pos_scale(); Vector3f pos{x * scale_factor, y * scale_factor, z * scale_factor}; diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_MAV.h b/libraries/AP_VisualOdom/AP_VisualOdom_MAV.h index 6c09f4589a3f51..18d5fed7096fd0 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_MAV.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom_MAV.h @@ -13,8 +13,8 @@ class AP_VisualOdom_MAV : public AP_VisualOdom_Backend // constructor using AP_VisualOdom_Backend::AP_VisualOdom_Backend; - // consume vision position estimate data and send to EKF. distances in meters - void handle_vision_position_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) override; + // consume vision pose estimate data and send to EKF. distances in meters + void handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) override; // consume vision velocity estimate data and send to EKF, velocity in NED meters per second void handle_vision_speed_estimate(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, uint8_t reset_counter) override; diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp index ff8739eb45f504..e23a13b93ff9e8 100644 --- a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp @@ -86,6 +86,12 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: _RATE_PDMX + // @DisplayName: Wheel rate control PD sum maximum + // @Description: Wheel rate control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0.000 1.000 + // @User: Advanced + AP_SUBGROUPINFO(_rate_pid0, "_RATE_", 3, AP_WheelRateControl, AC_PID), // @Param: 2_RATE_FF @@ -156,6 +162,12 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: 2_RATE_PDMX + // @DisplayName: Wheel rate control PD sum maximum + // @Description: Wheel rate control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output + // @Range: 0.000 1.000 + // @User: Advanced + AP_SUBGROUPINFO(_rate_pid1, "2_RATE_", 4, AP_WheelRateControl, AC_PID), AP_GROUPEND diff --git a/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp b/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp index 518bd26fd7b124..cb82bef21bca85 100644 --- a/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp +++ b/libraries/AP_WheelEncoder/WheelEncoder_Quadrature.cpp @@ -34,7 +34,7 @@ void AP_WheelEncoder_Quadrature::update_pin(uint8_t &pin, // remove old gpio event callback if present if (pin != (uint8_t)-1 && !hal.gpio->detach_interrupt(pin)) { - gcs().send_text(MAV_SEVERITY_WARNING, "WEnc: Failed to detach from pin %u", pin); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "WEnc: Failed to detach from pin %u", pin); // ignore this failure or the user may be stuck } @@ -51,7 +51,7 @@ void AP_WheelEncoder_Quadrature::update_pin(uint8_t &pin, bool, uint32_t), AP_HAL::GPIO::INTERRUPT_BOTH)) { - gcs().send_text(MAV_SEVERITY_WARNING, "WEnc: Failed to attach to pin %u", pin); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "WEnc: Failed to attach to pin %u", pin); } pin_value = hal.gpio->read(pin); } diff --git a/libraries/AP_Winch/AP_Winch.cpp b/libraries/AP_Winch/AP_Winch.cpp index deb769f7331f00..5a5a7bc9b90744 100644 --- a/libraries/AP_Winch/AP_Winch.cpp +++ b/libraries/AP_Winch/AP_Winch.cpp @@ -2,6 +2,7 @@ #if AP_WINCH_ENABLED +#include #include "AP_Winch_PWM.h" #include "AP_Winch_Daiwa.h" @@ -32,6 +33,13 @@ const AP_Param::GroupInfo AP_Winch::var_info[] = { // @User: Standard AP_GROUPINFO("_POS_P", 3, AP_Winch, config.pos_p, 1.0f), + // @Param: _OPTIONS + // @DisplayName: Winch options + // @Description: Winch options + // @Bitmask: 0:Spin freely on startup, 1:Verbose output, 2:Retry if stuck (Daiwa only) + // @User: Standard + AP_GROUPINFO("_OPTIONS", 4, AP_Winch, config.options, 7.0f), + // 4 was _RATE_PID AP_GROUPEND @@ -81,6 +89,13 @@ void AP_Winch::init() } if (backend != nullptr) { backend->init(); + + // initialise control mode + if (backend->option_enabled(Options::SpinFreelyOnStartup)) { + relax(); + } else { + set_desired_rate(0); + } } } @@ -92,6 +107,11 @@ void AP_Winch::release_length(float length) } config.length_desired = backend->get_current_length() + length; config.control_mode = ControlMode::POSITION; + + // display verbose output to user + if (backend->option_enabled(Options::VerboseOutput)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Winch: lowering %4.1fm to %4.1fm", (double)length, (double)config.length_desired); + } } // deploy line at specified speed in m/s (+ve deploys line, -ve retracts line, 0 stops) diff --git a/libraries/AP_Winch/AP_Winch.h b/libraries/AP_Winch/AP_Winch.h index 0536932327f616..df1ecf9c896c8c 100644 --- a/libraries/AP_Winch/AP_Winch.h +++ b/libraries/AP_Winch/AP_Winch.h @@ -82,6 +82,13 @@ class AP_Winch { DAIWA = 2 }; + // enum for OPTIONS parameter + enum class Options : int16_t { + SpinFreelyOnStartup = (1U << 0), // winch allows line to be manually pulled out soon after startup + VerboseOutput = (1U << 1), // verbose output of winch state sent to GCS + RetryIfStuck = (1U << 2), // retries to raise or lower if winch stops + }; + // winch states enum class ControlMode : uint8_t { RELAXED = 0, // winch is realxed @@ -94,6 +101,7 @@ class AP_Winch { AP_Int8 type; // winch type AP_Float rate_max; // deploy or retract rate maximum (in m/s). AP_Float pos_p; // position error P gain + AP_Int16 options; // options bitmask ControlMode control_mode; // state of winch control (using target position or target rate) float length_desired; // target desired length (in meters) float rate_desired; // target deploy rate (in m/s, +ve = deploying, -ve = retracting) diff --git a/libraries/AP_Winch/AP_Winch_Backend.h b/libraries/AP_Winch/AP_Winch_Backend.h index ef749a11f681f9..0504a753db86b0 100644 --- a/libraries/AP_Winch/AP_Winch_Backend.h +++ b/libraries/AP_Winch/AP_Winch_Backend.h @@ -42,6 +42,11 @@ class AP_Winch_Backend { // write log virtual void write_log() = 0; + // helper to check if option enabled + bool option_enabled(AP_Winch::Options option) const { + return (config.options & uint16_t(option)) != 0; + } + protected: // calculate the pilot desired rate (+ve deploys line, -ve retracts line, 0 stops) from rc input diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.cpp b/libraries/AP_Winch/AP_Winch_Daiwa.cpp index 67c274506d1320..21da2625214b4d 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.cpp +++ b/libraries/AP_Winch/AP_Winch_Daiwa.cpp @@ -6,8 +6,15 @@ #include #include +#define AP_WINCH_DAIWA_STUCK_TIMEOUT_MS 1000 // winch is considered stuck if unmoving for this many milliseconds +#define AP_WINCH_DAIWA_STUCK_CENTER_MS 1000 // stuck protection outputs zero rate for this many milliseconds +#define AP_WINCH_DAIWA_STUCK_LENGTH_MIN 0.1 // stuck protection active when line length is more than this many meters +#define AP_WINCH_DAIWA_STUCK_RATE_MIN 0.2 // stuck protection active when desired rate is at least this value (+ve or -ve) + extern const AP_HAL::HAL& hal; +const char* AP_Winch_Daiwa::send_text_prefix = "Winch:"; + // true if winch is healthy bool AP_Winch_Daiwa::healthy() const { @@ -40,6 +47,9 @@ void AP_Winch_Daiwa::update() // send outputs to winch control_winch(); + + // update_user + update_user(); } //send generator status @@ -212,7 +222,10 @@ void AP_Winch_Daiwa::control_winch() } // apply acceleration limited to rate - const float rate_limited = get_rate_limited_by_accel(config.rate_desired, dt); + float rate_limited = get_rate_limited_by_accel(config.rate_desired, dt); + + // apply stuck protection to rate + rate_limited = get_stuck_protected_rate(now_ms, rate_limited); // use linear interpolation to calculate output to move winch at desired rate float scaled_output = 0; @@ -222,4 +235,146 @@ void AP_Winch_Daiwa::control_winch() SRV_Channels::set_output_scaled(SRV_Channel::k_winch, scaled_output); } +// returns the rate which may be modified to unstick the winch +// if the winch stops, the rate is temporarily set to zero +// now_ms should be set to the current system time +// rate should be the rate used to calculate the final PWM output to the winch +float AP_Winch_Daiwa::get_stuck_protected_rate(uint32_t now_ms, float rate) +{ + // exit immediately if stuck protection disabled + if (!option_enabled(AP_Winch::Options::RetryIfStuck)) { + return rate; + } + + // check for timeout + bool timeout = (now_ms - stuck_protection.last_update_ms) > 1000; + stuck_protection.last_update_ms = now_ms; + + // check if winch is nearly fully pulled in + const bool near_thread_start = (latest.line_length < AP_WINCH_DAIWA_STUCK_LENGTH_MIN) && is_negative(rate); + + // check if rate is near zero (winch may not move with very low desired rates) + const bool rate_near_zero = fabsf(rate) < AP_WINCH_DAIWA_STUCK_RATE_MIN; + + // return rate unchanged if this protection has not been called recently or winch is unhealthy + // or if winch is moving, desired rate is near zero or winch has stopped at thread start or thread end + if (timeout || !healthy() || latest.moving || rate_near_zero || near_thread_start || latest.thread_end) { + // notify user when winch becomes unstuck + if (option_enabled(AP_Winch::Options::VerboseOutput) && (stuck_protection.stuck_start_ms != 0) && (stuck_protection.user_notified)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s unstuck", send_text_prefix); + } + // reset stuck protection state + stuck_protection.stuck_start_ms = 0; + return rate; + } + + // winch is healthy, with non-zero requested rate but not moving + // record when winch became stuck + if (stuck_protection.stuck_start_ms == 0) { + stuck_protection.stuck_start_ms = now_ms; + stuck_protection.user_notified = false; + } + + // if stuck for between 1 to 2 seconds return zero rate + const uint32_t stuck_time_ms = (now_ms - stuck_protection.stuck_start_ms); + if (stuck_time_ms > AP_WINCH_DAIWA_STUCK_TIMEOUT_MS) { + // notify user + if (!stuck_protection.user_notified) { + stuck_protection.user_notified = true; + if (option_enabled(AP_Winch::Options::VerboseOutput)) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s stuck", send_text_prefix); + } + } + + // return zero rate for 1 second + if (stuck_time_ms <= (AP_WINCH_DAIWA_STUCK_TIMEOUT_MS+AP_WINCH_DAIWA_STUCK_CENTER_MS)) { + return 0; + } + + // rate has been set to zero for 1 sec so release and restart stuck detection + stuck_protection.stuck_start_ms = 0; + + // rate used for acceleration limiting also reset to zero + set_previous_rate(0.0f); + + // update user + if (option_enabled(AP_Winch::Options::VerboseOutput)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s retrying", send_text_prefix); + } + } + + // give winch more time to start moving + return rate; +} + +// update user with changes to winch state via send text messages +void AP_Winch_Daiwa::update_user() +{ + // exit immediately if verbose output disabled + if (!option_enabled(AP_Winch::Options::VerboseOutput)) { + return; + } + + // send updates at no more than 2hz + uint32_t now_ms = AP_HAL::millis(); + if (now_ms - user_update.last_ms < 500) { + return; + } + bool update_sent = false; + + // health change + const bool now_healthy = healthy(); + if (user_update.healthy != now_healthy) { + user_update.healthy = now_healthy; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %shealthy", send_text_prefix, now_healthy ? "" : "not "); + update_sent = true; + } + + // thread end + if (latest.thread_end && (user_update.thread_end != latest.thread_end)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s thread end", send_text_prefix); + update_sent = true; + } + user_update.thread_end = latest.thread_end; + + // moving state + if (user_update.moving != latest.moving) { + // 0:stopped, 1:retracting line, 2:extending line, 3:clutch engaged, 4:zero reset + static const char* moving_str[] = {"stopped", "raising", "lowering", "free spinning", "zero reset"}; + if (latest.moving < ARRAY_SIZE(moving_str)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %s", send_text_prefix, moving_str[latest.moving]); + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s move state uknown", send_text_prefix); + } + update_sent = true; + } + user_update.moving = latest.moving; + + // clutch state + if (user_update.clutch != latest.clutch) { + // 0:clutch off, 1:clutch engaged weakly, 2:clutch engaged strongly, motor can spin freely + static const char* clutch_str[] = {"off", "weak", "strong (free)"}; + if (user_update.clutch < ARRAY_SIZE(clutch_str)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s clutch %s", send_text_prefix, clutch_str[latest.moving]); + } else { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s clutch state uknown", send_text_prefix); + } + update_sent = true; + } + user_update.clutch = latest.clutch; + + // length in meters + const float latest_line_length_rounded = roundf(latest.line_length); + if (!is_equal(user_update.line_length, latest_line_length_rounded)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %dm", send_text_prefix, (int)latest_line_length_rounded); + update_sent = true; + } + user_update.line_length = latest_line_length_rounded; + + // record time message last sent to user + if (update_sent) { + user_update.last_ms = now_ms; + } +} + #endif // AP_WINCH_DAIWA_ENABLED diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.h b/libraries/AP_Winch/AP_Winch_Daiwa.h index 61b9dc630bc7a0..301a73d9e9b070 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.h +++ b/libraries/AP_Winch/AP_Winch_Daiwa.h @@ -63,6 +63,12 @@ class AP_Winch_Daiwa : public AP_Winch_Backend { // update pwm outputs to control winch void control_winch(); + // returns the rate which may be modified to unstick the winch + // if the winch stops, the rate is temporarily set to zero + // now_ms should be set to the current system time + // rate should be the rate used to calculate the final PWM output to the winch + float get_stuck_protected_rate(uint32_t now_ms, float rate); + static const uint8_t buff_len_max = 20; // buffer maximum length static const int16_t output_dz = 100; // output deadzone in scale of -1000 to +1000 const float line_length_correction_factor = 0.003333f; // convert winch counter to meters @@ -106,6 +112,25 @@ class AP_Winch_Daiwa : public AP_Winch_Backend { WAITING_FOR_PCB_TEMP, WAITING_FOR_MOTOR_TEMP } parse_state; + + // update user with changes to winch state via send text messages + static const char* send_text_prefix;// send text prefix string to reduce flash cost + void update_user(); + struct { + uint32_t last_ms; // system time of last update to user + bool healthy; // latest reported health + float line_length; + bool thread_end; // true if end of thread has been detected + uint8_t moving; // 0:stopped, 1:retracting line, 2:extending line, 3:clutch engaged, 4:zero reset + uint8_t clutch; // 0:clutch off, 1:clutch engaged weakly, 2:clutch engaged strongly, motor can spin freely + } user_update; + + // stuck protection + struct { + uint32_t last_update_ms; // system time that stuck protection was last called + uint32_t stuck_start_ms; // system time that winch became stuck (0 if not stuck) + bool user_notified; // true if user has been notified that winch is stuck + } stuck_protection; }; #endif // AP_WINCH_DAIWA_ENABLED diff --git a/libraries/AP_WindVane/Tools/Bluetooth NMEA receiver/Bluetooth NMEA receiver.ino b/libraries/AP_WindVane/Tools/Bluetooth NMEA receiver/Bluetooth NMEA receiver.ino index 3a6dee42ee6ea8..5788e16ab4de54 100644 --- a/libraries/AP_WindVane/Tools/Bluetooth NMEA receiver/Bluetooth NMEA receiver.ino +++ b/libraries/AP_WindVane/Tools/Bluetooth NMEA receiver/Bluetooth NMEA receiver.ino @@ -1,214 +1,214 @@ -#include - -// This code uses the bluefruit libary52 from Adafruit -// Documentation here: https://learn.adafruit.com/bluefruit-nrf52-feather-learning-guide/bluefruit-nrf52-api -// Should work with any nrf52 Bluetooth Arduino, tested with Seeed XIAO nRF52840 Sense - -// Wind vane address, found with mobile app -#define WIND_VANE_ADDRESS 0xDDB7BEB45638 - -// Define services and charicteristics to moniter -BLEClientService env_sense(0x181A); // Environmental Sensing -BLEClientCharacteristic wind_speed(0x2A72); // Apparent Wind Speed -BLEClientCharacteristic wind_dir(0x2A73); // Apparent Wind Direcetion - -BLEClientService bat_sense(0x180F); // Battery Sensing -BLEClientCharacteristic bat_level(0x2A19); // Battery level - -ble_gap_addr_t addr; - -float speed; -float direction; -uint8_t battery_level; - -bool speed_new; -bool direction_new; -bool battery_new; - -uint32_t last_connect_attempt; - -#define RECONNECT_TIME_MS 1000 -#define NMEA_BAUD 57600 -#define LOW_BAT_BLINK_MS 200 - -void setup() -{ - // Disconected - digitalWrite(LED_RED, LOW); - - uint64_t address = WIND_VANE_ADDRESS; - memcpy(addr.addr, &address, BLE_GAP_ADDR_LEN); - - addr.addr_type = BLE_GAP_ADDR_TYPE_RANDOM_STATIC; - - // Extra info and debugging on USB, NMEA on serial 1 - Serial.begin(115200); - Serial1.begin(NMEA_BAUD); - - Serial.println("ArduPilot Bluetooth windvane to NMEA translator"); - - Bluefruit.begin(0, 1); - Bluefruit.setName("ArduPilot Bluetooth"); - - // Initialize services client - env_sense.begin(); - bat_sense.begin(); - - // Set notify callbacks - wind_speed.setNotifyCallback(speed_notify_callback); - wind_dir.setNotifyCallback(direction_notify_callback); - bat_level.setNotifyCallback(bat_notify_callback); - - // Initalize Caricterstics - wind_speed.begin(&env_sense); - wind_dir.begin(&env_sense); - bat_level.begin(&bat_sense); - - // Turn of LEDs, we do our own - Bluefruit.autoConnLed(false); - - // Callbacks for Central - Bluefruit.Central.setDisconnectCallback(disconnect_callback); - Bluefruit.Central.setConnectCallback(connect_callback); - - // Connect to known address - Bluefruit.Central.connect(&addr); - last_connect_attempt = millis(); -} - -bool low_battery; -uint32_t last_low_battery_blink; -char NMEA_buffer[50]; -void loop() -{ - if (!Bluefruit.connected(0)) { - // Disconected - digitalWrite(LED_RED, LOW); - digitalWrite(LED_GREEN, HIGH); - - const uint32_t now = millis(); - if (now - last_connect_attempt > RECONNECT_TIME_MS) { - // try and re-connect - Bluefruit.Central.connect(&addr); - last_connect_attempt = now; - } - return; - } - - // Connected, show green LED - digitalWrite(LED_GREEN, LOW); - - // flash red LED for low battery - if (low_battery) { - const uint32_t now = millis(); - if (now - last_low_battery_blink > LOW_BAT_BLINK_MS) { - digitalWrite(LED_RED, !digitalRead(LED_RED)); - last_low_battery_blink = now; - } - } else { - digitalWrite(LED_RED, HIGH); - } - - if (speed_new && direction_new) { - speed_new = false; - direction_new = false; - - Serial.printf("Wind Speed: %0.2f (m/s), Direction: %0.2f (deg), Battery: %u%%\n", speed, direction, battery_level); - - sprintf(NMEA_buffer, "APMWV,%0.2f,R,%0.2f,M,A", direction, speed); - Serial1.printf("$%s*%02X\n",NMEA_buffer, NMEA_checksum(NMEA_buffer)); - } - - if (battery_new) { - battery_new = false; - - sprintf(NMEA_buffer, "APXDR,G,%u,%%,BT", battery_level); - Serial1.printf("$%s*%02X\n",NMEA_buffer, NMEA_checksum(NMEA_buffer)); - - if (battery_level < 25) { - // Windvane enters low power mode at less than 20% battery - low_battery = true; - } else if (battery_level > 30) { - low_battery = false; - } - } - -} - -uint8_t NMEA_checksum(const char* NMEA_string) -{ - uint8_t checksum = 0; - for (uint8_t i = 0; i < strlen(NMEA_string); i++) { - checksum ^= NMEA_string[i]; - } - return checksum; -} - -void connect_callback(uint16_t conn_handle) -{ - Serial.println("Connected"); - - Serial.print("Discovering Environmental characteristics ... "); - if (!env_sense.discover(conn_handle) || !wind_speed.discover() || !wind_dir.discover()) { - Serial.println("Failed"); - Bluefruit.disconnect(conn_handle); - return; - } - Serial.println("Found"); - - - Serial.print("Discovering Battery characteristics ... "); - if (!bat_sense.discover(conn_handle) || !bat_level.discover()) { - Serial.println("failed"); - Bluefruit.disconnect(conn_handle); - return; - } - Serial.println("Found"); - - if (wind_speed.enableNotify() && wind_dir.enableNotify() && bat_level.enableNotify()) { - Serial.println("Ready to receive"); - } else { - Serial.println("Couldn't enable notify. Increase DEBUG LEVEL for troubleshooting"); - } - -} - -void disconnect_callback(uint16_t conn_handle, uint8_t reason) -{ - (void) conn_handle; - - speed_new = false; - direction_new = false; - battery_new = false; - - Serial.print("Disconnected, reason = 0x"); Serial.println(reason, HEX); -} - - -void speed_notify_callback(BLEClientCharacteristic* chr, uint8_t* data, uint16_t len) -{ - if (len == 2) { - uint16_t value; - memcpy(&value, data, 2); - speed = value * 0.01; - speed_new = true; - } -} - -void direction_notify_callback(BLEClientCharacteristic* chr, uint8_t* data, uint16_t len) -{ - if (len == 2) { - uint16_t value; - memcpy(&value, data, 2); - direction = value * 0.01; - direction_new = true; - } -} - -void bat_notify_callback(BLEClientCharacteristic* chr, uint8_t* data, uint16_t len) -{ - if (len == 1) { - battery_level = data[0]; - battery_new = true; - } -} +#include + +// This code uses the bluefruit libary52 from Adafruit +// Documentation here: https://learn.adafruit.com/bluefruit-nrf52-feather-learning-guide/bluefruit-nrf52-api +// Should work with any nrf52 Bluetooth Arduino, tested with Seeed XIAO nRF52840 Sense + +// Wind vane address, found with mobile app +#define WIND_VANE_ADDRESS 0xDDB7BEB45638 + +// Define services and charicteristics to moniter +BLEClientService env_sense(0x181A); // Environmental Sensing +BLEClientCharacteristic wind_speed(0x2A72); // Apparent Wind Speed +BLEClientCharacteristic wind_dir(0x2A73); // Apparent Wind Direcetion + +BLEClientService bat_sense(0x180F); // Battery Sensing +BLEClientCharacteristic bat_level(0x2A19); // Battery level + +ble_gap_addr_t addr; + +float speed; +float direction; +uint8_t battery_level; + +bool speed_new; +bool direction_new; +bool battery_new; + +uint32_t last_connect_attempt; + +#define RECONNECT_TIME_MS 1000 +#define NMEA_BAUD 57600 +#define LOW_BAT_BLINK_MS 200 + +void setup() +{ + // Disconected + digitalWrite(LED_RED, LOW); + + uint64_t address = WIND_VANE_ADDRESS; + memcpy(addr.addr, &address, BLE_GAP_ADDR_LEN); + + addr.addr_type = BLE_GAP_ADDR_TYPE_RANDOM_STATIC; + + // Extra info and debugging on USB, NMEA on serial 1 + Serial.begin(115200); + Serial1.begin(NMEA_BAUD); + + Serial.println("ArduPilot Bluetooth windvane to NMEA translator"); + + Bluefruit.begin(0, 1); + Bluefruit.setName("ArduPilot Bluetooth"); + + // Initialize services client + env_sense.begin(); + bat_sense.begin(); + + // Set notify callbacks + wind_speed.setNotifyCallback(speed_notify_callback); + wind_dir.setNotifyCallback(direction_notify_callback); + bat_level.setNotifyCallback(bat_notify_callback); + + // Initalize Caricterstics + wind_speed.begin(&env_sense); + wind_dir.begin(&env_sense); + bat_level.begin(&bat_sense); + + // Turn of LEDs, we do our own + Bluefruit.autoConnLed(false); + + // Callbacks for Central + Bluefruit.Central.setDisconnectCallback(disconnect_callback); + Bluefruit.Central.setConnectCallback(connect_callback); + + // Connect to known address + Bluefruit.Central.connect(&addr); + last_connect_attempt = millis(); +} + +bool low_battery; +uint32_t last_low_battery_blink; +char NMEA_buffer[50]; +void loop() +{ + if (!Bluefruit.connected(0)) { + // Disconected + digitalWrite(LED_RED, LOW); + digitalWrite(LED_GREEN, HIGH); + + const uint32_t now = millis(); + if (now - last_connect_attempt > RECONNECT_TIME_MS) { + // try and re-connect + Bluefruit.Central.connect(&addr); + last_connect_attempt = now; + } + return; + } + + // Connected, show green LED + digitalWrite(LED_GREEN, LOW); + + // flash red LED for low battery + if (low_battery) { + const uint32_t now = millis(); + if (now - last_low_battery_blink > LOW_BAT_BLINK_MS) { + digitalWrite(LED_RED, !digitalRead(LED_RED)); + last_low_battery_blink = now; + } + } else { + digitalWrite(LED_RED, HIGH); + } + + if (speed_new && direction_new) { + speed_new = false; + direction_new = false; + + Serial.printf("Wind Speed: %0.2f (m/s), Direction: %0.2f (deg), Battery: %u%%\n", speed, direction, battery_level); + + sprintf(NMEA_buffer, "APMWV,%0.2f,R,%0.2f,M,A", direction, speed); + Serial1.printf("$%s*%02X\n",NMEA_buffer, NMEA_checksum(NMEA_buffer)); + } + + if (battery_new) { + battery_new = false; + + sprintf(NMEA_buffer, "APXDR,G,%u,%%,BT", battery_level); + Serial1.printf("$%s*%02X\n",NMEA_buffer, NMEA_checksum(NMEA_buffer)); + + if (battery_level < 25) { + // Windvane enters low power mode at less than 20% battery + low_battery = true; + } else if (battery_level > 30) { + low_battery = false; + } + } + +} + +uint8_t NMEA_checksum(const char* NMEA_string) +{ + uint8_t checksum = 0; + for (uint8_t i = 0; i < strlen(NMEA_string); i++) { + checksum ^= NMEA_string[i]; + } + return checksum; +} + +void connect_callback(uint16_t conn_handle) +{ + Serial.println("Connected"); + + Serial.print("Discovering Environmental characteristics ... "); + if (!env_sense.discover(conn_handle) || !wind_speed.discover() || !wind_dir.discover()) { + Serial.println("Failed"); + Bluefruit.disconnect(conn_handle); + return; + } + Serial.println("Found"); + + + Serial.print("Discovering Battery characteristics ... "); + if (!bat_sense.discover(conn_handle) || !bat_level.discover()) { + Serial.println("failed"); + Bluefruit.disconnect(conn_handle); + return; + } + Serial.println("Found"); + + if (wind_speed.enableNotify() && wind_dir.enableNotify() && bat_level.enableNotify()) { + Serial.println("Ready to receive"); + } else { + Serial.println("Couldn't enable notify. Increase DEBUG LEVEL for troubleshooting"); + } + +} + +void disconnect_callback(uint16_t conn_handle, uint8_t reason) +{ + (void) conn_handle; + + speed_new = false; + direction_new = false; + battery_new = false; + + Serial.print("Disconnected, reason = 0x"); Serial.println(reason, HEX); +} + + +void speed_notify_callback(BLEClientCharacteristic* chr, uint8_t* data, uint16_t len) +{ + if (len == 2) { + uint16_t value; + memcpy(&value, data, 2); + speed = value * 0.01; + speed_new = true; + } +} + +void direction_notify_callback(BLEClientCharacteristic* chr, uint8_t* data, uint16_t len) +{ + if (len == 2) { + uint16_t value; + memcpy(&value, data, 2); + direction = value * 0.01; + direction_new = true; + } +} + +void bat_notify_callback(BLEClientCharacteristic* chr, uint8_t* data, uint16_t len) +{ + if (len == 1) { + battery_level = data[0]; + battery_new = true; + } +} diff --git a/libraries/AR_Motors/AP_MotorsUGV.cpp b/libraries/AR_Motors/AP_MotorsUGV.cpp index f16ef81ffd19f2..5bb429ef0564f1 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.cpp +++ b/libraries/AR_Motors/AP_MotorsUGV.cpp @@ -111,6 +111,13 @@ const AP_Param::GroupInfo AP_MotorsUGV::var_info[] = { // @User: Standard AP_GROUPINFO("VEC_ANGLEMAX", 13, AP_MotorsUGV, _vector_angle_max, 0.0f), + // @Param: THST_ASYM + // @DisplayName: Motor Thrust Asymmetry + // @Description: Thrust Asymetry. Used for skid-steering. 2.0 means your motors move twice as fast forward than they do backwards. + // @Range: 1.0 10.0 + // @User: Advanced + AP_GROUPINFO("THST_ASYM", 14, AP_MotorsUGV, _thrust_asymmetry, 1.0f), + AP_GROUPEND }; @@ -729,12 +736,43 @@ void AP_MotorsUGV::output_skid_steering(bool armed, float steering, float thrott float steering_scaled = steering / 4500.0f; // steering scaled -1 to +1 float throttle_scaled = throttle * 0.01f; // throttle scaled -1 to +1 + // sanitize values for asymmetry of thrust, mixer assumes forward thrust is always larger than reverse + const float thrust_asymmetry = MAX(_thrust_asymmetry, 1.0); + const float lower_throttle_limit = -1.0 / thrust_asymmetry; + + // Maximum steering is half way between upper and lower limits + const float best_steering_throttle = (1.0 + lower_throttle_limit) * 0.5; + float steering_range; + if (throttle_scaled < best_steering_throttle) { + // steering range is reduced as throttle will never be increased by mixer + steering_range = MAX(throttle_scaled,0.0) - lower_throttle_limit; + } else { + // full range available, throttle can always be lowered down to best_steering_throttle + steering_range = 1 - best_steering_throttle; + } + // apply constraints - steering_scaled = constrain_float(steering_scaled, -1.0f, 1.0f); - throttle_scaled = constrain_float(throttle_scaled, -1.0f, 1.0f); + if (steering_scaled > steering_range) { + limit.steer_right = true; + steering_scaled = steering_range; + } else if (steering_scaled < -steering_range) { + limit.steer_left = true; + steering_scaled = -steering_range; + } + if (throttle_scaled > 1.0) { + limit.throttle_upper = true; + throttle_scaled = 1.0; + } else if (throttle_scaled < lower_throttle_limit) { + limit.throttle_lower = true; + throttle_scaled = lower_throttle_limit; + } + + // All throttle or all steering will now fit, check if they will both fit together + const float max_output = throttle_scaled + fabsf(steering_scaled); + const float min_output = throttle_scaled - fabsf(steering_scaled); // check for saturation and scale back throttle and steering proportionally - const float saturation_value = fabsf(steering_scaled) + fabsf(throttle_scaled); + const float saturation_value = MAX(max_output, min_output / lower_throttle_limit); if (saturation_value > 1.0f) { // store pre-scaled values so we can set limit flags afterwards const float steering_scaled_orig = steering_scaled; @@ -745,11 +783,25 @@ void AP_MotorsUGV::output_skid_steering(bool armed, float steering, float thrott if (str_thr_mix >= 0.5f) { // prioritise steering over throttle steering_scaled *= linear_interpolate(fair_scaler, 1.0f, str_thr_mix, 0.5f, 1.0f); - throttle_scaled = (1.0f - fabsf(steering_scaled)) * (is_negative(throttle_scaled) ? -1.0f : 1.0f); + if (throttle_scaled >= best_steering_throttle) { + // constrained by upper limit + throttle_scaled = 1.0 - fabsf(steering_scaled); + } else { + // constrained by lower limit + throttle_scaled = fabsf(steering_scaled) + lower_throttle_limit; + } + } else { // prioritise throttle over steering throttle_scaled *= linear_interpolate(fair_scaler, 1.0f, 0.5f - str_thr_mix, 0.0f, 0.5f); - steering_scaled = (1.0f - fabsf(throttle_scaled)) * (is_negative(steering_scaled) ? -1.0f : 1.0f); + const float steering_sign = is_positive(steering_scaled) ? 1.0 : -1.0; + if (throttle_scaled >= best_steering_throttle) { + // constrained by upper limit + steering_scaled = (1.0 - throttle_scaled) * steering_sign; + } else { + // constrained by lower limit + steering_scaled = (throttle_scaled - lower_throttle_limit) * steering_sign; + } } // update limits if either steering or throttle has been reduced @@ -764,8 +816,16 @@ void AP_MotorsUGV::output_skid_steering(bool armed, float steering, float thrott } // add in throttle and steering - const float motor_left = throttle_scaled + steering_scaled; - const float motor_right = throttle_scaled - steering_scaled; + float motor_left = throttle_scaled + steering_scaled; + float motor_right = throttle_scaled - steering_scaled; + + // Apply asymmetry correction + if (is_negative(motor_right)) { + motor_right *= thrust_asymmetry; + } + if (is_negative(motor_left)) { + motor_left *= thrust_asymmetry; + } // send pwm value to each motor output_throttle(SRV_Channel::k_throttleLeft, 100.0f * motor_left, dt); diff --git a/libraries/AR_Motors/AP_MotorsUGV.h b/libraries/AR_Motors/AP_MotorsUGV.h index 14dead8e92648a..df61e8734d974f 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.h +++ b/libraries/AR_Motors/AP_MotorsUGV.h @@ -201,6 +201,7 @@ class AP_MotorsUGV { AP_Int8 _throttle_min; // throttle minimum percentage AP_Int8 _throttle_max; // throttle maximum percentage AP_Float _thrust_curve_expo; // thrust curve exponent from -1 to +1 with 0 being linear + AP_Float _thrust_asymmetry; // asymmetry factor, how much better your skid-steering motors are at going forward than backwards (forward/backward thrust ratio) AP_Float _vector_angle_max; // angle between steering's middle position and maximum position when using vectored thrust. zero to disable vectored thrust AP_Float _speed_scale_base; // speed above which steering is scaled down when using regular steering/throttle vehicles. zero to disable speed scaling AP_Float _steering_throttle_mix; // Steering vs Throttle priorisation. Higher numbers prioritise steering, lower numbers prioritise throttle. Only valid for Skid Steering vehicles diff --git a/libraries/Filter/HarmonicNotchFilter.cpp b/libraries/Filter/HarmonicNotchFilter.cpp index 3047cafd451350..82ae789ba5d97a 100644 --- a/libraries/Filter/HarmonicNotchFilter.cpp +++ b/libraries/Filter/HarmonicNotchFilter.cpp @@ -22,7 +22,6 @@ #include #define HNF_MAX_FILTERS HAL_HNF_MAX_FILTERS // must be even for double-notch filters -#define HNF_MAX_HARMONICS 8 // table of user settable parameters const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = { @@ -61,7 +60,22 @@ const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = { // @Param: HMNCS // @DisplayName: Harmonic Notch Filter harmonics // @Description: Bitmask of harmonic frequencies to apply Harmonic Notch Filter to. This option takes effect on the next reboot. A value of 0 disables this filter. The first harmonic refers to the base frequency. - // @Bitmask: 0:1st harmonic,1:2nd harmonic,2:3rd harmonic,3:4th hamronic,4:5th harmonic,5:6th harmonic,6:7th harmonic,7:8th harmonic + // @Bitmask: 0: 1st harmonic + // @Bitmask: 1: 2nd harmonic + // @Bitmask: 2: 3rd harmonic + // @Bitmask: 3: 4th harmonic + // @Bitmask: 4: 5th harmonic + // @Bitmask: 5: 6th harmonic + // @Bitmask: 6: 7th harmonic + // @Bitmask: 7: 8th harmonic + // @Bitmask: 8: 9th harmonic + // @Bitmask: 9: 10th harmonic + // @Bitmask: 10: 11th harmonic + // @Bitmask: 11: 12th harmonic + // @Bitmask: 12: 13th harmonic + // @Bitmask: 13: 14th harmonic + // @Bitmask: 14: 15th harmonic + // @Bitmask: 15: 16th harmonic // @User: Advanced // @RebootRequired: True AP_GROUPINFO("HMNCS", 5, HarmonicNotchFilterParams, _harmonics, 3), @@ -143,7 +157,7 @@ void HarmonicNotchFilter::init(float sample_freq_hz, float center_freq_hz, fl allocate a collection of, at most HNF_MAX_FILTERS, notch filters to be managed by this harmonic notch filter */ template -void HarmonicNotchFilter::allocate_filters(uint8_t num_notches, uint8_t harmonics, uint8_t composite_notches) +void HarmonicNotchFilter::allocate_filters(uint8_t num_notches, uint32_t harmonics, uint8_t composite_notches) { _composite_notches = MIN(composite_notches, 3); _num_harmonics = __builtin_popcount(harmonics); @@ -327,6 +341,11 @@ HarmonicNotchFilterParams::HarmonicNotchFilterParams(void) AP_Param::setup_object_defaults(this, var_info); } +void HarmonicNotchFilterParams::init() +{ + _harmonics.convert_parameter_width(AP_PARAM_INT8); +} + /* save changed parameters */ diff --git a/libraries/Filter/HarmonicNotchFilter.h b/libraries/Filter/HarmonicNotchFilter.h index 064365f0b27713..7de4df799df4e7 100644 --- a/libraries/Filter/HarmonicNotchFilter.h +++ b/libraries/Filter/HarmonicNotchFilter.h @@ -19,7 +19,7 @@ #include #include "NotchFilter.h" -#define HNF_MAX_HARMONICS 8 +#define HNF_MAX_HARMONICS 16 /* a filter that manages a set of notch filters targetted at a fundamental center frequency @@ -30,7 +30,7 @@ class HarmonicNotchFilter { public: ~HarmonicNotchFilter(); // allocate a bank of notch filters for this harmonic notch filter - void allocate_filters(uint8_t num_notches, uint8_t harmonics, uint8_t composite_notches); + void allocate_filters(uint8_t num_notches, uint32_t harmonics, uint8_t composite_notches); // expand filter bank with new filters void expand_filter_count(uint8_t num_notches); // initialize the underlying filters using the provided filter parameters @@ -56,7 +56,7 @@ class HarmonicNotchFilter { // quality factor of each filter float _Q; // a bitmask of the harmonics to use - uint8_t _harmonics; + uint32_t _harmonics; // number of notches that make up a composite notch uint8_t _composite_notches; // number of allocated filters @@ -95,16 +95,19 @@ class HarmonicNotchFilterParams : public NotchFilterParams { }; HarmonicNotchFilterParams(void); + + void init(); + // set the fundamental center frequency of the harmonic notch void set_center_freq_hz(float center_freq) { _center_freq_hz.set(center_freq); } // set the bandwidth of the harmonic notch void set_bandwidth_hz(float bandwidth_hz) { _bandwidth_hz.set(bandwidth_hz); } // harmonics enabled on the harmonic notch - uint8_t harmonics(void) const { return _harmonics; } + uint32_t harmonics(void) const { return _harmonics; } // set the harmonics value - void set_harmonics(uint8_t hmncs) { _harmonics.set(hmncs); } + void set_harmonics(uint32_t hmncs) { _harmonics.set(hmncs); } // has the user set the harmonics value - void set_default_harmonics(uint8_t hmncs) { _harmonics.set_default(hmncs); } + void set_default_harmonics(uint32_t hmncs) { _harmonics.set_default(hmncs); } // reference value of the harmonic notch float reference(void) const { return _reference; } void set_reference(float ref) { _reference.set(ref); } @@ -125,7 +128,7 @@ class HarmonicNotchFilterParams : public NotchFilterParams { private: // configured notch harmonics - AP_Int8 _harmonics; + AP_Int32 _harmonics; // notch reference value AP_Float _reference; // notch dynamic tracking mode diff --git a/libraries/Filter/LowPassFilter2p.cpp b/libraries/Filter/LowPassFilter2p.cpp index 8154ab002d00e7..7749387700502c 100644 --- a/libraries/Filter/LowPassFilter2p.cpp +++ b/libraries/Filter/LowPassFilter2p.cpp @@ -17,13 +17,12 @@ DigitalBiquadFilter::DigitalBiquadFilter() { template T DigitalBiquadFilter::apply(const T &sample, const struct biquad_params ¶ms) { - if(is_zero(params.cutoff_freq) || is_zero(params.sample_freq)) { + if(!is_positive(params.cutoff_freq) || !is_positive(params.sample_freq)) { return sample; } if (!initialised) { reset(sample, params); - initialised = true; } T delay_element_0 = sample - _delay_element_1 * params.a1 - _delay_element_2 * params.a2; @@ -37,7 +36,6 @@ T DigitalBiquadFilter::apply(const T &sample, const struct biquad_params &par template void DigitalBiquadFilter::reset() { - _delay_element_1 = _delay_element_2 = T(); initialised = false; } @@ -49,14 +47,15 @@ void DigitalBiquadFilter::reset(const T &value, const struct biquad_params &p template void DigitalBiquadFilter::compute_params(float sample_freq, float cutoff_freq, biquad_params &ret) { - ret.cutoff_freq = cutoff_freq; + // Keep well under Nyquist limit + ret.cutoff_freq = MIN(cutoff_freq, sample_freq * 0.4); ret.sample_freq = sample_freq; if (!is_positive(ret.cutoff_freq)) { // zero cutoff means pass-thru return; } - float fr = sample_freq/cutoff_freq; + float fr = ret.sample_freq / ret.cutoff_freq; float ohm = tanf(M_PI/fr); float c = 1.0f+2.0f*cosf(M_PI/4.0f)*ohm + ohm*ohm; @@ -103,10 +102,6 @@ float LowPassFilter2p::get_sample_freq(void) const { template T LowPassFilter2p::apply(const T &sample) { - if (!is_positive(_params.cutoff_freq)) { - // zero cutoff means pass-thru - return sample; - } return _filter.apply(sample, _params); } diff --git a/libraries/Filter/SlewCalculator2D.cpp b/libraries/Filter/SlewCalculator2D.cpp new file mode 100644 index 00000000000000..06a1555996a444 --- /dev/null +++ b/libraries/Filter/SlewCalculator2D.cpp @@ -0,0 +1,43 @@ +/* + 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 . + */ +/* + The SlewCalculator2D filter calculates a slew rate useful for detecting + oscillations in a 2-axis PID controller. + */ +#include "SlewCalculator2D.h" + +SlewCalculator2D::SlewCalculator2D() : + xlimiter(slew_rate_max, slew_rate_tau), + ylimiter(slew_rate_max, slew_rate_tau) +{ +} + +// apply filter to sample and calculate slewrate +void SlewCalculator2D::update(const Vector2f& sample, float dt) +{ + if (!is_positive(dt)) { + return; + } + + // call x and y slew rate limiter + xlimiter.modifier(sample.x, dt); + ylimiter.modifier(sample.y, dt); +} + +// get last oscillation slew rate +float SlewCalculator2D::get_slew_rate() const +{ + return safe_sqrt(sq(xlimiter.get_slew_rate()) + sq(xlimiter.get_slew_rate())); +} diff --git a/libraries/Filter/SlewCalculator2D.h b/libraries/Filter/SlewCalculator2D.h new file mode 100644 index 00000000000000..7402dd39e52490 --- /dev/null +++ b/libraries/Filter/SlewCalculator2D.h @@ -0,0 +1,30 @@ +#pragma once + +/* slew rate limiting filter. This is used to prevent oscillation of a + * controller by modifying the controllers output based on a maximum + * slew rate +*/ + +#include +#include +#include "SlewLimiter.h" + +class SlewCalculator2D { +public: + SlewCalculator2D(); + + CLASS_NO_COPY(SlewCalculator2D); + + // apply filter to sample and calculate slewrate + void update(const Vector2f& sample, float dt); + + // get last oscillation slew rate + float get_slew_rate() const; + +private: + SlewLimiter xlimiter; // X-axis 1D slew rate limiter + SlewLimiter ylimiter; // Y-axis 1D slew rate limiter + + float slew_rate_max = 0; // slew rate max (always zero) + float slew_rate_tau = 1.0; // slew rate tau (always 1.0) +}; diff --git a/libraries/Filter/SlewLimiter.cpp b/libraries/Filter/SlewLimiter.cpp index d179140cac7f76..455b00123093b3 100644 --- a/libraries/Filter/SlewLimiter.cpp +++ b/libraries/Filter/SlewLimiter.cpp @@ -26,6 +26,10 @@ */ #include "SlewLimiter.h" +#define WINDOW_MS 300 // time in msec required for a half cycle of the slowest oscillation frequency expected +#define MODIFIER_GAIN 1.5f // ratio of modifier reduction to slew rate exceedance ratio +#define DERIVATIVE_CUTOFF_FREQ 25.0f + SlewLimiter::SlewLimiter(const float &_slew_rate_max, const float &_slew_rate_tau) : slew_rate_max(_slew_rate_max), slew_rate_tau(_slew_rate_tau) @@ -85,7 +89,7 @@ float SlewLimiter::modifier(float sample, float dt) // Store a series of positive slew rate exceedance events if (!_pos_event_stored && slew_rate > slew_rate_max) { - if (_pos_event_index >= N_EVENTS) { + if (_pos_event_index >= SLEWLIMITER_N_EVENTS) { _pos_event_index = 0; } _pos_event_ms[_pos_event_index] = now_ms; @@ -96,7 +100,7 @@ float SlewLimiter::modifier(float sample, float dt) // Store a series of negative slew rate exceedance events if (!_neg_event_stored && -slew_rate > slew_rate_max) { - if (_neg_event_index >= N_EVENTS) { + if (_neg_event_index >= SLEWLIMITER_N_EVENTS) { _neg_event_index = 0; } _neg_event_ms[_neg_event_index] = now_ms; @@ -107,7 +111,7 @@ float SlewLimiter::modifier(float sample, float dt) // Find the oldest event time uint32_t oldest_ms = now_ms; - for (uint8_t index = 0; index < N_EVENTS; index++) { + for (uint8_t index = 0; index < SLEWLIMITER_N_EVENTS; index++) { oldest_ms = MIN(oldest_ms, _pos_event_ms[index]); oldest_ms = MIN(oldest_ms, _neg_event_ms[index]); } @@ -116,8 +120,8 @@ float SlewLimiter::modifier(float sample, float dt) // specified number of exceedance events. This prevents spikes due to control mode changed, etc causing // unwanted gain reduction and is only applied to the slew rate used for gain reduction float modifier_input = limited_raw_slew_rate; - if (now_ms - oldest_ms > (N_EVENTS + 1) * WINDOW_MS) { - const float oldest_time_from_window = 0.001f*(float)(now_ms - oldest_ms - (N_EVENTS + 1) * WINDOW_MS); + if (now_ms - oldest_ms > (SLEWLIMITER_N_EVENTS + 1) * WINDOW_MS) { + const float oldest_time_from_window = 0.001f*(float)(now_ms - oldest_ms - (SLEWLIMITER_N_EVENTS + 1) * WINDOW_MS); modifier_input *= expf(-oldest_time_from_window / slew_rate_tau); } diff --git a/libraries/Filter/SlewLimiter.h b/libraries/Filter/SlewLimiter.h index 34be2501e55b04..a35ed088066ba8 100644 --- a/libraries/Filter/SlewLimiter.h +++ b/libraries/Filter/SlewLimiter.h @@ -8,10 +8,7 @@ #include #include "LowPassFilter.h" -#define N_EVENTS 2 // number of positive and negative consecutive slew rate exceedance events recorded where a value of 2 corresponds to a complete cycle -#define WINDOW_MS 300 // time in msec required for a half cycle of the slowest oscillation frequency expected -#define MODIFIER_GAIN 1.5f // ratio of modifier reduction to slew rate exceedance ratio -#define DERIVATIVE_CUTOFF_FREQ 25.0f +#define SLEWLIMITER_N_EVENTS 2 // number of positive and negative consecutive slew rate exceedance events recorded where a value of 2 corresponds to a complete cycle class SlewLimiter { public: @@ -45,8 +42,8 @@ class SlewLimiter { uint32_t _max_neg_slew_event_ms; uint8_t _pos_event_index; uint8_t _neg_event_index; - uint32_t _pos_event_ms[N_EVENTS]; - uint32_t _neg_event_ms[N_EVENTS]; + uint32_t _pos_event_ms[SLEWLIMITER_N_EVENTS]; + uint32_t _neg_event_ms[SLEWLIMITER_N_EVENTS]; bool _pos_event_stored; bool _neg_event_stored; }; diff --git a/libraries/Filter/tests/wscript b/libraries/Filter/tests/wscript index cd3e5e3ce7c9d9..d158413807bea8 100644 --- a/libraries/Filter/tests/wscript +++ b/libraries/Filter/tests/wscript @@ -4,4 +4,5 @@ def build(bld): bld.ap_find_tests( use='ap', + DOUBLE_PRECISION_SOURCES = ['test_notchfilter.cpp'] ) diff --git a/libraries/GCS_MAVLink/GCS.cpp b/libraries/GCS_MAVLink/GCS.cpp index 7ff1e7ec3ca420..0393f04930bb0a 100644 --- a/libraries/GCS_MAVLink/GCS.cpp +++ b/libraries/GCS_MAVLink/GCS.cpp @@ -1,3 +1,7 @@ +#include "GCS_config.h" + +#if HAL_GCS_ENABLED + #include "GCS.h" #include @@ -180,10 +184,12 @@ void GCS::update_sensor_status_flags() #if AP_BARO_ENABLED const AP_Baro &barometer = AP::baro(); - control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; - control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; - if (barometer.all_healthy()) { - control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; + if (barometer.num_instances() > 0) { + control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; + control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; + if (barometer.all_healthy()) { + control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; + } } #endif @@ -375,3 +381,5 @@ bool GCS_MAVLINK::check_payload_size(uint16_t max_payload_len) } return true; } + +#endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index eafb935e9f1324..2e70c63450bdf2 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -28,10 +28,6 @@ #define GCS_DEBUG_SEND_MESSAGE_TIMINGS 0 -#ifndef HAL_HIGH_LATENCY2_ENABLED -#define HAL_HIGH_LATENCY2_ENABLED 1 -#endif - // macros used to determine if a message will fit in the space available. void gcs_out_of_space_to_send(mavlink_channel_t chan); @@ -165,7 +161,7 @@ class GCS_MAVLINK_InProgress Type task; MAV_CMD mav_cmd; - static class GCS_MAVLINK_InProgress *get_task(MAV_CMD cmd, Type t, uint8_t sysid, uint8_t compid); + static class GCS_MAVLINK_InProgress *get_task(MAV_CMD cmd, Type t, uint8_t sysid, uint8_t compid, mavlink_channel_t chan); static void check_tasks(); @@ -519,14 +515,14 @@ class GCS_MAVLINK 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); + 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); virtual bool set_home_to_current_location(bool lock) = 0; virtual bool set_home(const Location& loc, bool lock) = 0; virtual MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet); - MAV_RESULT handle_command_do_aux_function(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_do_aux_function(const mavlink_command_int_t &packet); MAV_RESULT handle_command_storage_format(const mavlink_command_int_t &packet, const mavlink_message_t &msg); void handle_mission_request_list(const mavlink_message_t &msg); void handle_mission_request(const mavlink_message_t &msg); @@ -576,7 +572,7 @@ class GCS_MAVLINK void handle_common_message(const mavlink_message_t &msg); void handle_set_gps_global_origin(const mavlink_message_t &msg); void handle_setup_signing(const mavlink_message_t &msg) const; - virtual MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg); + virtual MAV_RESULT handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg); struct { HAL_Semaphore sem; bool taken; @@ -584,14 +580,14 @@ class GCS_MAVLINK void deadlock_sem(void); // reset a message interval via mavlink: - MAV_RESULT handle_command_set_message_interval(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_get_message_interval(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_set_message_interval(const mavlink_command_int_t &packet); + MAV_RESULT handle_command_get_message_interval(const mavlink_command_int_t &packet); bool get_ap_message_interval(ap_message id, uint16_t &interval_ms) const; - MAV_RESULT handle_command_request_message(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_request_message(const mavlink_command_int_t &packet); MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet); - virtual MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet); + virtual MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet); #if AP_MAVLINK_AUTOPILOT_VERSION_REQUEST_ENABLED void handle_send_autopilot_version(const mavlink_message_t &msg); @@ -633,25 +629,26 @@ class GCS_MAVLINK // generally this should not be overridden; Plane overrides it to ensure // failsafe isn't triggered during calibration - virtual MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg); + virtual MAV_RESULT handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg); - virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg); + virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg); virtual MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg); virtual MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet); MAV_RESULT handle_command_battery_reset(const mavlink_command_long_t &packet); void handle_command_long(const mavlink_message_t &msg); - MAV_RESULT handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_do_set_roi_sysid(const uint8_t sysid); - MAV_RESULT handle_command_do_set_roi_sysid(const mavlink_command_int_t &packet); - MAV_RESULT handle_command_do_set_roi_sysid(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_do_set_roi_none(); - - virtual MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet, const mavlink_message_t &msg); - MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet); - MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet); - virtual MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_accelcal_vehicle_pos(const mavlink_command_int_t &packet); + +#if HAL_MOUNT_ENABLED + virtual MAV_RESULT handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg); +#endif + + MAV_RESULT handle_command_mag_cal(const mavlink_command_int_t &packet); + MAV_RESULT handle_command_fixed_mag_cal_yaw(const mavlink_command_int_t &packet); + + MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg); + virtual MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg); MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet); MAV_RESULT handle_command_do_send_banner(const mavlink_command_long_t &packet); MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet); @@ -662,20 +659,20 @@ class GCS_MAVLINK MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet); MAV_RESULT handle_command_do_fence_enable(const mavlink_command_long_t &packet); MAV_RESULT handle_command_debug_trap(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_set_ekf_source_set(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_airframe_configuration(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_set_ekf_source_set(const mavlink_command_int_t &packet); + MAV_RESULT handle_command_airframe_configuration(const mavlink_command_int_t &packet); /* handle MAV_CMD_CAN_FORWARD and CAN_FRAME messages for CAN over MAVLink */ void can_frame_callback(uint8_t bus, const AP_HAL::CANFrame &); - MAV_RESULT handle_can_forward(const mavlink_command_long_t &packet, const mavlink_message_t &msg); +#if HAL_CANMANAGER_ENABLED + MAV_RESULT handle_can_forward(const mavlink_command_int_t &packet, const mavlink_message_t &msg); +#endif void handle_can_frame(const mavlink_message_t &msg) const; void handle_optical_flow(const mavlink_message_t &msg); - MAV_RESULT handle_command_fixed_mag_cal_yaw(const mavlink_command_int_t &packet); - void handle_manual_control(const mavlink_message_t &msg); // default empty handling of LANDING_TARGET @@ -770,7 +767,8 @@ class GCS_MAVLINK virtual void handleMessage(const mavlink_message_t &msg) = 0; - MAV_RESULT handle_servorelay_message(const mavlink_command_long_t &packet); + MAV_RESULT handle_servorelay_message(const mavlink_command_int_t &packet); + bool send_relay_status() const; static bool command_long_stores_location(const MAV_CMD command); @@ -1333,6 +1331,8 @@ void can_printf(const char *fmt, ...); #define GCS_SEND_TEXT(severity, format, args...) (void)severity; can_printf(format, ##args) #endif +#define GCS_SEND_MESSAGE(msg) gcs().send_message(msg) + #elif defined(HAL_BUILD_AP_PERIPH) && !defined(STM32F1) // map send text to can_printf() on larger AP_Periph boards @@ -1340,10 +1340,12 @@ extern "C" { void can_printf(const char *fmt, ...); } #define GCS_SEND_TEXT(severity, format, args...) can_printf(format, ##args) +#define GCS_SEND_MESSAGE(msg) #else // HAL_GCS_ENABLED // empty send text when we have no GCS #define GCS_SEND_TEXT(severity, format, args...) +#define GCS_SEND_MESSAGE(msg) #endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 73fe4b9d8b58e4..ee491c1bcc2e84 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -14,6 +14,11 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ + +#include "GCS_config.h" + +#if HAL_GCS_ENABLED + #include "GCS.h" #include @@ -88,6 +93,11 @@ #endif #include +#if HAL_WITH_IO_MCU +#include +extern AP_IOMCU iomcu; +#endif + #include extern const AP_HAL::HAL& hal; @@ -384,7 +394,7 @@ void GCS_MAVLINK::send_distance_sensor(const AP_RangeFinder_Backend *sensor, con return; } - uint8_t quality_pct = 0; + int8_t quality_pct; uint8_t quality; if (sensor->get_signal_quality_pct(quality_pct)) { // mavlink defines this field as 0 is unknown, 1 is invalid, 100 is perfect @@ -632,7 +642,6 @@ MISSION_STATE GCS_MAVLINK::mission_state(const AP_Mission &mission) const return MISSION_STATE_UNKNOWN; } -#if AP_MAVLINK_MISSION_SET_CURRENT_ENABLED void GCS_MAVLINK::send_mission_current(const class AP_Mission &mission, uint16_t seq) { auto num_commands = mission.num_commands(); @@ -651,6 +660,7 @@ void GCS_MAVLINK::send_mission_current(const class AP_Mission &mission, uint16_t mission_mode); // mission_mode } +#if AP_MAVLINK_MISSION_SET_CURRENT_ENABLED /* handle a MISSION_SET_CURRENT mavlink packet @@ -967,7 +977,9 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_SYSTEM_TIME, MSG_SYSTEM_TIME}, { MAVLINK_MSG_ID_RC_CHANNELS_SCALED, MSG_SERVO_OUT}, { MAVLINK_MSG_ID_PARAM_VALUE, MSG_NEXT_PARAM}, +#if AP_FENCE_ENABLED { MAVLINK_MSG_ID_FENCE_STATUS, MSG_FENCE_STATUS}, +#endif { MAVLINK_MSG_ID_AHRS, MSG_AHRS}, #if AP_SIM_ENABLED { MAVLINK_MSG_ID_SIMSTATE, MSG_SIMSTATE}, @@ -983,9 +995,11 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c #if AP_MAVLINK_BATTERY2_ENABLED { MAVLINK_MSG_ID_BATTERY2, MSG_BATTERY2}, #endif +#if AP_CAMERA_ENABLED { MAVLINK_MSG_ID_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK}, { MAVLINK_MSG_ID_CAMERA_INFORMATION, MSG_CAMERA_INFORMATION}, { MAVLINK_MSG_ID_CAMERA_SETTINGS, MSG_CAMERA_SETTINGS}, +#endif #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}, @@ -995,8 +1009,10 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c #if AP_OPTICALFLOW_ENABLED { MAVLINK_MSG_ID_OPTICAL_FLOW, MSG_OPTICAL_FLOW}, #endif +#if COMPASS_CAL_ENABLED { MAVLINK_MSG_ID_MAG_CAL_PROGRESS, MSG_MAG_CAL_PROGRESS}, { MAVLINK_MSG_ID_MAG_CAL_REPORT, MSG_MAG_CAL_REPORT}, +#endif { MAVLINK_MSG_ID_EKF_STATUS_REPORT, MSG_EKF_STATUS_REPORT}, { MAVLINK_MSG_ID_LOCAL_POSITION_NED, MSG_LOCAL_POSITION}, { MAVLINK_MSG_ID_PID_TUNING, MSG_PID_TUNING}, @@ -1011,7 +1027,9 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_ADSB_VEHICLE, MSG_ADSB_VEHICLE}, { MAVLINK_MSG_ID_BATTERY_STATUS, MSG_BATTERY_STATUS}, { MAVLINK_MSG_ID_AOA_SSA, MSG_AOA_SSA}, +#if HAL_LANDING_DEEPSTALL_ENABLED { MAVLINK_MSG_ID_DEEPSTALL, MSG_LANDING}, +#endif { MAVLINK_MSG_ID_EXTENDED_SYS_STATE, MSG_EXTENDED_SYS_STATE}, { MAVLINK_MSG_ID_AUTOPILOT_VERSION, MSG_AUTOPILOT_VERSION}, #if HAL_EFI_ENABLED @@ -1020,7 +1038,9 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c #if HAL_GENERATOR_ENABLED { MAVLINK_MSG_ID_GENERATOR_STATUS, MSG_GENERATOR_STATUS}, #endif +#if AP_WINCH_ENABLED { MAVLINK_MSG_ID_WINCH_STATUS, MSG_WINCH_STATUS}, +#endif #if HAL_WITH_ESC_TELEM { MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, MSG_ESC_TELEMETRY}, #endif @@ -1035,6 +1055,9 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c #endif #if HAL_ADSB_ENABLED { MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS, MSG_UAVIONIX_ADSB_OUT_STATUS}, +#endif +#if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED + { MAVLINK_MSG_ID_RELAY_STATUS, MSG_RELAY_STATUS}, #endif }; @@ -1294,7 +1317,7 @@ bool GCS_MAVLINK_InProgress::conclude(MAV_RESULT result) return true; } -GCS_MAVLINK_InProgress *GCS_MAVLINK_InProgress::get_task(MAV_CMD mav_cmd, GCS_MAVLINK_InProgress::Type t, uint8_t sysid, uint8_t compid) +GCS_MAVLINK_InProgress *GCS_MAVLINK_InProgress::get_task(MAV_CMD mav_cmd, GCS_MAVLINK_InProgress::Type t, uint8_t sysid, uint8_t compid, mavlink_channel_t chan) { // we can't have two outstanding tasks for the same command from // the same mavlink node or the result is ambiguous: @@ -1313,6 +1336,7 @@ GCS_MAVLINK_InProgress *GCS_MAVLINK_InProgress::get_task(MAV_CMD mav_cmd, GCS_MA if (_task.task != Type::NONE) { continue; } + _task.chan = chan; _task.task = t; _task.mav_cmd = mav_cmd; _task.requesting_sysid = sysid; @@ -1753,7 +1777,7 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us) bool parsed_packet = false; // Try to get a new message - if (mavlink_parse_char(chan, c, &msg, &status)) { + if (mavlink_frame_char_buffer(channel_buffer(), channel_status(), c, &msg, &status) == MAVLINK_FRAMING_OK) { hal.util->persistent_data.last_mavlink_msgid = msg.msgid; packetReceived(status, msg); parsed_packet = true; @@ -1907,7 +1931,9 @@ void GCS_MAVLINK::log_mavlink_stats() void GCS_MAVLINK::send_system_time() const { uint64_t time_unix = 0; +#if AP_RTC_ENABLED AP::rtc().get_utc_usec(time_unix); // may fail, leaving time_unix at 0 +#endif mavlink_msg_system_time_send( chan, @@ -2732,6 +2758,7 @@ void GCS_MAVLINK::send_named_float(const char *name, float value) const mavlink_msg_named_value_float_send(chan, AP_HAL::millis(), float_name, value); } +#if AP_AHRS_ENABLED void GCS_MAVLINK::send_home_position() const { if (!AP::ahrs().home_is_set()) { @@ -2741,20 +2768,24 @@ void GCS_MAVLINK::send_home_position() const const Location &home = AP::ahrs().get_home(); // get home position from origin - Vector3f home_pos_neu_cm; - if (!home.get_vector_from_origin_NEU(home_pos_neu_cm)) { - return; + Vector3f home_pos_ned; + if (home.get_vector_from_origin_NEU(home_pos_ned)) { + // convert NEU in cm to NED in meters + home_pos_ned *= 0.01f; + home_pos_ned.z *= -1; + } else { + home_pos_ned = Vector3f{NAN, NAN, NAN}; } - const float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; + const float q[4] {NAN, NAN, NAN, NAN}; mavlink_msg_home_position_send( chan, home.lat, home.lng, home.alt * 10, - home_pos_neu_cm.x * 0.01f, // position of home on x-axis in meters - home_pos_neu_cm.y * 0.01f, // position of home on y-axis in meters - home_pos_neu_cm.z * -0.01f, // position of home on z-axis in meters in NED frame + home_pos_ned.x, + home_pos_ned.y, + home_pos_ned.z, q, 0.0f, 0.0f, 0.0f, AP_HAL::micros64()); @@ -2773,6 +2804,7 @@ void GCS_MAVLINK::send_gps_global_origin() const ekf_origin.alt * 10, AP_HAL::micros64()); } +#endif // AP_AHRS_ENABLED MAV_STATE GCS_MAVLINK::system_status() const { @@ -2804,7 +2836,7 @@ void GCS_MAVLINK::send_heartbeat() const system_status()); } -MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_int_t &packet) { if (packet.param2 > 2) { return MAV_RESULT_DENIED; @@ -2819,7 +2851,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_lon return MAV_RESULT_ACCEPTED; } -MAV_RESULT GCS_MAVLINK::handle_command_set_message_interval(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_set_message_interval(const mavlink_command_int_t &packet) { return set_message_interval((uint32_t)packet.param1, (int32_t)packet.param2); } @@ -2889,7 +2921,7 @@ uint8_t GCS::get_channel_from_port_number(uint8_t port_num) return UINT8_MAX; } -MAV_RESULT GCS_MAVLINK::handle_command_request_message(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_request_message(const mavlink_command_int_t &packet) { const uint32_t mavlink_id = (uint32_t)packet.param1; const ap_message id = mavlink_id_to_ap_message_id(mavlink_id); @@ -2921,7 +2953,7 @@ bool GCS_MAVLINK::get_ap_message_interval(ap_message id, uint16_t &interval_ms) return false; } -MAV_RESULT GCS_MAVLINK::handle_command_get_message_interval(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_get_message_interval(const mavlink_command_int_t &packet) { if (txspace() < PAYLOAD_SIZE(chan, MESSAGE_INTERVAL) + PAYLOAD_SIZE(chan, COMMAND_ACK)) { return MAV_RESULT_TEMPORARILY_REJECTED; @@ -3092,11 +3124,12 @@ void GCS_MAVLINK::send_vfr_hud() motors. That can be dangerous when a preflight reboot is done with the pilot close to the aircraft and can also damage the aircraft */ -MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { if (is_equal(packet.param1, 42.0f) && is_equal(packet.param2, 24.0f) && is_equal(packet.param3, 71.0f)) { +#if AP_MAVLINK_FAILURE_CREATION_ENABLED if (is_equal(packet.param4, 93.0f)) { // this is a magic sequence to force the main loop to // lockup. This is for testing the stm32 watchdog @@ -3150,6 +3183,8 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); return MAV_RESULT_ACCEPTED; } +#endif // AP_MAVLINK_FAILURE_CREATION_ENABLED + #if HAL_ENABLE_DFU_BOOT if (is_equal(packet.param4, 99.0f)) { #if AP_SIGNED_FIRMWARE @@ -3177,8 +3212,8 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &pa // refuse reboot when armed: if (hal.util->get_soft_armed()) { /// but allow it if forced: - const float magic_force_reboot_value = 20190226; - if (!is_equal(packet.param6, magic_force_reboot_value)) { + const uint32_t magic_force_reboot_value = 20190226; + if (packet.y != magic_force_reboot_value) { return MAV_RESULT_FAILED; } } @@ -3229,7 +3264,7 @@ void GCS_MAVLINK::deadlock_sem(void) /* handle a flight termination request */ -MAV_RESULT GCS_MAVLINK::handle_flight_termination(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_flight_termination(const mavlink_command_int_t &packet) { #if AP_ADVANCEDFAILSAFE_ENABLED AP_AdvancedFailsafe *failsafe = AP::advancedfailsafe(); @@ -3402,6 +3437,7 @@ void GCS_MAVLINK::handle_named_value(const mavlink_message_t &msg) const msg.compid); } +#if AP_RTC_ENABLED void GCS_MAVLINK::handle_system_time_message(const mavlink_message_t &msg) { mavlink_system_time_t packet; @@ -3409,6 +3445,7 @@ void GCS_MAVLINK::handle_system_time_message(const mavlink_message_t &msg) AP::rtc().set_utc_usec(packet.time_unix_usec, AP_RTC::SOURCE_MAVLINK_SYSTEM_TIME); } +#endif #if AP_CAMERA_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_long_t &packet) @@ -3564,7 +3601,7 @@ void GCS_MAVLINK::handle_odometry(const mavlink_message_t &msg) } const uint32_t timestamp_ms = correct_offboard_timestamp_usec_to_ms(m.time_usec, PAYLOAD_SIZE(chan, ODOMETRY)); - visual_odom->handle_vision_position_estimate(m.time_usec, timestamp_ms, m.x, m.y, m.z, q, posErr, angErr, m.reset_counter); + visual_odom->handle_pose_estimate(m.time_usec, timestamp_ms, m.x, m.y, m.z, q, posErr, angErr, m.reset_counter); // convert velocity vector from FRD to NED frame Vector3f vel{m.vx, m.vy, m.vz}; @@ -3601,7 +3638,7 @@ void GCS_MAVLINK::handle_common_vision_position_estimate_data(const uint64_t use angErr = cbrtf(sq(covariance[15])+sq(covariance[18])+sq(covariance[20])); } - visual_odom->handle_vision_position_estimate(usec, timestamp_ms, x, y, z, roll, pitch, yaw, posErr, angErr, reset_counter); + visual_odom->handle_pose_estimate(usec, timestamp_ms, x, y, z, roll, pitch, yaw, posErr, angErr, reset_counter); } void GCS_MAVLINK::handle_att_pos_mocap(const mavlink_message_t &msg) @@ -3617,7 +3654,7 @@ void GCS_MAVLINK::handle_att_pos_mocap(const mavlink_message_t &msg) return; } // note: att_pos_mocap does not include reset counter - visual_odom->handle_vision_position_estimate(m.time_usec, timestamp_ms, m.x, m.y, m.z, m.q, 0, 0, 0); + visual_odom->handle_pose_estimate(m.time_usec, timestamp_ms, m.x, m.y, m.z, m.q, 0, 0, 0); } void GCS_MAVLINK::handle_vision_speed_estimate(const mavlink_message_t &msg) @@ -3712,33 +3749,34 @@ void GCS_MAVLINK::handle_optical_flow(const mavlink_message_t &msg) #endif +#if COMPASS_CAL_ENABLED /* handle MAV_CMD_FIXED_MAG_CAL_YAW */ MAV_RESULT GCS_MAVLINK::handle_command_fixed_mag_cal_yaw(const mavlink_command_int_t &packet) { -#if COMPASS_CAL_ENABLED Compass &compass = AP::compass(); return compass.mag_cal_fixed_yaw(packet.param1, uint8_t(packet.param2), packet.param3, packet.param4); -#else - return MAV_RESULT_UNSUPPORTED; -#endif } +MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_int_t &packet) +{ + return AP::compass().handle_mag_cal_command(packet); +} +#endif // COMPASS_CAL_ENABLED + +#if HAL_CANMANAGER_ENABLED /* handle MAV_CMD_CAN_FORWARD */ -MAV_RESULT GCS_MAVLINK::handle_can_forward(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK::handle_can_forward(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { -#if HAL_CANMANAGER_ENABLED return AP::can().handle_can_forward(chan, packet, msg) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED; -#else - return MAV_RESULT_UNSUPPORTED; -#endif } +#endif /* handle CAN_FRAME messages @@ -3845,12 +3883,15 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) handle_set_gps_global_origin(msg); break; +#if AP_MAVLINK_MSG_DEVICE_OP_ENABLED case MAVLINK_MSG_ID_DEVICE_OP_READ: handle_device_op_read(msg); break; case MAVLINK_MSG_ID_DEVICE_OP_WRITE: handle_device_op_write(msg); break; +#endif + case MAVLINK_MSG_ID_TIMESYNC: handle_timesync(msg); break; @@ -3911,20 +3952,26 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) handle_command_int(msg); break; +#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT case MAVLINK_MSG_ID_FENCE_POINT: case MAVLINK_MSG_ID_FENCE_FETCH_POINT: handle_fence_message(msg); break; +#endif #if HAL_MOUNT_ENABLED +#if AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED case MAVLINK_MSG_ID_MOUNT_CONFIGURE: // deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE send_received_message_deprecation_warning("MOUNT_CONFIGURE"); handle_mount_message(msg); break; +#endif +#if AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED case MAVLINK_MSG_ID_MOUNT_CONTROL: // deprecated. Use MAV_CMD_DO_MOUNT_CONTROL send_received_message_deprecation_warning("MOUNT_CONTROL"); handle_mount_message(msg); break; +#endif case MAVLINK_MSG_ID_GIMBAL_REPORT: case MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION: case MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS: @@ -3938,9 +3985,11 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) handle_param_value(msg); break; +#if AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED case MAVLINK_MSG_ID_SERIAL_CONTROL: handle_serial_control(msg); break; +#endif case MAVLINK_MSG_ID_GPS_RTCM_DATA: case MAVLINK_MSG_ID_GPS_INPUT: @@ -3971,7 +4020,7 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) break; #endif -#if HAL_RALLY_ENABLED +#if AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED case MAVLINK_MSG_ID_RALLY_POINT: case MAVLINK_MSG_ID_RALLY_FETCH_POINT: handle_common_rally_message(msg); @@ -4019,9 +4068,11 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) break; #endif // HAL_VISUALODOM_ENABLED +#if AP_RTC_ENABLED case MAVLINK_MSG_ID_SYSTEM_TIME: handle_system_time_message(msg); break; +#endif case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE: handle_rc_channels_override(msg); @@ -4097,11 +4148,13 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) #if AP_EFI_MAV_ENABLED case MAVLINK_MSG_ID_EFI_STATUS: - AP_EFI *efi = AP::EFI(); - if (efi) { - efi->handle_EFI_message(msg); - } - break; + { + AP_EFI *efi = AP::EFI(); + if (efi) { + efi->handle_EFI_message(msg); + } + break; + } #endif } @@ -4197,6 +4250,17 @@ void GCS_MAVLINK::send_banner() send_text(MAV_SEVERITY_INFO, "%s", sysid); } + // send MCUID if we can +#if HAL_WITH_IO_MCU +#define REVID_MASK 0xFFFF0000 +#define DEVID_MASK 0xFFF + if (AP_BoardConfig::io_enabled()) { + uint32_t mcuid = iomcu.get_mcu_id(); + send_text(MAV_SEVERITY_INFO, "IOMCU: %x %x %lx", uint16_t(mcuid & DEVID_MASK), uint16_t((mcuid & REVID_MASK) >> 16U), + iomcu.get_cpu_id()); + } +#endif + // send RC output mode info if available char banner_msg[50]; if (hal.rcout->get_output_mode_banner(banner_msg, sizeof(banner_msg))) { @@ -4288,7 +4352,7 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro(const mavlink AP_Airspeed *airspeed = AP_Airspeed::get_singleton(); if (airspeed != nullptr) { - GCS_MAVLINK_InProgress *task = GCS_MAVLINK_InProgress::get_task(MAV_CMD_PREFLIGHT_CALIBRATION, GCS_MAVLINK_InProgress::Type::AIRSPEED_CAL, msg.sysid, msg.compid); + GCS_MAVLINK_InProgress *task = GCS_MAVLINK_InProgress::get_task(MAV_CMD_PREFLIGHT_CALIBRATION, GCS_MAVLINK_InProgress::Type::AIRSPEED_CAL, msg.sysid, msg.compid, chan); if (task == nullptr) { return MAV_RESULT_TEMPORARILY_REJECTED; } @@ -4299,7 +4363,7 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro(const mavlink return MAV_RESULT_IN_PROGRESS; } -MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { MAV_RESULT ret = MAV_RESULT_UNSUPPORTED; @@ -4322,7 +4386,7 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm rc().calibrating(is_positive(packet.param4)); #if HAL_INS_ACCELCAL_ENABLED - if (is_equal(packet.param5,1.0f)) { + if (packet.x == 1) { // start with gyro calibration if (!AP::ins().calibrate_gyros()) { return MAV_RESULT_FAILED; @@ -4335,11 +4399,11 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm #endif #if AP_INERTIALSENSOR_ENABLED - if (is_equal(packet.param5,2.0f)) { + if (packet.x == 2) { return AP::ins().calibrate_trim(); } - if (is_equal(packet.param5,4.0f)) { + if (packet.x == 4) { // simple accel calibration return AP::ins().simple_accel_cal(); } @@ -4349,7 +4413,7 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm compass to be written as valid. This is useful when reloading parameters after a full parameter erase */ - if (is_equal(packet.param5,76.0f)) { + if (packet.x == 76) { // force existing accel calibration to be accepted as valid AP::ins().force_save_calibration(); ret = MAV_RESULT_ACCEPTED; @@ -4365,7 +4429,7 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm return ret; } -MAV_RESULT GCS_MAVLINK::handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) +MAV_RESULT GCS_MAVLINK::handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { if (hal.util->get_soft_armed()) { // *preflight*, remember? @@ -4426,13 +4490,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_battery_reset(const mavlink_command_long_ return MAV_RESULT_FAILED; } -#if COMPASS_CAL_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_long_t &packet) -{ - return AP::compass().handle_mag_cal_command(packet); -} -#endif - #if AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet) { @@ -4490,7 +4547,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_debug_trap(const mavlink_command_long_t & return MAV_RESULT_UNSUPPORTED; } -MAV_RESULT GCS_MAVLINK::handle_command_set_ekf_source_set(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_set_ekf_source_set(const mavlink_command_int_t &packet) { // source set must be between 1 and 3 uint32_t source_set = uint32_t(packet.param1); @@ -4556,7 +4613,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_sprayer(const mavlink_command_long_t & /* handle MAV_CMD_AIRFRAME_CONFIGURATION for landing gear control */ -MAV_RESULT GCS_MAVLINK::handle_command_airframe_configuration(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_airframe_configuration(const mavlink_command_int_t &packet) { // Param 1: Select which gear, not used in ArduPilot // Param 2: 0 = Deploy, 1 = Retract @@ -4578,7 +4635,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_airframe_configuration(const mavlink_comm #endif #if HAL_INS_ACCELCAL_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_command_int_t &packet) { if (AP::ins().get_acal() == nullptr || !AP::ins().get_acal()->gcs_vehicle_position(packet.param1)) { @@ -4588,18 +4645,16 @@ MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_comman } #endif // HAL_INS_ACCELCAL_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_mount(const mavlink_command_long_t &packet, const mavlink_message_t &msg) -{ #if HAL_MOUNT_ENABLED +MAV_RESULT GCS_MAVLINK::handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg) +{ AP_Mount *mount = AP::mount(); if (mount == nullptr) { return MAV_RESULT_UNSUPPORTED; } - return mount->handle_command_long(packet, msg); -#else - return MAV_RESULT_UNSUPPORTED; -#endif + return mount->handle_command(packet, msg); } +#endif // HAL_MOUNT_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_command_int_t &packet) { @@ -4629,7 +4684,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_comman return MAV_RESULT_UNSUPPORTED; } -MAV_RESULT GCS_MAVLINK::try_command_long_as_command_int(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg) { MAV_FRAME frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; if (command_long_stores_location((MAV_CMD)packet.command)) { @@ -4663,21 +4718,15 @@ MAV_RESULT GCS_MAVLINK::try_command_long_as_command_int(const mavlink_command_lo mavlink_command_int_t command_int; convert_COMMAND_LONG_to_COMMAND_INT(packet, command_int, frame); - return handle_command_int_packet(command_int); + return handle_command_int_packet(command_int, msg); } -MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) { MAV_RESULT result = MAV_RESULT_FAILED; switch (packet.command) { -#if HAL_INS_ACCELCAL_ENABLED - case MAV_CMD_ACCELCAL_VEHICLE_POS: - result = handle_command_accelcal_vehicle_pos(packet); - break; -#endif - case MAV_CMD_DO_SET_MODE: result = handle_command_do_set_mode(packet); break; @@ -4686,9 +4735,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t result = handle_command_do_send_banner(packet); break; +#if AP_FENCE_ENABLED case MAV_CMD_DO_FENCE_ENABLE: result = handle_command_do_fence_enable(packet); break; +#endif #if HAL_HIGH_LATENCY2_ENABLED case MAV_CMD_CONTROL_HIGH_LATENCY: @@ -4696,15 +4747,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t break; #endif // HAL_HIGH_LATENCY2_ENABLED -#if COMPASS_CAL_ENABLED - case MAV_CMD_DO_START_MAG_CAL: - case MAV_CMD_DO_ACCEPT_MAG_CAL: - case MAV_CMD_DO_CANCEL_MAG_CAL: { - result = handle_command_mag_cal(packet); - break; - } -#endif - case MAV_CMD_START_RX_PAIR: result = handle_rc_bind(packet); break; @@ -4716,6 +4758,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t case MAV_CMD_SET_CAMERA_ZOOM: case MAV_CMD_SET_CAMERA_FOCUS: case MAV_CMD_IMAGE_START_CAPTURE: + case MAV_CMD_IMAGE_STOP_CAPTURE: case MAV_CMD_CAMERA_TRACK_POINT: case MAV_CMD_CAMERA_TRACK_RECTANGLE: case MAV_CMD_CAMERA_STOP_TRACKING: @@ -4742,9 +4785,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t } #endif - case MAV_CMD_DO_SET_ROI_SYSID: - return handle_command_do_set_roi_sysid(packet); - case MAV_CMD_DO_JUMP_TAG: case MAV_CMD_DO_SET_MISSION_CURRENT: result = handle_command_do_set_mission_current(packet); @@ -4786,55 +4826,8 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t result = handle_command_debug_trap(packet); break; - case MAV_CMD_SET_EKF_SOURCE_SET: - result = handle_command_set_ekf_source_set(packet); - break; - - case MAV_CMD_PREFLIGHT_STORAGE: - if (is_equal(packet.param1, 2.0f)) { - AP_Param::erase_all(); - send_text(MAV_SEVERITY_WARNING, "All parameters reset, reboot board"); - result= MAV_RESULT_ACCEPTED; - } - break; - - case MAV_CMD_DO_AUX_FUNCTION: - result = handle_command_do_aux_function(packet); - break; - - case MAV_CMD_SET_MESSAGE_INTERVAL: - result = handle_command_set_message_interval(packet); - break; - - case MAV_CMD_GET_MESSAGE_INTERVAL: - result = handle_command_get_message_interval(packet); - break; - - case MAV_CMD_REQUEST_MESSAGE: - result = handle_command_request_message(packet); - break; - -#if AP_SERVORELAYEVENTS_ENABLED - case MAV_CMD_DO_SET_SERVO: - case MAV_CMD_DO_REPEAT_SERVO: - case MAV_CMD_DO_SET_RELAY: - case MAV_CMD_DO_REPEAT_RELAY: - result = handle_servorelay_message(packet); - break; -#endif - - case MAV_CMD_DO_FLIGHTTERMINATION: - result = handle_flight_termination(packet); - break; - -#if AP_LANDINGGEAR_ENABLED - case MAV_CMD_AIRFRAME_CONFIGURATION: - result = handle_command_airframe_configuration(packet); - break; -#endif - default: - result = try_command_long_as_command_int(packet); + result = try_command_long_as_command_int(packet, msg); break; } @@ -4890,6 +4883,21 @@ bool GCS_MAVLINK::command_long_stores_location(const MAV_CMD command) return false; } +// returns a value suitable for COMMAND_INT.x or y based on a value +// coming in from COMMAND_LONG.p5 or p6: +static int32_t convert_COMMAND_LONG_loc_param(float param, bool stores_location) +{ + if (isnan(param)) { + return 0; + } + + if (stores_location) { + return param *1e7; + } + + return param; +} + void GCS_MAVLINK::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame) { out = {}; @@ -4903,13 +4911,9 @@ void GCS_MAVLINK::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long out.param2 = in.param2; out.param3 = in.param3; out.param4 = in.param4; - if (command_long_stores_location((MAV_CMD)in.command)) { - out.x = in.param5 *1e7; - out.y = in.param6 *1e7; - } else { - out.x = in.param5; - out.y = in.param6; - } + const bool stores_location = command_long_stores_location((MAV_CMD)in.command); + out.x = convert_COMMAND_LONG_loc_param(in.param5, stores_location); + out.y = convert_COMMAND_LONG_loc_param(in.param6, stores_location); out.z = in.param7; } @@ -4929,34 +4933,7 @@ void GCS_MAVLINK::handle_command_long(const mavlink_message_t &msg) hal.util->persistent_data.last_mavlink_cmd = packet.command; - MAV_RESULT result; - - // special handling of messages that need the mavlink_message_t - switch (packet.command) { - case MAV_CMD_CAN_FORWARD: - result = handle_can_forward(packet, msg); - break; - - case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: - result = handle_preflight_reboot(packet, msg); - break; - - case MAV_CMD_PREFLIGHT_CALIBRATION: - result = handle_command_preflight_calibration(packet, msg); - break; - - case MAV_CMD_DO_MOUNT_CONFIGURE: - case MAV_CMD_DO_MOUNT_CONTROL: - case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: - case MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE: - // some mount commands require the source sysid and compid - result = handle_command_mount(packet, msg); - break; - - default: - result = handle_command_long_packet(packet); - break; - } + const MAV_RESULT result = handle_command_long_packet(packet, msg); // send ACK or NAK mavlink_msg_command_ack_send(chan, packet.command, result, @@ -5060,42 +5037,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_external_position_estimate(const mavl } #endif // AP_AHRS_POSITION_RESET_ENABLED -#if HAL_MOUNT_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi_none() -{ - AP_Mount *mount = AP::mount(); - if (mount == nullptr) { - return MAV_RESULT_UNSUPPORTED; - } - mount->set_mode_to_default(); - return MAV_RESULT_ACCEPTED; -} -#endif - -MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi_sysid(const uint8_t sysid) -{ -#if HAL_MOUNT_ENABLED - AP_Mount *mount = AP::mount(); - if (mount == nullptr) { - return MAV_RESULT_UNSUPPORTED; - } - mount->set_target_sysid(sysid); - return MAV_RESULT_ACCEPTED; -#else - return MAV_RESULT_UNSUPPORTED; -#endif -} - -MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi_sysid(const mavlink_command_int_t &packet) -{ - return handle_command_do_set_roi_sysid((uint8_t)packet.param1); -} - -MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi_sysid(const mavlink_command_long_t &packet) -{ - return handle_command_do_set_roi_sysid((uint8_t)packet.param1); -} - 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 @@ -5125,7 +5066,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_storage_format(const mavlink_command_int_ !is_equal(packet.param2, 1.0f)) { return MAV_RESULT_UNSUPPORTED; } - GCS_MAVLINK_InProgress *task = GCS_MAVLINK_InProgress::get_task(MAV_CMD_STORAGE_FORMAT, GCS_MAVLINK_InProgress::Type::SD_FORMAT, msg.sysid, msg.compid); + GCS_MAVLINK_InProgress *task = GCS_MAVLINK_InProgress::get_task(MAV_CMD_STORAGE_FORMAT, GCS_MAVLINK_InProgress::Type::SD_FORMAT, msg.sysid, msg.compid, chan); if (task == nullptr) { return MAV_RESULT_TEMPORARILY_REJECTED; } @@ -5137,18 +5078,41 @@ MAV_RESULT GCS_MAVLINK::handle_command_storage_format(const mavlink_command_int_ } #endif -MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch (packet.command) { +#if HAL_INS_ACCELCAL_ENABLED + case MAV_CMD_ACCELCAL_VEHICLE_POS: + return handle_command_accelcal_vehicle_pos(packet); +#endif + +#if AP_LANDINGGEAR_ENABLED + case MAV_CMD_AIRFRAME_CONFIGURATION: + return handle_command_airframe_configuration(packet); +#endif +#if HAL_CANMANAGER_ENABLED + case MAV_CMD_CAN_FORWARD: + return handle_can_forward(packet, msg); +#endif + + case MAV_CMD_DO_AUX_FUNCTION: + return handle_command_do_aux_function(packet); + + case MAV_CMD_DO_FLIGHTTERMINATION: + return handle_flight_termination(packet); + case MAV_CMD_DO_SET_ROI: case MAV_CMD_DO_SET_ROI_LOCATION: return handle_command_do_set_roi(packet); - case MAV_CMD_DO_SET_ROI_SYSID: - return handle_command_do_set_roi_sysid(packet); #if HAL_MOUNT_ENABLED + case MAV_CMD_DO_SET_ROI_SYSID: case MAV_CMD_DO_SET_ROI_NONE: - return handle_command_do_set_roi_none(); -#endif + case MAV_CMD_DO_MOUNT_CONFIGURE: + case MAV_CMD_DO_MOUNT_CONTROL: + case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW: + case MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE: + return handle_command_mount(packet, msg); +#endif // HAL_MOUNT_ENABLED case MAV_CMD_DO_SET_HOME: return handle_command_do_set_home(packet); #if AP_AHRS_POSITION_RESET_ENABLED @@ -5157,8 +5121,37 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p #endif case MAV_CMD_COMPONENT_ARM_DISARM: return handle_command_component_arm_disarm(packet); + +#if COMPASS_CAL_ENABLED case MAV_CMD_FIXED_MAG_CAL_YAW: return handle_command_fixed_mag_cal_yaw(packet); + case MAV_CMD_DO_START_MAG_CAL: + case MAV_CMD_DO_ACCEPT_MAG_CAL: + case MAV_CMD_DO_CANCEL_MAG_CAL: + return handle_command_mag_cal(packet); +#endif + + case MAV_CMD_PREFLIGHT_CALIBRATION: + return handle_command_preflight_calibration(packet, msg); + + case MAV_CMD_PREFLIGHT_STORAGE: + if (is_equal(packet.param1, 2.0f)) { + AP_Param::erase_all(); + send_text(MAV_SEVERITY_WARNING, "All parameters reset, reboot board"); + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_DENIED; + + case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: + return handle_preflight_reboot(packet, msg); + +#if AP_MAVLINK_SERVO_RELAY_ENABLED + case MAV_CMD_DO_SET_SERVO: + case MAV_CMD_DO_REPEAT_SERVO: + case MAV_CMD_DO_SET_RELAY: + case MAV_CMD_DO_REPEAT_RELAY: + return handle_servorelay_message(packet); +#endif #if AP_SCRIPTING_ENABLED case MAV_CMD_SCRIPTING: @@ -5170,7 +5163,28 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p return scripting->handle_command_int_packet(packet); } #endif // AP_SCRIPTING_ENABLED + + case MAV_CMD_SET_EKF_SOURCE_SET: + return handle_command_set_ekf_source_set(packet); + +#if AP_FILESYSTEM_FORMAT_ENABLED + case MAV_CMD_STORAGE_FORMAT: + return handle_command_storage_format(packet, msg); +#endif + + // support for dealing with streamrate for a specific message and + // requesting a message instance: + case MAV_CMD_SET_MESSAGE_INTERVAL: + return handle_command_set_message_interval(packet); + + case MAV_CMD_GET_MESSAGE_INTERVAL: + return handle_command_get_message_interval(packet); + + case MAV_CMD_REQUEST_MESSAGE: + return handle_command_request_message(packet); + } + return MAV_RESULT_UNSUPPORTED; } @@ -5190,19 +5204,7 @@ void GCS_MAVLINK::handle_command_int(const mavlink_message_t &msg) hal.util->persistent_data.last_mavlink_cmd = packet.command; - MAV_RESULT result; - - // special handling of messages that need the mavlink_message_t - switch (packet.command) { -#if AP_FILESYSTEM_FORMAT_ENABLED - case MAV_CMD_STORAGE_FORMAT: - result = handle_command_storage_format(packet, msg); - break; -#endif - default: - result = handle_command_int_packet(packet); - break; - } + const MAV_RESULT result = handle_command_int_packet(packet, msg); // send ACK or NAK mavlink_msg_command_ack_send(chan, packet.command, result, @@ -5551,6 +5553,19 @@ void GCS_MAVLINK::send_uavionix_adsb_out_status() const } #endif +#if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED +bool GCS_MAVLINK::send_relay_status() const +{ + AP_Relay *relay = AP::relay(); + if (relay == nullptr) { + // must only return false if out of space: + return true; + } + + return relay->send_relay_status(*this); +} +#endif // AP_MAVLINK_MSG_RELAY_STATUS_ENABLED + void GCS_MAVLINK::send_autopilot_state_for_gimbal_device() const { // get attitude @@ -5594,7 +5609,8 @@ void GCS_MAVLINK::send_autopilot_state_for_gimbal_device() const 0, // velocity estimated delay in micros rate_ef_targets.z, // feed forward angular velocity z est_status_flags, // estimator status - 0); // landed_state (see MAV_LANDED_STATE) + 0, // landed_state (see MAV_LANDED_STATE) + AP::ahrs().get_yaw_rate_earth()); // [rad/s] Z component of angular velocity in NED (North, East, Down). NaN if unknown } void GCS_MAVLINK::send_received_message_deprecation_warning(const char * message) @@ -5652,6 +5668,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_global_position_int(); break; +#if AP_AHRS_ENABLED case MSG_HOME: CHECK_PAYLOAD_SIZE(HOME_POSITION); send_home_position(); @@ -5661,6 +5678,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) CHECK_PAYLOAD_SIZE(GPS_GLOBAL_ORIGIN); send_gps_global_origin(); break; +#endif // AP_AHRS_ENABLED #if AP_RPM_ENABLED case MSG_RPM: @@ -5707,10 +5725,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_meminfo(); break; +#if AP_FENCE_ENABLED case MSG_FENCE_STATUS: CHECK_PAYLOAD_SIZE(FENCE_STATUS); send_fence_status(); break; +#endif case MSG_RANGEFINDER: CHECK_PAYLOAD_SIZE(RANGEFINDER); @@ -5748,7 +5768,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) if (camera == nullptr) { break; } - CHECK_PAYLOAD_SIZE(CAMERA_INFORMATION); + CHECK_PAYLOAD_SIZE(CAMERA_SETTINGS); camera->send_camera_settings(chan); } break; @@ -6011,6 +6031,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) #endif break; + case MSG_RELAY_STATUS: +#if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED + ret = send_relay_status(); + break; +#endif + default: // try_send_message must always at some stage return true for // a message, or we will attempt to infinitely retry the @@ -6701,3 +6727,5 @@ MAV_RESULT GCS_MAVLINK::handle_control_high_latency(const mavlink_command_long_t return MAV_RESULT_ACCEPTED; } #endif // HAL_HIGH_LATENCY2_ENABLED + +#endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_DeviceOp.cpp b/libraries/GCS_MAVLink/GCS_DeviceOp.cpp index b7418ad78c6676..ddaa450c71b365 100644 --- a/libraries/GCS_MAVLink/GCS_DeviceOp.cpp +++ b/libraries/GCS_MAVLink/GCS_DeviceOp.cpp @@ -15,6 +15,11 @@ /* handle device operations over MAVLink */ + +#include "GCS_config.h" + +#if AP_MAVLINK_MSG_DEVICE_OP_ENABLED + #include #include #include @@ -137,3 +142,5 @@ void GCS_MAVLINK::handle_device_op_write(const mavlink_message_t &msg) packet.request_id, retcode); } + +#endif // AP_MAVLINK_MSG_DEVICE_OP_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_Dummy.cpp b/libraries/GCS_MAVLink/GCS_Dummy.cpp index 135318e3137f23..8b70c6c26c664d 100644 --- a/libraries/GCS_MAVLink/GCS_Dummy.cpp +++ b/libraries/GCS_MAVLink/GCS_Dummy.cpp @@ -1,4 +1,9 @@ +#include "GCS_config.h" + +#if HAL_GCS_ENABLED + #include "GCS_Dummy.h" + #include #define FORCE_VERSION_H_INCLUDE @@ -22,3 +27,5 @@ void GCS_Dummy::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_l ::printf("\n"); #endif } + +#endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_Dummy.h b/libraries/GCS_MAVLink/GCS_Dummy.h index e588bf5c1c356b..2d273d58bdb5b2 100644 --- a/libraries/GCS_MAVLink/GCS_Dummy.h +++ b/libraries/GCS_MAVLink/GCS_Dummy.h @@ -1,3 +1,7 @@ +#include "GCS_config.h" + +#if HAL_GCS_ENABLED + #include "GCS.h" #include @@ -72,3 +76,5 @@ class GCS_Dummy : public GCS MAV_TYPE frame_type() const override { return MAV_TYPE_FIXED_WING; } uint32_t custom_mode() const override { return 3; } // magic number }; + +#endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_FTP.cpp b/libraries/GCS_MAVLink/GCS_FTP.cpp index 1bbced0c6fa60c..71eef91f427123 100644 --- a/libraries/GCS_MAVLink/GCS_FTP.cpp +++ b/libraries/GCS_MAVLink/GCS_FTP.cpp @@ -14,6 +14,11 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ + +#include "GCS_config.h" + +#if HAL_GCS_ENABLED + #include #include "GCS.h" @@ -169,7 +174,7 @@ void GCS_MAVLINK::ftp_worker(void) { } // if it's a rerequest and we still have the last response then send it - if ((request.sysid == reply.sysid) && (request.compid = reply.compid) && + if ((request.sysid == reply.sysid) && (request.compid == reply.compid) && (request.session == reply.session) && (request.seq_number + 1 == reply.seq_number)) { ftp_push_replies(reply); continue; @@ -266,7 +271,7 @@ void GCS_MAVLINK::ftp_worker(void) { const size_t file_size = st.st_size; // actually open the file - ftp.fd = AP::FS().open((char *)request.data, 0); + ftp.fd = AP::FS().open((char *)request.data, O_RDONLY); if (ftp.fd == -1) { ftp_error(reply, FTP_ERROR::FailErrno); break; @@ -696,3 +701,5 @@ void GCS_MAVLINK::ftp_list_dir(struct pending_ftp &request, struct pending_ftp & AP::FS().closedir(dir); } + +#endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_Fence.cpp b/libraries/GCS_MAVLink/GCS_Fence.cpp index c99b99ece4ffae..5d93d7644b3afc 100644 --- a/libraries/GCS_MAVLink/GCS_Fence.cpp +++ b/libraries/GCS_MAVLink/GCS_Fence.cpp @@ -1,3 +1,8 @@ +#include "GCS_config.h" +#include + +#if HAL_GCS_ENABLED && AP_FENCE_ENABLED + #include "GCS.h" #include @@ -6,7 +11,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_fence_enable(const mavlink_command_long_t &packet) { -#if AP_FENCE_ENABLED AC_Fence *fence = AP::fence(); if (fence == nullptr) { return MAV_RESULT_UNSUPPORTED; @@ -30,14 +34,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_fence_enable(const mavlink_command_lon default: return MAV_RESULT_FAILED; } -#else - return MAV_RESULT_UNSUPPORTED; -#endif // AP_FENCE_ENABLED } +#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT void GCS_MAVLINK::handle_fence_message(const mavlink_message_t &msg) { -#if AP_FENCE_ENABLED AC_Fence *fence = AP::fence(); if (fence == nullptr) { return; @@ -54,13 +55,12 @@ void GCS_MAVLINK::handle_fence_message(const mavlink_message_t &msg) #endif break; } -#endif // AP_FENCE_ENABLED } +#endif // AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT // fence_send_mavlink_status - send fence status to ground station void GCS_MAVLINK::send_fence_status() const { -#if AP_FENCE_ENABLED const AC_Fence *fence = AP::fence(); if (fence == nullptr) { return; @@ -102,5 +102,6 @@ void GCS_MAVLINK::send_fence_status() const mavlink_breach_type, fence->get_breach_time(), breach_mitigation); -#endif // AP_FENCE_ENABLED } + +#endif // HAL_GCS_ENABLED && AP_FENCE_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.cpp b/libraries/GCS_MAVLink/GCS_MAVLink.cpp index 41ef15b49780c4..436a26f5f6e1a9 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.cpp +++ b/libraries/GCS_MAVLink/GCS_MAVLink.cpp @@ -19,6 +19,11 @@ This provides some support code and variables for MAVLink enabled sketches */ + +#include "GCS_config.h" + +#if HAL_MAVLINK_BINDINGS_ENABLED + #include "GCS.h" #include "GCS_MAVLink.h" @@ -36,6 +41,10 @@ extern const AP_HAL::HAL& hal; #pragma GCC diagnostic pop #endif +#endif // HAL_MAVLINK_BINDINGS_ENABLED + +#if HAL_GCS_ENABLED + AP_HAL::UARTDriver *mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS]; bool gcs_alternative_active[MAVLINK_COMM_NUM_BUFFERS]; @@ -173,3 +182,5 @@ HAL_Semaphore &comm_chan_lock(mavlink_channel_t chan) { return chan_locks[uint8_t(chan)]; } + +#endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_Param.cpp b/libraries/GCS_MAVLink/GCS_Param.cpp index 45b4ebd0726826..75cc85b63f6c0a 100644 --- a/libraries/GCS_MAVLink/GCS_Param.cpp +++ b/libraries/GCS_MAVLink/GCS_Param.cpp @@ -14,6 +14,11 @@ You should have received a copy of the GNU General Public License along with this program. If not, see . */ + +#include "GCS_config.h" + +#if HAL_GCS_ENABLED + #include #include "GCS.h" @@ -461,3 +466,5 @@ void GCS_MAVLINK::handle_common_param_message(const mavlink_message_t &msg) break; } } + +#endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_Rally.cpp b/libraries/GCS_MAVLink/GCS_Rally.cpp index 8ef69c5f6d4075..c19c9d55b5b2b0 100644 --- a/libraries/GCS_MAVLink/GCS_Rally.cpp +++ b/libraries/GCS_MAVLink/GCS_Rally.cpp @@ -21,7 +21,7 @@ #include #include -#if HAL_RALLY_ENABLED +#if AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED void GCS_MAVLINK::handle_rally_point(const mavlink_message_t &msg) const { @@ -105,4 +105,4 @@ void GCS_MAVLINK::handle_common_rally_message(const mavlink_message_t &msg) break; } } -#endif //#if HAL_RALLY_ENABLED +#endif // AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_ServoRelay.cpp b/libraries/GCS_MAVLink/GCS_ServoRelay.cpp index 65f949a00e730a..c624268763f1ba 100644 --- a/libraries/GCS_MAVLink/GCS_ServoRelay.cpp +++ b/libraries/GCS_MAVLink/GCS_ServoRelay.cpp @@ -2,9 +2,9 @@ #include "AP_ServoRelayEvents/AP_ServoRelayEvents.h" -#if AP_SERVORELAYEVENTS_ENABLED +#if AP_MAVLINK_SERVO_RELAY_ENABLED -MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_int_t &packet) { AP_ServoRelayEvents *handler = AP::servorelayevents(); if (handler == nullptr) { @@ -48,4 +48,4 @@ MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t & return result; } -#endif +#endif // AP_MAVLINK_SERVO_RELAY_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_Signing.cpp b/libraries/GCS_MAVLink/GCS_Signing.cpp index c0dff3b80a8386..394d669a9cb97d 100644 --- a/libraries/GCS_MAVLink/GCS_Signing.cpp +++ b/libraries/GCS_MAVLink/GCS_Signing.cpp @@ -15,6 +15,10 @@ along with this program. If not, see . */ +#include "GCS_config.h" + +#if HAL_GCS_ENABLED + #include "GCS.h" extern const AP_HAL::HAL& hal; @@ -259,3 +263,4 @@ uint8_t GCS_MAVLINK::packet_overhead_chan(mavlink_channel_t chan) return MAVLINK_NUM_NON_PAYLOAD_BYTES + reserved_space; } +#endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/GCS_config.h b/libraries/GCS_MAVLink/GCS_config.h index 42b2a0c97fe0df..889a5c1448423d 100644 --- a/libraries/GCS_MAVLink/GCS_config.h +++ b/libraries/GCS_MAVLink/GCS_config.h @@ -1,16 +1,25 @@ #pragma once #include +#include #ifndef HAL_GCS_ENABLED #define HAL_GCS_ENABLED 1 #endif +#ifndef HAL_MAVLINK_BINDINGS_ENABLED +#define HAL_MAVLINK_BINDINGS_ENABLED HAL_GCS_ENABLED +#endif + // BATTERY2 is slated to be removed: #ifndef AP_MAVLINK_BATTERY2_ENABLED #define AP_MAVLINK_BATTERY2_ENABLED 1 #endif +#ifndef HAL_HIGH_LATENCY2_ENABLED +#define HAL_HIGH_LATENCY2_ENABLED 1 +#endif + // handling of MISSION_SET_CURRENT (the message) is slated to be // removed. It has signficant deficiencies vs MAV_CMD_DO_SET_CURRENT. // The command was added to the spec in January 2019 and to MAVLink in @@ -36,3 +45,36 @@ #define HAL_MAVLINK_INTERVALS_FROM_FILES_ENABLED ((AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED) && BOARD_FLASH_SIZE > 1024) #endif +#ifndef AP_MAVLINK_MSG_RELAY_STATUS_ENABLED +#define AP_MAVLINK_MSG_RELAY_STATUS_ENABLED HAL_GCS_ENABLED && AP_RELAY_ENABLED +#endif + +// allow removal of developer-centric mavlink commands +#ifndef AP_MAVLINK_FAILURE_CREATION_ENABLED +#define AP_MAVLINK_FAILURE_CREATION_ENABLED 1 +#endif + +#ifndef AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED +#define AP_MAVLINK_RALLY_POINT_PROTOCOL_ENABLED HAL_GCS_ENABLED && HAL_RALLY_ENABLED +#endif + +#ifndef AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED +#define AP_MAVLINK_MSG_MOUNT_CONFIGURE_ENABLED HAL_GCS_ENABLED +#endif + +#ifndef AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED +#define AP_MAVLINK_MSG_MOUNT_CONTROL_ENABLED HAL_GCS_ENABLED +#endif + +// this is for both read and write messages: +#ifndef AP_MAVLINK_MSG_DEVICE_OP_ENABLED +#define AP_MAVLINK_MSG_DEVICE_OP_ENABLED HAL_GCS_ENABLED +#endif + +#ifndef AP_MAVLINK_SERVO_RELAY_ENABLED +#define AP_MAVLINK_SERVO_RELAY_ENABLED HAL_GCS_ENABLED && AP_SERVORELAYEVENTS_ENABLED +#endif + +#ifndef AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED +#define AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED HAL_GCS_ENABLED +#endif diff --git a/libraries/GCS_MAVLink/GCS_serial_control.cpp b/libraries/GCS_MAVLink/GCS_serial_control.cpp index 133297dbcbb30d..50322e2e5dac29 100644 --- a/libraries/GCS_MAVLink/GCS_serial_control.cpp +++ b/libraries/GCS_MAVLink/GCS_serial_control.cpp @@ -17,6 +17,9 @@ along with this program. If not, see . */ +#include "GCS_config.h" + +#if AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED #include #include "GCS.h" @@ -199,3 +202,5 @@ void GCS_MAVLINK::handle_serial_control(const mavlink_message_t &msg) goto more_data; } } + +#endif // AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED diff --git a/libraries/GCS_MAVLink/MAVLink_routing.cpp b/libraries/GCS_MAVLink/MAVLink_routing.cpp index 8015102a472fcf..2c05833e617b38 100644 --- a/libraries/GCS_MAVLink/MAVLink_routing.cpp +++ b/libraries/GCS_MAVLink/MAVLink_routing.cpp @@ -16,6 +16,10 @@ /// @file MAVLink_routing.h /// @brief handle routing of MAVLink packets by sysid/componentid +#include "GCS_config.h" + +#if HAL_GCS_ENABLED + #include #include #include @@ -405,3 +409,4 @@ void MAVLink_routing::get_targets(const mavlink_message_t &msg, int16_t &sysid, } } +#endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/MissionItemProtocol.cpp b/libraries/GCS_MAVLink/MissionItemProtocol.cpp index 63ca81965f2313..302f9dd833704d 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol.cpp @@ -1,3 +1,7 @@ +#include "GCS_config.h" + +#if HAL_GCS_ENABLED + #include "MissionItemProtocol.h" #include "GCS.h" @@ -380,3 +384,5 @@ void MissionItemProtocol::update() link->send_message(next_item_ap_message_id()); } } + +#endif // HAL_GCS_ENABLED diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp index 5c308ea5dbf48d..bea8f3dd89dba9 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp @@ -1,11 +1,14 @@ +#include "GCS_config.h" +#include + +#if HAL_GCS_ENABLED && AP_FENCE_ENABLED + #include "MissionItemProtocol_Fence.h" #include #include #include -#if AP_FENCE_ENABLED - /* public function to format mission item as mavlink_mission_item_int_t */ @@ -244,4 +247,4 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::allocate_update_resources() return MAV_MISSION_ACCEPTED; } -#endif // AP_FENCE_ENABLED +#endif // HAL_GCS_ENABLED && AP_FENCE_ENABLED diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp index 2c7a57c0a6b4ec..8ba19415bacbe2 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp @@ -16,14 +16,17 @@ along with this program. If not, see . */ +#include "GCS_config.h" +#include + +#if HAL_GCS_ENABLED && HAL_RALLY_ENABLED + #include "MissionItemProtocol_Rally.h" #include #include #include -#if HAL_RALLY_ENABLED - MAV_MISSION_RESULT MissionItemProtocol_Rally::append_item(const mavlink_mission_item_int_t &cmd) { RallyLocation rallyloc; @@ -139,4 +142,4 @@ void MissionItemProtocol_Rally::truncate(const mavlink_mission_count_t &packet) rally.truncate(packet.count); } -#endif // HAL_RALLY_ENABLED +#endif // HAL_GCS_ENABLED && HAL_RALLY_ENABLED diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp index 6878ae92bb0ad5..311b27e157d85e 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp @@ -16,6 +16,11 @@ along with this program. If not, see . */ +#include "GCS_config.h" +#include + +#if HAL_GCS_ENABLED && AP_MISSION_ENABLED + #include "MissionItemProtocol_Waypoints.h" #include @@ -139,3 +144,5 @@ void MissionItemProtocol_Waypoints::truncate(const mavlink_mission_count_t &pack // new mission arriving, truncate mission to be the same length mission.truncate(packet.count); } + +#endif // HAL_GCS_ENABLED && AP_MISSION_ENABLED diff --git a/libraries/GCS_MAVLink/ap_message.h b/libraries/GCS_MAVLink/ap_message.h index 271a009e58cd4d..6b4fbb0e295878 100644 --- a/libraries/GCS_MAVLink/ap_message.h +++ b/libraries/GCS_MAVLink/ap_message.h @@ -87,5 +87,6 @@ enum ap_message : uint8_t { MSG_ATTITUDE_TARGET, MSG_HYGROMETER, MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, + MSG_RELAY_STATUS, MSG_LAST // MSG_LAST must be the last entry in this enum }; diff --git a/libraries/GCS_MAVLink/examples/routing/routing.cpp b/libraries/GCS_MAVLink/examples/routing/routing.cpp index c89abeb5a56b71..7ebb9103a72715 100644 --- a/libraries/GCS_MAVLink/examples/routing/routing.cpp +++ b/libraries/GCS_MAVLink/examples/routing/routing.cpp @@ -24,6 +24,7 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { }; static MAVLink_routing routing; +static mavlink_status_t status; void setup(void) { @@ -40,7 +41,7 @@ void loop(void) mavlink_message_t msg; mavlink_heartbeat_t heartbeat = {0}; - mavlink_msg_heartbeat_encode(3, 1, &msg, &heartbeat); + mavlink_msg_heartbeat_encode_status(3, 1, &status, &msg, &heartbeat); GCS_MAVLINK *dummy_link = gcs().chan(0); @@ -51,7 +52,7 @@ void loop(void) // incoming non-targetted message mavlink_attitude_t attitude = {0}; - mavlink_msg_attitude_encode(3, 1, &msg, &attitude); + mavlink_msg_attitude_encode_status(3, 1, &status, &msg, &attitude); if (!routing.check_and_forward(*dummy_link, msg)) { hal.console->printf("attitude should be processed locally\n"); err_count++; @@ -61,7 +62,7 @@ void loop(void) mavlink_param_set_t param_set = {0}; param_set.target_system = mavlink_system.sysid+1; param_set.target_component = mavlink_system.compid; - mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set); + mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set); if (routing.check_and_forward(*dummy_link, msg)) { hal.console->printf("param set 1 should not be processed locally\n"); err_count++; @@ -70,7 +71,7 @@ void loop(void) // incoming targeted message for us param_set.target_system = mavlink_system.sysid; param_set.target_component = mavlink_system.compid; - mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set); + mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set); if (!routing.check_and_forward(*dummy_link, msg)) { hal.console->printf("param set 2 should be processed locally\n"); err_count++; @@ -80,7 +81,7 @@ void loop(void) // should be processed locally param_set.target_system = mavlink_system.sysid; param_set.target_component = mavlink_system.compid+1; - mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set); + mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set); if (!routing.check_and_forward(*dummy_link, msg)) { hal.console->printf("param set 3 should be processed locally\n"); err_count++; @@ -89,7 +90,7 @@ void loop(void) // incoming broadcast message should be processed locally param_set.target_system = 0; param_set.target_component = mavlink_system.compid+1; - mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set); + mavlink_msg_param_set_encode_status(3, 1, &status, &msg, ¶m_set); if (!routing.check_and_forward(*dummy_link, msg)) { hal.console->printf("param set 4 should be processed locally\n"); err_count++; diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 417e6d1007e115..c8179e325995d7 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -108,24 +108,22 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @DisplayName: RC input option // @Description: Function assigned to this RC channel // @Values{Copter, Rover, Plane, Blimp}: 0:Do Nothing - // @Values{Copter}: 2:Flip + // @Values{Copter}: 2:FLIP Mode // @Values{Copter}: 3:Simple Mode - // @Values{Copter, Rover}: 4:RTL - // @Values{Plane}: 4:ModeRTL + // @Values{Copter, Rover, Plane}: 4:RTL // @Values{Copter}: 5:Save Trim // @Values{Rover}: 5:Save Trim (4.1 and lower) // @Values{Copter, Rover}: 7:Save WP // @Values{Copter, Rover, Plane}: 9:Camera Trigger - // @Values{Copter}: 10:RangeFinder - // @Values{Copter, Rover, Plane}: 11:Fence + // @Values{Copter}: 10:RangeFinder Enable + // @Values{Copter, Rover, Plane}: 11:Fence Enable // @Values{Copter}: 13:Super Simple Mode // @Values{Copter}: 14:Acro Trainer - // @Values{Copter}: 15:Sprayer - // @Values{Copter, Rover}: 16:Auto - // @Values{Plane}: 16:ModeAuto - // @Values{Copter}: 17:AutoTune - // @Values{Copter, Blimp}: 18:Land - // @Values{Copter, Rover}: 19:Gripper + // @Values{Copter}: 15:Sprayer Enable + // @Values{Copter, Rover, Plane}: 16:AUTO Mode + // @Values{Copter}: 17:AUTOTUNE Mode + // @Values{Copter, Blimp}: 18:LAND Mode + // @Values{Copter, Rover}: 19:Gripper Release // @Values{Copter}: 21:Parachute Enable // @Values{Copter, Plane}: 22:Parachute Release // @Values{Copter}: 23:Parachute 3pos @@ -140,92 +138,88 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Plane}: 30:Lost Plane Sound // @Values{Copter, Rover, Plane}: 31:Motor Emergency Stop // @Values{Copter}: 32:Motor Interlock - // @Values{Copter}: 33:Brake + // @Values{Copter}: 33:BRAKE Mode // @Values{Copter, Rover, Plane}: 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off - // @Values{Copter}: 37:Throw - // @Values{Copter, Plane}: 38:ADSB Avoidance En - // @Values{Copter}: 39:PrecLoiter - // @Values{Copter, Rover}: 40:Proximity Avoidance + // @Values{Copter}: 37:THROW Mode + // @Values{Copter, Plane}: 38:ADSB Avoidance Enable + // @Values{Copter}: 39:PrecLoiter Enable + // @Values{Copter, Rover}: 40:Proximity Avoidance Enable // @Values{Copter, Rover, Plane}: 41:ArmDisarm (4.1 and lower) - // @Values{Copter, Rover}: 42:SmartRTL - // @Values{Copter, Plane}: 43:InvertedFlight + // @Values{Copter, Rover}: 42:SMARTRTL Mode + // @Values{Copter, Plane}: 43:InvertedFlight Enable // @Values{Copter}: 44:Winch Enable, 45:Winch Control // @Values{Copter, Rover, Plane, Blimp}: 46:RC Override Enable // @Values{Copter}: 47:User Function 1, 48:User Function 2, 49:User Function 3 - // @Values{Rover}: 50:LearnCruise - // @Values{Rover}: 51:Manual - // @Values{Plane}: 51:ModeManual - // @Values{Copter, Rover}: 52:Acro - // @Values{Plane}: 52:ModeACRO - // @Values{Rover}: 53:Steering - // @Values{Rover}: 54:Hold - // @Values{Copter, Rover}: 55:Guided - // @Values{Plane}: 55:ModeGuided - // @Values{Copter, Rover}: 56:Loiter - // @Values{Plane}: 56:ModeLoiter - // @Values{Copter, Rover}: 57:Follow + // @Values{Rover}: 50:LearnCruise Speed + // @Values{Rover, Plane}: 51:MANUAL Mode + // @Values{Copter, Rover, Plane}: 52:ACRO Mode + // @Values{Rover}: 53:STEERING Mode + // @Values{Rover}: 54:HOLD Mode + // @Values{Copter, Rover, Plane}: 55:GUIDED Mode + // @Values{Copter, Rover, Plane}: 56:LOITER Mode + // @Values{Copter, Rover}: 57:FOLLOW Mode // @Values{Copter, Rover, Plane}: 58:Clear Waypoints // @Values{Rover}: 59:Simple Mode - // @Values{Copter}: 60:ZigZag + // @Values{Copter}: 60:ZigZag Mode // @Values{Copter}: 61:ZigZag SaveWP // @Values{Copter, Rover, Plane}: 62:Compass Learn // @Values{Rover}: 63:Sailboat Tack // @Values{Plane}: 64:Reverse Throttle // @Values{Copter, Rover, Plane, Blimp}: 65:GPS Disable // @Values{Copter, Rover, Plane}: 66:Relay5 On/Off, 67:Relay6 On/Off - // @Values{Copter}: 68:Stabilize - // @Values{Copter}: 69:PosHold - // @Values{Copter}: 70:AltHold - // @Values{Copter}: 71:FlowHold - // @Values{Copter}: 72:Circle - // @Values{Plane}: 72:ModeCircle - // @Values{Copter}: 73:Drift + // @Values{Copter}: 68:STABILIZE Mode + // @Values{Copter}: 69:POSHOLD Mode + // @Values{Copter}: 70:ALTHOLD Mode + // @Values{Copter}: 71:FLOWHOLD Mode + // @Values{Copter,Plane}: 72:CIRCLE Mode + // @Values{Copter}: 73:DRIFT Mode // @Values{Rover}: 74:Sailboat motoring 3pos // @Values{Copter}: 75:SurfaceTrackingUpDown - // @Values{Copter}: 76:Standby Mode - // @Values{Plane}: 77:ModeTakeoff + // @Values{Copter}: 76:STANDBY Mode + // @Values{Plane}: 77:TAKEOFF Mode // @Values{Copter, Rover, Plane}: 78:RunCam Control // @Values{Copter, Rover, Plane}: 79:RunCam OSD Control // @Values{Copter}: 80:VisOdom Align - // @Values{Rover}: 80:Viso Align + // @Values{Rover}: 80:VisoOdom Align // @Values{Copter, Rover, Plane, Blimp}: 81:Disarm // @Values{Plane}: 82:QAssist 3pos // @Values{Copter}: 83:ZigZag Auto - // @Values{Copter, Plane}: 84:Air Mode + // @Values{Copter, Plane}: 84:AirMode // @Values{Copter, Plane}: 85:Generator - // @Values{Plane}: 86: Non Auto Terrain Follow Disable + // @Values{Plane}: 86:Non Auto Terrain Follow Disable // @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{Plane}: 91:Airspeed Ratio Calibration - // @Values{Plane}: 92:FBWA + // @Values{Plane}: 92:FBWA Mode // @Values{Copter, Rover, Plane}: 94:VTX Power // @Values{Plane}: 95:FBWA taildragger takeoff mode - // @Values{Plane}: 96:trigger re-reading of mode switch + // @Values{Plane}: 96:Trigger re-reading of mode switch // @Values{Rover}: 97:Windvane home heading direction offset - // @Values{Plane}: 98: ModeTraining + // @Values{Plane}: 98:TRAINING Mode // @Values{Copter}: 99:AUTO RTL // @Values{Copter, Rover, Plane, Blimp}: 100:KillIMU1, 101:KillIMU2 // @Values{Copter, Rover, Plane}: 102:Camera Mode Toggle // @Values{Copter, Rover, Plane}: 105:GPS Disable Yaw // @Values{Rover, Plane}: 106:Disable Airspeed Use - // @Values{Plane}: 107: EnableFixedWingAutotune - // @Values{Plane}: 108: ModeQRTL + // @Values{Plane}: 107:Enable FW Autotune + // @Values{Plane}: 108:QRTL Mode + // @Values{Copter}: 109:use Custom Controller // @Values{Copter, Rover, Plane, Blimp}: 110:KillIMU3 - // @Values{Plane}: 150: CRUISE - // @Values{Copter}: 151:Turtle - // @Values{Copter}: 152:simple heading reset + // @Values{Plane}: 150:CRUISE Mode + // @Values{Copter}: 151:TURTLE Mode + // @Values{Copter}: 152:SIMPLE heading reset // @Values{Copter, Rover, Plane}: 153:ArmDisarm (4.2 and higher) // @Values{Blimp}: 153:ArmDisarm // @Values{Copter}: 154:ArmDisarm with AirMode (4.2 and higher) // @Values{Plane}: 154:ArmDisarm with Quadplane AirMode (4.2 and higher) - // @Values{Rover}: 155: set steering trim to current servo and RC - // @Values{Plane}: 155: set roll pitch and yaw trim to current servo and RC + // @Values{Rover}: 155:Set steering trim to current servo and RC + // @Values{Plane}: 155:Set roll pitch and yaw trim to current servo and RC // @Values{Rover}: 156:Torqeedo Clear Err - // @Values{Plane}: 157: Force FS Action to FBWA + // @Values{Plane}: 157:Force FS Action to FBWA // @Values{Copter, Plane}: 158:Optflow Calibration - // @Values{Copter}: 159:Force Flying + // @Values{Copter}: 159:Force IS_Flying // @Values{Plane}: 160:Weathervane Enable // @Values{Copter}: 161:Turbine Start(heli) // @Values{Copter, Rover, Plane}: 162:FFT Tune @@ -233,17 +227,19 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Copter, Rover, Plane, Blimp}: 164:Pause Stream Logging // @Values{Copter, Rover, Plane}: 165:Arm/Emergency Motor Stop // @Values{Copter, Rover, Plane, Blimp}: 166:Camera Record Video, 167:Camera Zoom, 168:Camera Manual Focus, 169:Camera Auto Focus - // @Values{Plane}: 170:Mode QStabilize + // @Values{Plane}: 170:QSTABILIZE Mode + // @Values{Plane}: 176:Quadplane Fwd Throttle Override enable // @Values{Copter, Rover, Plane, Blimp}: 171:Calibrate Compasses // @Values{Copter, Rover, Plane, Blimp}: 172:Battery MPPT Enable // @Values{Plane}: 173:Plane AUTO Mode Landing Abort // @Values{Copter, Rover, Plane, Blimp}: 174:Camera Image Tracking + // @Values{Copter, Rover, Plane, Blimp}: 175:Camera Lens // @Values{Rover}: 201:Roll // @Values{Rover}: 202:Pitch // @Values{Rover}: 207:MainSail // @Values{Rover, Plane}: 208:Flap - // @Values{Plane}: 209: Forward Throttle - // @Values{Plane}: 210: Airbrakes + // @Values{Plane}: 209:VTOL Forward Throttle + // @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, Rover, Plane}: 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 @@ -666,6 +662,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo case AUX_FUNC::MOUNT2_YAW: case AUX_FUNC::LOWEHEISER_STARTER: case AUX_FUNC::MAG_CAL: + case AUX_FUNC::CAMERA_IMAGE_TRACKING: break; // not really aux functions: @@ -702,10 +699,11 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo case AUX_FUNC::CAMERA_ZOOM: case AUX_FUNC::CAMERA_MANUAL_FOCUS: case AUX_FUNC::CAMERA_AUTO_FOCUS: + case AUX_FUNC::CAMERA_LENS: run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT); break; default: - gcs().send_text(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n", + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n", (unsigned)(this->ch_in+1), (unsigned)ch_option); #if CONFIG_HAL_BOARD == HAL_BOARD_SITL AP_BoardConfig::config_error("Failed to init: RC%u_OPTION: %u", @@ -769,6 +767,7 @@ const RC_Channel::LookupTable RC_Channel::lookuptable[] = { { 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"}, }; /* lookup the announcement for switch change */ @@ -832,7 +831,7 @@ bool RC_Channel::read_aux() // announce the change to the GCS: const char *aux_string = string_for_aux_function(_option); if (aux_string != nullptr) { - gcs().send_text(MAV_SEVERITY_INFO, "RC%i: %s %s", ch_in+1, aux_string, string_for_aux_pos(new_position)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "RC%i: %s %s", ch_in+1, aux_string, string_for_aux_pos(new_position)); } #endif @@ -872,19 +871,19 @@ void RC_Channel::do_aux_function_avoid_adsb(const AuxSwitchPos ch_flag) } // try to enable AP_Avoidance if (!adsb->enabled() || !adsb->healthy()) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB not available"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB not available"); return; } avoidance->enable(); AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_ENABLE); - gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Enabled"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Enabled"); return; } // disable AP_Avoidance avoidance->disable(); AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_DISABLE); - gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Disabled"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Disabled"); #endif } @@ -997,6 +996,16 @@ bool RC_Channel::do_aux_function_camera_image_tracking(const AuxSwitchPos ch_fla // Low or Mediums disables tracking. (0.5,0.5) is still passed in but ignored return camera->set_tracking(ch_flag == AuxSwitchPos::HIGH ? TrackingType::TRK_POINT : TrackingType::TRK_NONE, Vector2f{0.5, 0.5}, Vector2f{}); } + +bool RC_Channel::do_aux_function_camera_lens(const AuxSwitchPos ch_flag) +{ + AP_Camera *camera = AP::camera(); + if (camera == nullptr) { + return false; + } + // Low selects lens 0 (default), Mediums selects lens1, High selects lens2 + return camera->set_lens((uint8_t)ch_flag); +} #endif void RC_Channel::do_aux_function_runcam_control(const AuxSwitchPos ch_flag) @@ -1434,7 +1443,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos case AUX_FUNC::OPTFLOW_CAL: { AP_OpticalFlow *optflow = AP::opticalflow(); if (optflow == nullptr) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "OptFlow Cal: failed sensor not enabled"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "OptFlow Cal: failed sensor not enabled"); break; } if (ch_flag == AuxSwitchPos::HIGH) { @@ -1498,6 +1507,9 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos case AUX_FUNC::CAMERA_IMAGE_TRACKING: return do_aux_function_camera_image_tracking(ch_flag); + + case AUX_FUNC::CAMERA_LENS: + return do_aux_function_camera_lens(ch_flag); #endif #if HAL_MOUNT_ENABLED @@ -1545,7 +1557,8 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos } break; } - + +#if COMPASS_CAL_ENABLED case AUX_FUNC::MAG_CAL: { Compass &compass = AP::compass(); switch (ch_flag) { @@ -1563,12 +1576,13 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos const bool autoreboot = false; compass.start_calibration_all(retry, autosave, delay, autoreboot); } else { - gcs().send_text(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration"); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration"); } break; } break; } +#endif case AUX_FUNC::ARM_EMERGENCY_STOP: { switch (ch_flag) { @@ -1635,7 +1649,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos break; default: - gcs().send_text(MAV_SEVERITY_INFO, "Invalid channel option (%u)", (unsigned int)ch_option); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Invalid channel option (%u)", (unsigned int)ch_option); return false; } diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 871b3affdaeb02..46520602a1d038 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -214,7 +214,7 @@ class RC_Channel { DISABLE_AIRSPEED_USE = 106, // equivalent to AIRSPEED_USE 0 FW_AUTOTUNE = 107, // fixed wing auto tune QRTL = 108, // QRTL mode - CUSTOM_CONTROLLER = 109, + CUSTOM_CONTROLLER = 109, // use Custom Controller KILL_IMU3 = 110, // disable third IMU (for IMU failure testing) LOWEHEISER_STARTER = 111, // allows for manually running starter @@ -247,6 +247,8 @@ class RC_Channel { BATTERY_MPPT_ENABLE = 172,// Battery MPPT Power enable. high = ON, mid = auto (controlled by mppt/batt driver), low = OFF. This effects all MPPTs. PLANE_AUTO_LANDING_ABORT = 173, // Abort Glide-slope or VTOL landing during payload place or do_land type mission items CAMERA_IMAGE_TRACKING = 174, // camera image tracking + CAMERA_LENS = 175, // camera lens selection + VFWD_THR_OVERRIDE = 176, // force enabled VTOL forward throttle method // inputs from 200 will eventually used to replace RCMAP @@ -346,6 +348,7 @@ class RC_Channel { bool do_aux_function_camera_manual_focus(const AuxSwitchPos ch_flag); bool do_aux_function_camera_auto_focus(const AuxSwitchPos ch_flag); bool do_aux_function_camera_image_tracking(const AuxSwitchPos ch_flag); + bool do_aux_function_camera_lens(const AuxSwitchPos ch_flag); void do_aux_function_runcam_control(const AuxSwitchPos ch_flag); void do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag); void do_aux_function_fence(const AuxSwitchPos ch_flag); @@ -477,7 +480,7 @@ class RC_Channels { // returns a mask indicating which channels have overrides. Bit 0 // is RC channel 1. Beware this is not a cheap call. - static uint16_t get_override_mask(); + uint16_t get_override_mask() const; class RC_Channel *find_channel_for_option(const RC_Channel::aux_func_t option); bool duplicate_options_exist(); diff --git a/libraries/RC_Channel/RC_Channels.cpp b/libraries/RC_Channel/RC_Channels.cpp index 7a240508816eb5..8578904f5a4603 100644 --- a/libraries/RC_Channel/RC_Channels.cpp +++ b/libraries/RC_Channel/RC_Channels.cpp @@ -114,7 +114,7 @@ void RC_Channels::clear_overrides(void) // copter and plane, RC_Channels needs to control failsafes to resolve this } -uint16_t RC_Channels::get_override_mask(void) +uint16_t RC_Channels::get_override_mask(void) const { uint16_t ret = 0; RC_Channels &_rc = rc(); diff --git a/libraries/RC_Channel/RC_Channels_VarInfo.h b/libraries/RC_Channel/RC_Channels_VarInfo.h index 814a17e17a894e..8302be931d6a52 100644 --- a/libraries/RC_Channel/RC_Channels_VarInfo.h +++ b/libraries/RC_Channel/RC_Channels_VarInfo.h @@ -96,6 +96,7 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = { // @Bitmask: 0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe bit but allow other RC failsafes if setup, 3:FPort Pad, 4:Log RC input bytes, 5:Arming check throttle for 0 input, 6:Skip the arming check for neutral Roll/Pitch/Yaw sticks, 7:Allow Switch reverse, 8:Use passthrough for CRSF telemetry, 9:Suppress CRSF mode/rate message for ELRS systems,10:Enable multiple receiver support, 11:Use Link Quality for RSSI with CRSF, 12:Annotate CRSF flight mode with * on disarm, 13: Use 420kbaud for ELRS protocol AP_GROUPINFO("_OPTIONS", 33, RC_CHANNELS_SUBCLASS, _options, (uint32_t)RC_Channels::Option::ARMING_CHECK_THROTTLE), + // _PROTOCOLS copied to AP_Periph/Parameters.cpp // @Param: _PROTOCOLS // @DisplayName: RC protocols enabled // @Description: Bitmask of enabled RC protocols. Allows narrowing the protocol detection to only specific types of RC receivers which can avoid issues with incorrect detection. Set to 1 to enable all protocols. diff --git a/libraries/SITL/SIM_ADSB.cpp b/libraries/SITL/SIM_ADSB.cpp index 82cfe6173e3c9a..4e2d4be70936a9 100644 --- a/libraries/SITL/SIM_ADSB.cpp +++ b/libraries/SITL/SIM_ADSB.cpp @@ -171,17 +171,10 @@ void ADSB::send_report(const class Aircraft &aircraft) heartbeat.mavlink_version = 0; heartbeat.custom_mode = 0; - /* - save and restore sequence number for chan0, as it is used by - generated encode functions - */ - mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0); - uint8_t saved_seq = chan0_status->current_tx_seq; - chan0_status->current_tx_seq = mavlink.seq; - len = mavlink_msg_heartbeat_encode(vehicle_system_id, - vehicle_component_id, - &msg, &heartbeat); - chan0_status->current_tx_seq = saved_seq; + len = mavlink_msg_heartbeat_encode_status(vehicle_system_id, + vehicle_component_id, + &mavlink.status, + &msg, &heartbeat); write_to_autopilot((char*)&msg.magic, len); @@ -235,14 +228,11 @@ void ADSB::send_report(const class Aircraft &aircraft) adsb_vehicle.squawk = 1200; - mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0); - uint8_t saved_seq = chan0_status->current_tx_seq; - chan0_status->current_tx_seq = mavlink.seq; - len = mavlink_msg_adsb_vehicle_encode(vehicle_system_id, + len = mavlink_msg_adsb_vehicle_encode_status(vehicle_system_id, MAV_COMP_ID_ADSB, + &mavlink.status, &msg, &adsb_vehicle); - chan0_status->current_tx_seq = saved_seq; - + uint8_t msgbuf[len]; len = mavlink_msg_to_send_buffer(msgbuf, &msg); if (len > 0) { @@ -255,17 +245,11 @@ void ADSB::send_report(const class Aircraft &aircraft) if (_sitl->adsb_tx && now - last_tx_report_ms > 1000) { last_tx_report_ms = now; - mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0); - uint8_t saved_seq = chan0_status->current_tx_seq; - uint8_t saved_flags = chan0_status->flags; - chan0_status->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1; - chan0_status->current_tx_seq = mavlink.seq; const mavlink_uavionix_adsb_transceiver_health_report_t health_report = {UAVIONIX_ADSB_RF_HEALTH_OK}; - len = mavlink_msg_uavionix_adsb_transceiver_health_report_encode(vehicle_system_id, - MAV_COMP_ID_ADSB, - &msg, &health_report); - chan0_status->current_tx_seq = saved_seq; - chan0_status->flags = saved_flags; + len = mavlink_msg_uavionix_adsb_transceiver_health_report_encode_status(vehicle_system_id, + MAV_COMP_ID_ADSB, + &mavlink.status, + &msg, &health_report); uint8_t msgbuf[len]; len = mavlink_msg_to_send_buffer(msgbuf, &msg); diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index 7c8082b460f719..1632e5d9e969cd 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -16,8 +16,6 @@ parent class for aircraft simulators */ -#define ALLOW_DOUBLE_MATH_FUNCTIONS - #include "SIM_Aircraft.h" #include @@ -73,9 +71,9 @@ Aircraft::Aircraft(const char *frame_str) : sitl->ahrs_rotation_inv = sitl->ahrs_rotation.transposed(); } - // init rangefinder array to -1 to signify no data + // init rangefinder array to NaN to signify no data for (uint8_t i = 0; i < ARRAY_SIZE(rangefinder_m); i++){ - rangefinder_m[i] = -1.0f; + rangefinder_m[i] = nanf(""); } } @@ -300,9 +298,9 @@ void Aircraft::sync_frame_time(void) uint32_t now_ms = last_wall_time_us / 1000ULL; float dt_wall = (now_ms - last_fps_report_ms) * 0.001; - if (dt_wall > 2.0) { + if (dt_wall > 0.01) { // 0.01s average + achieved_rate_hz = (frame_counter - last_frame_count) / dt_wall; #if 0 - const float achieved_rate_hz = (frame_counter - last_frame_count) / dt_wall; ::printf("Rate: target:%.1f achieved:%.1f speedup %.1f/%.1f\n", rate_hz*target_speedup, achieved_rate_hz, achieved_rate_hz/rate_hz, target_speedup); @@ -473,14 +471,16 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) // @Field: VE: Velocity east // @Field: VD: Velocity down // @Field: As: Airspeed +// @Field: ASpdU: Achieved simulation speedup value Vector3d pos = get_position_relhome(); Vector3f vel = get_velocity_ef(); - AP::logger().WriteStreaming("SIM2", "TimeUS,PN,PE,PD,VN,VE,VD,As", - "Qdddffff", + 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); + airspeed_pitot, + achieved_rate_hz/rate_hz); } } @@ -1084,6 +1084,13 @@ float Aircraft::get_local_updraft(const Vector3d ¤tPos) thermals_x[0] = -180.0; thermals_y[0] = -260.0; break; + case 4: + n_thermals = 1; + thermals_w[0] = 5.0; + thermals_r[0] = 30.0; + thermals_x[0] = 0; + thermals_y[0] = 0; + break; default: AP_BoardConfig::config_error("Bad thermal scenario"); } diff --git a/libraries/SITL/SIM_Aircraft.h b/libraries/SITL/SIM_Aircraft.h index 0a4d5768932cba..04ef0e946a994d 100644 --- a/libraries/SITL/SIM_Aircraft.h +++ b/libraries/SITL/SIM_Aircraft.h @@ -151,6 +151,7 @@ class Aircraft { void set_dronecan_device(DroneCANDevice *_dronecan) { dronecan = _dronecan; } #endif float get_battery_voltage() const { return battery_voltage; } + float get_battery_temperature() const { return battery.get_temperature(); } protected: SIM *sitl; @@ -224,6 +225,7 @@ class Aircraft { uint64_t frame_time_us; uint64_t last_wall_time_us; uint32_t last_fps_report_ms; + float achieved_rate_hz; // achieved speedup rate int64_t sleep_debt_us; uint32_t last_frame_count; uint8_t instance; diff --git a/libraries/SITL/SIM_BalanceBot.cpp b/libraries/SITL/SIM_BalanceBot.cpp index f3b11d0c9036c0..998003e4d60ce7 100644 --- a/libraries/SITL/SIM_BalanceBot.cpp +++ b/libraries/SITL/SIM_BalanceBot.cpp @@ -16,8 +16,6 @@ Balance Bot simulator class */ -#define ALLOW_DOUBLE_MATH_FUNCTIONS - #include "SIM_BalanceBot.h" #include @@ -87,7 +85,7 @@ void BalanceBot::update(const struct sitl_input &input) const float delta_time = frame_time_us * 1.0e-6f; // yaw rate in degrees/s - const float yaw_rate = calc_yaw_rate(steering); + float yaw_rate = calc_yaw_rate(steering); // obtain roll, pitch, yaw from dcm float r, p, y; @@ -95,7 +93,18 @@ void BalanceBot::update(const struct sitl_input &input) float theta = p; //radians float ang_vel = gyro.y; //radians/s - + if (!hal.util->get_soft_armed()) { + // simulated fingers uprighting the vehicle + const float p_gain = 200; + const float pitch_response = -sin(p) * p_gain * delta_time; + ang_vel += pitch_response; + + // simulated fingers rotating the vehicle + const float y_gain = 100000; + const float yaw_response = -sin(wrap_180(y)) * y_gain * delta_time; + yaw_rate += yaw_response; + } + // t1,t2,t3 are terms in the equation to find vehicle frame x acceleration const float t1 = ((2.0f*gear_ratio*k_t*v/(R*r_w)) - (2.0f*gear_ratio*k_t*k_e*velocity_vf_x/(R*r_w*r_w)) - (m_p*l*ang_vel*ang_vel*sin(theta))) * (i_p + m_p*l*l); const float t2 = -m_p*l*cos(theta)*((2.0f*gear_ratio*k_t*k_e*velocity_vf_x/(R*r_w)) - (2.0f*gear_ratio*k_t*v/(R)) + (m_p*GRAVITY_MSS*l*sin(theta))); @@ -134,15 +143,20 @@ void BalanceBot::update(const struct sitl_input &input) // we are on the ground, so our vertical accel is zero accel_earth.z = 0; - if (!hal.util->get_soft_armed()) { + if (!hal.util->get_soft_armed() && + p < radians(2)) { // reset to vertical when not armed for faster testing accel_earth.zero(); velocity_ef.zero(); - dcm.identity(); - gyro.zero(); velocity_vf_x =0; + gyro[1] = 0; // no pitch rate + if (y < radians(2)) { + // no rates at all: + dcm.identity(); + gyro.zero(); + } } - + // work out acceleration as seen by the accelerometers. It sees the kinematic // acceleration (ie. real movement), plus gravity accel_body += dcm.transposed() * (Vector3f(0, 0, -GRAVITY_MSS)); diff --git a/libraries/SITL/SIM_Battery.cpp b/libraries/SITL/SIM_Battery.cpp index ba8a17b263b5fb..d5a7219c36d77d 100644 --- a/libraries/SITL/SIM_Battery.cpp +++ b/libraries/SITL/SIM_Battery.cpp @@ -150,6 +150,15 @@ void Battery::set_current(float current) } voltage_filter.apply(voltage); + + { + const uint64_t temperature_dt = now - temperature.last_update_micros; + temperature.last_update_micros = now; + // 1 amp*1 second == 0.1 degrees of energy. Did those units hurt? + temperature.kelvin += 0.1 * current * temperature_dt * 0.000001; + // decay temperature at some %second towards ambient + temperature.kelvin -= (temperature.kelvin - 273) * 0.10 * temperature_dt * 0.000001; + } } float Battery::get_voltage(void) const diff --git a/libraries/SITL/SIM_Battery.h b/libraries/SITL/SIM_Battery.h index 14c72d08df044d..af592c00ebc837 100644 --- a/libraries/SITL/SIM_Battery.h +++ b/libraries/SITL/SIM_Battery.h @@ -34,6 +34,9 @@ class Battery { void set_current(float current_amps); float get_voltage(void) const; + // return battery temperature in Kelvin: + float get_temperature(void) const { return temperature.kelvin; } + private: float capacity_Ah; float resistance; @@ -42,6 +45,11 @@ class Battery { float remaining_Ah; uint64_t last_us; + struct { + float kelvin = 273; + uint64_t last_update_micros; + } temperature; + // 10Hz filter for battery voltage LowPassFilterFloat voltage_filter{10}; diff --git a/libraries/SITL/SIM_Blimp.cpp b/libraries/SITL/SIM_Blimp.cpp index 73e41d0eae12d3..c5f8835b851b50 100644 --- a/libraries/SITL/SIM_Blimp.cpp +++ b/libraries/SITL/SIM_Blimp.cpp @@ -16,9 +16,8 @@ Blimp simulator class */ -#define ALLOW_DOUBLE_MATH_FUNCTIONS - #include "SIM_Blimp.h" +#include #include @@ -32,17 +31,21 @@ Blimp::Blimp(const char *frame_str) : mass = 0.07; radius = 0.25; moment_of_inertia = {0.004375, 0.004375, 0.004375}; //m*r^2 for hoop... - k_tan = 5.52e-4; //Tangential (thrust) multiplier + cog = {0, 0, 0.1}; //10 cm down from center (i.e. center of buoyancy), for now + k_tan = 0.6e-7; //Tangential (thrust) and normal force multipliers + k_nor = 0;//3.4e-7; drag_constant = 0.05; - drag_gyr_constant = 0.08; + drag_gyr_constant = 0.15; lock_step_scheduled = true; - ::printf("Starting Blimp AirFish model...\n"); + ::printf("Starting Blimp model\n"); } // calculate rotational and linear accelerations -void Blimp::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel) +void Blimp::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; } @@ -50,55 +53,131 @@ void Blimp::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel //all fin setup for (uint8_t i=0; i<4; i++) { fin[i].last_angle = fin[i].angle; - fin[i].angle = filtered_servo_angle(input, i)*radians(75.0f); //for servo range of -75 deg to +75 deg - + if (input.servos[i] == 0) { + fin[i].angle = 0; + fin[1].servo_angle = 0; + } else { + fin[i].angle = filtered_servo_angle(input, i)*radians(45.0f)+radians(13.5); //for servo range of -75 deg to +75 deg + fin[i].servo_angle = filtered_servo_angle(input, i); + } + if (fin[i].angle < fin[i].last_angle) fin[i].dir = 0; //thus 0 = "angle is reducing" else fin[i].dir = 1; - - fin[i].vel = (fin[i].angle - fin[i].last_angle)/delta_time; //rad/s - fin[i].vel = constrain_float(fin[i].vel, radians(-450), radians(450)); - fin[i].T = pow(fin[i].vel,2) * k_tan; - + + fin[i].vel = degrees(fin[i].angle - fin[i].last_angle)/delta_time; //Could also do multi-point derivative filter - DerivativeFilter.cpp + //deg/s (should really be rad/s, but that would require modifying k_tan, k_nor) + //all other angles should be in radians. + fin[i].vel = constrain_float(fin[i].vel, -450, 450); + fin[i].T = sq(fin[i].vel) * k_tan; + fin[i].N = sq(fin[i].vel) * k_nor; + if (fin[i].dir == 0) fin[i].N = -fin[1].N; //normal force flips when fin changes direction + fin[i].Fx = 0; fin[i].Fy = 0; fin[i].Fz = 0; } - //TODO: Add normal force calculations and include roll & pitch oscillation. //Back fin - fin[0].Fx = fin[0].T*cos(fin[0].angle); //causes forward movement - fin[0].Fz = fin[0].T*sin(fin[0].angle); //causes height change + fin[0].Fx = fin[0].T*cos(fin[0].angle);// + fin[0].N*sin(fin[0].angle); //causes forward movement + fin[0].Fz = fin[0].T*sin(fin[0].angle);// - fin[0].N*cos(fin[0].angle); //causes height & wobble in y //Front fin - fin[1].Fx = -fin[1].T*cos(fin[1].angle); //causes backward movement - fin[1].Fz = fin[1].T*sin(fin[1].angle); //causes height change + fin[1].Fx = -fin[1].T*cos(fin[1].angle);// - fin[1].N*sin(fin[1].angle); //causes backward movement + fin[1].Fz = fin[1].T*sin(fin[1].angle);// - fin[1].N*cos(fin[1].angle); //causes height & wobble in y //Right fin - fin[2].Fy = -fin[2].T*cos(fin[2].angle); //causes left movement - fin[2].Fx = fin[2].T*sin(fin[2].angle); //causes yaw + fin[2].Fy = -fin[2].T*cos(fin[2].angle);// - fin[2].N*sin(fin[2].angle); //causes left movement + fin[2].Fx = fin[2].T*sin(fin[2].angle);// - fin[2].N*cos(fin[2].angle); //cause yaw & wobble in z //Left fin - fin[3].Fy = fin[3].T*cos(fin[3].angle); //causes right movement - fin[3].Fx = -fin[3].T*sin(fin[3].angle); //causes yaw + fin[3].Fy = fin[3].T*cos(fin[3].angle);// + fin[3].N*sin(fin[3].angle); //causes right movement + fin[3].Fx = fin[3].T*sin(fin[3].angle);// + fin[3].N*cos(fin[3].angle); //causes yaw & wobble in z - Vector3f force_bf{0,0,0}; + Vector3f F_BF{0,0,0}; for (uint8_t i=0; i<4; i++) { - force_bf.x = force_bf.x + fin[i].Fx; - force_bf.y = force_bf.y + fin[i].Fy; - force_bf.z = force_bf.z + fin[i].Fz; + F_BF.x = F_BF.x + fin[i].Fx; + F_BF.y = F_BF.y + fin[i].Fy; + F_BF.z = F_BF.z + fin[i].Fz; } - //mass in kg, thus accel in m/s/s - body_accel.x = force_bf.x/mass; - body_accel.y = force_bf.y/mass; - body_accel.z = force_bf.z/mass; + body_acc.x = F_BF.x/mass; //mass in kg, thus accel in m/s/s + body_acc.y = F_BF.y/mass; + body_acc.z = F_BF.z/mass; Vector3f rot_T{0,0,0}; - rot_T.z = fin[2].Fx * radius + fin[3].Fx * radius;//in N*m (Torque = force * lever arm) + AP::logger().WriteStreaming("SFT", "TimeUS,f0,f1,f2,f3", + "Qffff", + AP_HAL::micros64(), + fin[0].T, fin[1].T, fin[2].T, fin[3].T); + AP::logger().WriteStreaming("SFN", "TimeUS,n0,n1,n2,n3", + "Qffff", + AP_HAL::micros64(), + fin[0].N, fin[1].N, fin[2].N, fin[3].N); + AP::logger().WriteStreaming("SBA1", "TimeUS,ax,ay,az", + "Qfff", + AP_HAL::micros64(), + body_acc.x, body_acc.y, body_acc.z); + AP::logger().WriteStreaming("SFA1", "TimeUS,f0,f1,f2,f3", + "Qffff", + AP_HAL::micros64(), + fin[0].angle, fin[1].angle, fin[2].angle, fin[3].angle); + AP::logger().WriteStreaming("SFAN", "TimeUS,f0,f1,f2,f3", + "Qffff", + AP_HAL::micros64(), + fin[0].servo_angle, fin[1].servo_angle, fin[2].servo_angle, fin[3].servo_angle); + AP::logger().WriteStreaming("SSAN", "TimeUS,f0,f1,f2,f3", + "QHHHH", + AP_HAL::micros64(), + input.servos[0], input.servos[1], input.servos[2], input.servos[3]); + AP::logger().WriteStreaming("SFV1", "TimeUS,f0,f1,f2,f3", + "Qffff", + AP_HAL::micros64(), + fin[0].vel, fin[1].vel, fin[2].vel, fin[3].vel); + AP::logger().WriteStreaming("SRT1", "TimeUS,rtx,rty,rtz", + "Qfff", + AP_HAL::micros64(), + rot_T.x, rot_T.y, rot_T.z); + +#if 0 //"Wobble" attempt + rot_T.y = fin[0].Fz * radius + fin[1].Fz * radius; + AP::logger().WriteStreaming("SRT2", "TimeUS,rtx,rty,rtz", + "Qfff", + AP_HAL::micros64(), + rot_T.x, rot_T.y, rot_T.z); + // the blimp has pendulum stability due to the centre of gravity being lower than the centre of buoyancy + Vector3f ang; //x,y,z correspond to roll, pitch, yaw. + dcm.to_euler(&ang.x, &ang.y, &ang.z); //rpy in radians + Vector3f ang_ef = dcm * ang; + rot_T.x -= mass*GRAVITY_MSS*sinf(M_PI-ang_ef.x)/cog.z; + rot_T.y -= mass*GRAVITY_MSS*sinf(M_PI-ang_ef.y)/cog.z; + AP::logger().WriteStreaming("SRT3", "TimeUS,rtx,rty,rtz", + "Qfff", + AP_HAL::micros64(), + rot_T.x, rot_T.y, rot_T.z); + AP::logger().WriteStreaming("SAN1", "TimeUS,anx,any,anz", + "Qfff", + AP_HAL::micros64(), + ang.x, ang.y, ang.z); + AP::logger().WriteStreaming("SAN2", "TimeUS,anx,any,anz", + "Qfff", + AP_HAL::micros64(), + ang_ef.x, ang_ef.y, ang_ef.z); + AP::logger().WriteStreaming("SAF1", "TimeUS,afx,afy,afz", + "Qfff", + AP_HAL::micros64(), + sinf(ang.x), sinf(ang.y), sinf(ang.z)); + AP::logger().WriteStreaming("SMGC", "TimeUS,m,g,cz", + "Qfff", + AP_HAL::micros64(), + mass, GRAVITY_MSS, cog.z); +#endif + + rot_T.z = fin[2].Fx * radius - fin[3].Fx * radius;//in N*m (Torque = force * lever arm) //rot accel = torque / moment of inertia - rot_accel.x = 0; - rot_accel.y = 0; + //Torque = moment force. + rot_accel.x = rot_T.x / moment_of_inertia.x; + rot_accel.y = rot_T.y / moment_of_inertia.y; rot_accel.z = rot_T.z / moment_of_inertia.z; } @@ -107,10 +186,10 @@ void Blimp::calculate_forces(const struct sitl_input &input, Vector3f &rot_accel */ void Blimp::update(const struct sitl_input &input) { - delta_time = frame_time_us * 1.0e-6f; + float delta_time = frame_time_us * 1.0e-6f; Vector3f rot_accel = Vector3f(0,0,0); - calculate_forces(input, rot_accel, accel_body); + calculate_forces(input, accel_body, rot_accel); if (hal.scheduler->is_system_initialized()) { float gyr_sq = gyro.length_squared(); @@ -122,12 +201,23 @@ void Blimp::update(const struct sitl_input &input) } } +#if 0 + AP::logger().WriteStreaming("SBLM", "TimeUS,RAx,RAy,RAz", + "Qfff", + AP_HAL::micros64(), + rot_accel.x, rot_accel.y, rot_accel.z); +#endif + // 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)); + // Vector3f ang; //x,y,z correspond to roll, pitch, yaw. + // dcm.to_euler(&ang.x, &ang.y, &ang.z); //rpy in radians + // dcm.from_euler(0.0f, 0.0f, ang.z); // update attitude dcm.rotate(gyro * delta_time); dcm.normalize(); @@ -141,10 +231,10 @@ void Blimp::update(const struct sitl_input &input) accel_body += bf_drag_accel; } - // add lifting force exactly equal to gravity, for neutral buoyancy + // add lifting force exactly equal to gravity, for neutral buoyancy (buoyancy in ef) accel_body += dcm.transposed() * Vector3f(0,0,-GRAVITY_MSS); } - + Vector3f accel_earth = dcm * accel_body; accel_earth += Vector3f(0.0f, 0.0f, GRAVITY_MSS); //add gravity velocity_ef += accel_earth * delta_time; @@ -153,4 +243,6 @@ void Blimp::update(const struct sitl_input &input) update_position(); //updates the position from the Vector3f position time_advance(); update_mag_field_bf(); + rate_hz = sitl->loop_rate_hz; + } diff --git a/libraries/SITL/SIM_Blimp.h b/libraries/SITL/SIM_Blimp.h index 646b4662644fe7..042341c5a1bc52 100644 --- a/libraries/SITL/SIM_Blimp.h +++ b/libraries/SITL/SIM_Blimp.h @@ -19,6 +19,8 @@ #pragma once #include "SIM_Aircraft.h" +// #include "SIM_Motor.h" +// #include "SIM_Frame.h" namespace SITL { @@ -26,9 +28,11 @@ struct Fins { float angle; float last_angle; + float servo_angle; bool dir; - float vel; // velocity, in rad/s + float vel; // velocity, in m/s float T; //Tangential (thrust) force, in Neutons + float N; //Normal force, in Newtons float Fx; //Fx,y,z = Force in bodyframe orientation at servo position, in Newtons float Fy; float Fz; @@ -54,15 +58,17 @@ class Blimp : public Aircraft { float mass; //kilograms float radius; //metres Vector3f moment_of_inertia; + Vector3f cog; //centre of gravity location relative to center of blimp //Airfish-specific variables Fins fin[4]; - float k_tan; //Tangential force multiplier + float k_tan; //Tangential and normal force multipliers + float k_nor; float drag_constant; float drag_gyr_constant; - float delta_time; void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel); + float sq(float a) {return pow(a,2);} }; } diff --git a/libraries/SITL/SIM_DroneCANDevice.cpp b/libraries/SITL/SIM_DroneCANDevice.cpp index 51d1c9ac3d7340..598a53a0dadeb9 100644 --- a/libraries/SITL/SIM_DroneCANDevice.cpp +++ b/libraries/SITL/SIM_DroneCANDevice.cpp @@ -217,9 +217,9 @@ void DroneCANDevice::update_rangefinder() { msg.sensor_id = 0; msg.sensor_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_SENSOR_TYPE_LIDAR; const float dist = AP::sitl()->get_rangefinder(0); - if (is_positive(dist)) { + if (!isnan(dist)) { msg.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_VALID_RANGE; - msg.range = dist; + msg.range = MAX(0, dist); } else { msg.reading_type = UAVCAN_EQUIPMENT_RANGE_SENSOR_MEASUREMENT_READING_TYPE_TOO_FAR; msg.range = 0; diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index a0b41ae95da3a7..a9a22dde116f32 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -556,7 +556,7 @@ void FlightAxis::update(const struct sitl_input &input) if (is_positive(dcm.c.z)) { rangefinder_m[0] = state.m_altitudeAGL_MTR / dcm.c.z; } else { - rangefinder_m[0] = -1; + rangefinder_m[0] = nanf(""); } report_FPS(); diff --git a/libraries/SITL/SIM_Frame.cpp b/libraries/SITL/SIM_Frame.cpp index 81fb426190ed7c..e16ceabb8f9f80 100644 --- a/libraries/SITL/SIM_Frame.cpp +++ b/libraries/SITL/SIM_Frame.cpp @@ -553,13 +553,14 @@ void Frame::calculate_forces(const Aircraft &aircraft, Vector3f vel_air_bf = aircraft.get_dcm().transposed() * aircraft.get_velocity_air_ef(); + const auto *_sitl = AP::sitl(); for (uint8_t i=0; iget_voltage(), use_drag); torque += mtorque; thrust += mthrust; // simulate motor rpm - if (!is_zero(AP::sitl()->vibe_motor)) { + if (!is_zero(_sitl->vibe_motor)) { rpm[motor_offset+i] = motors[i].get_command() * AP::sitl()->vibe_motor * 60.0f; } } diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 2e74a90b125a61..67cc25b31db3c4 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -12,21 +12,13 @@ #include -#define ALLOW_DOUBLE_MATH_FUNCTIONS - +#include #include #include #include +#include #include - -// simulated CAN GPS devices get fed from our SITL estimates: -#if HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED -#include -#include -#include -#include -extern const HAL_SITL& hal_sitl; -#endif +#include // the number of GPS leap seconds - copied from AP_GPS.h #define GPS_LEAPSECONDS_MILLIS 18000ULL @@ -42,47 +34,48 @@ struct GPS_TOW { uint32_t ms; }; -GPS::GPS(uint8_t _instance) : - SerialDevice(8192, 2048), - instance{_instance} +// 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} { +} -#if HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED - const uint8_t num_gps = 2; - // pipe number is SITL instance number (e.g. -I argument to - // sim_vehicle.py) times the max number of GPSs + the gps instance - // number: - const uint8_t num = num_gps * hal_sitl.get_instance() + instance; - if (asprintf(&_gps_fifo, "/tmp/gps_fifo%u", (unsigned)num) == -1) { // FIXME - needs to work with simulated periph-gps - AP_BoardConfig::allocation_error("gps_fifo filepath"); - } - if (mkfifo(_gps_fifo, 0666) < 0) { - if (errno != EEXIST) { - printf("MKFIFO failed with %m\n"); +ssize_t GPS_Backend::write_to_autopilot(const char *p, size_t size) const +{ + return front.write_to_autopilot(p, size); +} + +ssize_t GPS_Backend::read_from_autopilot(char *buffer, size_t size) const +{ + return front.read_from_autopilot(buffer, size); +} + +void GPS_Backend::update(const GPS_Data &d) +{ + if (_sitl == nullptr) { + _sitl = AP::sitl(); + if (_sitl == nullptr) { + return; } } -#endif + + update_read(&d); + update_write(&d); +} + +GPS::GPS(uint8_t _instance) : + SerialDevice(8192, 2048), + instance{_instance} +{ } uint32_t GPS::device_baud() const { - if (_sitl == nullptr) { + if (backend == nullptr) { return 0; } - switch ((Type)_sitl->gps_type[instance].get()) { - case Type::NOVA: - return 19200; - case Type::NONE: - case Type::UBLOX: - case Type::NMEA: - case Type::SBP: - case Type::SBP2: -#if AP_SIM_GPS_FILE_ENABLED - case Type::FILE: -#endif - return 0; // 0 meaning unset - } - return 0; // 0 meaning unset + return backend->device_baud(); } /* @@ -98,15 +91,6 @@ ssize_t GPS::write_to_autopilot(const char *p, size_t size) const return -1; } -#if HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED - // also write to external fifo - int fd = open(_gps_fifo, O_WRONLY | O_NONBLOCK); - if (fd >= 0) { - UNUSED_RESULT(write(fd, p, size)); - close(fd); - } -#endif - const float byteloss = _sitl->gps_byteloss[instance]; // shortcut if we're not doing byteloss: @@ -161,7 +145,7 @@ static void simulation_timeval(struct timeval *tv) /* send a UBLOX GPS message */ -void GPS::send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size) +void GPS_UBlox::send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size) { const uint8_t PREAMBLE1 = 0xb5; const uint8_t PREAMBLE2 = 0x62; @@ -186,7 +170,7 @@ void GPS::send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size) } /* - return GPS time of week in milliseconds + return GPS time of week */ static GPS_TOW gps_time() { @@ -205,7 +189,7 @@ static GPS_TOW gps_time() /* send a new set of GPS UBLOX packets */ -void GPS::update_ubx(const struct gps_data *d) +void GPS_UBlox::update_write(const GPS_Data *d) { struct PACKED ubx_nav_posllh { uint32_t time; // GPS msToW @@ -389,7 +373,7 @@ void GPS::update_ubx(const struct gps_data *d) 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 ? _sitl->gps_numsats[instance] : 3; sol.time = gps_tow.ms; sol.week = gps_tow.week; @@ -415,7 +399,7 @@ void GPS::update_ubx(const struct 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 ? _sitl->gps_numsats[instance] : 3; pvt.lon = d->longitude * 1.0e7; pvt.lat = d->latitude * 1.0e7; pvt.height = d->altitude * 1000.0f; @@ -491,7 +475,7 @@ void GPS::update_ubx(const struct gps_data *d) /* formatted print of NMEA message, with checksum appended */ -void GPS::nmea_printf(const char *fmt, ...) +void GPS_NMEA::nmea_printf(const char *fmt, ...) { va_list ap; @@ -508,7 +492,7 @@ void GPS::nmea_printf(const char *fmt, ...) /* send a new GPS NMEA packet */ -void GPS::update_nmea(const struct gps_data *d) +void GPS_NMEA::update_write(const GPS_Data *d) { struct timeval tv; struct tm *tm; @@ -549,19 +533,16 @@ void GPS::update_nmea(const struct gps_data *d) d->have_lock?_sitl->gps_numsats[instance]:3, 1.2, d->altitude); - const float speed_mps = norm(d->speedN, d->speedE); + + const float speed_mps = d->speed_2d(); const float speed_knots = speed_mps * M_PER_SEC_TO_KNOTS; - - float heading = ToDeg(atan2f(d->speedE, d->speedN)); - if (heading < 0) { - heading += 360.0f; - } + const auto heading_rad = d->heading(); //$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, - heading, + heading_rad, + heading_rad, speed_knots, speed_knots * KNOTS_TO_METERS_PER_SECOND * 3.6); @@ -571,7 +552,7 @@ void GPS::update_nmea(const struct gps_data *d) lat_string, lng_string, speed_knots, - heading, + heading_rad, dstring); if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_HDT) { @@ -588,7 +569,7 @@ void GPS::update_nmea(const struct gps_data *d) d->altitude, wrap_360(d->yaw_deg), d->pitch_deg, - heading, + heading_rad, speed_mps, d->roll_deg, d->have_lock?1:0, // 2=rtkfloat 3=rtkfixed, @@ -601,7 +582,7 @@ void GPS::update_nmea(const struct gps_data *d) } } -void GPS::sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload) +void GPS_SBP_Common::sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload) { if (len != 0 && payload == 0) { return; //SBP_NULL_ERROR; @@ -624,7 +605,7 @@ void GPS::sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, u write_to_autopilot((char*)&crc, 2); } -void GPS::update_sbp(const struct gps_data *d) +void GPS_SBP::update_write(const GPS_Data *d) { struct sbp_heartbeat_t { bool sys_error : 1; @@ -697,7 +678,7 @@ void GPS::update_sbp(const struct gps_data *d) pos.height = d->altitude; pos.h_accuracy = _sitl->gps_accuracy[instance]*1000; pos.v_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.n_sats = _sitl->gps_numsats[instance]; + pos.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; // Send single point position solution pos.flags = 0; @@ -712,7 +693,7 @@ void GPS::update_sbp(const struct gps_data *d) velned.d = 1e3 * d->speedD; velned.h_accuracy = 5e3; velned.v_accuracy = 5e3; - velned.n_sats = _sitl->gps_numsats[instance]; + velned.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; velned.flags = 0; sbp_send_message(SBP_VEL_NED_MSGTYPE, 0x2222, sizeof(velned), (uint8_t*)&velned); @@ -738,7 +719,7 @@ void GPS::update_sbp(const struct gps_data *d) } -void GPS::update_sbp2(const struct gps_data *d) +void GPS_SBP2::update_write(const GPS_Data *d) { struct sbp_heartbeat_t { bool sys_error : 1; @@ -811,7 +792,7 @@ void GPS::update_sbp2(const struct gps_data *d) pos.height = d->altitude; pos.h_accuracy = _sitl->gps_accuracy[instance]*1000; pos.v_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.n_sats = _sitl->gps_numsats[instance]; + pos.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; // Send single point position solution pos.flags = 1; @@ -826,7 +807,7 @@ void GPS::update_sbp2(const struct gps_data *d) velned.d = 1e3 * d->speedD; velned.h_accuracy = 5e3; velned.v_accuracy = 5e3; - velned.n_sats = _sitl->gps_numsats[instance]; + velned.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; velned.flags = 1; sbp_send_message(SBP_VEL_NED_MSGTYPE, 0x2222, sizeof(velned), (uint8_t*)&velned); @@ -850,7 +831,7 @@ void GPS::update_sbp2(const struct gps_data *d) do_every_count++; } -void GPS::update_nova(const struct gps_data *d) +void GPS_NOVA::update_write(const GPS_Data *d) { static struct PACKED nova_header { @@ -971,7 +952,7 @@ void GPS::update_nova(const struct gps_data *d) bestpos.lat = d->latitude; bestpos.lng = d->longitude; bestpos.hgt = d->altitude; - bestpos.svsused = _sitl->gps_numsats[instance]; + bestpos.svsused = d->have_lock ? _sitl->gps_numsats[instance] : 3; bestpos.latsdev=0.2; bestpos.lngsdev=0.2; bestpos.hgtsdev=0.2; @@ -981,7 +962,7 @@ void GPS::update_nova(const struct gps_data *d) nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&bestpos, sizeof(bestpos)); } -void GPS::nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen) +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); @@ -993,7 +974,7 @@ write_to_autopilot((char*)payload, payloadlen); } #define CRC32_POLYNOMIAL 0xEDB88320L -uint32_t GPS::CRC32Value(uint32_t icrc) +uint32_t GPS_NOVA::CRC32Value(uint32_t icrc) { int i; uint32_t crc = icrc; @@ -1007,7 +988,7 @@ uint32_t GPS::CRC32Value(uint32_t icrc) return crc; } -uint32_t GPS::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc) +uint32_t GPS_NOVA::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc) { while ( length-- != 0 ) { @@ -1016,11 +997,382 @@ uint32_t GPS::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc return( crc ); } +void GPS_GSOF::update_write(const GPS_Data *d) +{ + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 + constexpr uint8_t GSOF_POS_TIME_TYPE { 0x01 }; + constexpr uint8_t GSOF_POS_TIME_LEN { 0x0A }; + // TODO magic number until SITL supports GPS bootcount based on GPSN_ENABLE + const uint8_t bootcount = 17; + + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%201 + enum class POS_FLAGS_1 : uint8_t { + NEW_POSITION = 1U << 0, + CLOCK_FIX_CALULATED = 1U << 1, + HORIZ_FROM_THIS_POS = 1U << 2, + HEIGHT_FROM_THIS_POS = 1U << 3, + RESERVED_4 = 1U << 4, + LEAST_SQ_POSITION = 1U << 5, + RESERVED_6 = 1U << 6, + POSITION_L1_PSEUDORANGES = 1U << 7 + }; + const uint8_t pos_flags_1 { + uint8_t(POS_FLAGS_1::NEW_POSITION) | + uint8_t(POS_FLAGS_1::CLOCK_FIX_CALULATED) | + uint8_t(POS_FLAGS_1::HORIZ_FROM_THIS_POS) | + uint8_t(POS_FLAGS_1::HEIGHT_FROM_THIS_POS) | + uint8_t(POS_FLAGS_1::RESERVED_4) | + uint8_t(POS_FLAGS_1::LEAST_SQ_POSITION) | + uint8_t(POS_FLAGS_1::POSITION_L1_PSEUDORANGES) + }; + + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%202 + enum class POS_FLAGS_2 : uint8_t { + DIFFERENTIAL_POS = 1U << 0, + DIFFERENTIAL_POS_PHASE_RTK = 1U << 1, + POSITION_METHOD_FIXED_PHASE = 1U << 2, + OMNISTAR_ACTIVE = 1U << 3, + DETERMINED_WITH_STATIC_CONSTRAINT = 1U << 4, + NETWORK_RTK = 1U << 5, + DITHERED_RTK = 1U << 6, + BEACON_DGNSS = 1U << 7, + }; + + // Simulate a GPS without RTK in SIM since there is no RTK SIM params. + // This means these flags are unset: + // NETWORK_RTK, DITHERED_RTK, BEACON_DGNSS + uint8_t pos_flags_2 {0}; + if(d->have_lock) { + pos_flags_2 |= uint8_t(POS_FLAGS_2::DIFFERENTIAL_POS); + pos_flags_2 |= uint8_t(POS_FLAGS_2::DIFFERENTIAL_POS_PHASE_RTK); + pos_flags_2 |= uint8_t(POS_FLAGS_2::POSITION_METHOD_FIXED_PHASE); + pos_flags_2 |= uint8_t(POS_FLAGS_2::OMNISTAR_ACTIVE); + pos_flags_2 |= uint8_t(POS_FLAGS_2::DETERMINED_WITH_STATIC_CONSTRAINT); + } + + const auto gps_tow = gps_time(); + const struct PACKED gsof_pos_time { + const uint8_t OUTPUT_RECORD_TYPE; + const uint8_t RECORD_LEN; + uint32_t time_week_ms; + uint16_t time_week; + uint8_t num_sats; + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%201 + uint8_t pos_flags_1; + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%202 + uint8_t pos_flags_2; + uint8_t initialized_num; + } pos_time { + GSOF_POS_TIME_TYPE, + GSOF_POS_TIME_LEN, + htobe32(gps_tow.ms), + htobe16(gps_tow.week), + d->have_lock ? _sitl->gps_numsats[instance] : uint8_t(3), + pos_flags_1, + pos_flags_2, + bootcount + }; + static_assert(sizeof(gsof_pos_time) - (sizeof(gsof_pos_time::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_time::RECORD_LEN)) == GSOF_POS_TIME_LEN); + + constexpr uint8_t GSOF_POS_TYPE = 0x02; + constexpr uint8_t GSOF_POS_LEN = 0x18; + + const struct PACKED gsof_pos { + const uint8_t OUTPUT_RECORD_TYPE; + const uint8_t RECORD_LEN; + uint64_t lat; + uint64_t lng; + uint64_t alt; + } pos { + GSOF_POS_TYPE, + GSOF_POS_LEN, + pack_double_into_gsof_packet(d->latitude * DEG_TO_RAD_DOUBLE), + pack_double_into_gsof_packet(d->longitude * DEG_TO_RAD_DOUBLE), + pack_double_into_gsof_packet(static_cast(d->altitude)) + }; + static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN); + + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Velocity.html + constexpr uint8_t GSOF_VEL_TYPE = 0x08; + // use the smaller packet by ignoring local coordinate system + constexpr uint8_t GSOF_VEL_LEN = 0x0D; + + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags + enum class VEL_FIELDS : uint8_t { + VALID = 1U << 0, + CONSECUTIVE_MEASUREMENTS = 1U << 1, + HEADING_VALID = 1U << 2, + RESERVED_3 = 1U << 3, + RESERVED_4 = 1U << 4, + RESERVED_5 = 1U << 5, + RESERVED_6 = 1U << 6, + RESERVED_7 = 1U << 7, + }; + uint8_t vel_flags {0}; + if(d->have_lock) { + vel_flags |= uint8_t(VEL_FIELDS::VALID); + vel_flags |= uint8_t(VEL_FIELDS::CONSECUTIVE_MEASUREMENTS); + vel_flags |= uint8_t(VEL_FIELDS::HEADING_VALID); + } + + const struct PACKED gsof_vel { + const uint8_t OUTPUT_RECORD_TYPE; + const uint8_t RECORD_LEN; + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags + uint8_t flags; + uint32_t horiz_m_p_s; + uint32_t heading_rad; + uint32_t vertical_m_p_s; + } vel { + GSOF_VEL_TYPE, + GSOF_VEL_LEN, + vel_flags, + pack_float_into_gsof_packet(d->speed_2d()), + pack_float_into_gsof_packet(d->heading()), + // Trimble API has ambiguous direction here. + // Intentionally narrow from double. + pack_float_into_gsof_packet(static_cast(d->speedD)) + }; + static_assert(sizeof(gsof_vel) - (sizeof(gsof_vel::OUTPUT_RECORD_TYPE) + sizeof(gsof_vel::RECORD_LEN)) == GSOF_VEL_LEN); + + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_PDOP.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____12 + constexpr uint8_t GSOF_DOP_TYPE = 0x09; + constexpr uint8_t GSOF_DOP_LEN = 0x10; + const struct PACKED gsof_dop { + const uint8_t OUTPUT_RECORD_TYPE { GSOF_DOP_TYPE }; + const uint8_t RECORD_LEN { GSOF_DOP_LEN }; + uint32_t pdop = htobe32(1); + uint32_t hdop = htobe32(1); + uint32_t vdop = htobe32(1); + uint32_t tdop = htobe32(1); + } dop {}; + // Check the payload size calculation in the compiler + constexpr auto dop_size = sizeof(gsof_dop); + static_assert(dop_size == 18); + constexpr auto dop_record_type_size = sizeof(gsof_dop::OUTPUT_RECORD_TYPE); + static_assert(dop_record_type_size == 1); + constexpr auto len_size = sizeof(gsof_dop::RECORD_LEN); + static_assert(len_size == 1); + constexpr auto dop_payload_size = dop_size - (dop_record_type_size + len_size); + static_assert(dop_payload_size == GSOF_DOP_LEN); + + constexpr uint8_t GSOF_POS_SIGMA_TYPE = 0x0C; + constexpr uint8_t GSOF_POS_SIGMA_LEN = 0x26; + const struct PACKED gsof_pos_sigma { + const uint8_t OUTPUT_RECORD_TYPE { GSOF_POS_SIGMA_TYPE }; + const uint8_t RECORD_LEN { GSOF_POS_SIGMA_LEN }; + uint32_t pos_rms = htobe32(0); + uint32_t sigma_e = htobe32(0); + uint32_t sigma_n = htobe32(0); + uint32_t cov_en = htobe32(0); + uint32_t sigma_up = htobe32(0); + uint32_t semi_major_axis = htobe32(0); + uint32_t semi_minor_axis = htobe32(0); + uint32_t orientation = htobe32(0); + uint32_t unit_variance = htobe32(0); + uint16_t n_epocs = htobe32(1); // Always 1 for kinematic. + } pos_sigma {}; + static_assert(sizeof(gsof_pos_sigma) - (sizeof(gsof_pos_sigma::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_sigma::RECORD_LEN)) == GSOF_POS_SIGMA_LEN); + + // TODO add GSOF49 + const uint8_t payload_sz = sizeof(pos_time) + sizeof(pos) + sizeof(vel) + sizeof(dop) + sizeof(pos_sigma); + uint8_t buf[payload_sz] = {}; + uint8_t offset = 0; + memcpy(&buf[offset], &pos_time, sizeof(pos_time)); + offset += sizeof(pos_time); + memcpy(&buf[offset], &pos, sizeof(pos)); + offset += sizeof(pos); + memcpy(&buf[offset], &vel, sizeof(vel)); + offset += sizeof(vel); + memcpy(&buf[offset], &dop, sizeof(dop)); + offset += sizeof(dop); + memcpy(&buf[offset], &pos_sigma, sizeof(pos_sigma)); + offset += sizeof(pos_sigma); + assert(offset == payload_sz); + send_gsof(buf, sizeof(buf)); +} + + +void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) +{ + // All Trimble "Data Collector" packets, including GSOF, are comprised of three fields: + // * A fixed-length packet header (dcol_header) + // * A variable-length data frame (buf) + // * A fixed-length packet trailer (dcol_trailer) + // Reference: // https://receiverhelp.trimble.com/oem-gnss/index.html#API_DataCollectorFormatPacketStructure.html?TocPath=API%2520Documentation%257CData%2520collector%2520format%2520packets%257CData%2520collector%2520format%253A%2520packet%2520structure%257C_____0 + + const uint8_t STX = 0x02; + // status bitfield + // https://receiverhelp.trimble.com/oem-gnss/index.html#API_ReceiverStatusByte.html?TocPath=API%2520Documentation%257CData%2520collector%2520format%2520packets%257CData%2520collector%2520format%253A%2520packet%2520structure%257C_____1 + const uint8_t STATUS = 0xa8; + const uint8_t PACKET_TYPE = 0x40; // Report Packet 40h (GENOUT) + + // Before writing the GSOF data buffer, the GSOF header needs added between the DCOL header and the payload data frame. + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_GSOF.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____2 + + static uint8_t TRANSMISSION_NUMBER = 0; // Functionally, this is a sequence number + // Most messages, even GSOF49, only take one page. For SIM, assume it. + assert(size < 0xFA); // GPS SIM doesn't yet support paging + constexpr uint8_t PAGE_INDEX = 0; + constexpr uint8_t MAX_PAGE_INDEX = 0; + const uint8_t gsof_header[3] = { + TRANSMISSION_NUMBER, + PAGE_INDEX, + MAX_PAGE_INDEX, + + }; + ++TRANSMISSION_NUMBER; + + // A captured GSOF49 packet from BD940 has LENGTH field set to 0x6d = 109 bytes. + // A captured GSOF49 packet from BD940 has total bytes of 115 bytes. + // Thus, the following 5 bytes are not counted. + // 1) STX + // 2) STATUS + // 3) PACKET TYPE + // 4) LENGTH + // 5) CHECKSUM + // 6) ETX + // This aligns with manual's idea of data bytes: + // "Each message begins with a 4-byte header, followed by the bytes of data in each packet. The packet ends with a 2-byte trailer." + // Thus, for this implementation with single-page single-record per DCOL packet, + // the length is simply the sum of data packet size, the gsof_header size. + const uint8_t length = size + sizeof(gsof_header); + const uint8_t dcol_header[4] { + STX, + STATUS, + PACKET_TYPE, + length + }; + + + + // Sum bytes (status + type + length + data bytes) and modulo 256 the summation + // Because it's a uint8, use natural overflow + uint8_t csum = STATUS + PACKET_TYPE + length; + for (size_t i = 0; i < ARRAY_SIZE(gsof_header); i++) { + csum += gsof_header[i]; + } + for (size_t i = 0; i < size; i++) { + csum += buf[i]; + } + + constexpr uint8_t ETX = 0x03; + const uint8_t dcol_trailer[2] = { + csum, + ETX + }; + + write_to_autopilot((char*)dcol_header, sizeof(dcol_header)); + write_to_autopilot((char*)gsof_header, sizeof(gsof_header)); + write_to_autopilot((char*)buf, size); + write_to_autopilot((char*)dcol_trailer, sizeof(dcol_trailer)); + const uint8_t total_size = sizeof(dcol_header) + sizeof(gsof_header) + size + sizeof(dcol_trailer); + // Validate length based on everything but DCOL h + if(dcol_header[3] != total_size - (sizeof(dcol_header) + sizeof(dcol_trailer))) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } +} + +uint64_t GPS_GSOF::pack_double_into_gsof_packet(const double& src) +{ + uint64_t dst; + static_assert(sizeof(src) == sizeof(dst)); + memcpy(&dst, &src, sizeof(dst)); + dst = htobe64(dst); + return dst; +} + +uint32_t GPS_GSOF::pack_float_into_gsof_packet(const float& src) +{ + uint32_t dst; + static_assert(sizeof(src) == sizeof(dst)); + memcpy(&dst, &src, sizeof(dst)); + dst = htobe32(dst); + return dst; +} + +/* + send MSP GPS data + */ +void GPS_MSP::update_write(const GPS_Data *d) +{ + struct PACKED { + // header + struct PACKED { + uint8_t dollar = '$'; + uint8_t magic = 'X'; + uint8_t code = '<'; + uint8_t flags; + uint16_t cmd = 0x1F03; // GPS + uint16_t size = 52; + } hdr; + uint8_t instance; + uint16_t gps_week; + uint32_t ms_tow; + uint8_t fix_type; + uint8_t satellites_in_view; + uint16_t horizontal_pos_accuracy; // [cm] + uint16_t vertical_pos_accuracy; // [cm] + uint16_t horizontal_vel_accuracy; // [cm/s] + uint16_t hdop; + int32_t longitude; + int32_t latitude; + int32_t msl_altitude; // cm + int32_t ned_vel_north; // cm/s + int32_t ned_vel_east; + int32_t ned_vel_down; + uint16_t ground_course; // deg * 100, 0..36000 + uint16_t true_yaw; // deg * 100, values of 0..36000 are valid. 65535 = no data available + uint16_t year; + uint8_t month; + uint8_t day; + uint8_t hour; + uint8_t min; + uint8_t sec; + + // footer CRC + uint8_t crc; + } msp_gps {}; + + auto t = gps_time(); + struct timeval tv; + simulation_timeval(&tv); + auto *tm = gmtime(&tv.tv_sec); + + 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.horizontal_vel_accuracy = 30; + msp_gps.hdop = 100; + msp_gps.longitude = d->longitude * 1.0e7; + msp_gps.latitude = d->latitude * 1.0e7; + msp_gps.msl_altitude = d->altitude * 100; + msp_gps.ned_vel_north = 100 * d->speedN; + msp_gps.ned_vel_east = 100 * d->speedE; + msp_gps.ned_vel_down = 100 * d->speedD; + msp_gps.ground_course = ToDeg(atan2f(d->speedE, d->speedN)) * 100; + msp_gps.true_yaw = wrap_360(d->yaw_deg)*100U; // can send 65535 for no yaw + msp_gps.year = tm->tm_year; + msp_gps.month = tm->tm_mon; + msp_gps.day = tm->tm_mday; + msp_gps.hour = tm->tm_hour; + msp_gps.min = tm->tm_min; + msp_gps.sec = tm->tm_sec; + + // CRC is over packet without first 3 bytes and trailing CRC byte + msp_gps.crc = crc8_dvb_s2_update(0, (uint8_t *)&msp_gps.hdr.flags, sizeof(msp_gps)-4); + + write_to_autopilot((const char *)&msp_gps, sizeof(msp_gps)); +} + /* read file data logged from AP_GPS_DEBUG_LOGGING_ENABLED */ #if AP_SIM_GPS_FILE_ENABLED -void GPS::update_file() +void GPS_FILE::update_write(const GPS_Data *d) { static int fd[2] = {-1,-1}; static uint32_t base_time[2]; @@ -1071,6 +1423,63 @@ void GPS::update_file() } #endif // AP_SIM_GPS_FILE_ENABLED +void GPS::check_backend_allocation() +{ + const Type configured_type = Type(_sitl->gps_type[instance].get()); + if (allocated_type == configured_type) { + return; + } + + // mismatch; delete any already-allocated backend: + if (backend != nullptr) { + delete backend; + backend = nullptr; + } + + // attempt to allocate backend + switch (configured_type) { + case Type::NONE: + // no GPS attached + break; + + case Type::UBLOX: + backend = new GPS_UBlox(*this, instance); + break; + + case Type::NMEA: + backend = new GPS_NMEA(*this, instance); + break; + + case Type::SBP: + backend = new GPS_SBP(*this, instance); + break; + + case Type::SBP2: + backend = new GPS_SBP2(*this, instance); + break; + + case Type::NOVA: + backend = new GPS_NOVA(*this, instance); + break; + + case Type::MSP: + backend = new GPS_MSP(*this, instance); + break; + + case Type::GSOF: + backend = new GPS_GSOF(*this, instance); + break; + +#if AP_SIM_GPS_FILE_ENABLED + case Type::FILE: + backend = new GPS_FILE(*this, instance); + break; +#endif + }; + + allocated_type = configured_type; +} + /* possibly send a new GPS packet */ @@ -1080,6 +1489,11 @@ void GPS::update() return; } + check_backend_allocation(); + if (backend == nullptr) { + return; + } + double latitude =_sitl->state.latitude; double longitude = _sitl->state.longitude; float altitude = _sitl->state.altitude; @@ -1111,7 +1525,7 @@ void GPS::update() const uint8_t idx = instance; // alias to avoid code churn - struct gps_data d; + struct GPS_Data d {}; // simulate delayed lock times bool have_lock = (!_sitl->gps_disable[idx] && now_ms >= _sitl->gps_lock_time[idx]*1000UL); @@ -1121,11 +1535,7 @@ void GPS::update() return; } - // swallow any config bytes - char c; - read_from_autopilot(&c, 1); - - last_update = now_ms; + last_update = now_ms; d.latitude = latitude; d.longitude = longitude; @@ -1136,7 +1546,7 @@ void GPS::update() // 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]; - // Add offet to c.g. velocity to get velocity at antenna and add simulated error + // Add offset to c.g. velocity to get velocity at antenna and add simulated error Vector3f velErrorNED = _sitl->gps_vel_err[idx]; d.speedN = speedN + (velErrorNED.x * rand_float()); d.speedE = speedE + (velErrorNED.y * rand_float()); @@ -1144,12 +1554,12 @@ void GPS::update() d.have_lock = have_lock; if (_sitl->gps_drift_alt[idx] > 0) { - // slow altitude drift + // add slow altitude drift controlled by a slow sine wave d.altitude += _sitl->gps_drift_alt[idx]*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 + // the vehicle c.g. and GPS antenna Vector3f posRelOffsetBF = _sitl->gps_pos_offset[idx]; if (!posRelOffsetBF.is_zero()) { // get a rotation matrix following DCM conventions (body to earth) @@ -1191,45 +1601,20 @@ void GPS::update() d.longitude += glitch_offsets.y; d.altitude += glitch_offsets.z; + backend->update(d); // i.e. reading configuration etc from autopilot +} - // do GPS-type-dependent updates: - switch ((Type)_sitl->gps_type[instance].get()) { - case Type::NONE: - // no GPS attached - break; - - case Type::UBLOX: - update_ubx(&d); - break; - - case Type::NMEA: - update_nmea(&d); - break; - - case Type::SBP: - update_sbp(&d); - break; - - case Type::SBP2: - update_sbp2(&d); - break; - - case Type::NOVA: - update_nova(&d); - break; - -#if AP_SIM_GPS_FILE_ENABLED - case Type::FILE: - update_file(); - break; -#endif - } +void GPS_Backend::update_read(const GPS_Data *d) +{ + // swallow any config bytes + char c; + read_from_autopilot(&c, 1); } /* get delayed data by interpolation */ -GPS::gps_data GPS::interpolate_data(const gps_data &d, uint32_t delay_ms) +GPS_Data GPS::interpolate_data(const GPS_Data &d, uint32_t delay_ms) { const uint8_t N = ARRAY_SIZE(_gps_history); const uint32_t now_ms = d.timestamp_ms; @@ -1244,9 +1629,9 @@ GPS::gps_data GPS::interpolate_data(const gps_data &d, uint32_t delay_ms) if (delay_ms >= dt1 && delay_ms <= dt2) { // we will interpolate this pair of samples. Start with // the older sample - const gps_data &s1 = _gps_history[i+1]; - const gps_data &s2 = _gps_history[i]; - gps_data d2 = s1; + const GPS_Data &s1 = _gps_history[i+1]; + const GPS_Data &s2 = _gps_history[i]; + GPS_Data d2 = s1; const float p = (dt2 - delay_ms) / MAX(1,float(dt2 - dt1)); d2.latitude += p * (s2.latitude - s1.latitude); d2.longitude += p * (s2.longitude - s1.longitude); @@ -1254,7 +1639,7 @@ GPS::gps_data GPS::interpolate_data(const gps_data &d, uint32_t delay_ms) d2.speedN += p * (s2.speedN - s1.speedN); d2.speedE += p * (s2.speedE - s1.speedE); d2.speedD += p * (s2.speedD - s1.speedD); - d2.yaw_deg += p * (s2.yaw_deg - s1.yaw_deg); + d2.yaw_deg += p * wrap_180(s2.yaw_deg - s1.yaw_deg); return d2; } } @@ -1262,4 +1647,16 @@ GPS::gps_data GPS::interpolate_data(const gps_data &d, uint32_t delay_ms) return _gps_history[N-1]; } +float GPS_Data::heading() const +{ + const auto velocity = Vector2d{speedE, speedN}; + return velocity.angle(); +} + +float GPS_Data::speed_2d() const +{ + const auto velocity = Vector2d{speedN, speedE}; + return velocity.length(); +} + #endif // HAL_SIM_GPS_ENABLED diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index d96c40ed226908..746a5832a777a0 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -26,15 +26,11 @@ param set SERIAL5_PROTOCOL 5 #include #ifndef HAL_SIM_GPS_ENABLED -#define HAL_SIM_GPS_ENABLED (AP_SIM_ENABLED && !defined(HAL_BUILD_AP_PERIPH)) +#define HAL_SIM_GPS_ENABLED AP_SIM_ENABLED #endif #if HAL_SIM_GPS_ENABLED -#ifndef HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED -#define HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) && !defined(CYGWIN_BUILD) -#endif - #ifndef AP_SIM_GPS_FILE_ENABLED // really need to use AP_FileSystem for this. #define AP_SIM_GPS_FILE_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX) @@ -44,6 +40,169 @@ param set SERIAL5_PROTOCOL 5 namespace SITL { +// for delay simulation: +struct GPS_Data { + uint32_t timestamp_ms; + double latitude; + double longitude; + float altitude; + double speedN; + double speedE; + double speedD; + double yaw_deg; + double roll_deg; + double pitch_deg; + bool have_lock; + + // Get heading [rad], where 0 = North in WGS-84 coordinate system + float heading() const WARN_IF_UNUSED; + + // Get 2D speed [m/s] in WGS-84 coordinate system + float speed_2d() const WARN_IF_UNUSED; +}; + + +class GPS_Backend { +public: + CLASS_NO_COPY(GPS_Backend); + + GPS_Backend(class GPS &front, uint8_t _instance); + virtual ~GPS_Backend() {} + + void update(const GPS_Data &d); + + // 0 baud means "unset" i.e. baud-rate checks should not apply + virtual uint32_t device_baud() const { return 0; } + + ssize_t write_to_autopilot(const char *p, size_t size) const; + ssize_t read_from_autopilot(char *buffer, size_t size) const; + +protected: + + uint8_t instance; + GPS &front; + + class SIM *_sitl; + +private: + + // read and process config from autopilot (e.g.) + virtual void update_read(const GPS_Data *d); + // writing fix information to autopilot (e.g.) + virtual void update_write(const GPS_Data *d) = 0; + +}; + +class GPS_FILE : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_FILE); + + using GPS_Backend::GPS_Backend; + + void update_write(const GPS_Data *d) override; +}; + +class GPS_GSOF : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_GSOF); + + using GPS_Backend::GPS_Backend; + + void update_write(const GPS_Data *d) override; + +private: + void send_gsof(const uint8_t *buf, const uint16_t size); + + uint64_t pack_double_into_gsof_packet(const double& src) WARN_IF_UNUSED; + uint32_t pack_float_into_gsof_packet(const float& src) WARN_IF_UNUSED; +}; + +class GPS_NMEA : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_NMEA); + + using GPS_Backend::GPS_Backend; + + void update_write(const GPS_Data *d) override; + +private: + + uint8_t nmea_checksum(const char *s); + void nmea_printf(const char *fmt, ...); + void update_nmea(const GPS_Data *d); + +}; + +class GPS_NOVA : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_NOVA); + + using GPS_Backend::GPS_Backend; + + void update_write(const GPS_Data *d) override; + + uint32_t device_baud() const override { return 19200; } + +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); +}; + +class GPS_MSP : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_MSP); + + using GPS_Backend::GPS_Backend; + + void update_write(const GPS_Data *d) override; +}; + +class GPS_SBP_Common : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_SBP_Common); + + using GPS_Backend::GPS_Backend; + +protected: + + void sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload); + +}; + +class GPS_SBP : public GPS_SBP_Common { +public: + CLASS_NO_COPY(GPS_SBP); + + using GPS_SBP_Common::GPS_SBP_Common; + + void update_write(const GPS_Data *d) override; + +}; + +class GPS_SBP2 : public GPS_SBP_Common { +public: + CLASS_NO_COPY(GPS_SBP2); + + using GPS_SBP_Common::GPS_SBP_Common; + + void update_write(const GPS_Data *d) override; + +}; + +class GPS_UBlox : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_UBlox); + + using GPS_Backend::GPS_Backend; + + void update_write(const GPS_Data *d) override; + +private: + void send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size); +}; + class GPS : public SerialDevice { public: @@ -59,6 +218,8 @@ class GPS : public SerialDevice { #endif NOVA = 8, SBP2 = 9, + GSOF = 11, // matches GPS_TYPE + MSP = 19, }; GPS(uint8_t _instance); @@ -78,55 +239,18 @@ class GPS : public SerialDevice { uint32_t last_update; // milliseconds - // for delay simulation: - struct gps_data { - uint32_t timestamp_ms; - double latitude; - double longitude; - float altitude; - double speedN; - double speedE; - double speedD; - double yaw_deg; - double roll_deg; - double pitch_deg; - bool have_lock; - }; // last 20 samples, allowing for up to 20 samples of delay - gps_data _gps_history[20]; - - -#if HAL_SIM_GPS_EXTERNAL_FIFO_ENABLED - // this will be allocated if needed: - char *_gps_fifo; -#endif + GPS_Data _gps_history[20]; bool _gps_has_basestation_position; - gps_data _gps_basestation_data; - - void send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size); - void update_ubx(const struct gps_data *d); - - uint8_t nmea_checksum(const char *s); - void nmea_printf(const char *fmt, ...); - void update_nmea(const struct gps_data *d); - - void sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload); - - void update_sbp(const struct gps_data *d); - void update_sbp2(const struct gps_data *d); - -#if AP_SIM_GPS_FILE_ENABLED - void update_file(); -#endif - - void update_nova(const struct gps_data *d); - 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); + GPS_Data _gps_basestation_data; // get delayed data - gps_data interpolate_data(const gps_data &d, uint32_t delay_ms); + GPS_Data interpolate_data(const GPS_Data &d, uint32_t delay_ms); + + uint8_t allocated_type; + GPS_Backend *backend; + void check_backend_allocation(); }; } diff --git a/libraries/SITL/SIM_Gimbal.cpp b/libraries/SITL/SIM_Gimbal.cpp index 0fc8607f48a90d..a1997dd00fbd19 100644 --- a/libraries/SITL/SIM_Gimbal.cpp +++ b/libraries/SITL/SIM_Gimbal.cpp @@ -236,13 +236,10 @@ void Gimbal::param_send(const struct gimbal_param *p) param_value.param_index = 0; param_value.param_type = MAV_PARAM_TYPE_REAL32; - mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0); - uint8_t saved_seq = chan0_status->current_tx_seq; - chan0_status->current_tx_seq = mavlink.seq; - uint16_t len = mavlink_msg_param_value_encode(vehicle_system_id, - vehicle_component_id, - &msg, ¶m_value); - chan0_status->current_tx_seq = saved_seq; + 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); @@ -366,17 +363,10 @@ void Gimbal::send_report(void) heartbeat.mavlink_version = 0; heartbeat.custom_mode = 0; - /* - save and restore sequence number for chan0, as it is used by - generated encode functions - */ - mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0); - uint8_t saved_seq = chan0_status->current_tx_seq; - chan0_status->current_tx_seq = mavlink.seq; - len = mavlink_msg_heartbeat_encode(vehicle_system_id, - vehicle_component_id, - &msg, &heartbeat); - chan0_status->current_tx_seq = saved_seq; + 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; @@ -403,13 +393,10 @@ void Gimbal::send_report(void) gimbal_report.joint_el = joint_angles.y; gimbal_report.joint_az = joint_angles.z; - mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0); - uint8_t saved_seq = chan0_status->current_tx_seq; - chan0_status->current_tx_seq = mavlink.seq; - len = mavlink_msg_gimbal_report_encode(vehicle_system_id, - vehicle_component_id, - &msg, &gimbal_report); - chan0_status->current_tx_seq = saved_seq; + 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); diff --git a/libraries/SITL/SIM_Gimbal.h b/libraries/SITL/SIM_Gimbal.h index 792f009a032556..53a2212a29f028 100644 --- a/libraries/SITL/SIM_Gimbal.h +++ b/libraries/SITL/SIM_Gimbal.h @@ -21,7 +21,7 @@ #include #ifndef HAL_SIM_GIMBAL_ENABLED -#define HAL_SIM_GIMBAL_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#define HAL_SIM_GIMBAL_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) && !defined(HAL_BUILD_AP_PERIPH) #endif #if HAL_SIM_GIMBAL_ENABLED diff --git a/libraries/SITL/SIM_Helicopter.cpp b/libraries/SITL/SIM_Helicopter.cpp index 6049f9fd6d5a13..81143f3e3da9af 100644 --- a/libraries/SITL/SIM_Helicopter.cpp +++ b/libraries/SITL/SIM_Helicopter.cpp @@ -132,13 +132,13 @@ void Helicopter::update(const struct sitl_input &input) float Lv = -0.006; float Xu = -0.125; float Yv = -0.375; - float Zw = -0.375; + float Zw = -2.25; float tail_rotor = (_servos_delayed[3]-1000) / 1000.0f; // thrust calculated based on 5 deg hover collective for 10lb aircraft at 1500RPM float coll = 50.0f * (swash1+swash2+swash3) / 3.0f - 25.0f; - thrust = thrust_scale * sq(rpm[0] * 0.104667f) * (0.25* (coll - hover_coll) + hover_coll); + thrust = (rpm[0] / nominal_rpm) * thrust_scale * sq(nominal_rpm * 0.104667f) * coll; // determine RPM rpm[0] = update_rpm(rpm[0], rsc, eng_torque, coll, dt); @@ -224,7 +224,7 @@ void Helicopter::update(const struct sitl_input &input) float Lv = -0.006f; float Xu = -0.125f; float Yv = -0.375f; - float Zw = -0.375f; + float Zw = -2.25f; float hub_dist = 1.8f; //meters float swash4 = (_servos_delayed[3]-1000) / 1000.0f; @@ -254,12 +254,12 @@ void Helicopter::update(const struct sitl_input &input) // determine RPM rpm[0] = update_rpm(rpm[0], rsc, eng_torque, (coll_1 + coll_2) * 0.5f, dt); - thrust_1 = 0.5f * thrust_scale * sq(rpm[0] * 0.104667f) * (0.25* (coll_1 - hover_coll) + hover_coll); - thrust_2 = 0.5f * thrust_scale * sq(rpm[0] * 0.104667f) * (0.25* (coll_2 - hover_coll) + hover_coll); + thrust_1 = 0.5f * thrust_scale * sq(rpm[0] * 0.104667f) * coll_1; + thrust_2 = 0.5f * thrust_scale * sq(rpm[0] * 0.104667f) * coll_2; // 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; + 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.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; @@ -279,11 +279,11 @@ void Helicopter::update(const struct sitl_input &input) float Lv = -0.006; float Xu = -0.125; float Yv = -0.375; - float Zw = -0.375; + float Zw = -2.25; // thrust calculated based on 5 deg hover collective for 10lb aircraft at 1500RPM float coll = 50.0f * (swash1+swash2+swash3) / 3.0f - 25.0f; - thrust = thrust_scale * sq(rpm[0] * 0.104667f) * (0.25* (coll - hover_coll) + hover_coll); + thrust = thrust_scale * sq(rpm[0] * 0.104667f) * coll; // determine RPM rpm[0] = update_rpm(rpm[0], rsc, eng_torque, coll, dt); @@ -396,9 +396,9 @@ float Helicopter::update_rpm(float curr_rpm, float throttle, float &engine_torqu rotor_torque = (sq(curr_rpm * 0.104667f) * (torque_mpog + torque_scale * powf(fabsf(collective),1.5f))) / izz; // Calculate autorotation effect on rotor - auto_ss_torque = sq(nominal_rpm * 0.104667f) * torque_mpog / izz; + auto_ss_torque = sq(nominal_rpm * 0.104667f) * (torque_mpog + torque_scale * powf(fabsf(-1.0f),1.5f)) / izz; if (is_positive(velocity_air_bf.z)) { - descent_torque = (velocity_air_bf.z - 7.0) * auto_ss_torque / 7.0f + auto_ss_torque; + descent_torque = (velocity_air_bf.z - 5.3) * auto_ss_torque / 5.3f + auto_ss_torque; } else { descent_torque = 0.0f; } diff --git a/libraries/SITL/SIM_I2C.cpp b/libraries/SITL/SIM_I2C.cpp index 40152ab7fe846b..51450870d74396 100644 --- a/libraries/SITL/SIM_I2C.cpp +++ b/libraries/SITL/SIM_I2C.cpp @@ -28,6 +28,7 @@ #include "SIM_BattMonitor_SMBus_Rotoye.h" #include "SIM_Airspeed_DLVR.h" #include "SIM_Temperature_TSYS01.h" +#include "SIM_Temperature_TSYS03.h" #include "SIM_Temperature_MCP9600.h" #include "SIM_ICM40609.h" #include "SIM_IS31FL3195.h" @@ -63,6 +64,9 @@ static Rotoye rotoye; static SIM_BattMonitor_SMBus_Generic smbus_generic; static Airspeed_DLVR airspeed_dlvr; static TSYS01 tsys01; +#if AP_SIM_TSYS03_ENABLED +static TSYS03 tsys03; +#endif static MCP9600 mcp9600; static ICM40609 icm40609; static MS5525 ms5525; @@ -107,6 +111,9 @@ struct i2c_device_at_address { #endif #if AP_SIM_IS31FL3195_ENABLED { 2, SIM_IS31FL3195_ADDR, is31fl3195 }, // IS31FL3195 RGB LED driver; see page 9 +#endif +#if AP_SIM_TSYS03_ENABLED + { 2, 0x40, tsys03 }, #endif { 2, 0x77, ms5611 }, // MS5611: BARO_PROBE_EXT = 2 }; diff --git a/libraries/SITL/SIM_ICEngine.cpp b/libraries/SITL/SIM_ICEngine.cpp index 113a569aba1b77..7c34c1e4cf428b 100644 --- a/libraries/SITL/SIM_ICEngine.cpp +++ b/libraries/SITL/SIM_ICEngine.cpp @@ -21,6 +21,8 @@ using namespace SITL; +#include + /* update engine state, returning power output from 0 to 1 */ @@ -49,12 +51,12 @@ float ICEngine::update(const struct sitl_input &input) } if (state.value != last_state.value) { - printf("choke:%u starter:%u ignition:%u\n", - (unsigned)state.choke, - (unsigned)state.starter, - (unsigned)state.ignition); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: choke:%u starter:%u ignition:%u", + (unsigned)state.choke, + (unsigned)state.starter, + (unsigned)state.ignition); } - + if (have_ignition && !state.ignition) { // engine is off if (!state.starter) { @@ -75,11 +77,11 @@ float ICEngine::update(const struct sitl_input &input) } if (start_time_us == 0 && state.starter) { if (throttle_demand > 0.2) { - printf("too much throttle to start: %.2f\n", throttle_demand); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: too much throttle to start: %.2f", throttle_demand); } else { // start the motor if (start_time_us == 0) { - printf("Engine started\n"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: Engine started"); } start_time_us = now; } @@ -88,7 +90,7 @@ float ICEngine::update(const struct sitl_input &input) uint32_t starter_time_us = (now - start_time_us); if (starter_time_us > 3000*1000UL && !overheat) { overheat = true; - printf("Starter overheat\n"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: Starter overheat"); } } else { overheat = false; @@ -109,7 +111,7 @@ float ICEngine::update(const struct sitl_input &input) engine_off: if (start_time_us != 0) { - printf("Engine stopped\n"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SIM_ICEngine: Engine stopped"); } last_update_us = AP_HAL::micros64(); start_time_us = 0; diff --git a/libraries/SITL/SIM_MS5611.cpp b/libraries/SITL/SIM_MS5611.cpp index d269272598b46f..a1957df17da61e 100644 --- a/libraries/SITL/SIM_MS5611.cpp +++ b/libraries/SITL/SIM_MS5611.cpp @@ -1,5 +1,3 @@ -#define ALLOW_DOUBLE_MATH_FUNCTIONS - #include "SIM_MS5611.h" #include diff --git a/libraries/SITL/SIM_LORD.cpp b/libraries/SITL/SIM_MicroStrain.cpp similarity index 92% rename from libraries/SITL/SIM_LORD.cpp rename to libraries/SITL/SIM_MicroStrain.cpp index af26dd4763e176..ce126f878bd97a 100644 --- a/libraries/SITL/SIM_LORD.cpp +++ b/libraries/SITL/SIM_MicroStrain.cpp @@ -13,9 +13,9 @@ along with this program. If not, see . */ /* - simulate LORD Microstrain serial device + simulate LORD MicroStrain serial device */ -#include "SIM_LORD.h" +#include "SIM_MicroStrain.h" #include #include #include @@ -24,7 +24,7 @@ using namespace SITL; -LORD::LORD() :SerialDevice::SerialDevice() +MicroStrain5::MicroStrain5() :SerialDevice::SerialDevice() { } @@ -48,7 +48,7 @@ static void simulation_timeval(struct timeval *tv) tv->tv_usec = new_usec % 1000000ULL; } -void LORD::generate_checksum(LORD_Packet& packet) +void MicroStrain5::generate_checksum(MicroStrain_Packet& packet) { uint8_t checksumByte1 = 0; uint8_t checksumByte2 = 0; @@ -67,7 +67,7 @@ void LORD::generate_checksum(LORD_Packet& packet) packet.checksum[1] = checksumByte2; } -void LORD::send_packet(LORD_Packet packet) +void MicroStrain5::send_packet(MicroStrain_Packet packet) { generate_checksum(packet); @@ -77,10 +77,10 @@ void LORD::send_packet(LORD_Packet packet) } -void LORD::send_imu_packet(void) +void MicroStrain5::send_imu_packet(void) { const auto &fdm = _sitl->state; - LORD_Packet packet; + MicroStrain_Packet packet; struct timeval tv; simulation_timeval(&tv); @@ -136,10 +136,10 @@ void LORD::send_imu_packet(void) } -void LORD::send_gnss_packet(void) +void MicroStrain5::send_gnss_packet(void) { const auto &fdm = _sitl->state; - LORD_Packet packet; + MicroStrain_Packet packet; struct timeval tv; simulation_timeval(&tv); @@ -205,10 +205,10 @@ void LORD::send_gnss_packet(void) send_packet(packet); } -void LORD::send_filter_packet(void) +void MicroStrain5::send_filter_packet(void) { const auto &fdm = _sitl->state; - LORD_Packet packet; + MicroStrain_Packet packet; struct timeval tv; simulation_timeval(&tv); @@ -254,9 +254,9 @@ void LORD::send_filter_packet(void) } /* - send LORD data + send MicroStrain data */ -void LORD::update(void) +void MicroStrain5::update(void) { if (!init_sitl_pointer()) { return; @@ -283,7 +283,7 @@ void LORD::update(void) } } -void LORD::put_float(LORD_Packet &packet, float f) +void MicroStrain5::put_float(MicroStrain_Packet &packet, float f) { uint32_t fbits = 0; memcpy(&fbits, &f, sizeof(fbits)); @@ -291,7 +291,7 @@ void LORD::put_float(LORD_Packet &packet, float f) packet.payload_size += sizeof(float); } -void LORD::put_double(LORD_Packet &packet, double d) +void MicroStrain5::put_double(MicroStrain_Packet &packet, double d) { uint64_t dbits = 0; memcpy(&dbits, &d, sizeof(dbits)); @@ -299,7 +299,7 @@ void LORD::put_double(LORD_Packet &packet, double d) packet.payload_size += sizeof(double); } -void LORD::put_int(LORD_Packet &packet, uint16_t t) +void MicroStrain5::put_int(MicroStrain_Packet &packet, uint16_t t) { put_be16_ptr(&packet.payload[packet.payload_size], t); packet.payload_size += sizeof(uint16_t); diff --git a/libraries/SITL/SIM_LORD.h b/libraries/SITL/SIM_MicroStrain.h similarity index 69% rename from libraries/SITL/SIM_LORD.h rename to libraries/SITL/SIM_MicroStrain.h index d32001a50369ae..ebed27a4dae81d 100644 --- a/libraries/SITL/SIM_LORD.h +++ b/libraries/SITL/SIM_MicroStrain.h @@ -6,7 +6,7 @@ // param set EAHRS_TYPE 2 // param set SERIAL4_PROTOCOL 36 // param set SERIAL4_BAUD 115 -// sim_vehicle.py -v ArduPlane -D --console --map -A --uartE=sim:LORD +// sim_vehicle.py -v ArduPlane -D --console --map -A --uartE=sim:MicroStrain #pragma once #include "SIM_Aircraft.h" @@ -17,17 +17,17 @@ namespace SITL { -class LORD : public SerialDevice +class MicroStrain5 : public SerialDevice { public: - LORD(); + MicroStrain5(); // update state void update(void); private: - struct LORD_Packet { + struct MicroStrain_Packet { uint8_t header[4]; uint8_t payload[256]; uint8_t checksum[2]; @@ -39,16 +39,16 @@ class LORD : public SerialDevice uint32_t last_gnss_pkt_us; uint32_t last_filter_pkt_us; - void generate_checksum(LORD_Packet&); + void generate_checksum(MicroStrain_Packet&); - void send_packet(LORD_Packet); + void send_packet(MicroStrain_Packet); void send_imu_packet(); void send_gnss_packet(); void send_filter_packet(); - void put_float(LORD_Packet&, float); - void put_double(LORD_Packet&, double); - void put_int(LORD_Packet&, uint16_t); + void put_float(MicroStrain_Packet&, float); + void put_double(MicroStrain_Packet&, double); + void put_int(MicroStrain_Packet&, uint16_t); uint64_t start_us; }; diff --git a/libraries/SITL/SIM_Morse.cpp b/libraries/SITL/SIM_Morse.cpp index d4303b87ee4fa2..81ba8ce34972f7 100644 --- a/libraries/SITL/SIM_Morse.cpp +++ b/libraries/SITL/SIM_Morse.cpp @@ -656,14 +656,11 @@ void Morse::send_report(void) } mavlink_message_t msg; - mavlink_status_t *chan0_status = mavlink_get_channel_status(MAVLINK_COMM_0); - uint8_t saved_seq = chan0_status->current_tx_seq; - chan0_status->current_tx_seq = mavlink.seq; - uint16_t len = mavlink_msg_obstacle_distance_encode( + uint16_t len = mavlink_msg_obstacle_distance_encode_status( mavlink_system.sysid, 13, + &mavlink.status, &msg, &packet); - chan0_status->current_tx_seq = saved_seq; uint8_t msgbuf[len]; len = mavlink_msg_to_send_buffer(msgbuf, &msg); diff --git a/libraries/SITL/SIM_Plane.cpp b/libraries/SITL/SIM_Plane.cpp index 043c249f65a829..4b32c10406267b 100644 --- a/libraries/SITL/SIM_Plane.cpp +++ b/libraries/SITL/SIM_Plane.cpp @@ -17,8 +17,6 @@ just enough to be able to debug control logic for new frame types */ -#define ALLOW_DOUBLE_MATH_FUNCTIONS - #include "SIM_Plane.h" #include diff --git a/libraries/SITL/SIM_RF_MAVLink.cpp b/libraries/SITL/SIM_RF_MAVLink.cpp index f7384bb63a5297..651eb66d5a7f18 100644 --- a/libraries/SITL/SIM_RF_MAVLink.cpp +++ b/libraries/SITL/SIM_RF_MAVLink.cpp @@ -43,10 +43,11 @@ uint32_t RF_MAVLink::packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t bu .vertical_fov = 0, // 0 is unknown vertical fov .quaternion = {0,0,0,0} // unknown/unused quat }; - const uint16_t len = mavlink_msg_distance_sensor_encode(system_id, - component_id, - &msg, - &distance_sensor); + const uint16_t len = mavlink_msg_distance_sensor_encode_status(system_id, + component_id, + &mav_status, + &msg, + &distance_sensor); if (len > buflen) { AP_HAL::panic("Insufficient buffer passed in"); } diff --git a/libraries/SITL/SIM_RF_MAVLink.h b/libraries/SITL/SIM_RF_MAVLink.h index cc5c284cb4ad26..23b04bdaf0ea00 100644 --- a/libraries/SITL/SIM_RF_MAVLink.h +++ b/libraries/SITL/SIM_RF_MAVLink.h @@ -39,7 +39,7 @@ class RF_MAVLink : public SerialRangeFinder { uint32_t packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t buflen) override; private: - + mavlink_status_t mav_status; }; } diff --git a/libraries/SITL/SIM_Ship.cpp b/libraries/SITL/SIM_Ship.cpp index 9e095f146e6940..f0bf379a133e61 100644 --- a/libraries/SITL/SIM_Ship.cpp +++ b/libraries/SITL/SIM_Ship.cpp @@ -178,9 +178,10 @@ void ShipSim::send_report(void) 0, 0}; mavlink_message_t msg; - mavlink_msg_heartbeat_encode( + mavlink_msg_heartbeat_encode_status( sys_id.get(), component_id, + &mav_status, &msg, &heartbeat); uint8_t buf[300]; @@ -221,9 +222,10 @@ void ShipSim::send_report(void) uint16_t(ship.heading_deg*100) }; mavlink_message_t msg; - mavlink_msg_global_position_int_encode( + mavlink_msg_global_position_int_encode_status( sys_id, component_id, + &mav_status, &msg, &global_position_int); uint8_t buf[300]; @@ -240,9 +242,10 @@ void ShipSim::send_report(void) 0, 0, ship.yaw_rate }; mavlink_message_t msg; - mavlink_msg_attitude_encode( + mavlink_msg_attitude_encode_status( sys_id, component_id, + &mav_status, &msg, &attitude); uint8_t buf[300]; diff --git a/libraries/SITL/SIM_Ship.h b/libraries/SITL/SIM_Ship.h index a9c4449b0a449a..cbb91ccba40554 100644 --- a/libraries/SITL/SIM_Ship.h +++ b/libraries/SITL/SIM_Ship.h @@ -85,6 +85,7 @@ class ShipSim { SocketAPM mav_socket { false }; bool mavlink_connected; + mavlink_status_t mav_status; void send_report(void); }; diff --git a/libraries/SITL/SIM_Temperature_TSYS03.cpp b/libraries/SITL/SIM_Temperature_TSYS03.cpp new file mode 100644 index 00000000000000..d3a036b9cbc127 --- /dev/null +++ b/libraries/SITL/SIM_Temperature_TSYS03.cpp @@ -0,0 +1,199 @@ +#include "SIM_config.h" + +#if AP_SIM_TSYS03_ENABLED + +#include "SIM_Temperature_TSYS03.h" + +#include + +#include + +constexpr const uint8_t SITL::TSYS03::serial[3]; + +int SITL::TSYS03::rdwr_handle_read(I2C::i2c_rdwr_ioctl_data *&data) +{ + // something is expecting a response.... + if (data->msgs[0].flags != 0) { + AP_HAL::panic("Unexpected flags"); + } + if (data->msgs[1].flags != I2C_M_RD) { + AP_HAL::panic("Unexpected flags"); + } + const uint8_t command = data->msgs[0].buf[0]; + switch ((Command)command) { + case Command::RESET: + AP_HAL::panic("Bad RESET"); + case Command::READ_SERIAL: { + if (state != State::RESET) { + // not sure if this is illegal or not? + AP_HAL::panic("reading serial outside RESET state"); + } + if (data->msgs[1].len != 4) { + AP_HAL::panic("Unexpected serial read length"); + } + memcpy(data->msgs[1].buf, serial, 3); + uint8_t crc = 0; + for (uint8_t i=0; i<3; i++) { + crc = crc8_dvb(crc, serial[i], 0x31); + } + data->msgs[1].buf[3] = crc; + break; + } + case Command::CONVERT: + AP_HAL::panic("Bad CONVERT"); + case Command::READ_ADC: { + if (data->msgs[1].len != 3) { + AP_HAL::panic("Unexpected adc read length"); + } + if (state == State::CONVERTING) { + // we've been asked for values while still converting. + // Return zeroes + } else if (state == State::CONVERTED) { + data->msgs[1].buf[1] = adc & 0xff; + data->msgs[1].buf[0] = adc >> 8; + + uint8_t crc = 0; + for (uint8_t i=0; i<2; i++) { + crc = crc8_dvb(crc, data->msgs[1].buf[i], 0x31); + } + data->msgs[1].buf[2] = crc; + + set_state(State::IDLE); + } else { + // AP_HAL::panic("READ_ADC in bad state"); + // this happens at startup + return -1; + } + break; + } + } + return 0; +} + +int SITL::TSYS03::rdwr_handle_write(I2C::i2c_rdwr_ioctl_data *&data) +{ + // incoming write-only command + const auto &msg = data->msgs[0]; + const uint8_t cmd = msg.buf[0]; + + switch ((Command)cmd) { + case Command::RESET: + set_state(State::RESET); + break; + case Command::READ_SERIAL: + AP_HAL::panic("bad serial read"); + case Command::CONVERT: + if (state != State::RESET && + state != State::CONVERTING && + state != State::IDLE && + state != State::READ_SERIAL) { + AP_HAL::panic("Convert outside reset/idle"); + } + set_state(State::CONVERTING); + break; + case Command::READ_ADC: + AP_HAL::panic("bad READ_ADC"); + } + return 0; +} + +int SITL::TSYS03::rdwr(I2C::i2c_rdwr_ioctl_data *&data) +{ + if (data->nmsgs == 2) { + return rdwr_handle_read(data); + } + + if (data->nmsgs == 1) { + return rdwr_handle_write(data); + } + return -1; +} + +// swiped from the driver: +float SITL::TSYS03::temperature_for_adc(const uint16_t _adc) const +{ + const float temperature = -40.0 + _adc * 165 / (powf(2, 16) - 1.0); + + return temperature; +} + +uint16_t SITL::TSYS03::calculate_adc(float temperature) const +{ + // bisect to find the adc24 value: + uint16_t min_adc = 0; + uint16_t max_adc = 0xffff; + uint16_t current_adc = (min_adc+(uint64_t)max_adc)/2; + float current_error = fabsf(temperature_for_adc(current_adc) - temperature); + bool bisect_down = false; + + // temperature_for_adc(9378708); // should be 10.59 + + while (labs(int32_t(max_adc - min_adc)) > 1 && current_error > 0.05) { + uint16_t candidate_adc; + if (bisect_down) { + candidate_adc = (min_adc+(uint64_t)current_adc)/2; + } else { + candidate_adc = (max_adc+(uint64_t)current_adc)/2; + } + const float candidate_temp = temperature_for_adc(candidate_adc); + const float candidate_error = fabsf(candidate_temp - temperature); + if (candidate_error > current_error) { + // worse result + if (bisect_down) { + min_adc = candidate_adc; + bisect_down = false; + } else { + max_adc = candidate_adc; + bisect_down = true; + } + } else { + // better result + if (bisect_down) { + max_adc = current_adc; + bisect_down = false; + } else { + min_adc = current_adc; + bisect_down = true; + } + current_adc = candidate_adc; + current_error = candidate_error; + } + } + return current_adc; +} + +void SITL::TSYS03::update(const class Aircraft &aircraft) +{ + switch (state) { + case State::UNKNOWN: + break; + case State::RESET: + if (time_in_state_ms() > 2) { + set_state(State::IDLE); + } + break; + case State::READ_SERIAL: + break; + case State::IDLE: + break; + case State::CONVERTING: + if (time_in_state_ms() > 5) { + const float temperature = get_sim_temperature(aircraft); + if (!is_equal(last_temperature, temperature)) { + last_temperature = temperature; + adc = calculate_adc(KELVIN_TO_C(temperature)); + } + set_state(State::CONVERTED); + } + break; + case State::CONVERTED: + break; + } +} + +float SITL::TSYS03::get_sim_temperature(const Aircraft &aircraft) const +{ + return aircraft.get_battery_temperature(); +} + +#endif // AP_SIM_TSYS03_ENABLED diff --git a/libraries/SITL/SIM_Temperature_TSYS03.h b/libraries/SITL/SIM_Temperature_TSYS03.h new file mode 100644 index 00000000000000..02d4c848e8d199 --- /dev/null +++ b/libraries/SITL/SIM_Temperature_TSYS03.h @@ -0,0 +1,81 @@ +#include "SIM_config.h" + +#if AP_SIM_TSYS03_ENABLED + +#include "SIM_I2CDevice.h" + +/* + Simulator for the TSYS03 temperature sensor + +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -f Callisto -A --speedup=1 +param set TEMP1_TYPE 4 +param fetch +param set TEMP1_BUS 2 +param set TEMP1_SRC 3 +param set TEMP1_SRC_ID 1 +graph BATTERY_STATUS.temperature*0.01 +reboot + +arm throttle +rc 3 2000 + +fly around, check BAT[0].temperature + +*/ + +namespace SITL { + +class TSYS03 : public I2CDevice +{ +public: + + void update(const class Aircraft &aircraft) override; + + int rdwr(I2C::i2c_rdwr_ioctl_data *&data) override; + +private: + + int rdwr_handle_read(I2C::i2c_rdwr_ioctl_data *&data); + int rdwr_handle_write(I2C::i2c_rdwr_ioctl_data *&data); + + // should be a call on aircraft: + float last_temperature = -1000.0f; + + enum class State { + UNKNOWN = 22, + RESET = 23, + READ_SERIAL = 24, + IDLE = 25, + CONVERTING = 26, + CONVERTED = 27, + } state = State::RESET; + + uint32_t state_start_time_ms; + + void set_state(State new_state) { + state = new_state; + state_start_time_ms = AP_HAL::millis(); + } + uint32_t time_in_state_ms() const { + return AP_HAL::millis() - state_start_time_ms; + } + + float get_sim_temperature(const class Aircraft &aircraft) const; + + float temperature_for_adc(uint16_t adc) const; + uint16_t calculate_adc(float temperature) const; + uint32_t adc; + + enum class Command { + RESET = 0x1E, + READ_SERIAL = 0x0A, + CONVERT = 0x46, + READ_ADC = 0x00, + }; + + static constexpr uint8_t serial[] { 0xAB, 0xCD, 0xEF }; +}; + +} // namespace SITL + +#endif // AP_SIM_TSYS03_ENABLED diff --git a/libraries/SITL/SIM_Vicon.cpp b/libraries/SITL/SIM_Vicon.cpp index dc7bb50422e065..b54374baf8752b 100644 --- a/libraries/SITL/SIM_Vicon.cpp +++ b/libraries/SITL/SIM_Vicon.cpp @@ -164,9 +164,10 @@ void Vicon::update_vicon_position_estimate(const Location &loc, pitch, yaw }; - mavlink_msg_vision_position_estimate_encode( + mavlink_msg_vision_position_estimate_encode_status( system_id, component_id, + &mav_status, &msg_buf[msg_buf_index].obs_msg, &vision_position_estimate ); @@ -184,9 +185,10 @@ void Vicon::update_vicon_position_estimate(const Location &loc, pitch, yaw }; - mavlink_msg_vicon_position_estimate_encode( + mavlink_msg_vicon_position_estimate_encode_status( system_id, component_id, + &mav_status, &msg_buf[msg_buf_index].obs_msg, &vicon_position_estimate); msg_buf[msg_buf_index].time_send_us = time_send_us; @@ -200,9 +202,10 @@ void Vicon::update_vicon_position_estimate(const Location &loc, vel_corrected.y, vel_corrected.z }; - mavlink_msg_vision_speed_estimate_encode( + mavlink_msg_vision_speed_estimate_encode_status( system_id, component_id, + &mav_status, &msg_buf[msg_buf_index].obs_msg, &vicon_speed_estimate ); @@ -232,9 +235,10 @@ void Vicon::update_vicon_position_estimate(const Location &loc, 0, MAV_ESTIMATOR_TYPE_VIO }; - mavlink_msg_odometry_encode( + mavlink_msg_odometry_encode_status( system_id, component_id, + &mav_status, &msg_buf[msg_buf_index].obs_msg, &odometry); msg_buf[msg_buf_index].time_send_us = time_send_us; @@ -270,9 +274,10 @@ void Vicon::update_vicon_position_estimate(const Location &loc, }, {pos_delta.x, pos_delta.y, pos_delta.z} }; - mavlink_msg_vision_position_delta_encode( + mavlink_msg_vision_position_delta_encode_status( system_id, component_id, + &mav_status, &msg_buf[msg_buf_index].obs_msg, &vision_position_delta); msg_buf[msg_buf_index].time_send_us = time_send_us; diff --git a/libraries/SITL/SIM_Vicon.h b/libraries/SITL/SIM_Vicon.h index e7eb27ca425a53..5cb9aadce4d3ad 100644 --- a/libraries/SITL/SIM_Vicon.h +++ b/libraries/SITL/SIM_Vicon.h @@ -77,6 +77,8 @@ class Vicon : public SerialDevice { // position delta message Quaternion _attitude_prev; // Rotation to previous MAV_FRAME_BODY_FRD from MAV_FRAME_LOCAL_NED Vector3d _position_prev; // previous position from origin (m) MAV_FRAME_LOCAL_NED + + mavlink_status_t mav_status; }; } diff --git a/libraries/SITL/SIM_config.h b/libraries/SITL/SIM_config.h index 5fd50080254b0f..92521f0b7f83c7 100644 --- a/libraries/SITL/SIM_config.h +++ b/libraries/SITL/SIM_config.h @@ -25,3 +25,7 @@ #ifndef AP_SIM_SHIP_ENABLED #define AP_SIM_SHIP_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 diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 1b80a07c867b05..3d3add90023858 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -17,8 +17,6 @@ SITL.cpp - software in the loop state */ -#define ALLOW_DOUBLE_MATH_FUNCTIONS - #include "SITL.h" #if AP_SIM_ENABLED @@ -49,6 +47,15 @@ extern const AP_HAL::HAL& hal; #endif #endif +#if (CONFIG_HAL_BOARD != HAL_BOARD_SITL) +// For on-hardware, set allowed relay channels to zero. +// Requires user to change the param to allow hadware access. +#define SIM_DEFAULT_ENABLED_RELAY_CHANNELS 0 +#else +// For SITL, set allowed relay channels to the full mask. +#define SIM_DEFAULT_ENABLED_RELAY_CHANNELS UINT16_MAX +#endif + namespace SITL { SIM *SIM::_singleton = nullptr; @@ -79,6 +86,11 @@ const AP_Param::GroupInfo SIM::var_info[] = { AP_GROUPINFO("WIND_TURB", 11, SIM, wind_turbulance, 0), AP_GROUPINFO("SERVO_SPEED", 16, SIM, servo_speed, 0.14), AP_GROUPINFO("SONAR_ROT", 17, SIM, sonar_rot, Rotation::ROTATION_PITCH_270), + // @Param: BATT_VOLTAGE + // @DisplayName: Simulated battery voltage + // @Description: Simulated battery (constant) voltage + // @Units: V + // @User: Advanced AP_GROUPINFO("BATT_VOLTAGE", 19, SIM, batt_voltage, 12.6f), AP_GROUPINFO("BATT_CAP_AH", 20, SIM, batt_capacity_ah, 0), AP_GROUPINFO("SONAR_GLITCH", 23, SIM, sonar_glitch, 0), @@ -94,10 +106,48 @@ const AP_Param::GroupInfo SIM::var_info[] = { // @Description: If set, if a numerical error occurs SITL will die with a floating point exception. // @User: Advanced AP_GROUPINFO("FLOAT_EXCEPT", 28, SIM, float_exception, 1), + + // @Param: CAN_SRV_MSK + // @DisplayName: Mask of CAN servos/ESCs + // @Description: The set of actuators controlled externally by CAN SITL AP_Periph + // @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15, 15: Servo 16, 16: Servo 17, 17: Servo 18, 18: Servo 19, 19: Servo 20, 20: Servo 21, 21: Servo 22, 22: Servo 23, 23: Servo 24, 24: Servo 25, 25: Servo 26, 26: Servo 27, 27: Servo 28, 28: Servo 29, 29: Servo 30, 30: Servo 31, 31: Servo 32 + // @User: Advanced + AP_GROUPINFO("CAN_SRV_MSK", 29, SIM, can_servo_mask, 0), + +#if HAL_NUM_CAN_IFACES > 0 + // @Param: CAN_TYPE1 + // @DisplayName: transport type for first CAN interface + // @Description: transport type for first CAN interface + // @Values: 0:MulticastUDP,1:SocketCAN + // @User: Advanced + AP_GROUPINFO("CAN_TYPE1", 30, SIM, can_transport[0], uint8_t(CANTransport::MulticastUDP)), +#endif + +#if HAL_NUM_CAN_IFACES > 1 + // @Param: CAN_TYPE2 + // @DisplayName: transport type for second CAN interface + // @Description: transport type for second CAN interface + // @Values: 0:MulticastUDP,1:SocketCAN + // @User: Advanced + AP_GROUPINFO("CAN_TYPE2", 31, SIM, can_transport[1], uint8_t(CANTransport::MulticastUDP)), +#endif + 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), AP_GROUPINFO("TERRAIN", 34, SIM, terrain_enable, 1), + // @Param: FLOW_RATE + // @DisplayName: Opflow Rate + // @Description: Opflow Data Rate + // @Units: Hz AP_GROUPINFO("FLOW_RATE", 35, SIM, flow_rate, 10), + // @Param: FLOW_DELAY + // @DisplayName: Opflow Delay + // @Description: Opflow data delay + // @Units: ms AP_GROUPINFO("FLOW_DELAY", 36, SIM, flow_delay, 0), AP_GROUPINFO("ADSB_COUNT", 45, SIM, adsb_plane_count, -1), AP_GROUPINFO("ADSB_RADIUS", 46, SIM, adsb_radius_m, 10000), @@ -110,9 +160,19 @@ const AP_Param::GroupInfo SIM::var_info[] = { // @Range: 1 10 // @User: Advanced AP_GROUPINFO("SPEEDUP", 52, SIM, speedup, -1), + // @Param: IMU_POS + // @DisplayName: IMU Offsets + // @Description: XYZ position of the IMU accelerometer relative to the body frame origin + // @Units: m + // @Vector3Parameter: 1 AP_GROUPINFO("IMU_POS", 53, SIM, imu_pos_offset, 0), AP_SUBGROUPEXTENSION("", 54, SIM, var_ins), AP_GROUPINFO("SONAR_POS", 55, SIM, rngfnd_pos_offset, 0), + // @Param: FLOW_POS + // @DisplayName: Opflow Pos + // @Description: XYZ position of the optical flow sensor focal point relative to the body frame origin + // @Units: m + // @Vector3Parameter: 1 AP_GROUPINFO("FLOW_POS", 56, SIM, optflow_pos_offset, 0), AP_GROUPINFO("ENGINE_FAIL", 58, SIM, engine_fail, 0), #if AP_SIM_SHIP_ENABLED @@ -189,6 +249,9 @@ const AP_Param::GroupInfo SIM::var_info2[] = { 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 AP_GROUPINFO("FLOW_RND", 34, SIM, flow_noise, 0.05f), AP_GROUPINFO("TWIST_X", 37, SIM, twist.x, 0), @@ -295,7 +358,9 @@ const AP_Param::GroupInfo SIM::var_info3[] = { AP_GROUPINFO("RATE_HZ", 22, SIM, loop_rate_hz, SIM_RATE_HZ_DEFAULT), - // count of simulated IMUs + // @Param: IMU_COUNT + // @DisplayName: IMU count + // @Description: Number of simulated IMUs to create AP_GROUPINFO("IMU_COUNT", 23, SIM, imu_count, 2), // @Path: ./SIM_FETtecOneWireESC.cpp @@ -374,9 +439,13 @@ const AP_Param::GroupInfo SIM::var_info3[] = { // @User: Advanced AP_GROUPINFO("UART_LOSS", 42, SIM, uart_byte_loss_pct, 0), - AP_SUBGROUPINFO(airspeed[0], "ARSPD_", 50, SIM, SIM::AirspeedParm), + // @Group: ARSPD_ + // @Path: ./SITL_Airspeed.cpp + AP_SUBGROUPINFO(airspeed[0], "ARSPD_", 50, SIM, AirspeedParm), #if AIRSPEED_MAX_SENSORS > 1 - AP_SUBGROUPINFO(airspeed[1], "ARSPD2_", 51, SIM, SIM::AirspeedParm), + // @Group: ARSPD2_ + // @Path: ./SITL_Airspeed.cpp + AP_SUBGROUPINFO(airspeed[1], "ARSPD2_", 51, SIM, AirspeedParm), #endif @@ -406,24 +475,6 @@ const AP_Param::GroupInfo SIM::BaroParm::var_info[] = { AP_GROUPEND }; -// user settable parameters for airspeed sensors -const AP_Param::GroupInfo SIM::AirspeedParm::var_info[] = { - // user settable parameters for the 1st airspeed sensor - AP_GROUPINFO("RND", 1, SIM::AirspeedParm, noise, 2.0), - AP_GROUPINFO("OFS", 2, SIM::AirspeedParm, offset, 2013), - // @Param: ARSPD_FAIL - // @DisplayName: Airspeed sensor failure - // @Description: Simulates Airspeed sensor 1 failure - // @Values: 0:Disabled, 1:Enabled - // @User: Advanced - AP_GROUPINFO("FAIL", 3, SIM::AirspeedParm, fail, 0), - AP_GROUPINFO("FAILP", 4, SIM::AirspeedParm, fail_pressure, 0), - AP_GROUPINFO("PITOT", 5, SIM::AirspeedParm, fail_pitot_pressure, 0), - AP_GROUPINFO("SIGN", 6, SIM::AirspeedParm, signflip, 0), - AP_GROUPINFO("RATIO", 7, SIM::AirspeedParm, ratio, 1.99), - AP_GROUPEND -}; - #if HAL_SIM_GPS_ENABLED // GPS SITL parameters const AP_Param::GroupInfo SIM::var_gps[] = { @@ -433,24 +484,84 @@ const AP_Param::GroupInfo SIM::var_gps[] = { // @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:SBP, 10:GSOF + // @Values: 0:None, 1:UBlox, 5:NMEA, 6:SBP, 7:File, 8:Nova, 9:SBP, 10:GSOF, 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: GPS2_DISABLE // @DisplayName: GPS 2 disable @@ -458,29 +569,101 @@ const AP_Param::GroupInfo SIM::var_gps[] = { // @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), + // @Param: INIT_LAT_OFS + // @DisplayName: Initial Latitude Offset + // @Description: GPS initial lat offset from origin AP_GROUPINFO("INIT_LAT_OFS", 45, SIM, gps_init_lat_ofs, 0), + // @Param: INIT_LON_OFS + // @DisplayName: Initial Longitude Offset + // @Description: GPS initial lon offset from origin AP_GROUPINFO("INIT_LON_OFS", 46, SIM, gps_init_lon_ofs, 0), + // @Param: INIT_ALT_OFS + // @DisplayName: Initial Altitude Offset + // @Description: GPS initial alt offset from origin AP_GROUPINFO("INIT_ALT_OFS", 47, SIM, gps_init_alt_ofs, 0), + // @Param: GPS_LOG_NUM + // @DisplayName: GPS Log Number + // @Description: Log number for GPS:update_file() AP_GROUPINFO("GPS_LOG_NUM", 48, SIM, gps_log_num, 0), AP_GROUPEND @@ -581,11 +764,24 @@ const AP_Param::GroupInfo SIM::var_ins[] = { AP_GROUPINFO("IMUT_TCONST", 3, SIM, imu_temp_tconst, 300), AP_GROUPINFO("IMUT_FIXED", 4, SIM, imu_temp_fixed, 0), #endif + // @Param: ACC1_BIAS + // @DisplayName: Accel 1 bias + // @Description: bias of simulated accelerometer sensor + // @User: Advanced + // @Vector3Parameter: 1 AP_GROUPINFO("ACC1_BIAS", 5, SIM, accel_bias[0], 0), #if INS_MAX_INSTANCES > 1 + // @Param: ACC2_BIAS + // @DisplayName: Accel 2 bias + // @CopyFieldsFrom: SIM_ACC1_BIAS + // @Vector3Parameter: 1 AP_GROUPINFO("ACC2_BIAS", 6, SIM, accel_bias[1], 0), #endif #if INS_MAX_INSTANCES > 2 + // @Param: ACC3_BIAS + // @DisplayName: Accel 3 bias + // @CopyFieldsFrom: SIM_ACC1_BIAS + // @Vector3Parameter: 1 AP_GROUPINFO("ACC3_BIAS", 7, SIM, accel_bias[2], 0), #endif AP_GROUPINFO("GYR1_RND", 8, SIM, gyro_noise[0], 0), @@ -602,11 +798,24 @@ const AP_Param::GroupInfo SIM::var_ins[] = { #if INS_MAX_INSTANCES > 2 AP_GROUPINFO("ACC3_RND", 13, SIM, accel_noise[2], 0), #endif + // @Param: GYR1_SCALE + // @DisplayName: Gyro 1 scaling factor + // @Description: scaling factors applied to simulated gyroscope + // @User: Advanced + // @Vector3Parameter: 1 AP_GROUPINFO("GYR1_SCALE", 14, SIM, gyro_scale[0], 0), #if INS_MAX_INSTANCES > 1 + // @Param: GYR2_SCALE + // @DisplayName: Gyro 2 scaling factor + // @CopyFieldsFrom: SIM_GYR1_SCALE + // @Vector3Parameter: 1 AP_GROUPINFO("GYR2_SCALE", 15, SIM, gyro_scale[1], 0), #endif #if INS_MAX_INSTANCES > 2 + // @Param: GYR3_SCALE + // @DisplayName: Gyro 3 scaling factor + // @CopyFieldsFrom: SIM_GYR1_SCALE + // @Vector3Parameter: 1 AP_GROUPINFO("GYR3_SCALE", 16, SIM, gyro_scale[2], 0), #endif // @Param: ACCEL1_FAIL @@ -643,11 +852,25 @@ const AP_Param::GroupInfo SIM::var_ins[] = { // @Values: 0:Disabled, 1:Readings stopped // @User: Advanced AP_GROUPINFO("ACC_FAIL_MSK", 21, SIM, accel_fail_mask, 0), + + // @Param: ACC1_SCAL + // @DisplayName: Accel 1 scaling factor + // @Description: scaling factors applied to simulated accelerometer + // @User: Advanced + // @Vector3Parameter: 1 AP_GROUPINFO("ACC1_SCAL", 22, SIM, accel_scale[0], 0), #if INS_MAX_INSTANCES > 1 + // @Param: ACC2_SCAL + // @DisplayName: Accel 2 scaling factor + // @CopyFieldsFrom: SIM_ACC1_SCAL + // @Vector3Parameter: 1 AP_GROUPINFO("ACC2_SCAL", 23, SIM, accel_scale[1], 0), #endif #if INS_MAX_INSTANCES > 2 + // @Param: ACC3_SCAL + // @DisplayName: Accel 3 scaling factor + // @CopyFieldsFrom: SIM_ACC1_SCAL + // @Vector3Parameter: 1 AP_GROUPINFO("ACC3_SCAL", 24, SIM, accel_scale[2], 0), #endif AP_GROUPINFO("ACC_TRIM", 25, SIM, accel_trim, 0), @@ -731,6 +954,10 @@ const AP_Param::GroupInfo SIM::var_ins[] = { #endif #if INS_MAX_INSTANCES > 3 + // @Param: ACC4_SCAL + // @DisplayName: Accel 4 scaling factor + // @CopyFieldsFrom: SIM_ACC1_SCAL + // @Vector3Parameter: 1 AP_GROUPINFO("ACC4_SCAL", 34, SIM, accel_scale[3], 0), // @Param: ACCEL4_FAIL @@ -740,12 +967,20 @@ const AP_Param::GroupInfo SIM::var_ins[] = { // @User: Advanced AP_GROUPINFO("ACCEL4_FAIL", 35, SIM, accel_fail[3], 0), + // @Param: GYR4_SCALE + // @DisplayName: Gyro 4 scaling factor + // @CopyFieldsFrom: SIM_GYR1_SCALE + // @Vector3Parameter: 1 AP_GROUPINFO("GYR4_SCALE", 36, SIM, gyro_scale[3], 0), AP_GROUPINFO("ACC4_RND", 37, SIM, accel_noise[3], 0), AP_GROUPINFO("GYR4_RND", 38, SIM, gyro_noise[3], 0), + // @Param: ACC4_BIAS + // @DisplayName: Accel 4 bias + // @CopyFieldsFrom: SIM_ACC1_BIAS + // @Vector3Parameter: 1 AP_GROUPINFO("ACC4_BIAS", 39, SIM, accel_bias[3], 0), // @Param: GYR4_BIAS_X @@ -768,6 +1003,10 @@ const AP_Param::GroupInfo SIM::var_ins[] = { #endif #if INS_MAX_INSTANCES > 4 + // @Param: ACC5_SCAL + // @DisplayName: Accel 4 scaling factor + // @CopyFieldsFrom: SIM_ACC1_SCAL + // @Vector3Parameter: 1 AP_GROUPINFO("ACC5_SCAL", 41, SIM, accel_scale[4], 0), @@ -778,12 +1017,20 @@ const AP_Param::GroupInfo SIM::var_ins[] = { // @User: Advanced AP_GROUPINFO("ACCEL5_FAIL", 42, SIM, accel_fail[4], 0), + // @Param: GYR5_SCALE + // @DisplayName: Gyro 5 scaling factor + // @CopyFieldsFrom: SIM_GYR1_SCALE + // @Vector3Parameter: 1 AP_GROUPINFO("GYR5_SCALE", 43, SIM, gyro_scale[4], 0), AP_GROUPINFO("ACC5_RND", 44, SIM, accel_noise[4], 0), AP_GROUPINFO("GYR5_RND", 45, SIM, gyro_noise[4], 0), + // @Param: ACC5_BIAS + // @DisplayName: Accel 5 bias + // @CopyFieldsFrom: SIM_ACC1_BIAS + // @Vector3Parameter: 1 AP_GROUPINFO("ACC5_BIAS", 46, SIM, accel_bias[4], 0), // @Param: GYR5_BIAS_X @@ -804,6 +1051,11 @@ const AP_Param::GroupInfo SIM::var_ins[] = { AP_GROUPINFO("GYR5_BIAS", 47, SIM, gyro_bias[4], 0), #endif + // @Param: OH_RELAY_MSK + // @DisplayName: SIM-on_hardware Relay Enable Mask + // @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), + // 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), @@ -885,7 +1137,9 @@ void SIM::sim_state_send(mavlink_channel_t chan) const 0.0, state.speedN, state.speedE, - state.speedD); + state.speedD, + (int32_t)(state.latitude*1.0e7), + (int32_t)(state.longitude*1.0e7)); } /* report SITL state to AP_Logger */ @@ -967,7 +1221,7 @@ float SIM::get_rangefinder(uint8_t instance) { if (instance < ARRAY_SIZE(state.rangefinder_m)) { return state.rangefinder_m[instance]; } - return -1; + return nanf(""); }; float SIM::measure_distance_at_angle_bf(const Location &location, float angle) const diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 2bac241ab120ec..4dfd9b251facbf 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -218,6 +218,16 @@ class SIM { AP_Int8 rc_fail; // fail RC input AP_Int8 rc_chancount; // channel count AP_Int8 float_exception; // enable floating point exception checks + AP_Int32 can_servo_mask; // mask of servos/escs coming from CAN + +#if HAL_NUM_CAN_IFACES + enum class CANTransport : uint8_t { + MulticastUDP = 0, + SocketCAN = 1 + }; + AP_Enum can_transport[HAL_NUM_CAN_IFACES]; +#endif + AP_Int8 flow_enable; // enable simulated optflow AP_Int16 flow_rate; // optflow data rate (Hz) AP_Int8 flow_delay; // optflow data delay @@ -236,6 +246,7 @@ class SIM { AP_Int16 loop_rate_hz; AP_Int16 loop_time_jitter_us; AP_Int32 on_hardware_output_enable_mask; // mask of output channels passed through to actual hardware + AP_Int16 on_hardware_relay_enable_mask; // mask of relays passed through to actual hardware AP_Float uart_byte_loss_pct; diff --git a/libraries/SITL/SITL_Airspeed.cpp b/libraries/SITL/SITL_Airspeed.cpp new file mode 100644 index 00000000000000..ea1289386bb1ea --- /dev/null +++ b/libraries/SITL/SITL_Airspeed.cpp @@ -0,0 +1,44 @@ +#include "SITL.h" + +#if AP_SIM_ENABLED + +namespace SITL { +// user settable parameters for airspeed sensors +const AP_Param::GroupInfo SIM::AirspeedParm::var_info[] = { + // user settable parameters for the 1st airspeed sensor + AP_GROUPINFO("RND", 1, AirspeedParm, noise, 2.0), + AP_GROUPINFO("OFS", 2, AirspeedParm, offset, 2013), + // @Param: FAIL + // @DisplayName: Airspeed sensor failure + // @Description: Simulates Airspeed sensor 1 failure + // @Values: 0:Disabled, 1:Enabled + // @User: Advanced + AP_GROUPINFO("FAIL", 3, AirspeedParm, fail, 0), + // @Param: FAILP + // @DisplayName: Airspeed sensor failure pressure + // @Description: Simulated airspeed sensor failure pressure + // @Units: Pa + // @User: Advanced + AP_GROUPINFO("FAILP", 4, AirspeedParm, fail_pressure, 0), + // @Param: PITOT + // @DisplayName: Airspeed pitot tube failure pressure + // @Description: Simulated airspeed sensor pitot tube failure pressure + // @Units: Pa + // @User: Advanced + AP_GROUPINFO("PITOT", 5, AirspeedParm, fail_pitot_pressure, 0), + // @Param: SIGN + // @DisplayName: Airspeed signflip + // @Description: Simulated airspeed sensor with reversed pitot/static connections + // @Values: 0:Disabled, 1:Enabled + // @User: Advanced + AP_GROUPINFO("SIGN", 6, AirspeedParm, signflip, 0), + // @Param: RATIO + // @DisplayName: Airspeed ratios + // @Description: Simulated airspeed sensor ratio + // @User: Advanced + AP_GROUPINFO("RATIO", 7, AirspeedParm, ratio, 1.99), + AP_GROUPEND +}; +} + +#endif // AP_SIM_ENABLED \ No newline at end of file diff --git a/libraries/SITL/examples/Webots_Python/controllers/ardupilot_vehicle_controller/webots_vehicle.py b/libraries/SITL/examples/Webots_Python/controllers/ardupilot_vehicle_controller/webots_vehicle.py index 3de1197bcb28c2..acd6f5641fbad4 100644 --- a/libraries/SITL/examples/Webots_Python/controllers/ardupilot_vehicle_controller/webots_vehicle.py +++ b/libraries/SITL/examples/Webots_Python/controllers/ardupilot_vehicle_controller/webots_vehicle.py @@ -1,4 +1,3 @@ -#!/usr/bin/env python3 ''' This file implements a class that acts as a bridge between ArduPilot SITL and Webots diff --git a/libraries/SITL/wscript b/libraries/SITL/wscript new file mode 100644 index 00000000000000..da492465783405 --- /dev/null +++ b/libraries/SITL/wscript @@ -0,0 +1,2 @@ +def configure(cfg): + cfg.env.DOUBLE_PRECISION_LIBRARIES['SITL'] = True diff --git a/libraries/SRV_Channel/SRV_Channel.h b/libraries/SRV_Channel/SRV_Channel.h index ea90ce2d4a8a94..90f49e11feaedb 100644 --- a/libraries/SRV_Channel/SRV_Channel.h +++ b/libraries/SRV_Channel/SRV_Channel.h @@ -507,8 +507,8 @@ class SRV_Channels { static AP_HAL::RCOutput::DshotEscType get_dshot_esc_type() { return AP_HAL::RCOutput::DshotEscType(_singleton->dshot_esc_type.get()); } static uint8_t get_dshot_rate() { return _singleton->dshot_rate.get(); } - - static uint8_t get_rc_fs_mask() { return _singleton->rc_fs_mask.get(); } + + static uint32_t get_rc_fs_mask() { return _singleton->rc_fs_mask.get(); } static SRV_Channel *srv_channel(uint8_t i) { #if NUM_SERVO_CHANNELS > 0 diff --git a/libraries/SRV_Channel/SRV_Channel_aux.cpp b/libraries/SRV_Channel/SRV_Channel_aux.cpp index 5b5fc63ef8329f..50557eed1b0b45 100644 --- a/libraries/SRV_Channel/SRV_Channel_aux.cpp +++ b/libraries/SRV_Channel/SRV_Channel_aux.cpp @@ -59,10 +59,18 @@ void SRV_Channel::output_ch(void) // non-mapped rc passthrough int16_t radio_in = c->get_radio_in(); if (passthrough_mapped) { - if ( ((1U<norm_input_dz() * 4500); + } else { + // no valid input. If we are in radio + // failsafe then go to trim values (if + // configured for this channel). Otherwise + // use the last-good value + if ( ((1U<